From 57d3036ee7e0d2f5ca5bc60349f580bad6f4bd46 Mon Sep 17 00:00:00 2001 From: Paul Riseborough Date: Sun, 1 May 2016 15:06:17 +1000 Subject: [PATCH] EKF: update derivation files --- matlab/scripts/Inertial Nav EKF/Airspeed.mat | Bin 8668 -> 8710 bytes matlab/scripts/Inertial Nav EKF/C_code24.txt | 1003 +++++++++-------- matlab/scripts/Inertial Nav EKF/Drag.mat | Bin 18266 -> 18384 bytes matlab/scripts/Inertial Nav EKF/H_LOSX.c | 21 +- matlab/scripts/Inertial Nav EKF/H_LOSY.c | 20 +- matlab/scripts/Inertial Nav EKF/K_LOSX.c | 204 ++-- matlab/scripts/Inertial Nav EKF/K_LOSY.c | 204 ++-- matlab/scripts/Inertial Nav EKF/M_code24.txt | 1003 +++++++++-------- .../scripts/Inertial Nav EKF/Magnetometer.mat | Bin 18619 -> 19484 bytes matlab/scripts/Inertial Nav EKF/Sideslip.mat | Bin 9665 -> 9809 bytes .../StateAndCovariancePrediction.mat | Bin 144862 -> 135809 bytes .../Inertial Nav EKF/StatePrediction.mat | Bin 120596 -> 106832 bytes .../Inertial Nav EKF/SymbolicOutput24.mat | Bin 194559 -> 184296 bytes .../Inertial Nav EKF/SymbolicOutput24.txt | 1003 +++++++++-------- .../scripts/Inertial Nav EKF/calcH_YAW312.c | 29 +- .../scripts/Inertial Nav EKF/calcH_YAW321.c | 29 +- matlab/scripts/Inertial Nav EKF/temp1.mat | Bin 1310 -> 1043 bytes matlab/scripts/Inertial Nav EKF/temp2.mat | Bin 2457 -> 2434 bytes matlab/scripts/Inertial Nav EKF/temp3.mat | Bin 2451 -> 2443 bytes 19 files changed, 1788 insertions(+), 1728 deletions(-) diff --git a/matlab/scripts/Inertial Nav EKF/Airspeed.mat b/matlab/scripts/Inertial Nav EKF/Airspeed.mat index 9dc46ab0fa96260f4fe15a8d3dc77f9799c8c4d4..fd834d9025b51a66a7c7752e9f550fe83b84b657 100644 GIT binary patch delta 8345 zcmV;KAZFj(Lxx0f6{;Z$o~Re`fx#^1JcB{`uXHzu4%k>HfOTfB%DZ{{9#HAOE%g>z{3Z z(*N@#!nZAgIT^=d{+ECGWq$Ps^MC)n-|7G1PxkS%{f~e7cT+$9vHfp;8T-vI&(I^* zFY-Sh`MV!~_x{(m{IFcz4}ZS><}Zx@Vf*pV=s*6M@n84zr{jP1e~bL-_+S4be`(zx z{|))gpXh(}|M5G1ZNL449{Stg`~BCw{9(NOpTGJ2e*W$k{qg3I*8lv^achBWy>E;e?joQdX^F>*1k4%>VR&Oy;Yz!DwGJp zi;Mn^IwBHuj5{q9y<1j zwSMuB6m>g7e=^Q)WW!r9RB7tblz4q9s3udtvq#*lohhjfI6g!uyObgnS1=$A?zSnG z+(szM^6LzUkgvsaR05|SN(@IWgr{o<)H?~3sC=k~sbn*wY!6KVTej3sGFmnMYFe>k zfkBa;XpuL#&D)m%a@3f=tr>3CeBFFpv2d~oh48Mnf0qTz_*}MKB^zsT0jf8Z@3a3rQi_bL3<=$B0?74Oli}T9p@#WB}B7aFkEHp#6SOHi1{e6Mm{o-(?Gk^k3 z+;j5#`^HG8aIs1X5q(q)gty-qt`S1n+O$^4qr8q@bnz5~rMbnK8O@Gth|SEqFiiq5 z*plwne{CTUOtuoEq>5xztoWI*S^;^1It`84b?)<;A*)GjXo}6}tQ^=Fjm#@Y+K=~& z5^0ejD`^5o5MQ}8ywGV}Q)e~mFTb4K(?8#6P33co8E#;iOc&?9gv?wM%`eOscd)EMIe?MYIXn$EXlV4LxGpb70>3`d`c!iylVMQYqURN>4xr ze^e-r)`;0U73}vpA*=G#-l^6>ZG6omX=LuJ=x`*qrceqp^4;^uL2)N+@z0%0fw(2$ z$+QrKzlR~4?y;z=08I4(c929o7%EDk!Vxnkfj(U_451$4xZ_d{aNQ@ye7eln8yQ%3 z2SZIrJUZ0aw_^2Cu{isgF9w4wjT2Tfe_zfRz#h|rDoT^N=8|uGbPsTOPp#Fx<#evg zY#K6PrgiH!%Sa1Zurj6f1DTeRC?=oXPGS&Xh|9SG zH~GC!%L?cZRHXi58)k3i>oFHq-|ho(3+*<4!$yE}VpnyPrN5%@tPt!M6gK(!@P1-Z zg-h1mpD2&Q1$TRp7&neM@BXf5e^o>n7TUsV9YLflz;P@D$8En2ojMt@HNAe^J1u3uB3y zlxFJ5!2!@@S;-8Sv(3H~2AR&EMcWx#k>%f#C^zOCEF!8=)7ge4x4o#8Qe!`}J{hQ? zOixff*S`#qgD#E*@7kl8M@LFm8e9CSvDMFL1aJEsw zrH8w`*OrW7s1u0Uj-24g|=#GcXMbs5Vc);e`S7g?LPiyw^@ zbbttTCX^_8wYdd12I;+uo>@bxHreYX(mOA?ZklNOxgr7%WYURmja{IUi@6$6fiIBN z6WF0ey4qRL3@QZ(f9N(Xr4GcyE<5=D`Var*cev^Nf8ZwOZ~quK{iOe8+_e6Lo3Nj7 zQ{lYWr1Fz@%MY|6r+jrLZ?C~TXK@UiiH4z=CJaVN_F8fp&2vYQULW85GMLRuQgzCZ zMlk^P$y_G^DTZZT-V_`)CdvFXjXmy4DjA(f>^rasuO0BQe|tk))|Ckx48XX&c+gl# z;9KP~wQM&|TBDAyoYHq1GV-|-ka-0V8x@+AQ^4Y4_0@aYokXQDSO)X1*}2#xgnPZV z+zyNNqghdj>|=@OO`)~4)GVQEZZ{x18SfXoY5|r=Yj$Ma`uk1nNRFxWdOp~Ut>Ffu zfExD?L3(9UfBn_tdpFQ5jgq(Ol1B@ps^f-2d(YU%N;N6GvT_g&0m;Zj8;@*kulZxq z59%117`q5+@d&qAd4P|ZkqU7OHbi}?!*7hKhY#FZl42;-k}+MArO7jZGSJ(hr)S)< z!#up`0GQMFYbHIbuF#aN8(?#s4%k(zX0vzs=1BLW=Axadctt_I0NCXAxZ%senX{|hM|T&q>s+to z616Xae;~ZxVz=s|IVz?g3FBQcJ2UY6xX@I8;PpK`xd`!Ck`VLU)Z8Nz`}m2hmgLO7 zDXz~Ojq#*q4sKJgZo<+;>dx6(x`9+pd4(X^7MEWCUS%ZGB}-4vUA>? zaz5iGUP}OhH70HK3H_i3Sn9rVo6AN4(sh<`|avk(d1a1Sy)c##9Exs(H>u5c(9f3@c@b5$9(LC zDW`xLY_yxQNa)|YRBb2yBvbyKI~@O7H9w3A)IOf$T~=h;OIx`RDXLnzMTZ@J)-53$ zMsQ+P#9~U^J3Mq2YRy}r1DyDJDNlJRe+_A&PdRC??06T>!Fcb>#q^$hhG;uk%z7g6 zIn@hqUJUh)pv{rYPajA1?LgM@!j-rLeu7O7R)2yh(B+Dbi~1h(uf=*90?_cZWA$aw z(Ss#7@^tgU7g$pOu-CGeL1F;FT)sB*DWql7pOua?-*v8wLZw_LJyq+T%7_GCf3%~T z3%H1uj}dXXWw44Bb*?7sS%QG^Jz_wMl*=XSA*5ZE=(aVc# z&s#%hKvee_66R!8M6S~(=UIeI6@6#~mq(aK zGEiWJC!23p5#6FLt;^a)WY~h;f3&u+Il*Q4OaqJdaY#KWDS%ig?}n|+v?eswy>hsv zuvDc_iff3mRMG4gLSctKI#I)o^^+WjBI)`*d4ESg7&0`1ET2+TfDv|%zU-P zZvY;P(BGEJy1yNZx`bN>H?vY$2OD)W?_psC1iw>M7+U$lZi_<`u!w+JSI>7l4*nTj zcvGV!IlnSE(m_GsSmanZVFIxAQuA`TKRq}#MRa6Nx_zdJxi3(gz0X1I72V&0yMhTu zU?+o3^81aCskSe7=}||Pe>hoASK5NCL%_zqw4a$uJ}SBO$rFuX!_BHH>`>=E@RQwO=HaOj zgEJbHCsoe}lyjuO9J61%-e#cD0Mgu#P7_O;34zcW%K=*_SV+N#f3TAo`PEUBWmVw9 zm?wA7fw6@T%{K#Lb4ba|eX|T+hS%A9mrju*whghVy$X99xyqq-21gBGcwOJ=>$qF$ z#>a!A*XqLnFD;!N$tD|9Y|2FX|D%yBhOn~x92hUtoW6k=GN;HcR5uq6^T z*7r1Qla@nM93BM#f2>ef1P+8AAE?pc4`qBC&1=7#B-rWOuLPyyq=G;)p-^? zDAu~X`Ci_y()KV1tUzW{NSjE8vfs(+Llj^IILi8w@Pbn0f0zJ9>%HM5slf21s=KyP zTVK!YJA6PZ_A~bS^?$2>{7?Tj{`%kl@sIJ>Px@cNU%d|RC~v8&+Y!^2abe4@i5q9X9Hs2wN|*l`urS9@u$C(R1*r)RNuy6q>O_Xl9!?kl!= z?2fJ8e~$d_^Fhg363G%aIwBN{A`#G{NExFd3bC%Y1 z!GyK&RKPg-Qq1O#2kP(R-ySo+L;4VzblG}fQ{fCckm|B%?^V|FxrJ5b&sXU%Z9^$E zHycHqAU>MN+dG{ts!Jhk?It=LbZb)Z4UX&fe}d5KA^!(}o~6g=Mg~D|>vqufAv(Tt z^{lCmU~?&T!yo~nhgQHLvz8{Asz^}LSRRMSUfm*53wFtyntDuR%KSk@ZfYFgB80fl6rw0pIk zf1ac6wRw2a9@VWpuM!T z!}^uu^-~r^AN(@R;Ua_5Kcry@hJkMHBYC9{N+D6w=2R8yKs%$WP^72vDYZb9*<(8$ zIl4HH&nQeKnwa)mq)$H4OVP`j&{`Ypf5+y9iqtwHiIAYT%OD%OjuH#V50%{=`XhKG zaea28Di#`&5ovb?7QBRt0Sh;ni zquqsOmi=&30IzP{p}BMIuTop3=(|rFY68aNkNn{{Ujdgy`+R3U@!Vea3?{6ge_=>O zxMMB8AL>ZSBsIm->0^z=fdoPPeIRLM3Pd=1*tLEaGuGryofL(&O=xy_^jtoLcdr0p zA&g0<>FBI2`-}Fn2&aX{M73KWcYtv4JBuouMWWZo*i?Ejd%t}1AoB za0x%uusZJ$hb<<2f3u@Bdkf5!5XZL6CidHk59D$y zbstB1FHyrNzQqjX_R|9+~j-c_^Vw^UMVzyehJsh5`0+Ns5&1w8L&Edw-w|z{_Kb zxmY9WtGz5pMWe@8MDw2prJU_*He5LM_9c=`9T1}D42B_ox5D@LlLD9K4z@k@hW z1JCo6Qaap=UNfxq7`$X9NquLdHPO@-T^R{qZdNj-!+p_kGmpE#f@DwMLbK=a&5bB~ z7Qzy9bo`wsnQA)x{yx{*LqSjYW>GVNB*}qYn&}k+a?4m#e~W#yc8+Ol4an45!w^4V zyXEPHcE2ep@_I{b+b-nMp`G2X|4JKVsb6dFv*ZM8OMa&cSPrQb_fC%NISE<^hlkEW z058H?eZ{i0mj-%Hie}6;4Tt8_Ay{0*xeXm)UZwJtISk<%Ei4OYp=8KjAQ#w*74i9b+w2;Uadzl~TtVK1Wx`DHd zNo&fG1pA%AoOAPnpxc>$JLmhoC`{n-Qv7_gW&HbXq`K`jt)%>H>pr&1W82=&^|S5! zv2`9>f8l3a@3G}uiFs^^7cL!*_N{xnmrTBjonzp>CCi09Pe{*$_U?IrSF@)7zW@LL z|NpI)N6z%d5r#hrl3{sa_zYUf;DR}{054{SUJXBc+OX_zxl;G_6_K7sj3zu@17 z0B>ACqgainstK~Y>orH0e8?Hutl5j)^!$7%e{8OTIBU=)MA4w9)#?%>YDr{!&tWfK z*UiZJ{wU(xmcF^3t<#$jqegxQ;{kD`W!pud9f+of_ATiN>YC!Ym{mHf`Tl~TfC!1Mp_6z%2H#^zeS@&eQY#u= zd(X2WgrkP8v+X0GKGIb0X`%HJ!3|(E4D8kM4IfTQ>TzsF)!*%U+AmXq@E}JK#q=66 zlBQ-6mC2#m9GU1sl{?}U8Bl1-f2xdS(WN9)FLtp(u)AmE-C>ID#@?~9$y*Z=MyW>& zZv#*^%&S%V3bd*B9}`2H8t6{1S6WVt{?z3H}IXa&D9Oy4Fyyxu*_A;kZxeApipEw3te~SW(mzY8_ zR4vuWQOWY?u?>HbQjUaHz{rSEi4?x+>DES#ZTrO)LPX}Gw6NaqUSNZ`f^q_M?y)v* z;BqFmr)Y2tf+3D5AEOt3W~mM4Lt#k5Apyf+LQRY&rf%KRDt)pvbeqNpyS@*_&tR4%w!)scCBy`b}Re`C87l(Ry6jI(g7p^KRZRUBh3_G4fUo1I3e0vMGf$5Hje zonfjl5h`X~3>Stliz}erX-6`>Vr5nnt>vI1%$a~r#ZH{dI%hhgj3Q6fl^MF(6+TV0 zR#TyUcL^HfEh0h_NI zEj7eaPmg8pAcO+vh2R1b4zZ^X8Xb-&^l<98CdDsENhmYUe^A5Waa5dj2?9&lCSwWb z;oX1xwhfoMR3M~>#lqPG3Qb9;dE86oy6pzf`o+z|nD=0^-TcT$NKoZK?H0hf?##6; zb{+Wp)1+L1-w@mz<_Sv^2C{k;L2t(M4i~}zxAS@UI^mMEniS$gNnR9natCDypYxul zuM0CZMXKwhf0bLSB4CZt#@HoQ-_$)y@9={NJ9vsnnNBL|Ne&xH>#Dtyl;n|&6+dVN z>?&E$eaO)7+HMu4Y@zr`HW)j#wQEceR>sK%m^X=9-`ew*r225ZC?0kcBxVa^*PUlM z-jZI%ZE_Q`t4xTe`pI1q+Y_7np=ml-^#ehD~pgV zm?tIMP%Y56ICea#VGKiX_a=xU6;V49-{qZ6jpRDwJXtS{d*SGraf^~IQizrb3=dW# zNc?^>s*v$yGQC+#W{zffjGc{wC(c3@xouYl$a}nqRJB?V6A0Z} zu(Uy5yptX94!A~jETaHhHy&;d1wROu3l?g=9k(`xB>m1av3D09On0aFc|rI|fb~7p z#RhscX6RmgB7MK|)$`LWH?L4v(~Fx#-kQFJf3rVhg0dh-YBOs*y)F@ z1bwlYF_1c=F-t~z$Th3(jjbva${v?&YUjxD%4w*1CfVTj5t^E?j4mW2XPbqtV2W8r zbHEeWn&G@!k3KRDd0U5-Ft^QZ+Q8nKn{ENIgItjhjxvOK}bmV!)>zx ze^nY}L!!i$s|l>Boz85235Q&$7H-Zi(6cWZtb6qZU7G#_#a~u4Et%~g<6D7zt0~%8 z5FbVCP_e^23)Qt-18;<74%-^>7J>>qSP|3Jiz0qnTMTL5hMuXjav-a+LBYEYndGtf z?jF^A+;`h9erdPB+v0`JYq6U5I$O`it@i zP&k%=LS(lK33W)K(@sKTIRdumO5-BYU88#{*|0Dp#i>LdCUe_ZBR zI7LJgla5r)cWWe;vmw_p`5t5z*%?(HS^%5IlwNTBh3EFw3_Kyv^gbY*O5SaMw zLK72Q`E1j27NcKH0mzS#5!q4#$E`%OgwHsEqKU`ZYRBU;>3V!2}b7g^l}U>KoIZk z+vOTMdyZx7c@Bi@4 z_N)HiZV^9C?oaVBRiZol{ zxZa(MbORj9SDYdWtQ!0TxIlLhkt6ngUfvdR1hi*jpJxnUbbzpsT0l=vI#^d2NhqWZ z)+Z#{laNxBg_p#lf)cVz*#d7g0nJpXdbHYoa>vLu!eBAhe*-E)$oq|&lFxG0g^sv; zjuGhieu-B}?yV4C9|Z@+fO`r2sl?jFAQ+OlH5XysvB9yJdZGg4A!EfFb?$mGH1r$G z1A>XlvTKO0L=0ww2HeBc_S`Z0O(-G;>7}3fh%ce-8<)diwD=*x-6-NMrK7M3g@-mS{G8QBMe&lEC zzG+0WGiZ$*-F2MhBRzrL-B9F3S2i}c5-3q_|L(_vOO2x0H3e+Sq7CWUZ$8n};q3>| z-> zlRlYzoNWgm9unE9O4&rcBm@4O=Lvc>dG!)ez#_W2?+&Z=WDHkGAWAokrE~($4;SnA z4=@xAsJjA9!u&q%TW-o4l`jj?AmX@8C1CP-M~3>SykWt5I_GQ{)sUqNdY{qQP`Bc# zf1F4nzZQ1B9M1LST!6q+{${!7+1CWnK#H<3v>@0_7(3Zb>i7PCDg|2*H&1 z7#P;B`C-q=Y(|S+5F|QUDU!32$1u20KW56tNGbYLU&!p`d?Z`}ny%V;mfHKsc1eep zs+4@if{73G1&?FiRc!#Kv{#UB8I4 zM97v7_N?qROenwgO=CeF$+kK3t^wZe_QxqI7HWemOhh!wxRxy~$uYH`!1*HDxH>gxm5i(cN)miQAR`x# zV*d09EH#i3XIILO>f^c8rc@ZA)Gcg<^;qa5VpV1rDz0`g(QPV#xMN2He}-{r#_}0h zH9!ELd~pI6BI}-t(qlDMlJx1{wriGDO1A}3wEWnX5~^Xt0VgSM>OhjJiKkni6jTsa zI_Zkv7{lVBvoe8{Vdp329;o=yQXRXtuH@*ChOuiviPH2!fYax;W8|lm$oiIC%%?f` zy$?E(W)`|iz9ea(U8xqfe;tNNQ(myEMB&%zu}6{xpp3#OyzTY$kX#leUfZFKSl$Ij ze2uvPdXJMqgHNvBd6VOTbeI5IiS{6l-ADnZ!5UF6W{_s@i%a()sB%x+6Q?Cnwg{?3 z5->0xFinH3-+=_QmDS;L1M)%0Y%3?Mm-8eDo{g2@R9Dke`KCKC*V-Ef$x*I zzpIv|t#YX8t)b+~hs#04V(@8J|9O6MoI3RGaAh@TalR3yMrF~{09K}s9fK6hagJb$wi=OSc9_N%wFMOqcKGO8Fb~cRfAFwtMH|kMi6`iTQE>{O zF_XaOoypX^UN~tDI==8q*J{WhWVTOcZ-7{-z@+RPe#}<)evO-bXG;v0!K|$}J~9dM zTFy0l2KiEIR#+h0P#}7pYYi>cbKsck1;}qTrxhN<*&5GKY| za1BvFg?qawe=(_4ee~$s3^Yx`_@z4J-oU78JAv3-cUZC#O$yGm=pTlNq-3lOdpb1d zR9f^+9RnL-Cqd0F;pB?|2oXC_0dB#@L!YbQ6JhG^0hbmh7z#Ca2CnYtBd~zd)9bD$ zN7Qir)HAdXOv#IxNY|>~Xu?&sN!a#l`Q1ce<~;Fg^eGNh-8w_h4+X}-g!sJ z9?+6VYeQ91n$HUOsMg4^R$029)qMjIhjN$y1Si4+QH8v7Yq)8`5boq!$E$;lxGw^t z)$PWK(=HIWN>au2@^Ol*1vb^Hxb#)Lc+x4=?D0%g{7pff2t3L4-i8kkr}pjcrS8mT z+d6K+f5&Q<`+jh~9_^w(%t0|lNgS>>yRp5n4Kq!3J6>J=UZRN0k;Eg*OwHNTM;G0m z)sVc|)%jVzP=RxZ;pS_rPiR&VVLe9F+BAXr`OG$}^s{#50~6row8+K~;EPKN>FlsD z!9-#U0=+S%9lM=kV1qo0gdCVwVk8^;Nd?pOe;HK1+Z@i@=bzJHJTE4MiUhH<)eY;{ z>kT;-hn()L#}#S~HG=BOo>Vo!l49jn$_jUvEJmRX`-SnoQ$1y4Bb6oJxM{z+skd9B z;HIoTQOMD;!r5UI0;BS%8w{jy#zwq1^%=5>ZesfA@XH!VMNQ~wh;0VH~T=cWWO{grkS z4hg(#liuq=>t-OlGMg8eMe~A)K%e{ldglchf8r)7{C953kK!vg;l!dm@^9R<>m1a4 z=cbSQ6E{Ix;Qhi){%~#c$#$-M1n4(ze>!e%8mn0_PnLRx&}vI&*+pS>*^o6exDpjW z4V;&aRiz*Ly8Nc2yt;<$V{vYZ0Q7IT$@ztw=B@B!0|2IiSxr)!in=@AI?jHUsmgPe za@gcht!peo5@cvwHD_>sSRO`1#hSt@mRH#g*+&5a#%GTJEmTg2tondZn&Tg6Obfs}kiw0&U?KtzZMh`x*km9IZEz z>GZ+779mq#bEJQ|gt^B(1-|ik^~`rjH>gAFvUU3AM_eFo3(Q#6Du zk5W{C6*rFV)D+xYxHjj49^PofdjgxX`j(-7rNaGPkJQ#aj{y2`GK`Q+E`9-VG}@Q@ z_U+6f@93;70_Z+cPc85ZfQLNr*7>xqPs^bW;S~PGE)>?nMpaK+kQ+WBe{2*L1Xeb4 z>ul2m{6N68t){CPdhhU0ysl7^oR}02bx;&}4%uh^YZbYiYF5lw*@0u7hkI%#YdMbW zb%NUDmOHh*>FyGp1&lEQJ6LR#UoU(}v~9i$m)g?|xhb*`S9403=;~beX1e#AayQc4 zWv~c$Oy>D(dFT=9VuJCpf0#Wx!Vk*FI*CKv7JdLGX+X{Ah3p_$CeQm z6R-tZG9^DcigKI^oEUq@?#VaS;3`McCsv!3%*-mn^_&$z)4UvNj*J2Nabp6dh3`*`gd7u4YMHdT?Zz z&O;9a469-seRLgcJ%|eHIvReGmQ7PU9{K>RP-h7CgdXjv(c(#yzKojLt~&NN`tm9Q zD<8`P#Vyq!LCiQxfAdOAlndkp3Y>}7G`XS`3o@UDlsoFH5N`h&BuzsvU6=VnG%cK^ zG$3A;hVp4a&j#6QT?_6NYnfj{CvRu*bTJ!zgY2r1Pa^J%ZX?H%$iX*YD@!TiIi<)E z0Swk_#Ys|u;Zs#NZKc+(nz&aGWfb;}y?*}R>hJ&Sf6QP1fATkf&R<{k-{Y@Nhc{Gs z-aJ`Ecfk+IyWJDdd{J4OARPZfN$2C#pV(+8r{P1#@*KDm;X6ru;DwA)(hE89Maa^d zk<(lfs^_*_D8qjoD*($^dB`uV35Sl*3Z$$lV=o$ zv$nkhqe^#ke@X_aGh=9d74B-TqCh6nWystBGuc`&xOoS^U)X)RKiO~>e7mQTNPf;R zw|BFa%_p|zRwk0mNax}kM$uQeY!==YJoJhzTrYUchEHiys8&WmIZ0|Zy9l;AeduEr zF^{&?W-f`oYkCpBTNjv*Cr(n&#CHbjO^nr1Jkz{+f1jkm?PO=pE%f$Mi5f{1Ney75 zvw;Wwf(JnT+Wdq->L=l5JzOa04D4LjCBg2O;cgLO?z>pn^pp#1xQgn_bFR-j%!+W? zao8(aw}Z~Q9WXD4iJk&>MOOC=y|ye-a*`fo0UIq5Jn}q#L}h9v6CFv-@+d-I;CJ`T z!|va;4SBBrVH~iA(OPfN==LBb{0Ss6O}pc9{9;FCk4Az;la2icKfEuvZB} zl!Tpn+=QtY>mBmMJ)PTL_|=WU(%2{mBlj6WYhd#~h~GnIkKY?g(I>8I72noHp_R)} z0*^J06=~=}q+Rba19sk>@d6xMI>sla8m2*ce>FIA2--R0la?9=D(Omq@U$HQp@k)N z0F=uR$gGvjC-k6*dMY%>q1M~efYT+J;}gWuhj!LhXv?u&@M`F+*$rBZJC3KwR-99q z=XpH62k-hpv!H{B`;c|MD}==P>^&h0?r^xh79@d(uKTVJWYrEO&&Z@%Gy>TkR|q94 zf1R!vxF{*006}@3lePM9On4)~qR(?7a22?hI^!FPiMg}E(V8?PPyU%C(t$pK`02Wv zQr+l+`Nx*`?(s3&PS7G^7Bh`WvxPLdwRsd?mJe+yFlS-FwD`6DM9wn!0Ly^HVvJr6 zi>%x-NE{&3_Fae2rRb8xS#HETpJ_~Q8B$SZ*R9p{#iQGe+Wbd znnO2%0k}mwjw)gzy4ExoHtX`=mX#YJPsvM!uuF@6cGI57tVfsU;Y+QYJ&g|+K0q;t zEO*>SuAqS$k6aDla1E8-xYw;x@93i)=|y&xaFmqYqsVwztzZj6AVEdS8f5+oIx60YDY3ZAUpe>@H%Ldz^Ktkr!F$Y*ju0@I$ zU&5(qKm`lL9A0T}=CPiIOo;vM)yg!EpgHscDMZ>EF%Y!@_*Cwgc^OH+MQoo40psKr?x+ojnmx;i( zMB`7WdL-l{4}HmaVQ*{W%(ypADqeU*s-K`|($9%rP_n4`gdbNaH4q$+8m}4&x3_4t zj2K*fCV*^~nhwNx66RMzcnfeC9@t5YHRsArZhRXKF#-@84*Jt4M3hJ#jz$4l&~a!ohn6Ww7H_A#k{!|l zNvd&P#N`oH9Iv3kcg`DY8xbHs zPhbD<>V%TmHM#<1YN=pI81XglLh7>I-K$IrihLx>-1Xxve`=h{D``_B0{{y?NTv?H zkFueGWuqVV10`U1qd?w*?Z-u8T))ymo$eb09;QfnrzBcW8sGZhS;Qv6Zy!iau*#cM z1~3KBJc{;{bs?Hm9RxuhhL(?~m4fCtC*m&9s|t^BlAJV5Ua(S7CwZg9WY3l?hUfTl z8HxeZrdd06f2j`|JD9+c;JYv?$b$w2dYdfV(OF=fs4J=`n|8L-Fs;d=B(F#$NDUY$ ze-))eob;#3oCeNX6TE3R7t9T7!h4@wQlkcRTB(nX(%Q!gt(A&;@>GNZLS$^5?yaIe z&nZ%1a4ggd#B;uT$Ywh9_{nvxtmaV(AF3&Hsu^5%rPs3()+_p-@Gzn6pu<+Y^r6CkKCsXO*JgB@t)fcvcu1KT=&qMBSe+_v>?>x3n)wpHB^p~LsL?dO~AblZNS68UD^<28F(Z`l{`657mDnLE4p zQxX8df1gYR(nR3p^kziKFI=(y4FCZD|E-ou4&+R+fcyUiPw*CqGq3`A;dw}Q<*DrQ zJeKX9$MQUsXP@95h4XO&s+<0yK}c*~Na1j#zsRsc%8V%G_f`4qWtPHpRT*~`tjg-te>UUcNg5>N^i*&UD#980M7mBuihfX1 zyz@x!K<@A+Jl9RrcT4M45bB3vRKdbHeuig2nPCbd_eK^)v8H=~Hr^WCD3eO3 zKcr!Z-z_aoI6FaLNzg?<~#&`YZG95y>Z)Ax7Da`vl_pn-<`bFNFME@-iH;LoqXolUtUQxedrtfP?Ge^1&a z0SXAJ2*top_B4_>5`9ke;$`p^CP`^@{6XveiX|xJ2NuJ>5t_!4H$6GrB?6Of0>>~! zrj@DG&pknds%?J0%Gi~u`eDvlwB(8u7OQtsb=9RJZZaLBR2-E9!VpDe_+I`SU8jC zDD{};RcwkRF^Q)ciwt=9XMYI#*6aC7z4%=PzL)KK@`9T5=tv63FlD#&`T}umZs+?<{8&`nQ`IT;@zQmP`83TdWEi_`n)v5y8;-@4hO>@9l@C+Yl>>K zN3e!mbRoS>F!g;(5Gr*ne5ovzxcW3!Hu?q}~fz2QDNfjVUS7e>_G~F zNtEv#1#Hh1LODSwDp#t$Qf}EY$2&`ouzwXmVV+*k%}qY49hId4*3)iNREvzuW{j_) z8`kCpL5GV^8(|)gfAFzR1slYJUP5f50lwA%jY#!dub^!&j^%j*hbGbJ>5+aRvQp+(S(1{Sn zW(jj0uf%YvqqKeJz{@%9Rxnzd#tn=XvUa^_yuWIa)D@!10S3Q5YefYzmI)4L-OLBE}0v5M$3dZ+(xr- zBYGu>1o|b7mrH{*4^_b#FL$R=>fIA9(We^ z;=R`ZcxK09fGS6j%a02g4+;Owg|@hj;Vak@r+*WpVS?y-S3Ftr?@j4F?8J5KA>Y?C zVS3HnJp|5;A{uH%I>s)N+)BBw5zbYt)rTGn<1%=_m(HjTwOtdgGL2HGg&ZAvp6W|2 ztmF{3e-T9=BmOx^cFiDU^J$8Qgqu^guxM=yVimkCpFaY+%=;n zodr=d_@%}sR5Z`jHJP{Zdam5HU#qj~yf(6&+1H zP%gzN-1$b(=VPoU=@kSg*dr2t?1#+rGSI9Yf8MNHD6q45b(f$o*$&s;E#uUfof%NU z`}0J*ZC95!QM@L6?We~=9}9oaHF5j2*x1EifihFToE?gl<|X4`r?-N|q;Ke@E+}oD z)|PBjVQW~t+{Bzrp)Rj0YVq0)lBi_aGntRl2UC(Qa+A*1^B`1NJSk21SXn8`Vix9} ze_-uvC@#ZiM1CZB*_rU*U9|g4oS_>Szjk6sSvrX^I?6a56TS!hElKaXKBCq&m`bI= zCdarvNlrlW3e2D1Y8gDobRLe-x|AE<3LKw^#)j*z9%dcX0Ria~s2)GXj8XGl+{w^q zKn|A}b9YI_47T@Zj;6p`fr_jbip4cvf1r82s=Jy)zI6tL+et#wAg16%PX|Sa-Z#kT zbCow}K6uY2a4&%J$T$W_(3O=MyAqCMN8T2>V3i6pON6nzK(PZL?w@lEPa%~V5|HqW zfLz)r5n~YX0W?la!^*C;$m#bi#U{6NOPA2fyP!P$RDwS>dNX%unt&22yn6#0fA6~i zS0kp|f!KL6mSnOUb7?8KRnPKeu<+<8MJc3_IfY(6@H->CU@76volO-9M;o=YpfxH} z_l}-)eWM<^%%N5hF_S>c(Xo!oEQJ{<)8E7Nl*VaFaG>}?U(hhJo5wp^M9Bxzx>NSzxscV|GyvN tfBPTegCF>xzx!W)lC@vrrT>!u$9!M&|N6WC)oPsK{Ibti`5Rp(ZXQ85HIM)R diff --git a/matlab/scripts/Inertial Nav EKF/C_code24.txt b/matlab/scripts/Inertial Nav EKF/C_code24.txt index 6572c81d01..7c6f9d1b5f 100644 --- a/matlab/scripts/Inertial Nav EKF/C_code24.txt +++ b/matlab/scripts/Inertial Nav EKF/C_code24.txt @@ -1,217 +1,205 @@ -float SF[25][1]; -SF[0] = daz_b/2 + dazNoise/2 - (daz*daz_s)/2; -SF[1] = day_b/2 + dayNoise/2 - (day*day_s)/2; -SF[2] = dax_b/2 + daxNoise/2 - (dax*dax_s)/2; -SF[3] = q3/2 - (q0*SF[0])/2 + (q1*SF[1])/2 - (q2*SF[2])/2; -SF[4] = q0/2 - (q1*SF[2])/2 - (q2*SF[1])/2 + (q3*SF[0])/2; -SF[5] = q1/2 + (q0*SF[2])/2 - (q2*SF[0])/2 - (q3*SF[1])/2; -SF[6] = q3/2 + (q0*SF[0])/2 - (q1*SF[1])/2 - (q2*SF[2])/2; -SF[7] = q0/2 - (q1*SF[2])/2 + (q2*SF[1])/2 - (q3*SF[0])/2; -SF[8] = q0/2 + (q1*SF[2])/2 - (q2*SF[1])/2 - (q3*SF[0])/2; -SF[9] = q2/2 + (q0*SF[1])/2 + (q1*SF[0])/2 + (q3*SF[2])/2; -SF[10] = q2/2 - (q0*SF[1])/2 - (q1*SF[0])/2 + (q3*SF[2])/2; -SF[11] = q2/2 + (q0*SF[1])/2 - (q1*SF[0])/2 - (q3*SF[2])/2; -SF[12] = q1/2 + (q0*SF[2])/2 + (q2*SF[0])/2 + (q3*SF[1])/2; -SF[13] = q1/2 - (q0*SF[2])/2 + (q2*SF[0])/2 - (q3*SF[1])/2; -SF[14] = q3/2 + (q0*SF[0])/2 + (q1*SF[1])/2 + (q2*SF[2])/2; -SF[15] = - sq(q0) - sq(q1) - sq(q2) - sq(q3); -SF[16] = dvz_b - dvz + dvzNoise; -SF[17] = dvx - dvxNoise; -SF[18] = dvy - dvyNoise; -SF[19] = sq(q2); -SF[20] = SF[19] - sq(q0) + sq(q1) - sq(q3); -SF[21] = SF[19] + sq(q0) - sq(q1) - sq(q3); -SF[22] = 2*q0*q1 - 2*q2*q3; -SF[23] = SF[19] - sq(q0) - sq(q1) + sq(q3); -SF[24] = 2*q1*q2; -float SG[5][1]; -SG[0] = - sq(q0) - sq(q1) - sq(q2) - sq(q3); +float SF[21][1]; +SF[0] = dvz - dvz_b; +SF[1] = dvy - dvy_b; +SF[2] = dvx - dvx_b; +SF[3] = 2*q1*SF[2] + 2*q2*SF[1] + 2*q3*SF[0]; +SF[4] = 2*q0*SF[1] - 2*q1*SF[0] + 2*q3*SF[2]; +SF[5] = 2*q0*SF[2] + 2*q2*SF[0] - 2*q3*SF[1]; +SF[6] = day/2 - day_b/2; +SF[7] = daz/2 - daz_b/2; +SF[8] = dax/2 - dax_b/2; +SF[9] = dax_b/2 - dax/2; +SF[10] = daz_b/2 - daz/2; +SF[11] = day_b/2 - day/2; +SF[12] = 2*q1*SF[1]; +SF[13] = 2*q0*SF[0]; +SF[14] = q1/2; +SF[15] = q2/2; +SF[16] = q3/2; +SF[17] = sq(q3); +SF[18] = sq(q2); +SF[19] = sq(q1); +SF[20] = sq(q0); +float SG[8][1]; +SG[0] = q0/2; SG[1] = sq(q3); SG[2] = sq(q2); SG[3] = sq(q1); SG[4] = sq(q0); -float SQ[10][1]; -SQ[0] = - sq(dvyNoise)*(2*q0*q1 + 2*q2*q3)*(SG[1] - SG[2] + SG[3] - SG[4]) - sq(dvzNoise)*(2*q0*q1 - 2*q2*q3)*(SG[1] - SG[2] - SG[3] + SG[4]) - sq(dvxNoise)*(2*q0*q2 - 2*q1*q3)*(2*q0*q3 + 2*q1*q2); -SQ[1] = sq(dvxNoise)*(2*q0*q2 - 2*q1*q3)*(SG[1] + SG[2] - SG[3] - SG[4]) + sq(dvzNoise)*(2*q0*q2 + 2*q1*q3)*(SG[1] - SG[2] - SG[3] + SG[4]) - sq(dvyNoise)*(2*q0*q1 + 2*q2*q3)*(2*q0*q3 - 2*q1*q2); -SQ[2] = sq(dvyNoise)*(2*q0*q3 - 2*q1*q2)*(SG[1] - SG[2] + SG[3] - SG[4]) - sq(dvxNoise)*(2*q0*q3 + 2*q1*q2)*(SG[1] + SG[2] - SG[3] - SG[4]) - sq(dvzNoise)*(2*q0*q1 - 2*q2*q3)*(2*q0*q2 + 2*q1*q3); -SQ[3] = sq(SG[0]); -SQ[4] = sq(dvyNoise); -SQ[5] = sq(dvzNoise); -SQ[6] = sq(dvxNoise); -SQ[7] = 2*q2*q3; -SQ[8] = 2*q1*q3; -SQ[9] = 2*q1*q2; -float SPP[23][1]; -SPP[0] = SF[17]*(2*q0*q1 + 2*q2*q3) + SF[18]*(2*q0*q2 - 2*q1*q3); -SPP[1] = SF[18]*(2*q0*q2 + 2*q1*q3) + SF[16]*(SF[24] - 2*q0*q3); -SPP[2] = 2*q3*SF[8] + 2*q1*SF[11] - 2*q0*SF[14] - 2*q2*SF[13]; -SPP[3] = 2*q1*SF[7] + 2*q2*SF[6] - 2*q0*SF[12] - 2*q3*SF[10]; -SPP[4] = 2*q0*SF[6] - 2*q3*SF[7] - 2*q1*SF[10] + 2*q2*SF[12]; -SPP[5] = 2*q0*SF[8] + 2*q2*SF[11] + 2*q1*SF[13] + 2*q3*SF[14]; -SPP[6] = 2*q0*SF[7] + 2*q3*SF[6] + 2*q2*SF[10] + 2*q1*SF[12]; -SPP[7] = 2*q1*SF[3] - 2*q2*SF[4] - 2*q3*SF[5] + 2*q0*SF[9]; -SPP[8] = 2*q0*SF[5] - 2*q1*SF[4] - 2*q2*SF[3] + 2*q3*SF[9]; -SPP[9] = SF[18]*SF[20] - SF[16]*(2*q0*q1 + 2*q2*q3); -SPP[10] = SF[17]*SF[20] + SF[16]*(2*q0*q2 - 2*q1*q3); -SPP[11] = SF[17]*SF[21] - SF[18]*(SF[24] + 2*q0*q3); -SPP[12] = SF[17]*SF[22] - SF[16]*(SF[24] + 2*q0*q3); -SPP[13] = 2*q0*SF[4] + 2*q1*SF[5] + 2*q3*SF[3] + 2*q2*SF[9]; -SPP[14] = 2*q2*SF[8] - 2*q0*SF[11] - 2*q1*SF[14] + 2*q3*SF[13]; -SPP[15] = SF[18]*SF[23] + SF[17]*(SF[24] - 2*q0*q3); -SPP[16] = daz*SF[19] + daz*sq(q0) + daz*sq(q1) + daz*sq(q3); -SPP[17] = day*SF[19] + day*sq(q0) + day*sq(q1) + day*sq(q3); -SPP[18] = dax*SF[19] + dax*sq(q0) + dax*sq(q1) + dax*sq(q3); -SPP[19] = SF[16]*SF[23] - SF[17]*(2*q0*q2 + 2*q1*q3); -SPP[20] = SF[16]*SF[21] - SF[18]*SF[22]; -SPP[21] = 2*q0*q2 + 2*q1*q3; -SPP[22] = SF[15]; +SG[5] = 2*q2*q3; +SG[6] = 2*q1*q3; +SG[7] = 2*q1*q2; +float SQ[11][1]; +SQ[0] = dvzVar*(SG[5] - 2*q0*q1)*(SG[1] - SG[2] - SG[3] + SG[4]) - dvyVar*(SG[5] + 2*q0*q1)*(SG[1] - SG[2] + SG[3] - SG[4]) + dvxVar*(SG[6] - 2*q0*q2)*(SG[7] + 2*q0*q3); +SQ[1] = dvzVar*(SG[6] + 2*q0*q2)*(SG[1] - SG[2] - SG[3] + SG[4]) - dvxVar*(SG[6] - 2*q0*q2)*(SG[1] + SG[2] - SG[3] - SG[4]) + dvyVar*(SG[5] + 2*q0*q1)*(SG[7] - 2*q0*q3); +SQ[2] = dvzVar*(SG[5] - 2*q0*q1)*(SG[6] + 2*q0*q2) - dvyVar*(SG[7] - 2*q0*q3)*(SG[1] - SG[2] + SG[3] - SG[4]) - dvxVar*(SG[7] + 2*q0*q3)*(SG[1] + SG[2] - SG[3] - SG[4]); +SQ[3] = (dayVar*q1*SG[0])/2 - (dazVar*q1*SG[0])/2 - (daxVar*q2*q3)/4; +SQ[4] = (dazVar*q2*SG[0])/2 - (daxVar*q2*SG[0])/2 - (dayVar*q1*q3)/4; +SQ[5] = (daxVar*q3*SG[0])/2 - (dayVar*q3*SG[0])/2 - (dazVar*q1*q2)/4; +SQ[6] = (daxVar*q1*q2)/4 - (dazVar*q3*SG[0])/2 - (dayVar*q1*q2)/4; +SQ[7] = (dazVar*q1*q3)/4 - (daxVar*q1*q3)/4 - (dayVar*q2*SG[0])/2; +SQ[8] = (dayVar*q2*q3)/4 - (daxVar*q1*SG[0])/2 - (dazVar*q2*q3)/4; +SQ[9] = sq(SG[0]); +SQ[10] = sq(q1); +float SPP[11][1]; +SPP[0] = SF[12] + SF[13] - 2*q2*SF[2]; +SPP[1] = SF[17] - SF[18] - SF[19] + SF[20]; +SPP[2] = SF[17] - SF[18] + SF[19] - SF[20]; +SPP[3] = SF[17] + SF[18] - SF[19] - SF[20]; +SPP[4] = 2*q0*q2 - 2*q1*q3; +SPP[5] = 2*q0*q1 - 2*q2*q3; +SPP[6] = 2*q0*q3 - 2*q1*q2; +SPP[7] = 2*q0*q1 + 2*q2*q3; +SPP[8] = 2*q0*q3 + 2*q1*q2; +SPP[9] = 2*q0*q2 + 2*q1*q3; +SPP[10] = SF[16]; float nextP[24][24]; -nextP[0][0] = SPP[5]*(P[0][0]*SPP[5] - P[1][0]*SPP[4] + P[2][0]*SPP[7] + P[9][0]*SPP[22] + P[12][0]*SPP[18]) - SPP[4]*(P[0][1]*SPP[5] - P[1][1]*SPP[4] + P[2][1]*SPP[7] + P[9][1]*SPP[22] + P[12][1]*SPP[18]) + SPP[7]*(P[0][2]*SPP[5] - P[1][2]*SPP[4] + P[2][2]*SPP[7] + P[9][2]*SPP[22] + P[12][2]*SPP[18]) + SPP[22]*(P[0][9]*SPP[5] - P[1][9]*SPP[4] + P[2][9]*SPP[7] + P[9][9]*SPP[22] + P[12][9]*SPP[18]) + SPP[18]*(P[0][12]*SPP[5] - P[1][12]*SPP[4] + P[2][12]*SPP[7] + P[9][12]*SPP[22] + P[12][12]*SPP[18]) + sq(daxNoise)*SQ[3]; -nextP[0][1] = SPP[6]*(P[0][1]*SPP[5] - P[1][1]*SPP[4] + P[2][1]*SPP[7] + P[9][1]*SPP[22] + P[12][1]*SPP[18]) - SPP[2]*(P[0][0]*SPP[5] - P[1][0]*SPP[4] + P[2][0]*SPP[7] + P[9][0]*SPP[22] + P[12][0]*SPP[18]) - SPP[8]*(P[0][2]*SPP[5] - P[1][2]*SPP[4] + P[2][2]*SPP[7] + P[9][2]*SPP[22] + P[12][2]*SPP[18]) + SPP[22]*(P[0][10]*SPP[5] - P[1][10]*SPP[4] + P[2][10]*SPP[7] + P[9][10]*SPP[22] + P[12][10]*SPP[18]) + SPP[17]*(P[0][13]*SPP[5] - P[1][13]*SPP[4] + P[2][13]*SPP[7] + P[9][13]*SPP[22] + P[12][13]*SPP[18]); -nextP[1][1] = SPP[6]*(P[1][1]*SPP[6] - P[0][1]*SPP[2] - P[2][1]*SPP[8] + P[10][1]*SPP[22] + P[13][1]*SPP[17]) - SPP[2]*(P[1][0]*SPP[6] - P[0][0]*SPP[2] - P[2][0]*SPP[8] + P[10][0]*SPP[22] + P[13][0]*SPP[17]) - SPP[8]*(P[1][2]*SPP[6] - P[0][2]*SPP[2] - P[2][2]*SPP[8] + P[10][2]*SPP[22] + P[13][2]*SPP[17]) + SPP[22]*(P[1][10]*SPP[6] - P[0][10]*SPP[2] - P[2][10]*SPP[8] + P[10][10]*SPP[22] + P[13][10]*SPP[17]) + SPP[17]*(P[1][13]*SPP[6] - P[0][13]*SPP[2] - P[2][13]*SPP[8] + P[10][13]*SPP[22] + P[13][13]*SPP[17]) + sq(dayNoise)*SQ[3]; -nextP[0][2] = SPP[14]*(P[0][0]*SPP[5] - P[1][0]*SPP[4] + P[2][0]*SPP[7] + P[9][0]*SPP[22] + P[12][0]*SPP[18]) - SPP[3]*(P[0][1]*SPP[5] - P[1][1]*SPP[4] + P[2][1]*SPP[7] + P[9][1]*SPP[22] + P[12][1]*SPP[18]) + SPP[13]*(P[0][2]*SPP[5] - P[1][2]*SPP[4] + P[2][2]*SPP[7] + P[9][2]*SPP[22] + P[12][2]*SPP[18]) + SPP[22]*(P[0][11]*SPP[5] - P[1][11]*SPP[4] + P[2][11]*SPP[7] + P[9][11]*SPP[22] + P[12][11]*SPP[18]) + SPP[16]*(P[0][14]*SPP[5] - P[1][14]*SPP[4] + P[2][14]*SPP[7] + P[9][14]*SPP[22] + P[12][14]*SPP[18]); -nextP[1][2] = SPP[14]*(P[1][0]*SPP[6] - P[0][0]*SPP[2] - P[2][0]*SPP[8] + P[10][0]*SPP[22] + P[13][0]*SPP[17]) - SPP[3]*(P[1][1]*SPP[6] - P[0][1]*SPP[2] - P[2][1]*SPP[8] + P[10][1]*SPP[22] + P[13][1]*SPP[17]) + SPP[13]*(P[1][2]*SPP[6] - P[0][2]*SPP[2] - P[2][2]*SPP[8] + P[10][2]*SPP[22] + P[13][2]*SPP[17]) + SPP[22]*(P[1][11]*SPP[6] - P[0][11]*SPP[2] - P[2][11]*SPP[8] + P[10][11]*SPP[22] + P[13][11]*SPP[17]) + SPP[16]*(P[1][14]*SPP[6] - P[0][14]*SPP[2] - P[2][14]*SPP[8] + P[10][14]*SPP[22] + P[13][14]*SPP[17]); -nextP[2][2] = SPP[14]*(P[0][0]*SPP[14] - P[1][0]*SPP[3] + P[2][0]*SPP[13] + P[11][0]*SPP[22] + P[14][0]*SPP[16]) - SPP[3]*(P[0][1]*SPP[14] - P[1][1]*SPP[3] + P[2][1]*SPP[13] + P[11][1]*SPP[22] + P[14][1]*SPP[16]) + SPP[13]*(P[0][2]*SPP[14] - P[1][2]*SPP[3] + P[2][2]*SPP[13] + P[11][2]*SPP[22] + P[14][2]*SPP[16]) + SPP[22]*(P[0][11]*SPP[14] - P[1][11]*SPP[3] + P[2][11]*SPP[13] + P[11][11]*SPP[22] + P[14][11]*SPP[16]) + SPP[16]*(P[0][14]*SPP[14] - P[1][14]*SPP[3] + P[2][14]*SPP[13] + P[11][14]*SPP[22] + P[14][14]*SPP[16]) + sq(dazNoise)*SQ[3]; -nextP[0][3] = P[0][3]*SPP[5] - P[1][3]*SPP[4] + P[2][3]*SPP[7] + P[9][3]*SPP[22] + P[12][3]*SPP[18] + SPP[1]*(P[0][0]*SPP[5] - P[1][0]*SPP[4] + P[2][0]*SPP[7] + P[9][0]*SPP[22] + P[12][0]*SPP[18]) + SPP[19]*(P[0][1]*SPP[5] - P[1][1]*SPP[4] + P[2][1]*SPP[7] + P[9][1]*SPP[22] + P[12][1]*SPP[18]) + SPP[15]*(P[0][2]*SPP[5] - P[1][2]*SPP[4] + P[2][2]*SPP[7] + P[9][2]*SPP[22] + P[12][2]*SPP[18]) - SPP[21]*(P[0][15]*SPP[5] - P[1][15]*SPP[4] + P[2][15]*SPP[7] + P[9][15]*SPP[22] + P[12][15]*SPP[18]); -nextP[1][3] = P[1][3]*SPP[6] - P[0][3]*SPP[2] - P[2][3]*SPP[8] + P[10][3]*SPP[22] + P[13][3]*SPP[17] + SPP[1]*(P[1][0]*SPP[6] - P[0][0]*SPP[2] - P[2][0]*SPP[8] + P[10][0]*SPP[22] + P[13][0]*SPP[17]) + SPP[19]*(P[1][1]*SPP[6] - P[0][1]*SPP[2] - P[2][1]*SPP[8] + P[10][1]*SPP[22] + P[13][1]*SPP[17]) + SPP[15]*(P[1][2]*SPP[6] - P[0][2]*SPP[2] - P[2][2]*SPP[8] + P[10][2]*SPP[22] + P[13][2]*SPP[17]) - SPP[21]*(P[1][15]*SPP[6] - P[0][15]*SPP[2] - P[2][15]*SPP[8] + P[10][15]*SPP[22] + P[13][15]*SPP[17]); -nextP[2][3] = P[0][3]*SPP[14] - P[1][3]*SPP[3] + P[2][3]*SPP[13] + P[11][3]*SPP[22] + P[14][3]*SPP[16] + SPP[1]*(P[0][0]*SPP[14] - P[1][0]*SPP[3] + P[2][0]*SPP[13] + P[11][0]*SPP[22] + P[14][0]*SPP[16]) + SPP[19]*(P[0][1]*SPP[14] - P[1][1]*SPP[3] + P[2][1]*SPP[13] + P[11][1]*SPP[22] + P[14][1]*SPP[16]) + SPP[15]*(P[0][2]*SPP[14] - P[1][2]*SPP[3] + P[2][2]*SPP[13] + P[11][2]*SPP[22] + P[14][2]*SPP[16]) - SPP[21]*(P[0][15]*SPP[14] - P[1][15]*SPP[3] + P[2][15]*SPP[13] + P[11][15]*SPP[22] + P[14][15]*SPP[16]); -nextP[3][3] = P[3][3] + P[0][3]*SPP[1] + P[1][3]*SPP[19] + P[2][3]*SPP[15] - P[15][3]*SPP[21] + SQ[5]*sq(SQ[8] + 2*q0*q2) + SQ[4]*sq(SQ[9] - 2*q0*q3) + SPP[1]*(P[3][0] + P[0][0]*SPP[1] + P[1][0]*SPP[19] + P[2][0]*SPP[15] - P[15][0]*SPP[21]) + SPP[19]*(P[3][1] + P[0][1]*SPP[1] + P[1][1]*SPP[19] + P[2][1]*SPP[15] - P[15][1]*SPP[21]) + SPP[15]*(P[3][2] + P[0][2]*SPP[1] + P[1][2]*SPP[19] + P[2][2]*SPP[15] - P[15][2]*SPP[21]) - SPP[21]*(P[3][15] + P[0][15]*SPP[1] + P[1][15]*SPP[19] + P[2][15]*SPP[15] - P[15][15]*SPP[21]) + SQ[6]*sq(SG[1] + SG[2] - SG[3] - SG[4]); -nextP[0][4] = P[0][4]*SPP[5] - P[1][4]*SPP[4] + P[2][4]*SPP[7] + P[9][4]*SPP[22] + P[12][4]*SPP[18] + SF[22]*(P[0][15]*SPP[5] - P[1][15]*SPP[4] + P[2][15]*SPP[7] + P[9][15]*SPP[22] + P[12][15]*SPP[18]) + SPP[12]*(P[0][1]*SPP[5] - P[1][1]*SPP[4] + P[2][1]*SPP[7] + P[9][1]*SPP[22] + P[12][1]*SPP[18]) + SPP[20]*(P[0][0]*SPP[5] - P[1][0]*SPP[4] + P[2][0]*SPP[7] + P[9][0]*SPP[22] + P[12][0]*SPP[18]) + SPP[11]*(P[0][2]*SPP[5] - P[1][2]*SPP[4] + P[2][2]*SPP[7] + P[9][2]*SPP[22] + P[12][2]*SPP[18]); -nextP[1][4] = P[1][4]*SPP[6] - P[0][4]*SPP[2] - P[2][4]*SPP[8] + P[10][4]*SPP[22] + P[13][4]*SPP[17] + SF[22]*(P[1][15]*SPP[6] - P[0][15]*SPP[2] - P[2][15]*SPP[8] + P[10][15]*SPP[22] + P[13][15]*SPP[17]) + SPP[12]*(P[1][1]*SPP[6] - P[0][1]*SPP[2] - P[2][1]*SPP[8] + P[10][1]*SPP[22] + P[13][1]*SPP[17]) + SPP[20]*(P[1][0]*SPP[6] - P[0][0]*SPP[2] - P[2][0]*SPP[8] + P[10][0]*SPP[22] + P[13][0]*SPP[17]) + SPP[11]*(P[1][2]*SPP[6] - P[0][2]*SPP[2] - P[2][2]*SPP[8] + P[10][2]*SPP[22] + P[13][2]*SPP[17]); -nextP[2][4] = P[0][4]*SPP[14] - P[1][4]*SPP[3] + P[2][4]*SPP[13] + P[11][4]*SPP[22] + P[14][4]*SPP[16] + SF[22]*(P[0][15]*SPP[14] - P[1][15]*SPP[3] + P[2][15]*SPP[13] + P[11][15]*SPP[22] + P[14][15]*SPP[16]) + SPP[12]*(P[0][1]*SPP[14] - P[1][1]*SPP[3] + P[2][1]*SPP[13] + P[11][1]*SPP[22] + P[14][1]*SPP[16]) + SPP[20]*(P[0][0]*SPP[14] - P[1][0]*SPP[3] + P[2][0]*SPP[13] + P[11][0]*SPP[22] + P[14][0]*SPP[16]) + SPP[11]*(P[0][2]*SPP[14] - P[1][2]*SPP[3] + P[2][2]*SPP[13] + P[11][2]*SPP[22] + P[14][2]*SPP[16]); -nextP[3][4] = P[3][4] + SQ[2] + P[0][4]*SPP[1] + P[1][4]*SPP[19] + P[2][4]*SPP[15] - P[15][4]*SPP[21] + SF[22]*(P[3][15] + P[0][15]*SPP[1] + P[1][15]*SPP[19] + P[2][15]*SPP[15] - P[15][15]*SPP[21]) + SPP[12]*(P[3][1] + P[0][1]*SPP[1] + P[1][1]*SPP[19] + P[2][1]*SPP[15] - P[15][1]*SPP[21]) + SPP[20]*(P[3][0] + P[0][0]*SPP[1] + P[1][0]*SPP[19] + P[2][0]*SPP[15] - P[15][0]*SPP[21]) + SPP[11]*(P[3][2] + P[0][2]*SPP[1] + P[1][2]*SPP[19] + P[2][2]*SPP[15] - P[15][2]*SPP[21]); -nextP[4][4] = P[4][4] + P[15][4]*SF[22] + P[0][4]*SPP[20] + P[1][4]*SPP[12] + P[2][4]*SPP[11] + SQ[5]*sq(SQ[7] - 2*q0*q1) + SQ[6]*sq(SQ[9] + 2*q0*q3) + SF[22]*(P[4][15] + P[15][15]*SF[22] + P[0][15]*SPP[20] + P[1][15]*SPP[12] + P[2][15]*SPP[11]) + SPP[12]*(P[4][1] + P[15][1]*SF[22] + P[0][1]*SPP[20] + P[1][1]*SPP[12] + P[2][1]*SPP[11]) + SPP[20]*(P[4][0] + P[15][0]*SF[22] + P[0][0]*SPP[20] + P[1][0]*SPP[12] + P[2][0]*SPP[11]) + SPP[11]*(P[4][2] + P[15][2]*SF[22] + P[0][2]*SPP[20] + P[1][2]*SPP[12] + P[2][2]*SPP[11]) + SQ[4]*sq(SG[1] - SG[2] + SG[3] - SG[4]); -nextP[0][5] = P[0][5]*SPP[5] - P[1][5]*SPP[4] + P[2][5]*SPP[7] + P[9][5]*SPP[22] + P[12][5]*SPP[18] + SF[20]*(P[0][15]*SPP[5] - P[1][15]*SPP[4] + P[2][15]*SPP[7] + P[9][15]*SPP[22] + P[12][15]*SPP[18]) - SPP[9]*(P[0][0]*SPP[5] - P[1][0]*SPP[4] + P[2][0]*SPP[7] + P[9][0]*SPP[22] + P[12][0]*SPP[18]) + SPP[0]*(P[0][2]*SPP[5] - P[1][2]*SPP[4] + P[2][2]*SPP[7] + P[9][2]*SPP[22] + P[12][2]*SPP[18]) + SPP[10]*(P[0][1]*SPP[5] - P[1][1]*SPP[4] + P[2][1]*SPP[7] + P[9][1]*SPP[22] + P[12][1]*SPP[18]); -nextP[1][5] = P[1][5]*SPP[6] - P[0][5]*SPP[2] - P[2][5]*SPP[8] + P[10][5]*SPP[22] + P[13][5]*SPP[17] + SF[20]*(P[1][15]*SPP[6] - P[0][15]*SPP[2] - P[2][15]*SPP[8] + P[10][15]*SPP[22] + P[13][15]*SPP[17]) - SPP[9]*(P[1][0]*SPP[6] - P[0][0]*SPP[2] - P[2][0]*SPP[8] + P[10][0]*SPP[22] + P[13][0]*SPP[17]) + SPP[0]*(P[1][2]*SPP[6] - P[0][2]*SPP[2] - P[2][2]*SPP[8] + P[10][2]*SPP[22] + P[13][2]*SPP[17]) + SPP[10]*(P[1][1]*SPP[6] - P[0][1]*SPP[2] - P[2][1]*SPP[8] + P[10][1]*SPP[22] + P[13][1]*SPP[17]); -nextP[2][5] = P[0][5]*SPP[14] - P[1][5]*SPP[3] + P[2][5]*SPP[13] + P[11][5]*SPP[22] + P[14][5]*SPP[16] + SF[20]*(P[0][15]*SPP[14] - P[1][15]*SPP[3] + P[2][15]*SPP[13] + P[11][15]*SPP[22] + P[14][15]*SPP[16]) - SPP[9]*(P[0][0]*SPP[14] - P[1][0]*SPP[3] + P[2][0]*SPP[13] + P[11][0]*SPP[22] + P[14][0]*SPP[16]) + SPP[0]*(P[0][2]*SPP[14] - P[1][2]*SPP[3] + P[2][2]*SPP[13] + P[11][2]*SPP[22] + P[14][2]*SPP[16]) + SPP[10]*(P[0][1]*SPP[14] - P[1][1]*SPP[3] + P[2][1]*SPP[13] + P[11][1]*SPP[22] + P[14][1]*SPP[16]); -nextP[3][5] = P[3][5] + SQ[1] + P[0][5]*SPP[1] + P[1][5]*SPP[19] + P[2][5]*SPP[15] - P[15][5]*SPP[21] + SF[20]*(P[3][15] + P[0][15]*SPP[1] + P[1][15]*SPP[19] + P[2][15]*SPP[15] - P[15][15]*SPP[21]) - SPP[9]*(P[3][0] + P[0][0]*SPP[1] + P[1][0]*SPP[19] + P[2][0]*SPP[15] - P[15][0]*SPP[21]) + SPP[0]*(P[3][2] + P[0][2]*SPP[1] + P[1][2]*SPP[19] + P[2][2]*SPP[15] - P[15][2]*SPP[21]) + SPP[10]*(P[3][1] + P[0][1]*SPP[1] + P[1][1]*SPP[19] + P[2][1]*SPP[15] - P[15][1]*SPP[21]); -nextP[4][5] = P[4][5] + SQ[0] + P[15][5]*SF[22] + P[0][5]*SPP[20] + P[1][5]*SPP[12] + P[2][5]*SPP[11] + SF[20]*(P[4][15] + P[15][15]*SF[22] + P[0][15]*SPP[20] + P[1][15]*SPP[12] + P[2][15]*SPP[11]) - SPP[9]*(P[4][0] + P[15][0]*SF[22] + P[0][0]*SPP[20] + P[1][0]*SPP[12] + P[2][0]*SPP[11]) + SPP[0]*(P[4][2] + P[15][2]*SF[22] + P[0][2]*SPP[20] + P[1][2]*SPP[12] + P[2][2]*SPP[11]) + SPP[10]*(P[4][1] + P[15][1]*SF[22] + P[0][1]*SPP[20] + P[1][1]*SPP[12] + P[2][1]*SPP[11]); -nextP[5][5] = P[5][5] + P[15][5]*SF[20] - P[0][5]*SPP[9] + P[1][5]*SPP[10] + P[2][5]*SPP[0] + SQ[4]*sq(SQ[7] + 2*q0*q1) + SQ[6]*sq(SQ[8] - 2*q0*q2) + SF[20]*(P[5][15] + P[15][15]*SF[20] - P[0][15]*SPP[9] + P[1][15]*SPP[10] + P[2][15]*SPP[0]) - SPP[9]*(P[5][0] + P[15][0]*SF[20] - P[0][0]*SPP[9] + P[1][0]*SPP[10] + P[2][0]*SPP[0]) + SPP[0]*(P[5][2] + P[15][2]*SF[20] - P[0][2]*SPP[9] + P[1][2]*SPP[10] + P[2][2]*SPP[0]) + SPP[10]*(P[5][1] + P[15][1]*SF[20] - P[0][1]*SPP[9] + P[1][1]*SPP[10] + P[2][1]*SPP[0]) + SQ[5]*sq(SG[1] - SG[2] - SG[3] + SG[4]); -nextP[0][6] = P[0][6]*SPP[5] - P[1][6]*SPP[4] + P[2][6]*SPP[7] + P[9][6]*SPP[22] + P[12][6]*SPP[18] + dt*(P[0][3]*SPP[5] - P[1][3]*SPP[4] + P[2][3]*SPP[7] + P[9][3]*SPP[22] + P[12][3]*SPP[18]); -nextP[1][6] = P[1][6]*SPP[6] - P[0][6]*SPP[2] - P[2][6]*SPP[8] + P[10][6]*SPP[22] + P[13][6]*SPP[17] + dt*(P[1][3]*SPP[6] - P[0][3]*SPP[2] - P[2][3]*SPP[8] + P[10][3]*SPP[22] + P[13][3]*SPP[17]); -nextP[2][6] = P[0][6]*SPP[14] - P[1][6]*SPP[3] + P[2][6]*SPP[13] + P[11][6]*SPP[22] + P[14][6]*SPP[16] + dt*(P[0][3]*SPP[14] - P[1][3]*SPP[3] + P[2][3]*SPP[13] + P[11][3]*SPP[22] + P[14][3]*SPP[16]); -nextP[3][6] = P[3][6] + P[0][6]*SPP[1] + P[1][6]*SPP[19] + P[2][6]*SPP[15] - P[15][6]*SPP[21] + dt*(P[3][3] + P[0][3]*SPP[1] + P[1][3]*SPP[19] + P[2][3]*SPP[15] - P[15][3]*SPP[21]); -nextP[4][6] = P[4][6] + P[15][6]*SF[22] + P[0][6]*SPP[20] + P[1][6]*SPP[12] + P[2][6]*SPP[11] + dt*(P[4][3] + P[15][3]*SF[22] + P[0][3]*SPP[20] + P[1][3]*SPP[12] + P[2][3]*SPP[11]); -nextP[5][6] = P[5][6] + P[15][6]*SF[20] - P[0][6]*SPP[9] + P[1][6]*SPP[10] + P[2][6]*SPP[0] + dt*(P[5][3] + P[15][3]*SF[20] - P[0][3]*SPP[9] + P[1][3]*SPP[10] + P[2][3]*SPP[0]); -nextP[6][6] = P[6][6] + P[3][6]*dt + dt*(P[6][3] + P[3][3]*dt); -nextP[0][7] = P[0][7]*SPP[5] - P[1][7]*SPP[4] + P[2][7]*SPP[7] + P[9][7]*SPP[22] + P[12][7]*SPP[18] + dt*(P[0][4]*SPP[5] - P[1][4]*SPP[4] + P[2][4]*SPP[7] + P[9][4]*SPP[22] + P[12][4]*SPP[18]); -nextP[1][7] = P[1][7]*SPP[6] - P[0][7]*SPP[2] - P[2][7]*SPP[8] + P[10][7]*SPP[22] + P[13][7]*SPP[17] + dt*(P[1][4]*SPP[6] - P[0][4]*SPP[2] - P[2][4]*SPP[8] + P[10][4]*SPP[22] + P[13][4]*SPP[17]); -nextP[2][7] = P[0][7]*SPP[14] - P[1][7]*SPP[3] + P[2][7]*SPP[13] + P[11][7]*SPP[22] + P[14][7]*SPP[16] + dt*(P[0][4]*SPP[14] - P[1][4]*SPP[3] + P[2][4]*SPP[13] + P[11][4]*SPP[22] + P[14][4]*SPP[16]); -nextP[3][7] = P[3][7] + P[0][7]*SPP[1] + P[1][7]*SPP[19] + P[2][7]*SPP[15] - P[15][7]*SPP[21] + dt*(P[3][4] + P[0][4]*SPP[1] + P[1][4]*SPP[19] + P[2][4]*SPP[15] - P[15][4]*SPP[21]); -nextP[4][7] = P[4][7] + P[15][7]*SF[22] + P[0][7]*SPP[20] + P[1][7]*SPP[12] + P[2][7]*SPP[11] + dt*(P[4][4] + P[15][4]*SF[22] + P[0][4]*SPP[20] + P[1][4]*SPP[12] + P[2][4]*SPP[11]); -nextP[5][7] = P[5][7] + P[15][7]*SF[20] - P[0][7]*SPP[9] + P[1][7]*SPP[10] + P[2][7]*SPP[0] + dt*(P[5][4] + P[15][4]*SF[20] - P[0][4]*SPP[9] + P[1][4]*SPP[10] + P[2][4]*SPP[0]); -nextP[6][7] = P[6][7] + P[3][7]*dt + dt*(P[6][4] + P[3][4]*dt); +nextP[0][0] = P[0][0] + P[1][0]*SF[9] + P[2][0]*SF[11] + P[3][0]*SF[10] + P[10][0]*SF[14] + P[11][0]*SF[15] + P[12][0]*SPP[10] + (daxVar*SQ[10])/4 + SF[9]*(P[0][1] + P[1][1]*SF[9] + P[2][1]*SF[11] + P[3][1]*SF[10] + P[10][1]*SF[14] + P[11][1]*SF[15] + P[12][1]*SPP[10]) + SF[11]*(P[0][2] + P[1][2]*SF[9] + P[2][2]*SF[11] + P[3][2]*SF[10] + P[10][2]*SF[14] + P[11][2]*SF[15] + P[12][2]*SPP[10]) + SF[10]*(P[0][3] + P[1][3]*SF[9] + P[2][3]*SF[11] + P[3][3]*SF[10] + P[10][3]*SF[14] + P[11][3]*SF[15] + P[12][3]*SPP[10]) + SF[14]*(P[0][10] + P[1][10]*SF[9] + P[2][10]*SF[11] + P[3][10]*SF[10] + P[10][10]*SF[14] + P[11][10]*SF[15] + P[12][10]*SPP[10]) + SF[15]*(P[0][11] + P[1][11]*SF[9] + P[2][11]*SF[11] + P[3][11]*SF[10] + P[10][11]*SF[14] + P[11][11]*SF[15] + P[12][11]*SPP[10]) + SPP[10]*(P[0][12] + P[1][12]*SF[9] + P[2][12]*SF[11] + P[3][12]*SF[10] + P[10][12]*SF[14] + P[11][12]*SF[15] + P[12][12]*SPP[10]) + (dayVar*sq(q2))/4 + (dazVar*sq(q3))/4; +nextP[0][1] = P[0][1] + SQ[8] + P[1][1]*SF[9] + P[2][1]*SF[11] + P[3][1]*SF[10] + P[10][1]*SF[14] + P[11][1]*SF[15] + P[12][1]*SPP[10] + SF[8]*(P[0][0] + P[1][0]*SF[9] + P[2][0]*SF[11] + P[3][0]*SF[10] + P[10][0]*SF[14] + P[11][0]*SF[15] + P[12][0]*SPP[10]) + SF[7]*(P[0][2] + P[1][2]*SF[9] + P[2][2]*SF[11] + P[3][2]*SF[10] + P[10][2]*SF[14] + P[11][2]*SF[15] + P[12][2]*SPP[10]) + SF[11]*(P[0][3] + P[1][3]*SF[9] + P[2][3]*SF[11] + P[3][3]*SF[10] + P[10][3]*SF[14] + P[11][3]*SF[15] + P[12][3]*SPP[10]) - SF[15]*(P[0][12] + P[1][12]*SF[9] + P[2][12]*SF[11] + P[3][12]*SF[10] + P[10][12]*SF[14] + P[11][12]*SF[15] + P[12][12]*SPP[10]) + SPP[10]*(P[0][11] + P[1][11]*SF[9] + P[2][11]*SF[11] + P[3][11]*SF[10] + P[10][11]*SF[14] + P[11][11]*SF[15] + P[12][11]*SPP[10]) - (q0*(P[0][10] + P[1][10]*SF[9] + P[2][10]*SF[11] + P[3][10]*SF[10] + P[10][10]*SF[14] + P[11][10]*SF[15] + P[12][10]*SPP[10]))/2; +nextP[1][1] = P[1][1] + P[0][1]*SF[8] + P[2][1]*SF[7] + P[3][1]*SF[11] - P[12][1]*SF[15] + P[11][1]*SPP[10] + daxVar*SQ[9] - (P[10][1]*q0)/2 + SF[8]*(P[1][0] + P[0][0]*SF[8] + P[2][0]*SF[7] + P[3][0]*SF[11] - P[12][0]*SF[15] + P[11][0]*SPP[10] - (P[10][0]*q0)/2) + SF[7]*(P[1][2] + P[0][2]*SF[8] + P[2][2]*SF[7] + P[3][2]*SF[11] - P[12][2]*SF[15] + P[11][2]*SPP[10] - (P[10][2]*q0)/2) + SF[11]*(P[1][3] + P[0][3]*SF[8] + P[2][3]*SF[7] + P[3][3]*SF[11] - P[12][3]*SF[15] + P[11][3]*SPP[10] - (P[10][3]*q0)/2) - SF[15]*(P[1][12] + P[0][12]*SF[8] + P[2][12]*SF[7] + P[3][12]*SF[11] - P[12][12]*SF[15] + P[11][12]*SPP[10] - (P[10][12]*q0)/2) + SPP[10]*(P[1][11] + P[0][11]*SF[8] + P[2][11]*SF[7] + P[3][11]*SF[11] - P[12][11]*SF[15] + P[11][11]*SPP[10] - (P[10][11]*q0)/2) + (dayVar*sq(q3))/4 + (dazVar*sq(q2))/4 - (q0*(P[1][10] + P[0][10]*SF[8] + P[2][10]*SF[7] + P[3][10]*SF[11] - P[12][10]*SF[15] + P[11][10]*SPP[10] - (P[10][10]*q0)/2))/2; +nextP[0][2] = P[0][2] + SQ[7] + P[1][2]*SF[9] + P[2][2]*SF[11] + P[3][2]*SF[10] + P[10][2]*SF[14] + P[11][2]*SF[15] + P[12][2]*SPP[10] + SF[6]*(P[0][0] + P[1][0]*SF[9] + P[2][0]*SF[11] + P[3][0]*SF[10] + P[10][0]*SF[14] + P[11][0]*SF[15] + P[12][0]*SPP[10]) + SF[10]*(P[0][1] + P[1][1]*SF[9] + P[2][1]*SF[11] + P[3][1]*SF[10] + P[10][1]*SF[14] + P[11][1]*SF[15] + P[12][1]*SPP[10]) + SF[8]*(P[0][3] + P[1][3]*SF[9] + P[2][3]*SF[11] + P[3][3]*SF[10] + P[10][3]*SF[14] + P[11][3]*SF[15] + P[12][3]*SPP[10]) + SF[14]*(P[0][12] + P[1][12]*SF[9] + P[2][12]*SF[11] + P[3][12]*SF[10] + P[10][12]*SF[14] + P[11][12]*SF[15] + P[12][12]*SPP[10]) - SPP[10]*(P[0][10] + P[1][10]*SF[9] + P[2][10]*SF[11] + P[3][10]*SF[10] + P[10][10]*SF[14] + P[11][10]*SF[15] + P[12][10]*SPP[10]) - (q0*(P[0][11] + P[1][11]*SF[9] + P[2][11]*SF[11] + P[3][11]*SF[10] + P[10][11]*SF[14] + P[11][11]*SF[15] + P[12][11]*SPP[10]))/2; +nextP[1][2] = P[1][2] + SQ[5] + P[0][2]*SF[8] + P[2][2]*SF[7] + P[3][2]*SF[11] - P[12][2]*SF[15] + P[11][2]*SPP[10] - (P[10][2]*q0)/2 + SF[6]*(P[1][0] + P[0][0]*SF[8] + P[2][0]*SF[7] + P[3][0]*SF[11] - P[12][0]*SF[15] + P[11][0]*SPP[10] - (P[10][0]*q0)/2) + SF[10]*(P[1][1] + P[0][1]*SF[8] + P[2][1]*SF[7] + P[3][1]*SF[11] - P[12][1]*SF[15] + P[11][1]*SPP[10] - (P[10][1]*q0)/2) + SF[8]*(P[1][3] + P[0][3]*SF[8] + P[2][3]*SF[7] + P[3][3]*SF[11] - P[12][3]*SF[15] + P[11][3]*SPP[10] - (P[10][3]*q0)/2) + SF[14]*(P[1][12] + P[0][12]*SF[8] + P[2][12]*SF[7] + P[3][12]*SF[11] - P[12][12]*SF[15] + P[11][12]*SPP[10] - (P[10][12]*q0)/2) - SPP[10]*(P[1][10] + P[0][10]*SF[8] + P[2][10]*SF[7] + P[3][10]*SF[11] - P[12][10]*SF[15] + P[11][10]*SPP[10] - (P[10][10]*q0)/2) - (q0*(P[1][11] + P[0][11]*SF[8] + P[2][11]*SF[7] + P[3][11]*SF[11] - P[12][11]*SF[15] + P[11][11]*SPP[10] - (P[10][11]*q0)/2))/2; +nextP[2][2] = P[2][2] + P[0][2]*SF[6] + P[1][2]*SF[10] + P[3][2]*SF[8] + P[12][2]*SF[14] - P[10][2]*SPP[10] + dayVar*SQ[9] + (dazVar*SQ[10])/4 - (P[11][2]*q0)/2 + SF[6]*(P[2][0] + P[0][0]*SF[6] + P[1][0]*SF[10] + P[3][0]*SF[8] + P[12][0]*SF[14] - P[10][0]*SPP[10] - (P[11][0]*q0)/2) + SF[10]*(P[2][1] + P[0][1]*SF[6] + P[1][1]*SF[10] + P[3][1]*SF[8] + P[12][1]*SF[14] - P[10][1]*SPP[10] - (P[11][1]*q0)/2) + SF[8]*(P[2][3] + P[0][3]*SF[6] + P[1][3]*SF[10] + P[3][3]*SF[8] + P[12][3]*SF[14] - P[10][3]*SPP[10] - (P[11][3]*q0)/2) + SF[14]*(P[2][12] + P[0][12]*SF[6] + P[1][12]*SF[10] + P[3][12]*SF[8] + P[12][12]*SF[14] - P[10][12]*SPP[10] - (P[11][12]*q0)/2) - SPP[10]*(P[2][10] + P[0][10]*SF[6] + P[1][10]*SF[10] + P[3][10]*SF[8] + P[12][10]*SF[14] - P[10][10]*SPP[10] - (P[11][10]*q0)/2) + (daxVar*sq(q3))/4 - (q0*(P[2][11] + P[0][11]*SF[6] + P[1][11]*SF[10] + P[3][11]*SF[8] + P[12][11]*SF[14] - P[10][11]*SPP[10] - (P[11][11]*q0)/2))/2; +nextP[0][3] = P[0][3] + SQ[6] + P[1][3]*SF[9] + P[2][3]*SF[11] + P[3][3]*SF[10] + P[10][3]*SF[14] + P[11][3]*SF[15] + P[12][3]*SPP[10] + SF[7]*(P[0][0] + P[1][0]*SF[9] + P[2][0]*SF[11] + P[3][0]*SF[10] + P[10][0]*SF[14] + P[11][0]*SF[15] + P[12][0]*SPP[10]) + SF[6]*(P[0][1] + P[1][1]*SF[9] + P[2][1]*SF[11] + P[3][1]*SF[10] + P[10][1]*SF[14] + P[11][1]*SF[15] + P[12][1]*SPP[10]) + SF[9]*(P[0][2] + P[1][2]*SF[9] + P[2][2]*SF[11] + P[3][2]*SF[10] + P[10][2]*SF[14] + P[11][2]*SF[15] + P[12][2]*SPP[10]) + SF[15]*(P[0][10] + P[1][10]*SF[9] + P[2][10]*SF[11] + P[3][10]*SF[10] + P[10][10]*SF[14] + P[11][10]*SF[15] + P[12][10]*SPP[10]) - SF[14]*(P[0][11] + P[1][11]*SF[9] + P[2][11]*SF[11] + P[3][11]*SF[10] + P[10][11]*SF[14] + P[11][11]*SF[15] + P[12][11]*SPP[10]) - (q0*(P[0][12] + P[1][12]*SF[9] + P[2][12]*SF[11] + P[3][12]*SF[10] + P[10][12]*SF[14] + P[11][12]*SF[15] + P[12][12]*SPP[10]))/2; +nextP[1][3] = P[1][3] + SQ[4] + P[0][3]*SF[8] + P[2][3]*SF[7] + P[3][3]*SF[11] - P[12][3]*SF[15] + P[11][3]*SPP[10] - (P[10][3]*q0)/2 + SF[7]*(P[1][0] + P[0][0]*SF[8] + P[2][0]*SF[7] + P[3][0]*SF[11] - P[12][0]*SF[15] + P[11][0]*SPP[10] - (P[10][0]*q0)/2) + SF[6]*(P[1][1] + P[0][1]*SF[8] + P[2][1]*SF[7] + P[3][1]*SF[11] - P[12][1]*SF[15] + P[11][1]*SPP[10] - (P[10][1]*q0)/2) + SF[9]*(P[1][2] + P[0][2]*SF[8] + P[2][2]*SF[7] + P[3][2]*SF[11] - P[12][2]*SF[15] + P[11][2]*SPP[10] - (P[10][2]*q0)/2) + SF[15]*(P[1][10] + P[0][10]*SF[8] + P[2][10]*SF[7] + P[3][10]*SF[11] - P[12][10]*SF[15] + P[11][10]*SPP[10] - (P[10][10]*q0)/2) - SF[14]*(P[1][11] + P[0][11]*SF[8] + P[2][11]*SF[7] + P[3][11]*SF[11] - P[12][11]*SF[15] + P[11][11]*SPP[10] - (P[10][11]*q0)/2) - (q0*(P[1][12] + P[0][12]*SF[8] + P[2][12]*SF[7] + P[3][12]*SF[11] - P[12][12]*SF[15] + P[11][12]*SPP[10] - (P[10][12]*q0)/2))/2; +nextP[2][3] = P[2][3] + SQ[3] + P[0][3]*SF[6] + P[1][3]*SF[10] + P[3][3]*SF[8] + P[12][3]*SF[14] - P[10][3]*SPP[10] - (P[11][3]*q0)/2 + SF[7]*(P[2][0] + P[0][0]*SF[6] + P[1][0]*SF[10] + P[3][0]*SF[8] + P[12][0]*SF[14] - P[10][0]*SPP[10] - (P[11][0]*q0)/2) + SF[6]*(P[2][1] + P[0][1]*SF[6] + P[1][1]*SF[10] + P[3][1]*SF[8] + P[12][1]*SF[14] - P[10][1]*SPP[10] - (P[11][1]*q0)/2) + SF[9]*(P[2][2] + P[0][2]*SF[6] + P[1][2]*SF[10] + P[3][2]*SF[8] + P[12][2]*SF[14] - P[10][2]*SPP[10] - (P[11][2]*q0)/2) + SF[15]*(P[2][10] + P[0][10]*SF[6] + P[1][10]*SF[10] + P[3][10]*SF[8] + P[12][10]*SF[14] - P[10][10]*SPP[10] - (P[11][10]*q0)/2) - SF[14]*(P[2][11] + P[0][11]*SF[6] + P[1][11]*SF[10] + P[3][11]*SF[8] + P[12][11]*SF[14] - P[10][11]*SPP[10] - (P[11][11]*q0)/2) - (q0*(P[2][12] + P[0][12]*SF[6] + P[1][12]*SF[10] + P[3][12]*SF[8] + P[12][12]*SF[14] - P[10][12]*SPP[10] - (P[11][12]*q0)/2))/2; +nextP[3][3] = P[3][3] + P[0][3]*SF[7] + P[1][3]*SF[6] + P[2][3]*SF[9] + P[10][3]*SF[15] - P[11][3]*SF[14] + (dayVar*SQ[10])/4 + dazVar*SQ[9] - (P[12][3]*q0)/2 + SF[7]*(P[3][0] + P[0][0]*SF[7] + P[1][0]*SF[6] + P[2][0]*SF[9] + P[10][0]*SF[15] - P[11][0]*SF[14] - (P[12][0]*q0)/2) + SF[6]*(P[3][1] + P[0][1]*SF[7] + P[1][1]*SF[6] + P[2][1]*SF[9] + P[10][1]*SF[15] - P[11][1]*SF[14] - (P[12][1]*q0)/2) + SF[9]*(P[3][2] + P[0][2]*SF[7] + P[1][2]*SF[6] + P[2][2]*SF[9] + P[10][2]*SF[15] - P[11][2]*SF[14] - (P[12][2]*q0)/2) + SF[15]*(P[3][10] + P[0][10]*SF[7] + P[1][10]*SF[6] + P[2][10]*SF[9] + P[10][10]*SF[15] - P[11][10]*SF[14] - (P[12][10]*q0)/2) - SF[14]*(P[3][11] + P[0][11]*SF[7] + P[1][11]*SF[6] + P[2][11]*SF[9] + P[10][11]*SF[15] - P[11][11]*SF[14] - (P[12][11]*q0)/2) + (daxVar*sq(q2))/4 - (q0*(P[3][12] + P[0][12]*SF[7] + P[1][12]*SF[6] + P[2][12]*SF[9] + P[10][12]*SF[15] - P[11][12]*SF[14] - (P[12][12]*q0)/2))/2; +nextP[0][4] = P[0][4] + P[1][4]*SF[9] + P[2][4]*SF[11] + P[3][4]*SF[10] + P[10][4]*SF[14] + P[11][4]*SF[15] + P[12][4]*SPP[10] + SF[5]*(P[0][0] + P[1][0]*SF[9] + P[2][0]*SF[11] + P[3][0]*SF[10] + P[10][0]*SF[14] + P[11][0]*SF[15] + P[12][0]*SPP[10]) + SF[3]*(P[0][1] + P[1][1]*SF[9] + P[2][1]*SF[11] + P[3][1]*SF[10] + P[10][1]*SF[14] + P[11][1]*SF[15] + P[12][1]*SPP[10]) - SF[4]*(P[0][3] + P[1][3]*SF[9] + P[2][3]*SF[11] + P[3][3]*SF[10] + P[10][3]*SF[14] + P[11][3]*SF[15] + P[12][3]*SPP[10]) + SPP[0]*(P[0][2] + P[1][2]*SF[9] + P[2][2]*SF[11] + P[3][2]*SF[10] + P[10][2]*SF[14] + P[11][2]*SF[15] + P[12][2]*SPP[10]) + SPP[3]*(P[0][13] + P[1][13]*SF[9] + P[2][13]*SF[11] + P[3][13]*SF[10] + P[10][13]*SF[14] + P[11][13]*SF[15] + P[12][13]*SPP[10]) + SPP[6]*(P[0][14] + P[1][14]*SF[9] + P[2][14]*SF[11] + P[3][14]*SF[10] + P[10][14]*SF[14] + P[11][14]*SF[15] + P[12][14]*SPP[10]) - SPP[9]*(P[0][15] + P[1][15]*SF[9] + P[2][15]*SF[11] + P[3][15]*SF[10] + P[10][15]*SF[14] + P[11][15]*SF[15] + P[12][15]*SPP[10]); +nextP[1][4] = P[1][4] + P[0][4]*SF[8] + P[2][4]*SF[7] + P[3][4]*SF[11] - P[12][4]*SF[15] + P[11][4]*SPP[10] - (P[10][4]*q0)/2 + SF[5]*(P[1][0] + P[0][0]*SF[8] + P[2][0]*SF[7] + P[3][0]*SF[11] - P[12][0]*SF[15] + P[11][0]*SPP[10] - (P[10][0]*q0)/2) + SF[3]*(P[1][1] + P[0][1]*SF[8] + P[2][1]*SF[7] + P[3][1]*SF[11] - P[12][1]*SF[15] + P[11][1]*SPP[10] - (P[10][1]*q0)/2) - SF[4]*(P[1][3] + P[0][3]*SF[8] + P[2][3]*SF[7] + P[3][3]*SF[11] - P[12][3]*SF[15] + P[11][3]*SPP[10] - (P[10][3]*q0)/2) + SPP[0]*(P[1][2] + P[0][2]*SF[8] + P[2][2]*SF[7] + P[3][2]*SF[11] - P[12][2]*SF[15] + P[11][2]*SPP[10] - (P[10][2]*q0)/2) + SPP[3]*(P[1][13] + P[0][13]*SF[8] + P[2][13]*SF[7] + P[3][13]*SF[11] - P[12][13]*SF[15] + P[11][13]*SPP[10] - (P[10][13]*q0)/2) + SPP[6]*(P[1][14] + P[0][14]*SF[8] + P[2][14]*SF[7] + P[3][14]*SF[11] - P[12][14]*SF[15] + P[11][14]*SPP[10] - (P[10][14]*q0)/2) - SPP[9]*(P[1][15] + P[0][15]*SF[8] + P[2][15]*SF[7] + P[3][15]*SF[11] - P[12][15]*SF[15] + P[11][15]*SPP[10] - (P[10][15]*q0)/2); +nextP[2][4] = P[2][4] + P[0][4]*SF[6] + P[1][4]*SF[10] + P[3][4]*SF[8] + P[12][4]*SF[14] - P[10][4]*SPP[10] - (P[11][4]*q0)/2 + SF[5]*(P[2][0] + P[0][0]*SF[6] + P[1][0]*SF[10] + P[3][0]*SF[8] + P[12][0]*SF[14] - P[10][0]*SPP[10] - (P[11][0]*q0)/2) + SF[3]*(P[2][1] + P[0][1]*SF[6] + P[1][1]*SF[10] + P[3][1]*SF[8] + P[12][1]*SF[14] - P[10][1]*SPP[10] - (P[11][1]*q0)/2) - SF[4]*(P[2][3] + P[0][3]*SF[6] + P[1][3]*SF[10] + P[3][3]*SF[8] + P[12][3]*SF[14] - P[10][3]*SPP[10] - (P[11][3]*q0)/2) + SPP[0]*(P[2][2] + P[0][2]*SF[6] + P[1][2]*SF[10] + P[3][2]*SF[8] + P[12][2]*SF[14] - P[10][2]*SPP[10] - (P[11][2]*q0)/2) + SPP[3]*(P[2][13] + P[0][13]*SF[6] + P[1][13]*SF[10] + P[3][13]*SF[8] + P[12][13]*SF[14] - P[10][13]*SPP[10] - (P[11][13]*q0)/2) + SPP[6]*(P[2][14] + P[0][14]*SF[6] + P[1][14]*SF[10] + P[3][14]*SF[8] + P[12][14]*SF[14] - P[10][14]*SPP[10] - (P[11][14]*q0)/2) - SPP[9]*(P[2][15] + P[0][15]*SF[6] + P[1][15]*SF[10] + P[3][15]*SF[8] + P[12][15]*SF[14] - P[10][15]*SPP[10] - (P[11][15]*q0)/2); +nextP[3][4] = P[3][4] + P[0][4]*SF[7] + P[1][4]*SF[6] + P[2][4]*SF[9] + P[10][4]*SF[15] - P[11][4]*SF[14] - (P[12][4]*q0)/2 + SF[5]*(P[3][0] + P[0][0]*SF[7] + P[1][0]*SF[6] + P[2][0]*SF[9] + P[10][0]*SF[15] - P[11][0]*SF[14] - (P[12][0]*q0)/2) + SF[3]*(P[3][1] + P[0][1]*SF[7] + P[1][1]*SF[6] + P[2][1]*SF[9] + P[10][1]*SF[15] - P[11][1]*SF[14] - (P[12][1]*q0)/2) - SF[4]*(P[3][3] + P[0][3]*SF[7] + P[1][3]*SF[6] + P[2][3]*SF[9] + P[10][3]*SF[15] - P[11][3]*SF[14] - (P[12][3]*q0)/2) + SPP[0]*(P[3][2] + P[0][2]*SF[7] + P[1][2]*SF[6] + P[2][2]*SF[9] + P[10][2]*SF[15] - P[11][2]*SF[14] - (P[12][2]*q0)/2) + SPP[3]*(P[3][13] + P[0][13]*SF[7] + P[1][13]*SF[6] + P[2][13]*SF[9] + P[10][13]*SF[15] - P[11][13]*SF[14] - (P[12][13]*q0)/2) + SPP[6]*(P[3][14] + P[0][14]*SF[7] + P[1][14]*SF[6] + P[2][14]*SF[9] + P[10][14]*SF[15] - P[11][14]*SF[14] - (P[12][14]*q0)/2) - SPP[9]*(P[3][15] + P[0][15]*SF[7] + P[1][15]*SF[6] + P[2][15]*SF[9] + P[10][15]*SF[15] - P[11][15]*SF[14] - (P[12][15]*q0)/2); +nextP[4][4] = P[4][4] + P[0][4]*SF[5] + P[1][4]*SF[3] - P[3][4]*SF[4] + P[2][4]*SPP[0] + P[13][4]*SPP[3] + P[14][4]*SPP[6] - P[15][4]*SPP[9] + dvyVar*sq(SG[7] - 2*q0*q3) + dvzVar*sq(SG[6] + 2*q0*q2) + SF[5]*(P[4][0] + P[0][0]*SF[5] + P[1][0]*SF[3] - P[3][0]*SF[4] + P[2][0]*SPP[0] + P[13][0]*SPP[3] + P[14][0]*SPP[6] - P[15][0]*SPP[9]) + SF[3]*(P[4][1] + P[0][1]*SF[5] + P[1][1]*SF[3] - P[3][1]*SF[4] + P[2][1]*SPP[0] + P[13][1]*SPP[3] + P[14][1]*SPP[6] - P[15][1]*SPP[9]) - SF[4]*(P[4][3] + P[0][3]*SF[5] + P[1][3]*SF[3] - P[3][3]*SF[4] + P[2][3]*SPP[0] + P[13][3]*SPP[3] + P[14][3]*SPP[6] - P[15][3]*SPP[9]) + SPP[0]*(P[4][2] + P[0][2]*SF[5] + P[1][2]*SF[3] - P[3][2]*SF[4] + P[2][2]*SPP[0] + P[13][2]*SPP[3] + P[14][2]*SPP[6] - P[15][2]*SPP[9]) + SPP[3]*(P[4][13] + P[0][13]*SF[5] + P[1][13]*SF[3] - P[3][13]*SF[4] + P[2][13]*SPP[0] + P[13][13]*SPP[3] + P[14][13]*SPP[6] - P[15][13]*SPP[9]) + SPP[6]*(P[4][14] + P[0][14]*SF[5] + P[1][14]*SF[3] - P[3][14]*SF[4] + P[2][14]*SPP[0] + P[13][14]*SPP[3] + P[14][14]*SPP[6] - P[15][14]*SPP[9]) - SPP[9]*(P[4][15] + P[0][15]*SF[5] + P[1][15]*SF[3] - P[3][15]*SF[4] + P[2][15]*SPP[0] + P[13][15]*SPP[3] + P[14][15]*SPP[6] - P[15][15]*SPP[9]) + dvxVar*sq(SG[1] + SG[2] - SG[3] - SG[4]); +nextP[0][5] = P[0][5] + P[1][5]*SF[9] + P[2][5]*SF[11] + P[3][5]*SF[10] + P[10][5]*SF[14] + P[11][5]*SF[15] + P[12][5]*SPP[10] + SF[4]*(P[0][0] + P[1][0]*SF[9] + P[2][0]*SF[11] + P[3][0]*SF[10] + P[10][0]*SF[14] + P[11][0]*SF[15] + P[12][0]*SPP[10]) + SF[3]*(P[0][2] + P[1][2]*SF[9] + P[2][2]*SF[11] + P[3][2]*SF[10] + P[10][2]*SF[14] + P[11][2]*SF[15] + P[12][2]*SPP[10]) + SF[5]*(P[0][3] + P[1][3]*SF[9] + P[2][3]*SF[11] + P[3][3]*SF[10] + P[10][3]*SF[14] + P[11][3]*SF[15] + P[12][3]*SPP[10]) - SPP[0]*(P[0][1] + P[1][1]*SF[9] + P[2][1]*SF[11] + P[3][1]*SF[10] + P[10][1]*SF[14] + P[11][1]*SF[15] + P[12][1]*SPP[10]) - SPP[8]*(P[0][13] + P[1][13]*SF[9] + P[2][13]*SF[11] + P[3][13]*SF[10] + P[10][13]*SF[14] + P[11][13]*SF[15] + P[12][13]*SPP[10]) + SPP[2]*(P[0][14] + P[1][14]*SF[9] + P[2][14]*SF[11] + P[3][14]*SF[10] + P[10][14]*SF[14] + P[11][14]*SF[15] + P[12][14]*SPP[10]) + SPP[5]*(P[0][15] + P[1][15]*SF[9] + P[2][15]*SF[11] + P[3][15]*SF[10] + P[10][15]*SF[14] + P[11][15]*SF[15] + P[12][15]*SPP[10]); +nextP[1][5] = P[1][5] + P[0][5]*SF[8] + P[2][5]*SF[7] + P[3][5]*SF[11] - P[12][5]*SF[15] + P[11][5]*SPP[10] - (P[10][5]*q0)/2 + SF[4]*(P[1][0] + P[0][0]*SF[8] + P[2][0]*SF[7] + P[3][0]*SF[11] - P[12][0]*SF[15] + P[11][0]*SPP[10] - (P[10][0]*q0)/2) + SF[3]*(P[1][2] + P[0][2]*SF[8] + P[2][2]*SF[7] + P[3][2]*SF[11] - P[12][2]*SF[15] + P[11][2]*SPP[10] - (P[10][2]*q0)/2) + SF[5]*(P[1][3] + P[0][3]*SF[8] + P[2][3]*SF[7] + P[3][3]*SF[11] - P[12][3]*SF[15] + P[11][3]*SPP[10] - (P[10][3]*q0)/2) - SPP[0]*(P[1][1] + P[0][1]*SF[8] + P[2][1]*SF[7] + P[3][1]*SF[11] - P[12][1]*SF[15] + P[11][1]*SPP[10] - (P[10][1]*q0)/2) - SPP[8]*(P[1][13] + P[0][13]*SF[8] + P[2][13]*SF[7] + P[3][13]*SF[11] - P[12][13]*SF[15] + P[11][13]*SPP[10] - (P[10][13]*q0)/2) + SPP[2]*(P[1][14] + P[0][14]*SF[8] + P[2][14]*SF[7] + P[3][14]*SF[11] - P[12][14]*SF[15] + P[11][14]*SPP[10] - (P[10][14]*q0)/2) + SPP[5]*(P[1][15] + P[0][15]*SF[8] + P[2][15]*SF[7] + P[3][15]*SF[11] - P[12][15]*SF[15] + P[11][15]*SPP[10] - (P[10][15]*q0)/2); +nextP[2][5] = P[2][5] + P[0][5]*SF[6] + P[1][5]*SF[10] + P[3][5]*SF[8] + P[12][5]*SF[14] - P[10][5]*SPP[10] - (P[11][5]*q0)/2 + SF[4]*(P[2][0] + P[0][0]*SF[6] + P[1][0]*SF[10] + P[3][0]*SF[8] + P[12][0]*SF[14] - P[10][0]*SPP[10] - (P[11][0]*q0)/2) + SF[3]*(P[2][2] + P[0][2]*SF[6] + P[1][2]*SF[10] + P[3][2]*SF[8] + P[12][2]*SF[14] - P[10][2]*SPP[10] - (P[11][2]*q0)/2) + SF[5]*(P[2][3] + P[0][3]*SF[6] + P[1][3]*SF[10] + P[3][3]*SF[8] + P[12][3]*SF[14] - P[10][3]*SPP[10] - (P[11][3]*q0)/2) - SPP[0]*(P[2][1] + P[0][1]*SF[6] + P[1][1]*SF[10] + P[3][1]*SF[8] + P[12][1]*SF[14] - P[10][1]*SPP[10] - (P[11][1]*q0)/2) - SPP[8]*(P[2][13] + P[0][13]*SF[6] + P[1][13]*SF[10] + P[3][13]*SF[8] + P[12][13]*SF[14] - P[10][13]*SPP[10] - (P[11][13]*q0)/2) + SPP[2]*(P[2][14] + P[0][14]*SF[6] + P[1][14]*SF[10] + P[3][14]*SF[8] + P[12][14]*SF[14] - P[10][14]*SPP[10] - (P[11][14]*q0)/2) + SPP[5]*(P[2][15] + P[0][15]*SF[6] + P[1][15]*SF[10] + P[3][15]*SF[8] + P[12][15]*SF[14] - P[10][15]*SPP[10] - (P[11][15]*q0)/2); +nextP[3][5] = P[3][5] + P[0][5]*SF[7] + P[1][5]*SF[6] + P[2][5]*SF[9] + P[10][5]*SF[15] - P[11][5]*SF[14] - (P[12][5]*q0)/2 + SF[4]*(P[3][0] + P[0][0]*SF[7] + P[1][0]*SF[6] + P[2][0]*SF[9] + P[10][0]*SF[15] - P[11][0]*SF[14] - (P[12][0]*q0)/2) + SF[3]*(P[3][2] + P[0][2]*SF[7] + P[1][2]*SF[6] + P[2][2]*SF[9] + P[10][2]*SF[15] - P[11][2]*SF[14] - (P[12][2]*q0)/2) + SF[5]*(P[3][3] + P[0][3]*SF[7] + P[1][3]*SF[6] + P[2][3]*SF[9] + P[10][3]*SF[15] - P[11][3]*SF[14] - (P[12][3]*q0)/2) - SPP[0]*(P[3][1] + P[0][1]*SF[7] + P[1][1]*SF[6] + P[2][1]*SF[9] + P[10][1]*SF[15] - P[11][1]*SF[14] - (P[12][1]*q0)/2) - SPP[8]*(P[3][13] + P[0][13]*SF[7] + P[1][13]*SF[6] + P[2][13]*SF[9] + P[10][13]*SF[15] - P[11][13]*SF[14] - (P[12][13]*q0)/2) + SPP[2]*(P[3][14] + P[0][14]*SF[7] + P[1][14]*SF[6] + P[2][14]*SF[9] + P[10][14]*SF[15] - P[11][14]*SF[14] - (P[12][14]*q0)/2) + SPP[5]*(P[3][15] + P[0][15]*SF[7] + P[1][15]*SF[6] + P[2][15]*SF[9] + P[10][15]*SF[15] - P[11][15]*SF[14] - (P[12][15]*q0)/2); +nextP[4][5] = P[4][5] + SQ[2] + P[0][5]*SF[5] + P[1][5]*SF[3] - P[3][5]*SF[4] + P[2][5]*SPP[0] + P[13][5]*SPP[3] + P[14][5]*SPP[6] - P[15][5]*SPP[9] + SF[4]*(P[4][0] + P[0][0]*SF[5] + P[1][0]*SF[3] - P[3][0]*SF[4] + P[2][0]*SPP[0] + P[13][0]*SPP[3] + P[14][0]*SPP[6] - P[15][0]*SPP[9]) + SF[3]*(P[4][2] + P[0][2]*SF[5] + P[1][2]*SF[3] - P[3][2]*SF[4] + P[2][2]*SPP[0] + P[13][2]*SPP[3] + P[14][2]*SPP[6] - P[15][2]*SPP[9]) + SF[5]*(P[4][3] + P[0][3]*SF[5] + P[1][3]*SF[3] - P[3][3]*SF[4] + P[2][3]*SPP[0] + P[13][3]*SPP[3] + P[14][3]*SPP[6] - P[15][3]*SPP[9]) - SPP[0]*(P[4][1] + P[0][1]*SF[5] + P[1][1]*SF[3] - P[3][1]*SF[4] + P[2][1]*SPP[0] + P[13][1]*SPP[3] + P[14][1]*SPP[6] - P[15][1]*SPP[9]) - SPP[8]*(P[4][13] + P[0][13]*SF[5] + P[1][13]*SF[3] - P[3][13]*SF[4] + P[2][13]*SPP[0] + P[13][13]*SPP[3] + P[14][13]*SPP[6] - P[15][13]*SPP[9]) + SPP[2]*(P[4][14] + P[0][14]*SF[5] + P[1][14]*SF[3] - P[3][14]*SF[4] + P[2][14]*SPP[0] + P[13][14]*SPP[3] + P[14][14]*SPP[6] - P[15][14]*SPP[9]) + SPP[5]*(P[4][15] + P[0][15]*SF[5] + P[1][15]*SF[3] - P[3][15]*SF[4] + P[2][15]*SPP[0] + P[13][15]*SPP[3] + P[14][15]*SPP[6] - P[15][15]*SPP[9]); +nextP[5][5] = P[5][5] + P[0][5]*SF[4] + P[2][5]*SF[3] + P[3][5]*SF[5] - P[1][5]*SPP[0] - P[13][5]*SPP[8] + P[14][5]*SPP[2] + P[15][5]*SPP[5] + dvxVar*sq(SG[7] + 2*q0*q3) + dvzVar*sq(SG[5] - 2*q0*q1) + SF[4]*(P[5][0] + P[0][0]*SF[4] + P[2][0]*SF[3] + P[3][0]*SF[5] - P[1][0]*SPP[0] - P[13][0]*SPP[8] + P[14][0]*SPP[2] + P[15][0]*SPP[5]) + SF[3]*(P[5][2] + P[0][2]*SF[4] + P[2][2]*SF[3] + P[3][2]*SF[5] - P[1][2]*SPP[0] - P[13][2]*SPP[8] + P[14][2]*SPP[2] + P[15][2]*SPP[5]) + SF[5]*(P[5][3] + P[0][3]*SF[4] + P[2][3]*SF[3] + P[3][3]*SF[5] - P[1][3]*SPP[0] - P[13][3]*SPP[8] + P[14][3]*SPP[2] + P[15][3]*SPP[5]) - SPP[0]*(P[5][1] + P[0][1]*SF[4] + P[2][1]*SF[3] + P[3][1]*SF[5] - P[1][1]*SPP[0] - P[13][1]*SPP[8] + P[14][1]*SPP[2] + P[15][1]*SPP[5]) - SPP[8]*(P[5][13] + P[0][13]*SF[4] + P[2][13]*SF[3] + P[3][13]*SF[5] - P[1][13]*SPP[0] - P[13][13]*SPP[8] + P[14][13]*SPP[2] + P[15][13]*SPP[5]) + SPP[2]*(P[5][14] + P[0][14]*SF[4] + P[2][14]*SF[3] + P[3][14]*SF[5] - P[1][14]*SPP[0] - P[13][14]*SPP[8] + P[14][14]*SPP[2] + P[15][14]*SPP[5]) + SPP[5]*(P[5][15] + P[0][15]*SF[4] + P[2][15]*SF[3] + P[3][15]*SF[5] - P[1][15]*SPP[0] - P[13][15]*SPP[8] + P[14][15]*SPP[2] + P[15][15]*SPP[5]) + dvyVar*sq(SG[1] - SG[2] + SG[3] - SG[4]); +nextP[0][6] = P[0][6] + P[1][6]*SF[9] + P[2][6]*SF[11] + P[3][6]*SF[10] + P[10][6]*SF[14] + P[11][6]*SF[15] + P[12][6]*SPP[10] + SF[4]*(P[0][1] + P[1][1]*SF[9] + P[2][1]*SF[11] + P[3][1]*SF[10] + P[10][1]*SF[14] + P[11][1]*SF[15] + P[12][1]*SPP[10]) - SF[5]*(P[0][2] + P[1][2]*SF[9] + P[2][2]*SF[11] + P[3][2]*SF[10] + P[10][2]*SF[14] + P[11][2]*SF[15] + P[12][2]*SPP[10]) + SF[3]*(P[0][3] + P[1][3]*SF[9] + P[2][3]*SF[11] + P[3][3]*SF[10] + P[10][3]*SF[14] + P[11][3]*SF[15] + P[12][3]*SPP[10]) + SPP[0]*(P[0][0] + P[1][0]*SF[9] + P[2][0]*SF[11] + P[3][0]*SF[10] + P[10][0]*SF[14] + P[11][0]*SF[15] + P[12][0]*SPP[10]) + SPP[4]*(P[0][13] + P[1][13]*SF[9] + P[2][13]*SF[11] + P[3][13]*SF[10] + P[10][13]*SF[14] + P[11][13]*SF[15] + P[12][13]*SPP[10]) - SPP[7]*(P[0][14] + P[1][14]*SF[9] + P[2][14]*SF[11] + P[3][14]*SF[10] + P[10][14]*SF[14] + P[11][14]*SF[15] + P[12][14]*SPP[10]) - SPP[1]*(P[0][15] + P[1][15]*SF[9] + P[2][15]*SF[11] + P[3][15]*SF[10] + P[10][15]*SF[14] + P[11][15]*SF[15] + P[12][15]*SPP[10]); +nextP[1][6] = P[1][6] + P[0][6]*SF[8] + P[2][6]*SF[7] + P[3][6]*SF[11] - P[12][6]*SF[15] + P[11][6]*SPP[10] - (P[10][6]*q0)/2 + SF[4]*(P[1][1] + P[0][1]*SF[8] + P[2][1]*SF[7] + P[3][1]*SF[11] - P[12][1]*SF[15] + P[11][1]*SPP[10] - (P[10][1]*q0)/2) - SF[5]*(P[1][2] + P[0][2]*SF[8] + P[2][2]*SF[7] + P[3][2]*SF[11] - P[12][2]*SF[15] + P[11][2]*SPP[10] - (P[10][2]*q0)/2) + SF[3]*(P[1][3] + P[0][3]*SF[8] + P[2][3]*SF[7] + P[3][3]*SF[11] - P[12][3]*SF[15] + P[11][3]*SPP[10] - (P[10][3]*q0)/2) + SPP[0]*(P[1][0] + P[0][0]*SF[8] + P[2][0]*SF[7] + P[3][0]*SF[11] - P[12][0]*SF[15] + P[11][0]*SPP[10] - (P[10][0]*q0)/2) + SPP[4]*(P[1][13] + P[0][13]*SF[8] + P[2][13]*SF[7] + P[3][13]*SF[11] - P[12][13]*SF[15] + P[11][13]*SPP[10] - (P[10][13]*q0)/2) - SPP[7]*(P[1][14] + P[0][14]*SF[8] + P[2][14]*SF[7] + P[3][14]*SF[11] - P[12][14]*SF[15] + P[11][14]*SPP[10] - (P[10][14]*q0)/2) - SPP[1]*(P[1][15] + P[0][15]*SF[8] + P[2][15]*SF[7] + P[3][15]*SF[11] - P[12][15]*SF[15] + P[11][15]*SPP[10] - (P[10][15]*q0)/2); +nextP[2][6] = P[2][6] + P[0][6]*SF[6] + P[1][6]*SF[10] + P[3][6]*SF[8] + P[12][6]*SF[14] - P[10][6]*SPP[10] - (P[11][6]*q0)/2 + SF[4]*(P[2][1] + P[0][1]*SF[6] + P[1][1]*SF[10] + P[3][1]*SF[8] + P[12][1]*SF[14] - P[10][1]*SPP[10] - (P[11][1]*q0)/2) - SF[5]*(P[2][2] + P[0][2]*SF[6] + P[1][2]*SF[10] + P[3][2]*SF[8] + P[12][2]*SF[14] - P[10][2]*SPP[10] - (P[11][2]*q0)/2) + SF[3]*(P[2][3] + P[0][3]*SF[6] + P[1][3]*SF[10] + P[3][3]*SF[8] + P[12][3]*SF[14] - P[10][3]*SPP[10] - (P[11][3]*q0)/2) + SPP[0]*(P[2][0] + P[0][0]*SF[6] + P[1][0]*SF[10] + P[3][0]*SF[8] + P[12][0]*SF[14] - P[10][0]*SPP[10] - (P[11][0]*q0)/2) + SPP[4]*(P[2][13] + P[0][13]*SF[6] + P[1][13]*SF[10] + P[3][13]*SF[8] + P[12][13]*SF[14] - P[10][13]*SPP[10] - (P[11][13]*q0)/2) - SPP[7]*(P[2][14] + P[0][14]*SF[6] + P[1][14]*SF[10] + P[3][14]*SF[8] + P[12][14]*SF[14] - P[10][14]*SPP[10] - (P[11][14]*q0)/2) - SPP[1]*(P[2][15] + P[0][15]*SF[6] + P[1][15]*SF[10] + P[3][15]*SF[8] + P[12][15]*SF[14] - P[10][15]*SPP[10] - (P[11][15]*q0)/2); +nextP[3][6] = P[3][6] + P[0][6]*SF[7] + P[1][6]*SF[6] + P[2][6]*SF[9] + P[10][6]*SF[15] - P[11][6]*SF[14] - (P[12][6]*q0)/2 + SF[4]*(P[3][1] + P[0][1]*SF[7] + P[1][1]*SF[6] + P[2][1]*SF[9] + P[10][1]*SF[15] - P[11][1]*SF[14] - (P[12][1]*q0)/2) - SF[5]*(P[3][2] + P[0][2]*SF[7] + P[1][2]*SF[6] + P[2][2]*SF[9] + P[10][2]*SF[15] - P[11][2]*SF[14] - (P[12][2]*q0)/2) + SF[3]*(P[3][3] + P[0][3]*SF[7] + P[1][3]*SF[6] + P[2][3]*SF[9] + P[10][3]*SF[15] - P[11][3]*SF[14] - (P[12][3]*q0)/2) + SPP[0]*(P[3][0] + P[0][0]*SF[7] + P[1][0]*SF[6] + P[2][0]*SF[9] + P[10][0]*SF[15] - P[11][0]*SF[14] - (P[12][0]*q0)/2) + SPP[4]*(P[3][13] + P[0][13]*SF[7] + P[1][13]*SF[6] + P[2][13]*SF[9] + P[10][13]*SF[15] - P[11][13]*SF[14] - (P[12][13]*q0)/2) - SPP[7]*(P[3][14] + P[0][14]*SF[7] + P[1][14]*SF[6] + P[2][14]*SF[9] + P[10][14]*SF[15] - P[11][14]*SF[14] - (P[12][14]*q0)/2) - SPP[1]*(P[3][15] + P[0][15]*SF[7] + P[1][15]*SF[6] + P[2][15]*SF[9] + P[10][15]*SF[15] - P[11][15]*SF[14] - (P[12][15]*q0)/2); +nextP[4][6] = P[4][6] + SQ[1] + P[0][6]*SF[5] + P[1][6]*SF[3] - P[3][6]*SF[4] + P[2][6]*SPP[0] + P[13][6]*SPP[3] + P[14][6]*SPP[6] - P[15][6]*SPP[9] + SF[4]*(P[4][1] + P[0][1]*SF[5] + P[1][1]*SF[3] - P[3][1]*SF[4] + P[2][1]*SPP[0] + P[13][1]*SPP[3] + P[14][1]*SPP[6] - P[15][1]*SPP[9]) - SF[5]*(P[4][2] + P[0][2]*SF[5] + P[1][2]*SF[3] - P[3][2]*SF[4] + P[2][2]*SPP[0] + P[13][2]*SPP[3] + P[14][2]*SPP[6] - P[15][2]*SPP[9]) + SF[3]*(P[4][3] + P[0][3]*SF[5] + P[1][3]*SF[3] - P[3][3]*SF[4] + P[2][3]*SPP[0] + P[13][3]*SPP[3] + P[14][3]*SPP[6] - P[15][3]*SPP[9]) + SPP[0]*(P[4][0] + P[0][0]*SF[5] + P[1][0]*SF[3] - P[3][0]*SF[4] + P[2][0]*SPP[0] + P[13][0]*SPP[3] + P[14][0]*SPP[6] - P[15][0]*SPP[9]) + SPP[4]*(P[4][13] + P[0][13]*SF[5] + P[1][13]*SF[3] - P[3][13]*SF[4] + P[2][13]*SPP[0] + P[13][13]*SPP[3] + P[14][13]*SPP[6] - P[15][13]*SPP[9]) - SPP[7]*(P[4][14] + P[0][14]*SF[5] + P[1][14]*SF[3] - P[3][14]*SF[4] + P[2][14]*SPP[0] + P[13][14]*SPP[3] + P[14][14]*SPP[6] - P[15][14]*SPP[9]) - SPP[1]*(P[4][15] + P[0][15]*SF[5] + P[1][15]*SF[3] - P[3][15]*SF[4] + P[2][15]*SPP[0] + P[13][15]*SPP[3] + P[14][15]*SPP[6] - P[15][15]*SPP[9]); +nextP[5][6] = P[5][6] + SQ[0] + P[0][6]*SF[4] + P[2][6]*SF[3] + P[3][6]*SF[5] - P[1][6]*SPP[0] - P[13][6]*SPP[8] + P[14][6]*SPP[2] + P[15][6]*SPP[5] + SF[4]*(P[5][1] + P[0][1]*SF[4] + P[2][1]*SF[3] + P[3][1]*SF[5] - P[1][1]*SPP[0] - P[13][1]*SPP[8] + P[14][1]*SPP[2] + P[15][1]*SPP[5]) - SF[5]*(P[5][2] + P[0][2]*SF[4] + P[2][2]*SF[3] + P[3][2]*SF[5] - P[1][2]*SPP[0] - P[13][2]*SPP[8] + P[14][2]*SPP[2] + P[15][2]*SPP[5]) + SF[3]*(P[5][3] + P[0][3]*SF[4] + P[2][3]*SF[3] + P[3][3]*SF[5] - P[1][3]*SPP[0] - P[13][3]*SPP[8] + P[14][3]*SPP[2] + P[15][3]*SPP[5]) + SPP[0]*(P[5][0] + P[0][0]*SF[4] + P[2][0]*SF[3] + P[3][0]*SF[5] - P[1][0]*SPP[0] - P[13][0]*SPP[8] + P[14][0]*SPP[2] + P[15][0]*SPP[5]) + SPP[4]*(P[5][13] + P[0][13]*SF[4] + P[2][13]*SF[3] + P[3][13]*SF[5] - P[1][13]*SPP[0] - P[13][13]*SPP[8] + P[14][13]*SPP[2] + P[15][13]*SPP[5]) - SPP[7]*(P[5][14] + P[0][14]*SF[4] + P[2][14]*SF[3] + P[3][14]*SF[5] - P[1][14]*SPP[0] - P[13][14]*SPP[8] + P[14][14]*SPP[2] + P[15][14]*SPP[5]) - SPP[1]*(P[5][15] + P[0][15]*SF[4] + P[2][15]*SF[3] + P[3][15]*SF[5] - P[1][15]*SPP[0] - P[13][15]*SPP[8] + P[14][15]*SPP[2] + P[15][15]*SPP[5]); +nextP[6][6] = P[6][6] + P[1][6]*SF[4] - P[2][6]*SF[5] + P[3][6]*SF[3] + P[0][6]*SPP[0] + P[13][6]*SPP[4] - P[14][6]*SPP[7] - P[15][6]*SPP[1] + dvxVar*sq(SG[6] - 2*q0*q2) + dvyVar*sq(SG[5] + 2*q0*q1) + SF[4]*(P[6][1] + P[1][1]*SF[4] - P[2][1]*SF[5] + P[3][1]*SF[3] + P[0][1]*SPP[0] + P[13][1]*SPP[4] - P[14][1]*SPP[7] - P[15][1]*SPP[1]) - SF[5]*(P[6][2] + P[1][2]*SF[4] - P[2][2]*SF[5] + P[3][2]*SF[3] + P[0][2]*SPP[0] + P[13][2]*SPP[4] - P[14][2]*SPP[7] - P[15][2]*SPP[1]) + SF[3]*(P[6][3] + P[1][3]*SF[4] - P[2][3]*SF[5] + P[3][3]*SF[3] + P[0][3]*SPP[0] + P[13][3]*SPP[4] - P[14][3]*SPP[7] - P[15][3]*SPP[1]) + SPP[0]*(P[6][0] + P[1][0]*SF[4] - P[2][0]*SF[5] + P[3][0]*SF[3] + P[0][0]*SPP[0] + P[13][0]*SPP[4] - P[14][0]*SPP[7] - P[15][0]*SPP[1]) + SPP[4]*(P[6][13] + P[1][13]*SF[4] - P[2][13]*SF[5] + P[3][13]*SF[3] + P[0][13]*SPP[0] + P[13][13]*SPP[4] - P[14][13]*SPP[7] - P[15][13]*SPP[1]) - SPP[7]*(P[6][14] + P[1][14]*SF[4] - P[2][14]*SF[5] + P[3][14]*SF[3] + P[0][14]*SPP[0] + P[13][14]*SPP[4] - P[14][14]*SPP[7] - P[15][14]*SPP[1]) - SPP[1]*(P[6][15] + P[1][15]*SF[4] - P[2][15]*SF[5] + P[3][15]*SF[3] + P[0][15]*SPP[0] + P[13][15]*SPP[4] - P[14][15]*SPP[7] - P[15][15]*SPP[1]) + dvzVar*sq(SG[1] - SG[2] - SG[3] + SG[4]); +nextP[0][7] = P[0][7] + P[1][7]*SF[9] + P[2][7]*SF[11] + P[3][7]*SF[10] + P[10][7]*SF[14] + P[11][7]*SF[15] + P[12][7]*SPP[10] + dt*(P[0][4] + P[1][4]*SF[9] + P[2][4]*SF[11] + P[3][4]*SF[10] + P[10][4]*SF[14] + P[11][4]*SF[15] + P[12][4]*SPP[10]); +nextP[1][7] = P[1][7] + P[0][7]*SF[8] + P[2][7]*SF[7] + P[3][7]*SF[11] - P[12][7]*SF[15] + P[11][7]*SPP[10] - (P[10][7]*q0)/2 + dt*(P[1][4] + P[0][4]*SF[8] + P[2][4]*SF[7] + P[3][4]*SF[11] - P[12][4]*SF[15] + P[11][4]*SPP[10] - (P[10][4]*q0)/2); +nextP[2][7] = P[2][7] + P[0][7]*SF[6] + P[1][7]*SF[10] + P[3][7]*SF[8] + P[12][7]*SF[14] - P[10][7]*SPP[10] - (P[11][7]*q0)/2 + dt*(P[2][4] + P[0][4]*SF[6] + P[1][4]*SF[10] + P[3][4]*SF[8] + P[12][4]*SF[14] - P[10][4]*SPP[10] - (P[11][4]*q0)/2); +nextP[3][7] = P[3][7] + P[0][7]*SF[7] + P[1][7]*SF[6] + P[2][7]*SF[9] + P[10][7]*SF[15] - P[11][7]*SF[14] - (P[12][7]*q0)/2 + dt*(P[3][4] + P[0][4]*SF[7] + P[1][4]*SF[6] + P[2][4]*SF[9] + P[10][4]*SF[15] - P[11][4]*SF[14] - (P[12][4]*q0)/2); +nextP[4][7] = P[4][7] + P[0][7]*SF[5] + P[1][7]*SF[3] - P[3][7]*SF[4] + P[2][7]*SPP[0] + P[13][7]*SPP[3] + P[14][7]*SPP[6] - P[15][7]*SPP[9] + dt*(P[4][4] + P[0][4]*SF[5] + P[1][4]*SF[3] - P[3][4]*SF[4] + P[2][4]*SPP[0] + P[13][4]*SPP[3] + P[14][4]*SPP[6] - P[15][4]*SPP[9]); +nextP[5][7] = P[5][7] + P[0][7]*SF[4] + P[2][7]*SF[3] + P[3][7]*SF[5] - P[1][7]*SPP[0] - P[13][7]*SPP[8] + P[14][7]*SPP[2] + P[15][7]*SPP[5] + dt*(P[5][4] + P[0][4]*SF[4] + P[2][4]*SF[3] + P[3][4]*SF[5] - P[1][4]*SPP[0] - P[13][4]*SPP[8] + P[14][4]*SPP[2] + P[15][4]*SPP[5]); +nextP[6][7] = P[6][7] + P[1][7]*SF[4] - P[2][7]*SF[5] + P[3][7]*SF[3] + P[0][7]*SPP[0] + P[13][7]*SPP[4] - P[14][7]*SPP[7] - P[15][7]*SPP[1] + dt*(P[6][4] + P[1][4]*SF[4] - P[2][4]*SF[5] + P[3][4]*SF[3] + P[0][4]*SPP[0] + P[13][4]*SPP[4] - P[14][4]*SPP[7] - P[15][4]*SPP[1]); nextP[7][7] = P[7][7] + P[4][7]*dt + dt*(P[7][4] + P[4][4]*dt); -nextP[0][8] = P[0][8]*SPP[5] - P[1][8]*SPP[4] + P[2][8]*SPP[7] + P[9][8]*SPP[22] + P[12][8]*SPP[18] + dt*(P[0][5]*SPP[5] - P[1][5]*SPP[4] + P[2][5]*SPP[7] + P[9][5]*SPP[22] + P[12][5]*SPP[18]); -nextP[1][8] = P[1][8]*SPP[6] - P[0][8]*SPP[2] - P[2][8]*SPP[8] + P[10][8]*SPP[22] + P[13][8]*SPP[17] + dt*(P[1][5]*SPP[6] - P[0][5]*SPP[2] - P[2][5]*SPP[8] + P[10][5]*SPP[22] + P[13][5]*SPP[17]); -nextP[2][8] = P[0][8]*SPP[14] - P[1][8]*SPP[3] + P[2][8]*SPP[13] + P[11][8]*SPP[22] + P[14][8]*SPP[16] + dt*(P[0][5]*SPP[14] - P[1][5]*SPP[3] + P[2][5]*SPP[13] + P[11][5]*SPP[22] + P[14][5]*SPP[16]); -nextP[3][8] = P[3][8] + P[0][8]*SPP[1] + P[1][8]*SPP[19] + P[2][8]*SPP[15] - P[15][8]*SPP[21] + dt*(P[3][5] + P[0][5]*SPP[1] + P[1][5]*SPP[19] + P[2][5]*SPP[15] - P[15][5]*SPP[21]); -nextP[4][8] = P[4][8] + P[15][8]*SF[22] + P[0][8]*SPP[20] + P[1][8]*SPP[12] + P[2][8]*SPP[11] + dt*(P[4][5] + P[15][5]*SF[22] + P[0][5]*SPP[20] + P[1][5]*SPP[12] + P[2][5]*SPP[11]); -nextP[5][8] = P[5][8] + P[15][8]*SF[20] - P[0][8]*SPP[9] + P[1][8]*SPP[10] + P[2][8]*SPP[0] + dt*(P[5][5] + P[15][5]*SF[20] - P[0][5]*SPP[9] + P[1][5]*SPP[10] + P[2][5]*SPP[0]); -nextP[6][8] = P[6][8] + P[3][8]*dt + dt*(P[6][5] + P[3][5]*dt); +nextP[0][8] = P[0][8] + P[1][8]*SF[9] + P[2][8]*SF[11] + P[3][8]*SF[10] + P[10][8]*SF[14] + P[11][8]*SF[15] + P[12][8]*SPP[10] + dt*(P[0][5] + P[1][5]*SF[9] + P[2][5]*SF[11] + P[3][5]*SF[10] + P[10][5]*SF[14] + P[11][5]*SF[15] + P[12][5]*SPP[10]); +nextP[1][8] = P[1][8] + P[0][8]*SF[8] + P[2][8]*SF[7] + P[3][8]*SF[11] - P[12][8]*SF[15] + P[11][8]*SPP[10] - (P[10][8]*q0)/2 + dt*(P[1][5] + P[0][5]*SF[8] + P[2][5]*SF[7] + P[3][5]*SF[11] - P[12][5]*SF[15] + P[11][5]*SPP[10] - (P[10][5]*q0)/2); +nextP[2][8] = P[2][8] + P[0][8]*SF[6] + P[1][8]*SF[10] + P[3][8]*SF[8] + P[12][8]*SF[14] - P[10][8]*SPP[10] - (P[11][8]*q0)/2 + dt*(P[2][5] + P[0][5]*SF[6] + P[1][5]*SF[10] + P[3][5]*SF[8] + P[12][5]*SF[14] - P[10][5]*SPP[10] - (P[11][5]*q0)/2); +nextP[3][8] = P[3][8] + P[0][8]*SF[7] + P[1][8]*SF[6] + P[2][8]*SF[9] + P[10][8]*SF[15] - P[11][8]*SF[14] - (P[12][8]*q0)/2 + dt*(P[3][5] + P[0][5]*SF[7] + P[1][5]*SF[6] + P[2][5]*SF[9] + P[10][5]*SF[15] - P[11][5]*SF[14] - (P[12][5]*q0)/2); +nextP[4][8] = P[4][8] + P[0][8]*SF[5] + P[1][8]*SF[3] - P[3][8]*SF[4] + P[2][8]*SPP[0] + P[13][8]*SPP[3] + P[14][8]*SPP[6] - P[15][8]*SPP[9] + dt*(P[4][5] + P[0][5]*SF[5] + P[1][5]*SF[3] - P[3][5]*SF[4] + P[2][5]*SPP[0] + P[13][5]*SPP[3] + P[14][5]*SPP[6] - P[15][5]*SPP[9]); +nextP[5][8] = P[5][8] + P[0][8]*SF[4] + P[2][8]*SF[3] + P[3][8]*SF[5] - P[1][8]*SPP[0] - P[13][8]*SPP[8] + P[14][8]*SPP[2] + P[15][8]*SPP[5] + dt*(P[5][5] + P[0][5]*SF[4] + P[2][5]*SF[3] + P[3][5]*SF[5] - P[1][5]*SPP[0] - P[13][5]*SPP[8] + P[14][5]*SPP[2] + P[15][5]*SPP[5]); +nextP[6][8] = P[6][8] + P[1][8]*SF[4] - P[2][8]*SF[5] + P[3][8]*SF[3] + P[0][8]*SPP[0] + P[13][8]*SPP[4] - P[14][8]*SPP[7] - P[15][8]*SPP[1] + dt*(P[6][5] + P[1][5]*SF[4] - P[2][5]*SF[5] + P[3][5]*SF[3] + P[0][5]*SPP[0] + P[13][5]*SPP[4] - P[14][5]*SPP[7] - P[15][5]*SPP[1]); nextP[7][8] = P[7][8] + P[4][8]*dt + dt*(P[7][5] + P[4][5]*dt); nextP[8][8] = P[8][8] + P[5][8]*dt + dt*(P[8][5] + P[5][5]*dt); -nextP[0][9] = P[0][9]*SPP[5] - P[1][9]*SPP[4] + P[2][9]*SPP[7] + P[9][9]*SPP[22] + P[12][9]*SPP[18]; -nextP[1][9] = P[1][9]*SPP[6] - P[0][9]*SPP[2] - P[2][9]*SPP[8] + P[10][9]*SPP[22] + P[13][9]*SPP[17]; -nextP[2][9] = P[0][9]*SPP[14] - P[1][9]*SPP[3] + P[2][9]*SPP[13] + P[11][9]*SPP[22] + P[14][9]*SPP[16]; -nextP[3][9] = P[3][9] + P[0][9]*SPP[1] + P[1][9]*SPP[19] + P[2][9]*SPP[15] - P[15][9]*SPP[21]; -nextP[4][9] = P[4][9] + P[15][9]*SF[22] + P[0][9]*SPP[20] + P[1][9]*SPP[12] + P[2][9]*SPP[11]; -nextP[5][9] = P[5][9] + P[15][9]*SF[20] - P[0][9]*SPP[9] + P[1][9]*SPP[10] + P[2][9]*SPP[0]; -nextP[6][9] = P[6][9] + P[3][9]*dt; -nextP[7][9] = P[7][9] + P[4][9]*dt; -nextP[8][9] = P[8][9] + P[5][9]*dt; -nextP[9][9] = P[9][9]; -nextP[0][10] = P[0][10]*SPP[5] - P[1][10]*SPP[4] + P[2][10]*SPP[7] + P[9][10]*SPP[22] + P[12][10]*SPP[18]; -nextP[1][10] = P[1][10]*SPP[6] - P[0][10]*SPP[2] - P[2][10]*SPP[8] + P[10][10]*SPP[22] + P[13][10]*SPP[17]; -nextP[2][10] = P[0][10]*SPP[14] - P[1][10]*SPP[3] + P[2][10]*SPP[13] + P[11][10]*SPP[22] + P[14][10]*SPP[16]; -nextP[3][10] = P[3][10] + P[0][10]*SPP[1] + P[1][10]*SPP[19] + P[2][10]*SPP[15] - P[15][10]*SPP[21]; -nextP[4][10] = P[4][10] + P[15][10]*SF[22] + P[0][10]*SPP[20] + P[1][10]*SPP[12] + P[2][10]*SPP[11]; -nextP[5][10] = P[5][10] + P[15][10]*SF[20] - P[0][10]*SPP[9] + P[1][10]*SPP[10] + P[2][10]*SPP[0]; -nextP[6][10] = P[6][10] + P[3][10]*dt; +nextP[0][9] = P[0][9] + P[1][9]*SF[9] + P[2][9]*SF[11] + P[3][9]*SF[10] + P[10][9]*SF[14] + P[11][9]*SF[15] + P[12][9]*SPP[10] + dt*(P[0][6] + P[1][6]*SF[9] + P[2][6]*SF[11] + P[3][6]*SF[10] + P[10][6]*SF[14] + P[11][6]*SF[15] + P[12][6]*SPP[10]); +nextP[1][9] = P[1][9] + P[0][9]*SF[8] + P[2][9]*SF[7] + P[3][9]*SF[11] - P[12][9]*SF[15] + P[11][9]*SPP[10] - (P[10][9]*q0)/2 + dt*(P[1][6] + P[0][6]*SF[8] + P[2][6]*SF[7] + P[3][6]*SF[11] - P[12][6]*SF[15] + P[11][6]*SPP[10] - (P[10][6]*q0)/2); +nextP[2][9] = P[2][9] + P[0][9]*SF[6] + P[1][9]*SF[10] + P[3][9]*SF[8] + P[12][9]*SF[14] - P[10][9]*SPP[10] - (P[11][9]*q0)/2 + dt*(P[2][6] + P[0][6]*SF[6] + P[1][6]*SF[10] + P[3][6]*SF[8] + P[12][6]*SF[14] - P[10][6]*SPP[10] - (P[11][6]*q0)/2); +nextP[3][9] = P[3][9] + P[0][9]*SF[7] + P[1][9]*SF[6] + P[2][9]*SF[9] + P[10][9]*SF[15] - P[11][9]*SF[14] - (P[12][9]*q0)/2 + dt*(P[3][6] + P[0][6]*SF[7] + P[1][6]*SF[6] + P[2][6]*SF[9] + P[10][6]*SF[15] - P[11][6]*SF[14] - (P[12][6]*q0)/2); +nextP[4][9] = P[4][9] + P[0][9]*SF[5] + P[1][9]*SF[3] - P[3][9]*SF[4] + P[2][9]*SPP[0] + P[13][9]*SPP[3] + P[14][9]*SPP[6] - P[15][9]*SPP[9] + dt*(P[4][6] + P[0][6]*SF[5] + P[1][6]*SF[3] - P[3][6]*SF[4] + P[2][6]*SPP[0] + P[13][6]*SPP[3] + P[14][6]*SPP[6] - P[15][6]*SPP[9]); +nextP[5][9] = P[5][9] + P[0][9]*SF[4] + P[2][9]*SF[3] + P[3][9]*SF[5] - P[1][9]*SPP[0] - P[13][9]*SPP[8] + P[14][9]*SPP[2] + P[15][9]*SPP[5] + dt*(P[5][6] + P[0][6]*SF[4] + P[2][6]*SF[3] + P[3][6]*SF[5] - P[1][6]*SPP[0] - P[13][6]*SPP[8] + P[14][6]*SPP[2] + P[15][6]*SPP[5]); +nextP[6][9] = P[6][9] + P[1][9]*SF[4] - P[2][9]*SF[5] + P[3][9]*SF[3] + P[0][9]*SPP[0] + P[13][9]*SPP[4] - P[14][9]*SPP[7] - P[15][9]*SPP[1] + dt*(P[6][6] + P[1][6]*SF[4] - P[2][6]*SF[5] + P[3][6]*SF[3] + P[0][6]*SPP[0] + P[13][6]*SPP[4] - P[14][6]*SPP[7] - P[15][6]*SPP[1]); +nextP[7][9] = P[7][9] + P[4][9]*dt + dt*(P[7][6] + P[4][6]*dt); +nextP[8][9] = P[8][9] + P[5][9]*dt + dt*(P[8][6] + P[5][6]*dt); +nextP[9][9] = P[9][9] + P[6][9]*dt + dt*(P[9][6] + P[6][6]*dt); +nextP[0][10] = P[0][10] + P[1][10]*SF[9] + P[2][10]*SF[11] + P[3][10]*SF[10] + P[10][10]*SF[14] + P[11][10]*SF[15] + P[12][10]*SPP[10]; +nextP[1][10] = P[1][10] + P[0][10]*SF[8] + P[2][10]*SF[7] + P[3][10]*SF[11] - P[12][10]*SF[15] + P[11][10]*SPP[10] - (P[10][10]*q0)/2; +nextP[2][10] = P[2][10] + P[0][10]*SF[6] + P[1][10]*SF[10] + P[3][10]*SF[8] + P[12][10]*SF[14] - P[10][10]*SPP[10] - (P[11][10]*q0)/2; +nextP[3][10] = P[3][10] + P[0][10]*SF[7] + P[1][10]*SF[6] + P[2][10]*SF[9] + P[10][10]*SF[15] - P[11][10]*SF[14] - (P[12][10]*q0)/2; +nextP[4][10] = P[4][10] + P[0][10]*SF[5] + P[1][10]*SF[3] - P[3][10]*SF[4] + P[2][10]*SPP[0] + P[13][10]*SPP[3] + P[14][10]*SPP[6] - P[15][10]*SPP[9]; +nextP[5][10] = P[5][10] + P[0][10]*SF[4] + P[2][10]*SF[3] + P[3][10]*SF[5] - P[1][10]*SPP[0] - P[13][10]*SPP[8] + P[14][10]*SPP[2] + P[15][10]*SPP[5]; +nextP[6][10] = P[6][10] + P[1][10]*SF[4] - P[2][10]*SF[5] + P[3][10]*SF[3] + P[0][10]*SPP[0] + P[13][10]*SPP[4] - P[14][10]*SPP[7] - P[15][10]*SPP[1]; nextP[7][10] = P[7][10] + P[4][10]*dt; nextP[8][10] = P[8][10] + P[5][10]*dt; -nextP[9][10] = P[9][10]; +nextP[9][10] = P[9][10] + P[6][10]*dt; nextP[10][10] = P[10][10]; -nextP[0][11] = P[0][11]*SPP[5] - P[1][11]*SPP[4] + P[2][11]*SPP[7] + P[9][11]*SPP[22] + P[12][11]*SPP[18]; -nextP[1][11] = P[1][11]*SPP[6] - P[0][11]*SPP[2] - P[2][11]*SPP[8] + P[10][11]*SPP[22] + P[13][11]*SPP[17]; -nextP[2][11] = P[0][11]*SPP[14] - P[1][11]*SPP[3] + P[2][11]*SPP[13] + P[11][11]*SPP[22] + P[14][11]*SPP[16]; -nextP[3][11] = P[3][11] + P[0][11]*SPP[1] + P[1][11]*SPP[19] + P[2][11]*SPP[15] - P[15][11]*SPP[21]; -nextP[4][11] = P[4][11] + P[15][11]*SF[22] + P[0][11]*SPP[20] + P[1][11]*SPP[12] + P[2][11]*SPP[11]; -nextP[5][11] = P[5][11] + P[15][11]*SF[20] - P[0][11]*SPP[9] + P[1][11]*SPP[10] + P[2][11]*SPP[0]; -nextP[6][11] = P[6][11] + P[3][11]*dt; +nextP[0][11] = P[0][11] + P[1][11]*SF[9] + P[2][11]*SF[11] + P[3][11]*SF[10] + P[10][11]*SF[14] + P[11][11]*SF[15] + P[12][11]*SPP[10]; +nextP[1][11] = P[1][11] + P[0][11]*SF[8] + P[2][11]*SF[7] + P[3][11]*SF[11] - P[12][11]*SF[15] + P[11][11]*SPP[10] - (P[10][11]*q0)/2; +nextP[2][11] = P[2][11] + P[0][11]*SF[6] + P[1][11]*SF[10] + P[3][11]*SF[8] + P[12][11]*SF[14] - P[10][11]*SPP[10] - (P[11][11]*q0)/2; +nextP[3][11] = P[3][11] + P[0][11]*SF[7] + P[1][11]*SF[6] + P[2][11]*SF[9] + P[10][11]*SF[15] - P[11][11]*SF[14] - (P[12][11]*q0)/2; +nextP[4][11] = P[4][11] + P[0][11]*SF[5] + P[1][11]*SF[3] - P[3][11]*SF[4] + P[2][11]*SPP[0] + P[13][11]*SPP[3] + P[14][11]*SPP[6] - P[15][11]*SPP[9]; +nextP[5][11] = P[5][11] + P[0][11]*SF[4] + P[2][11]*SF[3] + P[3][11]*SF[5] - P[1][11]*SPP[0] - P[13][11]*SPP[8] + P[14][11]*SPP[2] + P[15][11]*SPP[5]; +nextP[6][11] = P[6][11] + P[1][11]*SF[4] - P[2][11]*SF[5] + P[3][11]*SF[3] + P[0][11]*SPP[0] + P[13][11]*SPP[4] - P[14][11]*SPP[7] - P[15][11]*SPP[1]; nextP[7][11] = P[7][11] + P[4][11]*dt; nextP[8][11] = P[8][11] + P[5][11]*dt; -nextP[9][11] = P[9][11]; +nextP[9][11] = P[9][11] + P[6][11]*dt; nextP[10][11] = P[10][11]; nextP[11][11] = P[11][11]; -nextP[0][12] = P[0][12]*SPP[5] - P[1][12]*SPP[4] + P[2][12]*SPP[7] + P[9][12]*SPP[22] + P[12][12]*SPP[18]; -nextP[1][12] = P[1][12]*SPP[6] - P[0][12]*SPP[2] - P[2][12]*SPP[8] + P[10][12]*SPP[22] + P[13][12]*SPP[17]; -nextP[2][12] = P[0][12]*SPP[14] - P[1][12]*SPP[3] + P[2][12]*SPP[13] + P[11][12]*SPP[22] + P[14][12]*SPP[16]; -nextP[3][12] = P[3][12] + P[0][12]*SPP[1] + P[1][12]*SPP[19] + P[2][12]*SPP[15] - P[15][12]*SPP[21]; -nextP[4][12] = P[4][12] + P[15][12]*SF[22] + P[0][12]*SPP[20] + P[1][12]*SPP[12] + P[2][12]*SPP[11]; -nextP[5][12] = P[5][12] + P[15][12]*SF[20] - P[0][12]*SPP[9] + P[1][12]*SPP[10] + P[2][12]*SPP[0]; -nextP[6][12] = P[6][12] + P[3][12]*dt; +nextP[0][12] = P[0][12] + P[1][12]*SF[9] + P[2][12]*SF[11] + P[3][12]*SF[10] + P[10][12]*SF[14] + P[11][12]*SF[15] + P[12][12]*SPP[10]; +nextP[1][12] = P[1][12] + P[0][12]*SF[8] + P[2][12]*SF[7] + P[3][12]*SF[11] - P[12][12]*SF[15] + P[11][12]*SPP[10] - (P[10][12]*q0)/2; +nextP[2][12] = P[2][12] + P[0][12]*SF[6] + P[1][12]*SF[10] + P[3][12]*SF[8] + P[12][12]*SF[14] - P[10][12]*SPP[10] - (P[11][12]*q0)/2; +nextP[3][12] = P[3][12] + P[0][12]*SF[7] + P[1][12]*SF[6] + P[2][12]*SF[9] + P[10][12]*SF[15] - P[11][12]*SF[14] - (P[12][12]*q0)/2; +nextP[4][12] = P[4][12] + P[0][12]*SF[5] + P[1][12]*SF[3] - P[3][12]*SF[4] + P[2][12]*SPP[0] + P[13][12]*SPP[3] + P[14][12]*SPP[6] - P[15][12]*SPP[9]; +nextP[5][12] = P[5][12] + P[0][12]*SF[4] + P[2][12]*SF[3] + P[3][12]*SF[5] - P[1][12]*SPP[0] - P[13][12]*SPP[8] + P[14][12]*SPP[2] + P[15][12]*SPP[5]; +nextP[6][12] = P[6][12] + P[1][12]*SF[4] - P[2][12]*SF[5] + P[3][12]*SF[3] + P[0][12]*SPP[0] + P[13][12]*SPP[4] - P[14][12]*SPP[7] - P[15][12]*SPP[1]; nextP[7][12] = P[7][12] + P[4][12]*dt; nextP[8][12] = P[8][12] + P[5][12]*dt; -nextP[9][12] = P[9][12]; +nextP[9][12] = P[9][12] + P[6][12]*dt; nextP[10][12] = P[10][12]; nextP[11][12] = P[11][12]; nextP[12][12] = P[12][12]; -nextP[0][13] = P[0][13]*SPP[5] - P[1][13]*SPP[4] + P[2][13]*SPP[7] + P[9][13]*SPP[22] + P[12][13]*SPP[18]; -nextP[1][13] = P[1][13]*SPP[6] - P[0][13]*SPP[2] - P[2][13]*SPP[8] + P[10][13]*SPP[22] + P[13][13]*SPP[17]; -nextP[2][13] = P[0][13]*SPP[14] - P[1][13]*SPP[3] + P[2][13]*SPP[13] + P[11][13]*SPP[22] + P[14][13]*SPP[16]; -nextP[3][13] = P[3][13] + P[0][13]*SPP[1] + P[1][13]*SPP[19] + P[2][13]*SPP[15] - P[15][13]*SPP[21]; -nextP[4][13] = P[4][13] + P[15][13]*SF[22] + P[0][13]*SPP[20] + P[1][13]*SPP[12] + P[2][13]*SPP[11]; -nextP[5][13] = P[5][13] + P[15][13]*SF[20] - P[0][13]*SPP[9] + P[1][13]*SPP[10] + P[2][13]*SPP[0]; -nextP[6][13] = P[6][13] + P[3][13]*dt; +nextP[0][13] = P[0][13] + P[1][13]*SF[9] + P[2][13]*SF[11] + P[3][13]*SF[10] + P[10][13]*SF[14] + P[11][13]*SF[15] + P[12][13]*SPP[10]; +nextP[1][13] = P[1][13] + P[0][13]*SF[8] + P[2][13]*SF[7] + P[3][13]*SF[11] - P[12][13]*SF[15] + P[11][13]*SPP[10] - (P[10][13]*q0)/2; +nextP[2][13] = P[2][13] + P[0][13]*SF[6] + P[1][13]*SF[10] + P[3][13]*SF[8] + P[12][13]*SF[14] - P[10][13]*SPP[10] - (P[11][13]*q0)/2; +nextP[3][13] = P[3][13] + P[0][13]*SF[7] + P[1][13]*SF[6] + P[2][13]*SF[9] + P[10][13]*SF[15] - P[11][13]*SF[14] - (P[12][13]*q0)/2; +nextP[4][13] = P[4][13] + P[0][13]*SF[5] + P[1][13]*SF[3] - P[3][13]*SF[4] + P[2][13]*SPP[0] + P[13][13]*SPP[3] + P[14][13]*SPP[6] - P[15][13]*SPP[9]; +nextP[5][13] = P[5][13] + P[0][13]*SF[4] + P[2][13]*SF[3] + P[3][13]*SF[5] - P[1][13]*SPP[0] - P[13][13]*SPP[8] + P[14][13]*SPP[2] + P[15][13]*SPP[5]; +nextP[6][13] = P[6][13] + P[1][13]*SF[4] - P[2][13]*SF[5] + P[3][13]*SF[3] + P[0][13]*SPP[0] + P[13][13]*SPP[4] - P[14][13]*SPP[7] - P[15][13]*SPP[1]; nextP[7][13] = P[7][13] + P[4][13]*dt; nextP[8][13] = P[8][13] + P[5][13]*dt; -nextP[9][13] = P[9][13]; +nextP[9][13] = P[9][13] + P[6][13]*dt; nextP[10][13] = P[10][13]; nextP[11][13] = P[11][13]; nextP[12][13] = P[12][13]; nextP[13][13] = P[13][13]; -nextP[0][14] = P[0][14]*SPP[5] - P[1][14]*SPP[4] + P[2][14]*SPP[7] + P[9][14]*SPP[22] + P[12][14]*SPP[18]; -nextP[1][14] = P[1][14]*SPP[6] - P[0][14]*SPP[2] - P[2][14]*SPP[8] + P[10][14]*SPP[22] + P[13][14]*SPP[17]; -nextP[2][14] = P[0][14]*SPP[14] - P[1][14]*SPP[3] + P[2][14]*SPP[13] + P[11][14]*SPP[22] + P[14][14]*SPP[16]; -nextP[3][14] = P[3][14] + P[0][14]*SPP[1] + P[1][14]*SPP[19] + P[2][14]*SPP[15] - P[15][14]*SPP[21]; -nextP[4][14] = P[4][14] + P[15][14]*SF[22] + P[0][14]*SPP[20] + P[1][14]*SPP[12] + P[2][14]*SPP[11]; -nextP[5][14] = P[5][14] + P[15][14]*SF[20] - P[0][14]*SPP[9] + P[1][14]*SPP[10] + P[2][14]*SPP[0]; -nextP[6][14] = P[6][14] + P[3][14]*dt; +nextP[0][14] = P[0][14] + P[1][14]*SF[9] + P[2][14]*SF[11] + P[3][14]*SF[10] + P[10][14]*SF[14] + P[11][14]*SF[15] + P[12][14]*SPP[10]; +nextP[1][14] = P[1][14] + P[0][14]*SF[8] + P[2][14]*SF[7] + P[3][14]*SF[11] - P[12][14]*SF[15] + P[11][14]*SPP[10] - (P[10][14]*q0)/2; +nextP[2][14] = P[2][14] + P[0][14]*SF[6] + P[1][14]*SF[10] + P[3][14]*SF[8] + P[12][14]*SF[14] - P[10][14]*SPP[10] - (P[11][14]*q0)/2; +nextP[3][14] = P[3][14] + P[0][14]*SF[7] + P[1][14]*SF[6] + P[2][14]*SF[9] + P[10][14]*SF[15] - P[11][14]*SF[14] - (P[12][14]*q0)/2; +nextP[4][14] = P[4][14] + P[0][14]*SF[5] + P[1][14]*SF[3] - P[3][14]*SF[4] + P[2][14]*SPP[0] + P[13][14]*SPP[3] + P[14][14]*SPP[6] - P[15][14]*SPP[9]; +nextP[5][14] = P[5][14] + P[0][14]*SF[4] + P[2][14]*SF[3] + P[3][14]*SF[5] - P[1][14]*SPP[0] - P[13][14]*SPP[8] + P[14][14]*SPP[2] + P[15][14]*SPP[5]; +nextP[6][14] = P[6][14] + P[1][14]*SF[4] - P[2][14]*SF[5] + P[3][14]*SF[3] + P[0][14]*SPP[0] + P[13][14]*SPP[4] - P[14][14]*SPP[7] - P[15][14]*SPP[1]; nextP[7][14] = P[7][14] + P[4][14]*dt; nextP[8][14] = P[8][14] + P[5][14]*dt; -nextP[9][14] = P[9][14]; +nextP[9][14] = P[9][14] + P[6][14]*dt; nextP[10][14] = P[10][14]; nextP[11][14] = P[11][14]; nextP[12][14] = P[12][14]; nextP[13][14] = P[13][14]; nextP[14][14] = P[14][14]; -nextP[0][15] = P[0][15]*SPP[5] - P[1][15]*SPP[4] + P[2][15]*SPP[7] + P[9][15]*SPP[22] + P[12][15]*SPP[18]; -nextP[1][15] = P[1][15]*SPP[6] - P[0][15]*SPP[2] - P[2][15]*SPP[8] + P[10][15]*SPP[22] + P[13][15]*SPP[17]; -nextP[2][15] = P[0][15]*SPP[14] - P[1][15]*SPP[3] + P[2][15]*SPP[13] + P[11][15]*SPP[22] + P[14][15]*SPP[16]; -nextP[3][15] = P[3][15] + P[0][15]*SPP[1] + P[1][15]*SPP[19] + P[2][15]*SPP[15] - P[15][15]*SPP[21]; -nextP[4][15] = P[4][15] + P[15][15]*SF[22] + P[0][15]*SPP[20] + P[1][15]*SPP[12] + P[2][15]*SPP[11]; -nextP[5][15] = P[5][15] + P[15][15]*SF[20] - P[0][15]*SPP[9] + P[1][15]*SPP[10] + P[2][15]*SPP[0]; -nextP[6][15] = P[6][15] + P[3][15]*dt; +nextP[0][15] = P[0][15] + P[1][15]*SF[9] + P[2][15]*SF[11] + P[3][15]*SF[10] + P[10][15]*SF[14] + P[11][15]*SF[15] + P[12][15]*SPP[10]; +nextP[1][15] = P[1][15] + P[0][15]*SF[8] + P[2][15]*SF[7] + P[3][15]*SF[11] - P[12][15]*SF[15] + P[11][15]*SPP[10] - (P[10][15]*q0)/2; +nextP[2][15] = P[2][15] + P[0][15]*SF[6] + P[1][15]*SF[10] + P[3][15]*SF[8] + P[12][15]*SF[14] - P[10][15]*SPP[10] - (P[11][15]*q0)/2; +nextP[3][15] = P[3][15] + P[0][15]*SF[7] + P[1][15]*SF[6] + P[2][15]*SF[9] + P[10][15]*SF[15] - P[11][15]*SF[14] - (P[12][15]*q0)/2; +nextP[4][15] = P[4][15] + P[0][15]*SF[5] + P[1][15]*SF[3] - P[3][15]*SF[4] + P[2][15]*SPP[0] + P[13][15]*SPP[3] + P[14][15]*SPP[6] - P[15][15]*SPP[9]; +nextP[5][15] = P[5][15] + P[0][15]*SF[4] + P[2][15]*SF[3] + P[3][15]*SF[5] - P[1][15]*SPP[0] - P[13][15]*SPP[8] + P[14][15]*SPP[2] + P[15][15]*SPP[5]; +nextP[6][15] = P[6][15] + P[1][15]*SF[4] - P[2][15]*SF[5] + P[3][15]*SF[3] + P[0][15]*SPP[0] + P[13][15]*SPP[4] - P[14][15]*SPP[7] - P[15][15]*SPP[1]; nextP[7][15] = P[7][15] + P[4][15]*dt; nextP[8][15] = P[8][15] + P[5][15]*dt; -nextP[9][15] = P[9][15]; +nextP[9][15] = P[9][15] + P[6][15]*dt; nextP[10][15] = P[10][15]; nextP[11][15] = P[11][15]; nextP[12][15] = P[12][15]; nextP[13][15] = P[13][15]; nextP[14][15] = P[14][15]; nextP[15][15] = P[15][15]; -nextP[0][16] = P[0][16]*SPP[5] - P[1][16]*SPP[4] + P[2][16]*SPP[7] + P[9][16]*SPP[22] + P[12][16]*SPP[18]; -nextP[1][16] = P[1][16]*SPP[6] - P[0][16]*SPP[2] - P[2][16]*SPP[8] + P[10][16]*SPP[22] + P[13][16]*SPP[17]; -nextP[2][16] = P[0][16]*SPP[14] - P[1][16]*SPP[3] + P[2][16]*SPP[13] + P[11][16]*SPP[22] + P[14][16]*SPP[16]; -nextP[3][16] = P[3][16] + P[0][16]*SPP[1] + P[1][16]*SPP[19] + P[2][16]*SPP[15] - P[15][16]*SPP[21]; -nextP[4][16] = P[4][16] + P[15][16]*SF[22] + P[0][16]*SPP[20] + P[1][16]*SPP[12] + P[2][16]*SPP[11]; -nextP[5][16] = P[5][16] + P[15][16]*SF[20] - P[0][16]*SPP[9] + P[1][16]*SPP[10] + P[2][16]*SPP[0]; -nextP[6][16] = P[6][16] + P[3][16]*dt; +nextP[0][16] = P[0][16] + P[1][16]*SF[9] + P[2][16]*SF[11] + P[3][16]*SF[10] + P[10][16]*SF[14] + P[11][16]*SF[15] + P[12][16]*SPP[10]; +nextP[1][16] = P[1][16] + P[0][16]*SF[8] + P[2][16]*SF[7] + P[3][16]*SF[11] - P[12][16]*SF[15] + P[11][16]*SPP[10] - (P[10][16]*q0)/2; +nextP[2][16] = P[2][16] + P[0][16]*SF[6] + P[1][16]*SF[10] + P[3][16]*SF[8] + P[12][16]*SF[14] - P[10][16]*SPP[10] - (P[11][16]*q0)/2; +nextP[3][16] = P[3][16] + P[0][16]*SF[7] + P[1][16]*SF[6] + P[2][16]*SF[9] + P[10][16]*SF[15] - P[11][16]*SF[14] - (P[12][16]*q0)/2; +nextP[4][16] = P[4][16] + P[0][16]*SF[5] + P[1][16]*SF[3] - P[3][16]*SF[4] + P[2][16]*SPP[0] + P[13][16]*SPP[3] + P[14][16]*SPP[6] - P[15][16]*SPP[9]; +nextP[5][16] = P[5][16] + P[0][16]*SF[4] + P[2][16]*SF[3] + P[3][16]*SF[5] - P[1][16]*SPP[0] - P[13][16]*SPP[8] + P[14][16]*SPP[2] + P[15][16]*SPP[5]; +nextP[6][16] = P[6][16] + P[1][16]*SF[4] - P[2][16]*SF[5] + P[3][16]*SF[3] + P[0][16]*SPP[0] + P[13][16]*SPP[4] - P[14][16]*SPP[7] - P[15][16]*SPP[1]; nextP[7][16] = P[7][16] + P[4][16]*dt; nextP[8][16] = P[8][16] + P[5][16]*dt; -nextP[9][16] = P[9][16]; +nextP[9][16] = P[9][16] + P[6][16]*dt; nextP[10][16] = P[10][16]; nextP[11][16] = P[11][16]; nextP[12][16] = P[12][16]; @@ -219,16 +207,16 @@ nextP[13][16] = P[13][16]; nextP[14][16] = P[14][16]; nextP[15][16] = P[15][16]; nextP[16][16] = P[16][16]; -nextP[0][17] = P[0][17]*SPP[5] - P[1][17]*SPP[4] + P[2][17]*SPP[7] + P[9][17]*SPP[22] + P[12][17]*SPP[18]; -nextP[1][17] = P[1][17]*SPP[6] - P[0][17]*SPP[2] - P[2][17]*SPP[8] + P[10][17]*SPP[22] + P[13][17]*SPP[17]; -nextP[2][17] = P[0][17]*SPP[14] - P[1][17]*SPP[3] + P[2][17]*SPP[13] + P[11][17]*SPP[22] + P[14][17]*SPP[16]; -nextP[3][17] = P[3][17] + P[0][17]*SPP[1] + P[1][17]*SPP[19] + P[2][17]*SPP[15] - P[15][17]*SPP[21]; -nextP[4][17] = P[4][17] + P[15][17]*SF[22] + P[0][17]*SPP[20] + P[1][17]*SPP[12] + P[2][17]*SPP[11]; -nextP[5][17] = P[5][17] + P[15][17]*SF[20] - P[0][17]*SPP[9] + P[1][17]*SPP[10] + P[2][17]*SPP[0]; -nextP[6][17] = P[6][17] + P[3][17]*dt; +nextP[0][17] = P[0][17] + P[1][17]*SF[9] + P[2][17]*SF[11] + P[3][17]*SF[10] + P[10][17]*SF[14] + P[11][17]*SF[15] + P[12][17]*SPP[10]; +nextP[1][17] = P[1][17] + P[0][17]*SF[8] + P[2][17]*SF[7] + P[3][17]*SF[11] - P[12][17]*SF[15] + P[11][17]*SPP[10] - (P[10][17]*q0)/2; +nextP[2][17] = P[2][17] + P[0][17]*SF[6] + P[1][17]*SF[10] + P[3][17]*SF[8] + P[12][17]*SF[14] - P[10][17]*SPP[10] - (P[11][17]*q0)/2; +nextP[3][17] = P[3][17] + P[0][17]*SF[7] + P[1][17]*SF[6] + P[2][17]*SF[9] + P[10][17]*SF[15] - P[11][17]*SF[14] - (P[12][17]*q0)/2; +nextP[4][17] = P[4][17] + P[0][17]*SF[5] + P[1][17]*SF[3] - P[3][17]*SF[4] + P[2][17]*SPP[0] + P[13][17]*SPP[3] + P[14][17]*SPP[6] - P[15][17]*SPP[9]; +nextP[5][17] = P[5][17] + P[0][17]*SF[4] + P[2][17]*SF[3] + P[3][17]*SF[5] - P[1][17]*SPP[0] - P[13][17]*SPP[8] + P[14][17]*SPP[2] + P[15][17]*SPP[5]; +nextP[6][17] = P[6][17] + P[1][17]*SF[4] - P[2][17]*SF[5] + P[3][17]*SF[3] + P[0][17]*SPP[0] + P[13][17]*SPP[4] - P[14][17]*SPP[7] - P[15][17]*SPP[1]; nextP[7][17] = P[7][17] + P[4][17]*dt; nextP[8][17] = P[8][17] + P[5][17]*dt; -nextP[9][17] = P[9][17]; +nextP[9][17] = P[9][17] + P[6][17]*dt; nextP[10][17] = P[10][17]; nextP[11][17] = P[11][17]; nextP[12][17] = P[12][17]; @@ -237,16 +225,16 @@ nextP[14][17] = P[14][17]; nextP[15][17] = P[15][17]; nextP[16][17] = P[16][17]; nextP[17][17] = P[17][17]; -nextP[0][18] = P[0][18]*SPP[5] - P[1][18]*SPP[4] + P[2][18]*SPP[7] + P[9][18]*SPP[22] + P[12][18]*SPP[18]; -nextP[1][18] = P[1][18]*SPP[6] - P[0][18]*SPP[2] - P[2][18]*SPP[8] + P[10][18]*SPP[22] + P[13][18]*SPP[17]; -nextP[2][18] = P[0][18]*SPP[14] - P[1][18]*SPP[3] + P[2][18]*SPP[13] + P[11][18]*SPP[22] + P[14][18]*SPP[16]; -nextP[3][18] = P[3][18] + P[0][18]*SPP[1] + P[1][18]*SPP[19] + P[2][18]*SPP[15] - P[15][18]*SPP[21]; -nextP[4][18] = P[4][18] + P[15][18]*SF[22] + P[0][18]*SPP[20] + P[1][18]*SPP[12] + P[2][18]*SPP[11]; -nextP[5][18] = P[5][18] + P[15][18]*SF[20] - P[0][18]*SPP[9] + P[1][18]*SPP[10] + P[2][18]*SPP[0]; -nextP[6][18] = P[6][18] + P[3][18]*dt; +nextP[0][18] = P[0][18] + P[1][18]*SF[9] + P[2][18]*SF[11] + P[3][18]*SF[10] + P[10][18]*SF[14] + P[11][18]*SF[15] + P[12][18]*SPP[10]; +nextP[1][18] = P[1][18] + P[0][18]*SF[8] + P[2][18]*SF[7] + P[3][18]*SF[11] - P[12][18]*SF[15] + P[11][18]*SPP[10] - (P[10][18]*q0)/2; +nextP[2][18] = P[2][18] + P[0][18]*SF[6] + P[1][18]*SF[10] + P[3][18]*SF[8] + P[12][18]*SF[14] - P[10][18]*SPP[10] - (P[11][18]*q0)/2; +nextP[3][18] = P[3][18] + P[0][18]*SF[7] + P[1][18]*SF[6] + P[2][18]*SF[9] + P[10][18]*SF[15] - P[11][18]*SF[14] - (P[12][18]*q0)/2; +nextP[4][18] = P[4][18] + P[0][18]*SF[5] + P[1][18]*SF[3] - P[3][18]*SF[4] + P[2][18]*SPP[0] + P[13][18]*SPP[3] + P[14][18]*SPP[6] - P[15][18]*SPP[9]; +nextP[5][18] = P[5][18] + P[0][18]*SF[4] + P[2][18]*SF[3] + P[3][18]*SF[5] - P[1][18]*SPP[0] - P[13][18]*SPP[8] + P[14][18]*SPP[2] + P[15][18]*SPP[5]; +nextP[6][18] = P[6][18] + P[1][18]*SF[4] - P[2][18]*SF[5] + P[3][18]*SF[3] + P[0][18]*SPP[0] + P[13][18]*SPP[4] - P[14][18]*SPP[7] - P[15][18]*SPP[1]; nextP[7][18] = P[7][18] + P[4][18]*dt; nextP[8][18] = P[8][18] + P[5][18]*dt; -nextP[9][18] = P[9][18]; +nextP[9][18] = P[9][18] + P[6][18]*dt; nextP[10][18] = P[10][18]; nextP[11][18] = P[11][18]; nextP[12][18] = P[12][18]; @@ -256,16 +244,16 @@ nextP[15][18] = P[15][18]; nextP[16][18] = P[16][18]; nextP[17][18] = P[17][18]; nextP[18][18] = P[18][18]; -nextP[0][19] = P[0][19]*SPP[5] - P[1][19]*SPP[4] + P[2][19]*SPP[7] + P[9][19]*SPP[22] + P[12][19]*SPP[18]; -nextP[1][19] = P[1][19]*SPP[6] - P[0][19]*SPP[2] - P[2][19]*SPP[8] + P[10][19]*SPP[22] + P[13][19]*SPP[17]; -nextP[2][19] = P[0][19]*SPP[14] - P[1][19]*SPP[3] + P[2][19]*SPP[13] + P[11][19]*SPP[22] + P[14][19]*SPP[16]; -nextP[3][19] = P[3][19] + P[0][19]*SPP[1] + P[1][19]*SPP[19] + P[2][19]*SPP[15] - P[15][19]*SPP[21]; -nextP[4][19] = P[4][19] + P[15][19]*SF[22] + P[0][19]*SPP[20] + P[1][19]*SPP[12] + P[2][19]*SPP[11]; -nextP[5][19] = P[5][19] + P[15][19]*SF[20] - P[0][19]*SPP[9] + P[1][19]*SPP[10] + P[2][19]*SPP[0]; -nextP[6][19] = P[6][19] + P[3][19]*dt; +nextP[0][19] = P[0][19] + P[1][19]*SF[9] + P[2][19]*SF[11] + P[3][19]*SF[10] + P[10][19]*SF[14] + P[11][19]*SF[15] + P[12][19]*SPP[10]; +nextP[1][19] = P[1][19] + P[0][19]*SF[8] + P[2][19]*SF[7] + P[3][19]*SF[11] - P[12][19]*SF[15] + P[11][19]*SPP[10] - (P[10][19]*q0)/2; +nextP[2][19] = P[2][19] + P[0][19]*SF[6] + P[1][19]*SF[10] + P[3][19]*SF[8] + P[12][19]*SF[14] - P[10][19]*SPP[10] - (P[11][19]*q0)/2; +nextP[3][19] = P[3][19] + P[0][19]*SF[7] + P[1][19]*SF[6] + P[2][19]*SF[9] + P[10][19]*SF[15] - P[11][19]*SF[14] - (P[12][19]*q0)/2; +nextP[4][19] = P[4][19] + P[0][19]*SF[5] + P[1][19]*SF[3] - P[3][19]*SF[4] + P[2][19]*SPP[0] + P[13][19]*SPP[3] + P[14][19]*SPP[6] - P[15][19]*SPP[9]; +nextP[5][19] = P[5][19] + P[0][19]*SF[4] + P[2][19]*SF[3] + P[3][19]*SF[5] - P[1][19]*SPP[0] - P[13][19]*SPP[8] + P[14][19]*SPP[2] + P[15][19]*SPP[5]; +nextP[6][19] = P[6][19] + P[1][19]*SF[4] - P[2][19]*SF[5] + P[3][19]*SF[3] + P[0][19]*SPP[0] + P[13][19]*SPP[4] - P[14][19]*SPP[7] - P[15][19]*SPP[1]; nextP[7][19] = P[7][19] + P[4][19]*dt; nextP[8][19] = P[8][19] + P[5][19]*dt; -nextP[9][19] = P[9][19]; +nextP[9][19] = P[9][19] + P[6][19]*dt; nextP[10][19] = P[10][19]; nextP[11][19] = P[11][19]; nextP[12][19] = P[12][19]; @@ -276,16 +264,16 @@ nextP[16][19] = P[16][19]; nextP[17][19] = P[17][19]; nextP[18][19] = P[18][19]; nextP[19][19] = P[19][19]; -nextP[0][20] = P[0][20]*SPP[5] - P[1][20]*SPP[4] + P[2][20]*SPP[7] + P[9][20]*SPP[22] + P[12][20]*SPP[18]; -nextP[1][20] = P[1][20]*SPP[6] - P[0][20]*SPP[2] - P[2][20]*SPP[8] + P[10][20]*SPP[22] + P[13][20]*SPP[17]; -nextP[2][20] = P[0][20]*SPP[14] - P[1][20]*SPP[3] + P[2][20]*SPP[13] + P[11][20]*SPP[22] + P[14][20]*SPP[16]; -nextP[3][20] = P[3][20] + P[0][20]*SPP[1] + P[1][20]*SPP[19] + P[2][20]*SPP[15] - P[15][20]*SPP[21]; -nextP[4][20] = P[4][20] + P[15][20]*SF[22] + P[0][20]*SPP[20] + P[1][20]*SPP[12] + P[2][20]*SPP[11]; -nextP[5][20] = P[5][20] + P[15][20]*SF[20] - P[0][20]*SPP[9] + P[1][20]*SPP[10] + P[2][20]*SPP[0]; -nextP[6][20] = P[6][20] + P[3][20]*dt; +nextP[0][20] = P[0][20] + P[1][20]*SF[9] + P[2][20]*SF[11] + P[3][20]*SF[10] + P[10][20]*SF[14] + P[11][20]*SF[15] + P[12][20]*SPP[10]; +nextP[1][20] = P[1][20] + P[0][20]*SF[8] + P[2][20]*SF[7] + P[3][20]*SF[11] - P[12][20]*SF[15] + P[11][20]*SPP[10] - (P[10][20]*q0)/2; +nextP[2][20] = P[2][20] + P[0][20]*SF[6] + P[1][20]*SF[10] + P[3][20]*SF[8] + P[12][20]*SF[14] - P[10][20]*SPP[10] - (P[11][20]*q0)/2; +nextP[3][20] = P[3][20] + P[0][20]*SF[7] + P[1][20]*SF[6] + P[2][20]*SF[9] + P[10][20]*SF[15] - P[11][20]*SF[14] - (P[12][20]*q0)/2; +nextP[4][20] = P[4][20] + P[0][20]*SF[5] + P[1][20]*SF[3] - P[3][20]*SF[4] + P[2][20]*SPP[0] + P[13][20]*SPP[3] + P[14][20]*SPP[6] - P[15][20]*SPP[9]; +nextP[5][20] = P[5][20] + P[0][20]*SF[4] + P[2][20]*SF[3] + P[3][20]*SF[5] - P[1][20]*SPP[0] - P[13][20]*SPP[8] + P[14][20]*SPP[2] + P[15][20]*SPP[5]; +nextP[6][20] = P[6][20] + P[1][20]*SF[4] - P[2][20]*SF[5] + P[3][20]*SF[3] + P[0][20]*SPP[0] + P[13][20]*SPP[4] - P[14][20]*SPP[7] - P[15][20]*SPP[1]; nextP[7][20] = P[7][20] + P[4][20]*dt; nextP[8][20] = P[8][20] + P[5][20]*dt; -nextP[9][20] = P[9][20]; +nextP[9][20] = P[9][20] + P[6][20]*dt; nextP[10][20] = P[10][20]; nextP[11][20] = P[11][20]; nextP[12][20] = P[12][20]; @@ -297,16 +285,16 @@ nextP[17][20] = P[17][20]; nextP[18][20] = P[18][20]; nextP[19][20] = P[19][20]; nextP[20][20] = P[20][20]; -nextP[0][21] = P[0][21]*SPP[5] - P[1][21]*SPP[4] + P[2][21]*SPP[7] + P[9][21]*SPP[22] + P[12][21]*SPP[18]; -nextP[1][21] = P[1][21]*SPP[6] - P[0][21]*SPP[2] - P[2][21]*SPP[8] + P[10][21]*SPP[22] + P[13][21]*SPP[17]; -nextP[2][21] = P[0][21]*SPP[14] - P[1][21]*SPP[3] + P[2][21]*SPP[13] + P[11][21]*SPP[22] + P[14][21]*SPP[16]; -nextP[3][21] = P[3][21] + P[0][21]*SPP[1] + P[1][21]*SPP[19] + P[2][21]*SPP[15] - P[15][21]*SPP[21]; -nextP[4][21] = P[4][21] + P[15][21]*SF[22] + P[0][21]*SPP[20] + P[1][21]*SPP[12] + P[2][21]*SPP[11]; -nextP[5][21] = P[5][21] + P[15][21]*SF[20] - P[0][21]*SPP[9] + P[1][21]*SPP[10] + P[2][21]*SPP[0]; -nextP[6][21] = P[6][21] + P[3][21]*dt; +nextP[0][21] = P[0][21] + P[1][21]*SF[9] + P[2][21]*SF[11] + P[3][21]*SF[10] + P[10][21]*SF[14] + P[11][21]*SF[15] + P[12][21]*SPP[10]; +nextP[1][21] = P[1][21] + P[0][21]*SF[8] + P[2][21]*SF[7] + P[3][21]*SF[11] - P[12][21]*SF[15] + P[11][21]*SPP[10] - (P[10][21]*q0)/2; +nextP[2][21] = P[2][21] + P[0][21]*SF[6] + P[1][21]*SF[10] + P[3][21]*SF[8] + P[12][21]*SF[14] - P[10][21]*SPP[10] - (P[11][21]*q0)/2; +nextP[3][21] = P[3][21] + P[0][21]*SF[7] + P[1][21]*SF[6] + P[2][21]*SF[9] + P[10][21]*SF[15] - P[11][21]*SF[14] - (P[12][21]*q0)/2; +nextP[4][21] = P[4][21] + P[0][21]*SF[5] + P[1][21]*SF[3] - P[3][21]*SF[4] + P[2][21]*SPP[0] + P[13][21]*SPP[3] + P[14][21]*SPP[6] - P[15][21]*SPP[9]; +nextP[5][21] = P[5][21] + P[0][21]*SF[4] + P[2][21]*SF[3] + P[3][21]*SF[5] - P[1][21]*SPP[0] - P[13][21]*SPP[8] + P[14][21]*SPP[2] + P[15][21]*SPP[5]; +nextP[6][21] = P[6][21] + P[1][21]*SF[4] - P[2][21]*SF[5] + P[3][21]*SF[3] + P[0][21]*SPP[0] + P[13][21]*SPP[4] - P[14][21]*SPP[7] - P[15][21]*SPP[1]; nextP[7][21] = P[7][21] + P[4][21]*dt; nextP[8][21] = P[8][21] + P[5][21]*dt; -nextP[9][21] = P[9][21]; +nextP[9][21] = P[9][21] + P[6][21]*dt; nextP[10][21] = P[10][21]; nextP[11][21] = P[11][21]; nextP[12][21] = P[12][21]; @@ -319,16 +307,16 @@ nextP[18][21] = P[18][21]; nextP[19][21] = P[19][21]; nextP[20][21] = P[20][21]; nextP[21][21] = P[21][21]; -nextP[0][22] = P[0][22]*SPP[5] - P[1][22]*SPP[4] + P[2][22]*SPP[7] + P[9][22]*SPP[22] + P[12][22]*SPP[18]; -nextP[1][22] = P[1][22]*SPP[6] - P[0][22]*SPP[2] - P[2][22]*SPP[8] + P[10][22]*SPP[22] + P[13][22]*SPP[17]; -nextP[2][22] = P[0][22]*SPP[14] - P[1][22]*SPP[3] + P[2][22]*SPP[13] + P[11][22]*SPP[22] + P[14][22]*SPP[16]; -nextP[3][22] = P[3][22] + P[0][22]*SPP[1] + P[1][22]*SPP[19] + P[2][22]*SPP[15] - P[15][22]*SPP[21]; -nextP[4][22] = P[4][22] + P[15][22]*SF[22] + P[0][22]*SPP[20] + P[1][22]*SPP[12] + P[2][22]*SPP[11]; -nextP[5][22] = P[5][22] + P[15][22]*SF[20] - P[0][22]*SPP[9] + P[1][22]*SPP[10] + P[2][22]*SPP[0]; -nextP[6][22] = P[6][22] + P[3][22]*dt; +nextP[0][22] = P[0][22] + P[1][22]*SF[9] + P[2][22]*SF[11] + P[3][22]*SF[10] + P[10][22]*SF[14] + P[11][22]*SF[15] + P[12][22]*SPP[10]; +nextP[1][22] = P[1][22] + P[0][22]*SF[8] + P[2][22]*SF[7] + P[3][22]*SF[11] - P[12][22]*SF[15] + P[11][22]*SPP[10] - (P[10][22]*q0)/2; +nextP[2][22] = P[2][22] + P[0][22]*SF[6] + P[1][22]*SF[10] + P[3][22]*SF[8] + P[12][22]*SF[14] - P[10][22]*SPP[10] - (P[11][22]*q0)/2; +nextP[3][22] = P[3][22] + P[0][22]*SF[7] + P[1][22]*SF[6] + P[2][22]*SF[9] + P[10][22]*SF[15] - P[11][22]*SF[14] - (P[12][22]*q0)/2; +nextP[4][22] = P[4][22] + P[0][22]*SF[5] + P[1][22]*SF[3] - P[3][22]*SF[4] + P[2][22]*SPP[0] + P[13][22]*SPP[3] + P[14][22]*SPP[6] - P[15][22]*SPP[9]; +nextP[5][22] = P[5][22] + P[0][22]*SF[4] + P[2][22]*SF[3] + P[3][22]*SF[5] - P[1][22]*SPP[0] - P[13][22]*SPP[8] + P[14][22]*SPP[2] + P[15][22]*SPP[5]; +nextP[6][22] = P[6][22] + P[1][22]*SF[4] - P[2][22]*SF[5] + P[3][22]*SF[3] + P[0][22]*SPP[0] + P[13][22]*SPP[4] - P[14][22]*SPP[7] - P[15][22]*SPP[1]; nextP[7][22] = P[7][22] + P[4][22]*dt; nextP[8][22] = P[8][22] + P[5][22]*dt; -nextP[9][22] = P[9][22]; +nextP[9][22] = P[9][22] + P[6][22]*dt; nextP[10][22] = P[10][22]; nextP[11][22] = P[11][22]; nextP[12][22] = P[12][22]; @@ -342,16 +330,16 @@ nextP[19][22] = P[19][22]; nextP[20][22] = P[20][22]; nextP[21][22] = P[21][22]; nextP[22][22] = P[22][22]; -nextP[0][23] = P[0][23]*SPP[5] - P[1][23]*SPP[4] + P[2][23]*SPP[7] + P[9][23]*SPP[22] + P[12][23]*SPP[18]; -nextP[1][23] = P[1][23]*SPP[6] - P[0][23]*SPP[2] - P[2][23]*SPP[8] + P[10][23]*SPP[22] + P[13][23]*SPP[17]; -nextP[2][23] = P[0][23]*SPP[14] - P[1][23]*SPP[3] + P[2][23]*SPP[13] + P[11][23]*SPP[22] + P[14][23]*SPP[16]; -nextP[3][23] = P[3][23] + P[0][23]*SPP[1] + P[1][23]*SPP[19] + P[2][23]*SPP[15] - P[15][23]*SPP[21]; -nextP[4][23] = P[4][23] + P[15][23]*SF[22] + P[0][23]*SPP[20] + P[1][23]*SPP[12] + P[2][23]*SPP[11]; -nextP[5][23] = P[5][23] + P[15][23]*SF[20] - P[0][23]*SPP[9] + P[1][23]*SPP[10] + P[2][23]*SPP[0]; -nextP[6][23] = P[6][23] + P[3][23]*dt; +nextP[0][23] = P[0][23] + P[1][23]*SF[9] + P[2][23]*SF[11] + P[3][23]*SF[10] + P[10][23]*SF[14] + P[11][23]*SF[15] + P[12][23]*SPP[10]; +nextP[1][23] = P[1][23] + P[0][23]*SF[8] + P[2][23]*SF[7] + P[3][23]*SF[11] - P[12][23]*SF[15] + P[11][23]*SPP[10] - (P[10][23]*q0)/2; +nextP[2][23] = P[2][23] + P[0][23]*SF[6] + P[1][23]*SF[10] + P[3][23]*SF[8] + P[12][23]*SF[14] - P[10][23]*SPP[10] - (P[11][23]*q0)/2; +nextP[3][23] = P[3][23] + P[0][23]*SF[7] + P[1][23]*SF[6] + P[2][23]*SF[9] + P[10][23]*SF[15] - P[11][23]*SF[14] - (P[12][23]*q0)/2; +nextP[4][23] = P[4][23] + P[0][23]*SF[5] + P[1][23]*SF[3] - P[3][23]*SF[4] + P[2][23]*SPP[0] + P[13][23]*SPP[3] + P[14][23]*SPP[6] - P[15][23]*SPP[9]; +nextP[5][23] = P[5][23] + P[0][23]*SF[4] + P[2][23]*SF[3] + P[3][23]*SF[5] - P[1][23]*SPP[0] - P[13][23]*SPP[8] + P[14][23]*SPP[2] + P[15][23]*SPP[5]; +nextP[6][23] = P[6][23] + P[1][23]*SF[4] - P[2][23]*SF[5] + P[3][23]*SF[3] + P[0][23]*SPP[0] + P[13][23]*SPP[4] - P[14][23]*SPP[7] - P[15][23]*SPP[1]; nextP[7][23] = P[7][23] + P[4][23]*dt; nextP[8][23] = P[8][23] + P[5][23]*dt; -nextP[9][23] = P[9][23]; +nextP[9][23] = P[9][23] + P[6][23]*dt; nextP[10][23] = P[10][23]; nextP[11][23] = P[11][23]; nextP[12][23] = P[12][23]; @@ -371,311 +359,328 @@ SH_TAS[0] = 1/(sqrt(sq(ve - vwe) + sq(vn - vwn) + sq(vd))); SH_TAS[1] = (SH_TAS[0]*(2*ve - 2*vwe))/2; SH_TAS[2] = (SH_TAS[0]*(2*vn - 2*vwn))/2; float H_TAS[1][24]; -H_TAS[0][3] = SH_TAS[2]; -H_TAS[0][4] = SH_TAS[1]; -H_TAS[0][5] = vd*SH_TAS[0]; +H_TAS[0][4] = SH_TAS[2]; +H_TAS[0][5] = SH_TAS[1]; +H_TAS[0][6] = vd*SH_TAS[0]; H_TAS[0][22] = -SH_TAS[2]; H_TAS[0][23] = -SH_TAS[1]; float SK_TAS[2][1]; -SK_TAS[0] = 1/(R_TAS + SH_TAS[2]*(P[3][3]*SH_TAS[2] + P[4][3]*SH_TAS[1] - P[22][3]*SH_TAS[2] - P[23][3]*SH_TAS[1] + P[5][3]*vd*SH_TAS[0]) + SH_TAS[1]*(P[3][4]*SH_TAS[2] + P[4][4]*SH_TAS[1] - P[22][4]*SH_TAS[2] - P[23][4]*SH_TAS[1] + P[5][4]*vd*SH_TAS[0]) - SH_TAS[2]*(P[3][22]*SH_TAS[2] + P[4][22]*SH_TAS[1] - P[22][22]*SH_TAS[2] - P[23][22]*SH_TAS[1] + P[5][22]*vd*SH_TAS[0]) - SH_TAS[1]*(P[3][23]*SH_TAS[2] + P[4][23]*SH_TAS[1] - P[22][23]*SH_TAS[2] - P[23][23]*SH_TAS[1] + P[5][23]*vd*SH_TAS[0]) + vd*SH_TAS[0]*(P[3][5]*SH_TAS[2] + P[4][5]*SH_TAS[1] - P[22][5]*SH_TAS[2] - P[23][5]*SH_TAS[1] + P[5][5]*vd*SH_TAS[0])); +SK_TAS[0] = 1/(R_TAS + SH_TAS[2]*(P[4][4]*SH_TAS[2] + P[5][4]*SH_TAS[1] - P[22][4]*SH_TAS[2] - P[23][4]*SH_TAS[1] + P[6][4]*vd*SH_TAS[0]) + SH_TAS[1]*(P[4][5]*SH_TAS[2] + P[5][5]*SH_TAS[1] - P[22][5]*SH_TAS[2] - P[23][5]*SH_TAS[1] + P[6][5]*vd*SH_TAS[0]) - SH_TAS[2]*(P[4][22]*SH_TAS[2] + P[5][22]*SH_TAS[1] - P[22][22]*SH_TAS[2] - P[23][22]*SH_TAS[1] + P[6][22]*vd*SH_TAS[0]) - SH_TAS[1]*(P[4][23]*SH_TAS[2] + P[5][23]*SH_TAS[1] - P[22][23]*SH_TAS[2] - P[23][23]*SH_TAS[1] + P[6][23]*vd*SH_TAS[0]) + vd*SH_TAS[0]*(P[4][6]*SH_TAS[2] + P[5][6]*SH_TAS[1] - P[22][6]*SH_TAS[2] - P[23][6]*SH_TAS[1] + P[6][6]*vd*SH_TAS[0])); SK_TAS[1] = SH_TAS[1]; float Kfusion[24][1]; float Kfusion[1][1]; -Kfusion[0] = SK_TAS[0]*(P[0][3]*SH_TAS[2] - P[0][22]*SH_TAS[2] + P[0][4]*SK_TAS[1] - P[0][23]*SK_TAS[1] + P[0][5]*vd*SH_TAS[0]); -Kfusion[1] = SK_TAS[0]*(P[1][3]*SH_TAS[2] - P[1][22]*SH_TAS[2] + P[1][4]*SK_TAS[1] - P[1][23]*SK_TAS[1] + P[1][5]*vd*SH_TAS[0]); -Kfusion[2] = SK_TAS[0]*(P[2][3]*SH_TAS[2] - P[2][22]*SH_TAS[2] + P[2][4]*SK_TAS[1] - P[2][23]*SK_TAS[1] + P[2][5]*vd*SH_TAS[0]); -Kfusion[3] = SK_TAS[0]*(P[3][3]*SH_TAS[2] - P[3][22]*SH_TAS[2] + P[3][4]*SK_TAS[1] - P[3][23]*SK_TAS[1] + P[3][5]*vd*SH_TAS[0]); -Kfusion[4] = SK_TAS[0]*(P[4][3]*SH_TAS[2] - P[4][22]*SH_TAS[2] + P[4][4]*SK_TAS[1] - P[4][23]*SK_TAS[1] + P[4][5]*vd*SH_TAS[0]); -Kfusion[5] = SK_TAS[0]*(P[5][3]*SH_TAS[2] - P[5][22]*SH_TAS[2] + P[5][4]*SK_TAS[1] - P[5][23]*SK_TAS[1] + P[5][5]*vd*SH_TAS[0]); -Kfusion[6] = SK_TAS[0]*(P[6][3]*SH_TAS[2] - P[6][22]*SH_TAS[2] + P[6][4]*SK_TAS[1] - P[6][23]*SK_TAS[1] + P[6][5]*vd*SH_TAS[0]); -Kfusion[7] = SK_TAS[0]*(P[7][3]*SH_TAS[2] - P[7][22]*SH_TAS[2] + P[7][4]*SK_TAS[1] - P[7][23]*SK_TAS[1] + P[7][5]*vd*SH_TAS[0]); -Kfusion[8] = SK_TAS[0]*(P[8][3]*SH_TAS[2] - P[8][22]*SH_TAS[2] + P[8][4]*SK_TAS[1] - P[8][23]*SK_TAS[1] + P[8][5]*vd*SH_TAS[0]); -Kfusion[9] = SK_TAS[0]*(P[9][3]*SH_TAS[2] - P[9][22]*SH_TAS[2] + P[9][4]*SK_TAS[1] - P[9][23]*SK_TAS[1] + P[9][5]*vd*SH_TAS[0]); -Kfusion[10] = SK_TAS[0]*(P[10][3]*SH_TAS[2] - P[10][22]*SH_TAS[2] + P[10][4]*SK_TAS[1] - P[10][23]*SK_TAS[1] + P[10][5]*vd*SH_TAS[0]); -Kfusion[11] = SK_TAS[0]*(P[11][3]*SH_TAS[2] - P[11][22]*SH_TAS[2] + P[11][4]*SK_TAS[1] - P[11][23]*SK_TAS[1] + P[11][5]*vd*SH_TAS[0]); -Kfusion[12] = SK_TAS[0]*(P[12][3]*SH_TAS[2] - P[12][22]*SH_TAS[2] + P[12][4]*SK_TAS[1] - P[12][23]*SK_TAS[1] + P[12][5]*vd*SH_TAS[0]); -Kfusion[13] = SK_TAS[0]*(P[13][3]*SH_TAS[2] - P[13][22]*SH_TAS[2] + P[13][4]*SK_TAS[1] - P[13][23]*SK_TAS[1] + P[13][5]*vd*SH_TAS[0]); -Kfusion[14] = SK_TAS[0]*(P[14][3]*SH_TAS[2] - P[14][22]*SH_TAS[2] + P[14][4]*SK_TAS[1] - P[14][23]*SK_TAS[1] + P[14][5]*vd*SH_TAS[0]); -Kfusion[15] = SK_TAS[0]*(P[15][3]*SH_TAS[2] - P[15][22]*SH_TAS[2] + P[15][4]*SK_TAS[1] - P[15][23]*SK_TAS[1] + P[15][5]*vd*SH_TAS[0]); -Kfusion[16] = SK_TAS[0]*(P[16][3]*SH_TAS[2] - P[16][22]*SH_TAS[2] + P[16][4]*SK_TAS[1] - P[16][23]*SK_TAS[1] + P[16][5]*vd*SH_TAS[0]); -Kfusion[17] = SK_TAS[0]*(P[17][3]*SH_TAS[2] - P[17][22]*SH_TAS[2] + P[17][4]*SK_TAS[1] - P[17][23]*SK_TAS[1] + P[17][5]*vd*SH_TAS[0]); -Kfusion[18] = SK_TAS[0]*(P[18][3]*SH_TAS[2] - P[18][22]*SH_TAS[2] + P[18][4]*SK_TAS[1] - P[18][23]*SK_TAS[1] + P[18][5]*vd*SH_TAS[0]); -Kfusion[19] = SK_TAS[0]*(P[19][3]*SH_TAS[2] - P[19][22]*SH_TAS[2] + P[19][4]*SK_TAS[1] - P[19][23]*SK_TAS[1] + P[19][5]*vd*SH_TAS[0]); -Kfusion[20] = SK_TAS[0]*(P[20][3]*SH_TAS[2] - P[20][22]*SH_TAS[2] + P[20][4]*SK_TAS[1] - P[20][23]*SK_TAS[1] + P[20][5]*vd*SH_TAS[0]); -Kfusion[21] = SK_TAS[0]*(P[21][3]*SH_TAS[2] - P[21][22]*SH_TAS[2] + P[21][4]*SK_TAS[1] - P[21][23]*SK_TAS[1] + P[21][5]*vd*SH_TAS[0]); -Kfusion[22] = SK_TAS[0]*(P[22][3]*SH_TAS[2] - P[22][22]*SH_TAS[2] + P[22][4]*SK_TAS[1] - P[22][23]*SK_TAS[1] + P[22][5]*vd*SH_TAS[0]); -Kfusion[23] = SK_TAS[0]*(P[23][3]*SH_TAS[2] - P[23][22]*SH_TAS[2] + P[23][4]*SK_TAS[1] - P[23][23]*SK_TAS[1] + P[23][5]*vd*SH_TAS[0]); -float SH_BETA[10][1]; -SH_BETA[0] = (2*conj(q0)*conj(q3) + 2*conj(q1)*conj(q2))*(ve - vwe) - vd*(2*conj(q0)*conj(q2) - 2*conj(q1)*conj(q3)) + (vn - vwn)*(conjsq(q0) + conjsq(q1) - conjsq(q2) - conjsq(q3)); -SH_BETA[1] = vd*(2*conj(q0)*conj(q1) + 2*conj(q2)*conj(q3)) - (2*conj(q0)*conj(q3) - 2*conj(q1)*conj(q2))*(vn - vwn) + (ve - vwe)*(conjsq(q0) - conjsq(q1) + conjsq(q2) - conjsq(q3)); -SH_BETA[2] = (2*conj(q0)*conj(q2) + 2*conj(q1)*conj(q3))*(vn - vwn) - (2*conj(q0)*conj(q1) - 2*conj(q2)*conj(q3))*(ve - vwe) + vd*(conjsq(q0) - conjsq(q1) - conjsq(q2) + conjsq(q3)); -SH_BETA[3] = (conjsq(q0) - conjsq(q1) + conjsq(q2) - conjsq(q3))/SH_BETA[0]; +Kfusion[0] = SK_TAS[0]*(P[0][4]*SH_TAS[2] - P[0][22]*SH_TAS[2] + P[0][5]*SK_TAS[1] - P[0][23]*SK_TAS[1] + P[0][6]*vd*SH_TAS[0]); +Kfusion[1] = SK_TAS[0]*(P[1][4]*SH_TAS[2] - P[1][22]*SH_TAS[2] + P[1][5]*SK_TAS[1] - P[1][23]*SK_TAS[1] + P[1][6]*vd*SH_TAS[0]); +Kfusion[2] = SK_TAS[0]*(P[2][4]*SH_TAS[2] - P[2][22]*SH_TAS[2] + P[2][5]*SK_TAS[1] - P[2][23]*SK_TAS[1] + P[2][6]*vd*SH_TAS[0]); +Kfusion[3] = SK_TAS[0]*(P[3][4]*SH_TAS[2] - P[3][22]*SH_TAS[2] + P[3][5]*SK_TAS[1] - P[3][23]*SK_TAS[1] + P[3][6]*vd*SH_TAS[0]); +Kfusion[4] = SK_TAS[0]*(P[4][4]*SH_TAS[2] - P[4][22]*SH_TAS[2] + P[4][5]*SK_TAS[1] - P[4][23]*SK_TAS[1] + P[4][6]*vd*SH_TAS[0]); +Kfusion[5] = SK_TAS[0]*(P[5][4]*SH_TAS[2] - P[5][22]*SH_TAS[2] + P[5][5]*SK_TAS[1] - P[5][23]*SK_TAS[1] + P[5][6]*vd*SH_TAS[0]); +Kfusion[6] = SK_TAS[0]*(P[6][4]*SH_TAS[2] - P[6][22]*SH_TAS[2] + P[6][5]*SK_TAS[1] - P[6][23]*SK_TAS[1] + P[6][6]*vd*SH_TAS[0]); +Kfusion[7] = SK_TAS[0]*(P[7][4]*SH_TAS[2] - P[7][22]*SH_TAS[2] + P[7][5]*SK_TAS[1] - P[7][23]*SK_TAS[1] + P[7][6]*vd*SH_TAS[0]); +Kfusion[8] = SK_TAS[0]*(P[8][4]*SH_TAS[2] - P[8][22]*SH_TAS[2] + P[8][5]*SK_TAS[1] - P[8][23]*SK_TAS[1] + P[8][6]*vd*SH_TAS[0]); +Kfusion[9] = SK_TAS[0]*(P[9][4]*SH_TAS[2] - P[9][22]*SH_TAS[2] + P[9][5]*SK_TAS[1] - P[9][23]*SK_TAS[1] + P[9][6]*vd*SH_TAS[0]); +Kfusion[10] = SK_TAS[0]*(P[10][4]*SH_TAS[2] - P[10][22]*SH_TAS[2] + P[10][5]*SK_TAS[1] - P[10][23]*SK_TAS[1] + P[10][6]*vd*SH_TAS[0]); +Kfusion[11] = SK_TAS[0]*(P[11][4]*SH_TAS[2] - P[11][22]*SH_TAS[2] + P[11][5]*SK_TAS[1] - P[11][23]*SK_TAS[1] + P[11][6]*vd*SH_TAS[0]); +Kfusion[12] = SK_TAS[0]*(P[12][4]*SH_TAS[2] - P[12][22]*SH_TAS[2] + P[12][5]*SK_TAS[1] - P[12][23]*SK_TAS[1] + P[12][6]*vd*SH_TAS[0]); +Kfusion[13] = SK_TAS[0]*(P[13][4]*SH_TAS[2] - P[13][22]*SH_TAS[2] + P[13][5]*SK_TAS[1] - P[13][23]*SK_TAS[1] + P[13][6]*vd*SH_TAS[0]); +Kfusion[14] = SK_TAS[0]*(P[14][4]*SH_TAS[2] - P[14][22]*SH_TAS[2] + P[14][5]*SK_TAS[1] - P[14][23]*SK_TAS[1] + P[14][6]*vd*SH_TAS[0]); +Kfusion[15] = SK_TAS[0]*(P[15][4]*SH_TAS[2] - P[15][22]*SH_TAS[2] + P[15][5]*SK_TAS[1] - P[15][23]*SK_TAS[1] + P[15][6]*vd*SH_TAS[0]); +Kfusion[16] = SK_TAS[0]*(P[16][4]*SH_TAS[2] - P[16][22]*SH_TAS[2] + P[16][5]*SK_TAS[1] - P[16][23]*SK_TAS[1] + P[16][6]*vd*SH_TAS[0]); +Kfusion[17] = SK_TAS[0]*(P[17][4]*SH_TAS[2] - P[17][22]*SH_TAS[2] + P[17][5]*SK_TAS[1] - P[17][23]*SK_TAS[1] + P[17][6]*vd*SH_TAS[0]); +Kfusion[18] = SK_TAS[0]*(P[18][4]*SH_TAS[2] - P[18][22]*SH_TAS[2] + P[18][5]*SK_TAS[1] - P[18][23]*SK_TAS[1] + P[18][6]*vd*SH_TAS[0]); +Kfusion[19] = SK_TAS[0]*(P[19][4]*SH_TAS[2] - P[19][22]*SH_TAS[2] + P[19][5]*SK_TAS[1] - P[19][23]*SK_TAS[1] + P[19][6]*vd*SH_TAS[0]); +Kfusion[20] = SK_TAS[0]*(P[20][4]*SH_TAS[2] - P[20][22]*SH_TAS[2] + P[20][5]*SK_TAS[1] - P[20][23]*SK_TAS[1] + P[20][6]*vd*SH_TAS[0]); +Kfusion[21] = SK_TAS[0]*(P[21][4]*SH_TAS[2] - P[21][22]*SH_TAS[2] + P[21][5]*SK_TAS[1] - P[21][23]*SK_TAS[1] + P[21][6]*vd*SH_TAS[0]); +Kfusion[22] = SK_TAS[0]*(P[22][4]*SH_TAS[2] - P[22][22]*SH_TAS[2] + P[22][5]*SK_TAS[1] - P[22][23]*SK_TAS[1] + P[22][6]*vd*SH_TAS[0]); +Kfusion[23] = SK_TAS[0]*(P[23][4]*SH_TAS[2] - P[23][22]*SH_TAS[2] + P[23][5]*SK_TAS[1] - P[23][23]*SK_TAS[1] + P[23][6]*vd*SH_TAS[0]); +float SH_BETA[13][1]; +SH_BETA[0] = (vn - vwn)*(sq(q0) + sq(q1) - sq(q2) - sq(q3)) - vd*(2*q0*q2 - 2*q1*q3) + (ve - vwe)*(2*q0*q3 + 2*q1*q2); +SH_BETA[1] = (ve - vwe)*(sq(q0) - sq(q1) + sq(q2) - sq(q3)) + vd*(2*q0*q1 + 2*q2*q3) - (vn - vwn)*(2*q0*q3 - 2*q1*q2); +SH_BETA[2] = vn - vwn; +SH_BETA[3] = ve - vwe; SH_BETA[4] = 1/sq(SH_BETA[0]); -SH_BETA[5] = conjsq(q0) + conjsq(q1) - conjsq(q2) - conjsq(q3); -SH_BETA[6] = 2*conj(q0)*conj(q3); -SH_BETA[7] = 1/SH_BETA[0]; -SH_BETA[8] = SH_BETA[6] + 2*conj(q1)*conj(q2); -SH_BETA[9] = SH_BETA[6] - 2*conj(q1)*conj(q2); +SH_BETA[5] = 1/SH_BETA[0]; +SH_BETA[6] = SH_BETA[5]*(sq(q0) - sq(q1) + sq(q2) - sq(q3)); +SH_BETA[7] = sq(q0) + sq(q1) - sq(q2) - sq(q3); +SH_BETA[8] = 2*q0*SH_BETA[3] - 2*q3*SH_BETA[2] + 2*q1*vd; +SH_BETA[9] = 2*q0*SH_BETA[2] + 2*q3*SH_BETA[3] - 2*q2*vd; +SH_BETA[10] = 2*q2*SH_BETA[2] - 2*q1*SH_BETA[3] + 2*q0*vd; +SH_BETA[11] = 2*q1*SH_BETA[2] + 2*q2*SH_BETA[3] + 2*q3*vd; +SH_BETA[12] = 2*q0*q3; float H_BETA[1][24]; -H_BETA[0][0] = SH_BETA[2]*SH_BETA[7]; -H_BETA[0][1] = SH_BETA[1]*SH_BETA[2]*SH_BETA[4]; -H_BETA[0][2] = - sq(SH_BETA[1])*SH_BETA[4] - 1; -H_BETA[0][3] = - SH_BETA[7]*SH_BETA[9] - SH_BETA[1]*SH_BETA[4]*SH_BETA[5]; -H_BETA[0][4] = SH_BETA[3] - SH_BETA[1]*SH_BETA[4]*SH_BETA[8]; -H_BETA[0][5] = SH_BETA[7]*(2*conj(q0)*conj(q1) + 2*conj(q2)*conj(q3)) + SH_BETA[1]*SH_BETA[4]*(2*conj(q0)*conj(q2) - 2*conj(q1)*conj(q3)); -H_BETA[0][22] = SH_BETA[7]*SH_BETA[9] + SH_BETA[1]*SH_BETA[4]*SH_BETA[5]; -H_BETA[0][23] = SH_BETA[1]*SH_BETA[4]*SH_BETA[8] - SH_BETA[3]; -float SK_BETA[6][1]; -SK_BETA[0] = 1/(R_BETA + (SH_BETA[7]*(2*conj(q0)*conj(q1) + 2*conj(q2)*conj(q3)) + SH_BETA[1]*SH_BETA[4]*(2*conj(q0)*conj(q2) - 2*conj(q1)*conj(q3)))*(P[22][5]*(SH_BETA[7]*SH_BETA[9] + SH_BETA[1]*SH_BETA[4]*SH_BETA[5]) - P[3][5]*(SH_BETA[7]*SH_BETA[9] + SH_BETA[1]*SH_BETA[4]*SH_BETA[5]) - P[2][5]*(sq(SH_BETA[1])*SH_BETA[4] + 1) + P[5][5]*(SH_BETA[7]*(2*conj(q0)*conj(q1) + 2*conj(q2)*conj(q3)) + SH_BETA[1]*SH_BETA[4]*(2*conj(q0)*conj(q2) - 2*conj(q1)*conj(q3))) + P[4][5]*(SH_BETA[3] - SH_BETA[1]*SH_BETA[4]*SH_BETA[8]) - P[23][5]*(SH_BETA[3] - SH_BETA[1]*SH_BETA[4]*SH_BETA[8]) + P[0][5]*SH_BETA[2]*SH_BETA[7] + P[1][5]*SH_BETA[1]*SH_BETA[2]*SH_BETA[4]) + (SH_BETA[3] - SH_BETA[1]*SH_BETA[4]*SH_BETA[8])*(P[22][4]*(SH_BETA[7]*SH_BETA[9] + SH_BETA[1]*SH_BETA[4]*SH_BETA[5]) - P[3][4]*(SH_BETA[7]*SH_BETA[9] + SH_BETA[1]*SH_BETA[4]*SH_BETA[5]) - P[2][4]*(sq(SH_BETA[1])*SH_BETA[4] + 1) + P[5][4]*(SH_BETA[7]*(2*conj(q0)*conj(q1) + 2*conj(q2)*conj(q3)) + SH_BETA[1]*SH_BETA[4]*(2*conj(q0)*conj(q2) - 2*conj(q1)*conj(q3))) + P[4][4]*(SH_BETA[3] - SH_BETA[1]*SH_BETA[4]*SH_BETA[8]) - P[23][4]*(SH_BETA[3] - SH_BETA[1]*SH_BETA[4]*SH_BETA[8]) + P[0][4]*SH_BETA[2]*SH_BETA[7] + P[1][4]*SH_BETA[1]*SH_BETA[2]*SH_BETA[4]) - (SH_BETA[3] - SH_BETA[1]*SH_BETA[4]*SH_BETA[8])*(P[22][23]*(SH_BETA[7]*SH_BETA[9] + SH_BETA[1]*SH_BETA[4]*SH_BETA[5]) - P[3][23]*(SH_BETA[7]*SH_BETA[9] + SH_BETA[1]*SH_BETA[4]*SH_BETA[5]) - P[2][23]*(sq(SH_BETA[1])*SH_BETA[4] + 1) + P[5][23]*(SH_BETA[7]*(2*conj(q0)*conj(q1) + 2*conj(q2)*conj(q3)) + SH_BETA[1]*SH_BETA[4]*(2*conj(q0)*conj(q2) - 2*conj(q1)*conj(q3))) + P[4][23]*(SH_BETA[3] - SH_BETA[1]*SH_BETA[4]*SH_BETA[8]) - P[23][23]*(SH_BETA[3] - SH_BETA[1]*SH_BETA[4]*SH_BETA[8]) + P[0][23]*SH_BETA[2]*SH_BETA[7] + P[1][23]*SH_BETA[1]*SH_BETA[2]*SH_BETA[4]) - (SH_BETA[7]*SH_BETA[9] + SH_BETA[1]*SH_BETA[4]*SH_BETA[5])*(P[22][3]*(SH_BETA[7]*SH_BETA[9] + SH_BETA[1]*SH_BETA[4]*SH_BETA[5]) - P[3][3]*(SH_BETA[7]*SH_BETA[9] + SH_BETA[1]*SH_BETA[4]*SH_BETA[5]) - P[2][3]*(sq(SH_BETA[1])*SH_BETA[4] + 1) + P[5][3]*(SH_BETA[7]*(2*conj(q0)*conj(q1) + 2*conj(q2)*conj(q3)) + SH_BETA[1]*SH_BETA[4]*(2*conj(q0)*conj(q2) - 2*conj(q1)*conj(q3))) + P[4][3]*(SH_BETA[3] - SH_BETA[1]*SH_BETA[4]*SH_BETA[8]) - P[23][3]*(SH_BETA[3] - SH_BETA[1]*SH_BETA[4]*SH_BETA[8]) + P[0][3]*SH_BETA[2]*SH_BETA[7] + P[1][3]*SH_BETA[1]*SH_BETA[2]*SH_BETA[4]) + (SH_BETA[7]*SH_BETA[9] + SH_BETA[1]*SH_BETA[4]*SH_BETA[5])*(P[22][22]*(SH_BETA[7]*SH_BETA[9] + SH_BETA[1]*SH_BETA[4]*SH_BETA[5]) - P[3][22]*(SH_BETA[7]*SH_BETA[9] + SH_BETA[1]*SH_BETA[4]*SH_BETA[5]) - P[2][22]*(sq(SH_BETA[1])*SH_BETA[4] + 1) + P[5][22]*(SH_BETA[7]*(2*conj(q0)*conj(q1) + 2*conj(q2)*conj(q3)) + SH_BETA[1]*SH_BETA[4]*(2*conj(q0)*conj(q2) - 2*conj(q1)*conj(q3))) + P[4][22]*(SH_BETA[3] - SH_BETA[1]*SH_BETA[4]*SH_BETA[8]) - P[23][22]*(SH_BETA[3] - SH_BETA[1]*SH_BETA[4]*SH_BETA[8]) + P[0][22]*SH_BETA[2]*SH_BETA[7] + P[1][22]*SH_BETA[1]*SH_BETA[2]*SH_BETA[4]) - (sq(SH_BETA[1])*SH_BETA[4] + 1)*(P[22][2]*(SH_BETA[7]*SH_BETA[9] + SH_BETA[1]*SH_BETA[4]*SH_BETA[5]) - P[3][2]*(SH_BETA[7]*SH_BETA[9] + SH_BETA[1]*SH_BETA[4]*SH_BETA[5]) - P[2][2]*(sq(SH_BETA[1])*SH_BETA[4] + 1) + P[5][2]*(SH_BETA[7]*(2*conj(q0)*conj(q1) + 2*conj(q2)*conj(q3)) + SH_BETA[1]*SH_BETA[4]*(2*conj(q0)*conj(q2) - 2*conj(q1)*conj(q3))) + P[4][2]*(SH_BETA[3] - SH_BETA[1]*SH_BETA[4]*SH_BETA[8]) - P[23][2]*(SH_BETA[3] - SH_BETA[1]*SH_BETA[4]*SH_BETA[8]) + P[0][2]*SH_BETA[2]*SH_BETA[7] + P[1][2]*SH_BETA[1]*SH_BETA[2]*SH_BETA[4]) + SH_BETA[2]*SH_BETA[7]*(P[22][0]*(SH_BETA[7]*SH_BETA[9] + SH_BETA[1]*SH_BETA[4]*SH_BETA[5]) - P[3][0]*(SH_BETA[7]*SH_BETA[9] + SH_BETA[1]*SH_BETA[4]*SH_BETA[5]) - P[2][0]*(sq(SH_BETA[1])*SH_BETA[4] + 1) + P[5][0]*(SH_BETA[7]*(2*conj(q0)*conj(q1) + 2*conj(q2)*conj(q3)) + SH_BETA[1]*SH_BETA[4]*(2*conj(q0)*conj(q2) - 2*conj(q1)*conj(q3))) + P[4][0]*(SH_BETA[3] - SH_BETA[1]*SH_BETA[4]*SH_BETA[8]) - P[23][0]*(SH_BETA[3] - SH_BETA[1]*SH_BETA[4]*SH_BETA[8]) + P[0][0]*SH_BETA[2]*SH_BETA[7] + P[1][0]*SH_BETA[1]*SH_BETA[2]*SH_BETA[4]) + SH_BETA[1]*SH_BETA[2]*SH_BETA[4]*(P[22][1]*(SH_BETA[7]*SH_BETA[9] + SH_BETA[1]*SH_BETA[4]*SH_BETA[5]) - P[3][1]*(SH_BETA[7]*SH_BETA[9] + SH_BETA[1]*SH_BETA[4]*SH_BETA[5]) - P[2][1]*(sq(SH_BETA[1])*SH_BETA[4] + 1) + P[5][1]*(SH_BETA[7]*(2*conj(q0)*conj(q1) + 2*conj(q2)*conj(q3)) + SH_BETA[1]*SH_BETA[4]*(2*conj(q0)*conj(q2) - 2*conj(q1)*conj(q3))) + P[4][1]*(SH_BETA[3] - SH_BETA[1]*SH_BETA[4]*SH_BETA[8]) - P[23][1]*(SH_BETA[3] - SH_BETA[1]*SH_BETA[4]*SH_BETA[8]) + P[0][1]*SH_BETA[2]*SH_BETA[7] + P[1][1]*SH_BETA[1]*SH_BETA[2]*SH_BETA[4])); -SK_BETA[1] = SH_BETA[7]*(2*conj(q0)*conj(q1) + 2*conj(q2)*conj(q3)) + SH_BETA[1]*SH_BETA[4]*(2*conj(q0)*conj(q2) - 2*conj(q1)*conj(q3)); -SK_BETA[2] = SH_BETA[7]*SH_BETA[9] + SH_BETA[1]*SH_BETA[4]*SH_BETA[5]; -SK_BETA[3] = SH_BETA[3] - SH_BETA[1]*SH_BETA[4]*SH_BETA[8]; -SK_BETA[4] = sq(SH_BETA[1])*SH_BETA[4] + 1; -SK_BETA[5] = SH_BETA[2]; +H_BETA[0][0] = SH_BETA[5]*SH_BETA[8] - SH_BETA[1]*SH_BETA[4]*SH_BETA[9]; +H_BETA[0][1] = SH_BETA[5]*SH_BETA[10] - SH_BETA[1]*SH_BETA[4]*SH_BETA[11]; +H_BETA[0][2] = SH_BETA[5]*SH_BETA[11] + SH_BETA[1]*SH_BETA[4]*SH_BETA[10]; +H_BETA[0][3] = - SH_BETA[5]*SH_BETA[9] - SH_BETA[1]*SH_BETA[4]*SH_BETA[8]; +H_BETA[0][4] = - SH_BETA[5]*(SH_BETA[12] - 2*q1*q2) - SH_BETA[1]*SH_BETA[4]*SH_BETA[7]; +H_BETA[0][5] = SH_BETA[6] - SH_BETA[1]*SH_BETA[4]*(SH_BETA[12] + 2*q1*q2); +H_BETA[0][6] = SH_BETA[5]*(2*q0*q1 + 2*q2*q3) + SH_BETA[1]*SH_BETA[4]*(2*q0*q2 - 2*q1*q3); +H_BETA[0][22] = SH_BETA[5]*(SH_BETA[12] - 2*q1*q2) + SH_BETA[1]*SH_BETA[4]*SH_BETA[7]; +H_BETA[0][23] = SH_BETA[1]*SH_BETA[4]*(SH_BETA[12] + 2*q1*q2) - SH_BETA[6]; +float SK_BETA[8][1]; +SK_BETA[0] = 1/(R_BETA - (SH_BETA[5]*(SH_BETA[12] - 2*q1*q2) + SH_BETA[1]*SH_BETA[4]*SH_BETA[7])*(P[22][4]*(SH_BETA[5]*(SH_BETA[12] - 2*q1*q2) + SH_BETA[1]*SH_BETA[4]*SH_BETA[7]) - P[4][4]*(SH_BETA[5]*(SH_BETA[12] - 2*q1*q2) + SH_BETA[1]*SH_BETA[4]*SH_BETA[7]) + P[5][4]*(SH_BETA[6] - SH_BETA[1]*SH_BETA[4]*(SH_BETA[12] + 2*q1*q2)) - P[23][4]*(SH_BETA[6] - SH_BETA[1]*SH_BETA[4]*(SH_BETA[12] + 2*q1*q2)) + P[0][4]*(SH_BETA[5]*SH_BETA[8] - SH_BETA[1]*SH_BETA[4]*SH_BETA[9]) + P[1][4]*(SH_BETA[5]*SH_BETA[10] - SH_BETA[1]*SH_BETA[4]*SH_BETA[11]) + P[2][4]*(SH_BETA[5]*SH_BETA[11] + SH_BETA[1]*SH_BETA[4]*SH_BETA[10]) - P[3][4]*(SH_BETA[5]*SH_BETA[9] + SH_BETA[1]*SH_BETA[4]*SH_BETA[8]) + P[6][4]*(SH_BETA[5]*(2*q0*q1 + 2*q2*q3) + SH_BETA[1]*SH_BETA[4]*(2*q0*q2 - 2*q1*q3))) + (SH_BETA[5]*(SH_BETA[12] - 2*q1*q2) + SH_BETA[1]*SH_BETA[4]*SH_BETA[7])*(P[22][22]*(SH_BETA[5]*(SH_BETA[12] - 2*q1*q2) + SH_BETA[1]*SH_BETA[4]*SH_BETA[7]) - P[4][22]*(SH_BETA[5]*(SH_BETA[12] - 2*q1*q2) + SH_BETA[1]*SH_BETA[4]*SH_BETA[7]) + P[5][22]*(SH_BETA[6] - SH_BETA[1]*SH_BETA[4]*(SH_BETA[12] + 2*q1*q2)) - P[23][22]*(SH_BETA[6] - SH_BETA[1]*SH_BETA[4]*(SH_BETA[12] + 2*q1*q2)) + P[0][22]*(SH_BETA[5]*SH_BETA[8] - SH_BETA[1]*SH_BETA[4]*SH_BETA[9]) + P[1][22]*(SH_BETA[5]*SH_BETA[10] - SH_BETA[1]*SH_BETA[4]*SH_BETA[11]) + P[2][22]*(SH_BETA[5]*SH_BETA[11] + SH_BETA[1]*SH_BETA[4]*SH_BETA[10]) - P[3][22]*(SH_BETA[5]*SH_BETA[9] + SH_BETA[1]*SH_BETA[4]*SH_BETA[8]) + P[6][22]*(SH_BETA[5]*(2*q0*q1 + 2*q2*q3) + SH_BETA[1]*SH_BETA[4]*(2*q0*q2 - 2*q1*q3))) + (SH_BETA[6] - SH_BETA[1]*SH_BETA[4]*(SH_BETA[12] + 2*q1*q2))*(P[22][5]*(SH_BETA[5]*(SH_BETA[12] - 2*q1*q2) + SH_BETA[1]*SH_BETA[4]*SH_BETA[7]) - P[4][5]*(SH_BETA[5]*(SH_BETA[12] - 2*q1*q2) + SH_BETA[1]*SH_BETA[4]*SH_BETA[7]) + P[5][5]*(SH_BETA[6] - SH_BETA[1]*SH_BETA[4]*(SH_BETA[12] + 2*q1*q2)) - P[23][5]*(SH_BETA[6] - SH_BETA[1]*SH_BETA[4]*(SH_BETA[12] + 2*q1*q2)) + P[0][5]*(SH_BETA[5]*SH_BETA[8] - SH_BETA[1]*SH_BETA[4]*SH_BETA[9]) + P[1][5]*(SH_BETA[5]*SH_BETA[10] - SH_BETA[1]*SH_BETA[4]*SH_BETA[11]) + P[2][5]*(SH_BETA[5]*SH_BETA[11] + SH_BETA[1]*SH_BETA[4]*SH_BETA[10]) - P[3][5]*(SH_BETA[5]*SH_BETA[9] + SH_BETA[1]*SH_BETA[4]*SH_BETA[8]) + P[6][5]*(SH_BETA[5]*(2*q0*q1 + 2*q2*q3) + SH_BETA[1]*SH_BETA[4]*(2*q0*q2 - 2*q1*q3))) - (SH_BETA[6] - SH_BETA[1]*SH_BETA[4]*(SH_BETA[12] + 2*q1*q2))*(P[22][23]*(SH_BETA[5]*(SH_BETA[12] - 2*q1*q2) + SH_BETA[1]*SH_BETA[4]*SH_BETA[7]) - P[4][23]*(SH_BETA[5]*(SH_BETA[12] - 2*q1*q2) + SH_BETA[1]*SH_BETA[4]*SH_BETA[7]) + P[5][23]*(SH_BETA[6] - SH_BETA[1]*SH_BETA[4]*(SH_BETA[12] + 2*q1*q2)) - P[23][23]*(SH_BETA[6] - SH_BETA[1]*SH_BETA[4]*(SH_BETA[12] + 2*q1*q2)) + P[0][23]*(SH_BETA[5]*SH_BETA[8] - SH_BETA[1]*SH_BETA[4]*SH_BETA[9]) + P[1][23]*(SH_BETA[5]*SH_BETA[10] - SH_BETA[1]*SH_BETA[4]*SH_BETA[11]) + P[2][23]*(SH_BETA[5]*SH_BETA[11] + SH_BETA[1]*SH_BETA[4]*SH_BETA[10]) - P[3][23]*(SH_BETA[5]*SH_BETA[9] + SH_BETA[1]*SH_BETA[4]*SH_BETA[8]) + P[6][23]*(SH_BETA[5]*(2*q0*q1 + 2*q2*q3) + SH_BETA[1]*SH_BETA[4]*(2*q0*q2 - 2*q1*q3))) + (SH_BETA[5]*SH_BETA[8] - SH_BETA[1]*SH_BETA[4]*SH_BETA[9])*(P[22][0]*(SH_BETA[5]*(SH_BETA[12] - 2*q1*q2) + SH_BETA[1]*SH_BETA[4]*SH_BETA[7]) - P[4][0]*(SH_BETA[5]*(SH_BETA[12] - 2*q1*q2) + SH_BETA[1]*SH_BETA[4]*SH_BETA[7]) + P[5][0]*(SH_BETA[6] - SH_BETA[1]*SH_BETA[4]*(SH_BETA[12] + 2*q1*q2)) - P[23][0]*(SH_BETA[6] - SH_BETA[1]*SH_BETA[4]*(SH_BETA[12] + 2*q1*q2)) + P[0][0]*(SH_BETA[5]*SH_BETA[8] - SH_BETA[1]*SH_BETA[4]*SH_BETA[9]) + P[1][0]*(SH_BETA[5]*SH_BETA[10] - SH_BETA[1]*SH_BETA[4]*SH_BETA[11]) + P[2][0]*(SH_BETA[5]*SH_BETA[11] + SH_BETA[1]*SH_BETA[4]*SH_BETA[10]) - P[3][0]*(SH_BETA[5]*SH_BETA[9] + SH_BETA[1]*SH_BETA[4]*SH_BETA[8]) + P[6][0]*(SH_BETA[5]*(2*q0*q1 + 2*q2*q3) + SH_BETA[1]*SH_BETA[4]*(2*q0*q2 - 2*q1*q3))) + (SH_BETA[5]*SH_BETA[10] - SH_BETA[1]*SH_BETA[4]*SH_BETA[11])*(P[22][1]*(SH_BETA[5]*(SH_BETA[12] - 2*q1*q2) + SH_BETA[1]*SH_BETA[4]*SH_BETA[7]) - P[4][1]*(SH_BETA[5]*(SH_BETA[12] - 2*q1*q2) + SH_BETA[1]*SH_BETA[4]*SH_BETA[7]) + P[5][1]*(SH_BETA[6] - SH_BETA[1]*SH_BETA[4]*(SH_BETA[12] + 2*q1*q2)) - P[23][1]*(SH_BETA[6] - SH_BETA[1]*SH_BETA[4]*(SH_BETA[12] + 2*q1*q2)) + P[0][1]*(SH_BETA[5]*SH_BETA[8] - SH_BETA[1]*SH_BETA[4]*SH_BETA[9]) + P[1][1]*(SH_BETA[5]*SH_BETA[10] - SH_BETA[1]*SH_BETA[4]*SH_BETA[11]) + P[2][1]*(SH_BETA[5]*SH_BETA[11] + SH_BETA[1]*SH_BETA[4]*SH_BETA[10]) - P[3][1]*(SH_BETA[5]*SH_BETA[9] + SH_BETA[1]*SH_BETA[4]*SH_BETA[8]) + P[6][1]*(SH_BETA[5]*(2*q0*q1 + 2*q2*q3) + SH_BETA[1]*SH_BETA[4]*(2*q0*q2 - 2*q1*q3))) + (SH_BETA[5]*SH_BETA[11] + SH_BETA[1]*SH_BETA[4]*SH_BETA[10])*(P[22][2]*(SH_BETA[5]*(SH_BETA[12] - 2*q1*q2) + SH_BETA[1]*SH_BETA[4]*SH_BETA[7]) - P[4][2]*(SH_BETA[5]*(SH_BETA[12] - 2*q1*q2) + SH_BETA[1]*SH_BETA[4]*SH_BETA[7]) + P[5][2]*(SH_BETA[6] - SH_BETA[1]*SH_BETA[4]*(SH_BETA[12] + 2*q1*q2)) - P[23][2]*(SH_BETA[6] - SH_BETA[1]*SH_BETA[4]*(SH_BETA[12] + 2*q1*q2)) + P[0][2]*(SH_BETA[5]*SH_BETA[8] - SH_BETA[1]*SH_BETA[4]*SH_BETA[9]) + P[1][2]*(SH_BETA[5]*SH_BETA[10] - SH_BETA[1]*SH_BETA[4]*SH_BETA[11]) + P[2][2]*(SH_BETA[5]*SH_BETA[11] + SH_BETA[1]*SH_BETA[4]*SH_BETA[10]) - P[3][2]*(SH_BETA[5]*SH_BETA[9] + SH_BETA[1]*SH_BETA[4]*SH_BETA[8]) + P[6][2]*(SH_BETA[5]*(2*q0*q1 + 2*q2*q3) + SH_BETA[1]*SH_BETA[4]*(2*q0*q2 - 2*q1*q3))) - (SH_BETA[5]*SH_BETA[9] + SH_BETA[1]*SH_BETA[4]*SH_BETA[8])*(P[22][3]*(SH_BETA[5]*(SH_BETA[12] - 2*q1*q2) + SH_BETA[1]*SH_BETA[4]*SH_BETA[7]) - P[4][3]*(SH_BETA[5]*(SH_BETA[12] - 2*q1*q2) + SH_BETA[1]*SH_BETA[4]*SH_BETA[7]) + P[5][3]*(SH_BETA[6] - SH_BETA[1]*SH_BETA[4]*(SH_BETA[12] + 2*q1*q2)) - P[23][3]*(SH_BETA[6] - SH_BETA[1]*SH_BETA[4]*(SH_BETA[12] + 2*q1*q2)) + P[0][3]*(SH_BETA[5]*SH_BETA[8] - SH_BETA[1]*SH_BETA[4]*SH_BETA[9]) + P[1][3]*(SH_BETA[5]*SH_BETA[10] - SH_BETA[1]*SH_BETA[4]*SH_BETA[11]) + P[2][3]*(SH_BETA[5]*SH_BETA[11] + SH_BETA[1]*SH_BETA[4]*SH_BETA[10]) - P[3][3]*(SH_BETA[5]*SH_BETA[9] + SH_BETA[1]*SH_BETA[4]*SH_BETA[8]) + P[6][3]*(SH_BETA[5]*(2*q0*q1 + 2*q2*q3) + SH_BETA[1]*SH_BETA[4]*(2*q0*q2 - 2*q1*q3))) + (SH_BETA[5]*(2*q0*q1 + 2*q2*q3) + SH_BETA[1]*SH_BETA[4]*(2*q0*q2 - 2*q1*q3))*(P[22][6]*(SH_BETA[5]*(SH_BETA[12] - 2*q1*q2) + SH_BETA[1]*SH_BETA[4]*SH_BETA[7]) - P[4][6]*(SH_BETA[5]*(SH_BETA[12] - 2*q1*q2) + SH_BETA[1]*SH_BETA[4]*SH_BETA[7]) + P[5][6]*(SH_BETA[6] - SH_BETA[1]*SH_BETA[4]*(SH_BETA[12] + 2*q1*q2)) - P[23][6]*(SH_BETA[6] - SH_BETA[1]*SH_BETA[4]*(SH_BETA[12] + 2*q1*q2)) + P[0][6]*(SH_BETA[5]*SH_BETA[8] - SH_BETA[1]*SH_BETA[4]*SH_BETA[9]) + P[1][6]*(SH_BETA[5]*SH_BETA[10] - SH_BETA[1]*SH_BETA[4]*SH_BETA[11]) + P[2][6]*(SH_BETA[5]*SH_BETA[11] + SH_BETA[1]*SH_BETA[4]*SH_BETA[10]) - P[3][6]*(SH_BETA[5]*SH_BETA[9] + SH_BETA[1]*SH_BETA[4]*SH_BETA[8]) + P[6][6]*(SH_BETA[5]*(2*q0*q1 + 2*q2*q3) + SH_BETA[1]*SH_BETA[4]*(2*q0*q2 - 2*q1*q3)))); +SK_BETA[1] = SH_BETA[5]*(SH_BETA[12] - 2*q1*q2) + SH_BETA[1]*SH_BETA[4]*SH_BETA[7]; +SK_BETA[2] = SH_BETA[6] - SH_BETA[1]*SH_BETA[4]*(SH_BETA[12] + 2*q1*q2); +SK_BETA[3] = SH_BETA[5]*(2*q0*q1 + 2*q2*q3) + SH_BETA[1]*SH_BETA[4]*(2*q0*q2 - 2*q1*q3); +SK_BETA[4] = SH_BETA[5]*SH_BETA[10] - SH_BETA[1]*SH_BETA[4]*SH_BETA[11]; +SK_BETA[5] = SH_BETA[5]*SH_BETA[8] - SH_BETA[1]*SH_BETA[4]*SH_BETA[9]; +SK_BETA[6] = SH_BETA[5]*SH_BETA[11] + SH_BETA[1]*SH_BETA[4]*SH_BETA[10]; +SK_BETA[7] = SH_BETA[5]*SH_BETA[9] + SH_BETA[1]*SH_BETA[4]*SH_BETA[8]; float Kfusion[24][1]; float Kfusion[1][1]; -Kfusion[0] = SK_BETA[0]*(P[0][5]*SK_BETA[1] - P[0][2]*SK_BETA[4] - P[0][3]*SK_BETA[2] + P[0][4]*SK_BETA[3] + P[0][22]*SK_BETA[2] - P[0][23]*SK_BETA[3] + P[0][0]*SH_BETA[7]*SK_BETA[5] + P[0][1]*SH_BETA[1]*SH_BETA[4]*SK_BETA[5]); -Kfusion[1] = SK_BETA[0]*(P[1][5]*SK_BETA[1] - P[1][2]*SK_BETA[4] - P[1][3]*SK_BETA[2] + P[1][4]*SK_BETA[3] + P[1][22]*SK_BETA[2] - P[1][23]*SK_BETA[3] + P[1][0]*SH_BETA[7]*SK_BETA[5] + P[1][1]*SH_BETA[1]*SH_BETA[4]*SK_BETA[5]); -Kfusion[2] = SK_BETA[0]*(P[2][5]*SK_BETA[1] - P[2][2]*SK_BETA[4] - P[2][3]*SK_BETA[2] + P[2][4]*SK_BETA[3] + P[2][22]*SK_BETA[2] - P[2][23]*SK_BETA[3] + P[2][0]*SH_BETA[7]*SK_BETA[5] + P[2][1]*SH_BETA[1]*SH_BETA[4]*SK_BETA[5]); -Kfusion[3] = SK_BETA[0]*(P[3][5]*SK_BETA[1] - P[3][2]*SK_BETA[4] - P[3][3]*SK_BETA[2] + P[3][4]*SK_BETA[3] + P[3][22]*SK_BETA[2] - P[3][23]*SK_BETA[3] + P[3][0]*SH_BETA[7]*SK_BETA[5] + P[3][1]*SH_BETA[1]*SH_BETA[4]*SK_BETA[5]); -Kfusion[4] = SK_BETA[0]*(P[4][5]*SK_BETA[1] - P[4][2]*SK_BETA[4] - P[4][3]*SK_BETA[2] + P[4][4]*SK_BETA[3] + P[4][22]*SK_BETA[2] - P[4][23]*SK_BETA[3] + P[4][0]*SH_BETA[7]*SK_BETA[5] + P[4][1]*SH_BETA[1]*SH_BETA[4]*SK_BETA[5]); -Kfusion[5] = SK_BETA[0]*(P[5][5]*SK_BETA[1] - P[5][2]*SK_BETA[4] - P[5][3]*SK_BETA[2] + P[5][4]*SK_BETA[3] + P[5][22]*SK_BETA[2] - P[5][23]*SK_BETA[3] + P[5][0]*SH_BETA[7]*SK_BETA[5] + P[5][1]*SH_BETA[1]*SH_BETA[4]*SK_BETA[5]); -Kfusion[6] = SK_BETA[0]*(P[6][5]*SK_BETA[1] - P[6][2]*SK_BETA[4] - P[6][3]*SK_BETA[2] + P[6][4]*SK_BETA[3] + P[6][22]*SK_BETA[2] - P[6][23]*SK_BETA[3] + P[6][0]*SH_BETA[7]*SK_BETA[5] + P[6][1]*SH_BETA[1]*SH_BETA[4]*SK_BETA[5]); -Kfusion[7] = SK_BETA[0]*(P[7][5]*SK_BETA[1] - P[7][2]*SK_BETA[4] - P[7][3]*SK_BETA[2] + P[7][4]*SK_BETA[3] + P[7][22]*SK_BETA[2] - P[7][23]*SK_BETA[3] + P[7][0]*SH_BETA[7]*SK_BETA[5] + P[7][1]*SH_BETA[1]*SH_BETA[4]*SK_BETA[5]); -Kfusion[8] = SK_BETA[0]*(P[8][5]*SK_BETA[1] - P[8][2]*SK_BETA[4] - P[8][3]*SK_BETA[2] + P[8][4]*SK_BETA[3] + P[8][22]*SK_BETA[2] - P[8][23]*SK_BETA[3] + P[8][0]*SH_BETA[7]*SK_BETA[5] + P[8][1]*SH_BETA[1]*SH_BETA[4]*SK_BETA[5]); -Kfusion[9] = SK_BETA[0]*(P[9][5]*SK_BETA[1] - P[9][2]*SK_BETA[4] - P[9][3]*SK_BETA[2] + P[9][4]*SK_BETA[3] + P[9][22]*SK_BETA[2] - P[9][23]*SK_BETA[3] + P[9][0]*SH_BETA[7]*SK_BETA[5] + P[9][1]*SH_BETA[1]*SH_BETA[4]*SK_BETA[5]); -Kfusion[10] = SK_BETA[0]*(P[10][5]*SK_BETA[1] - P[10][2]*SK_BETA[4] - P[10][3]*SK_BETA[2] + P[10][4]*SK_BETA[3] + P[10][22]*SK_BETA[2] - P[10][23]*SK_BETA[3] + P[10][0]*SH_BETA[7]*SK_BETA[5] + P[10][1]*SH_BETA[1]*SH_BETA[4]*SK_BETA[5]); -Kfusion[11] = SK_BETA[0]*(P[11][5]*SK_BETA[1] - P[11][2]*SK_BETA[4] - P[11][3]*SK_BETA[2] + P[11][4]*SK_BETA[3] + P[11][22]*SK_BETA[2] - P[11][23]*SK_BETA[3] + P[11][0]*SH_BETA[7]*SK_BETA[5] + P[11][1]*SH_BETA[1]*SH_BETA[4]*SK_BETA[5]); -Kfusion[12] = SK_BETA[0]*(P[12][5]*SK_BETA[1] - P[12][2]*SK_BETA[4] - P[12][3]*SK_BETA[2] + P[12][4]*SK_BETA[3] + P[12][22]*SK_BETA[2] - P[12][23]*SK_BETA[3] + P[12][0]*SH_BETA[7]*SK_BETA[5] + P[12][1]*SH_BETA[1]*SH_BETA[4]*SK_BETA[5]); -Kfusion[13] = SK_BETA[0]*(P[13][5]*SK_BETA[1] - P[13][2]*SK_BETA[4] - P[13][3]*SK_BETA[2] + P[13][4]*SK_BETA[3] + P[13][22]*SK_BETA[2] - P[13][23]*SK_BETA[3] + P[13][0]*SH_BETA[7]*SK_BETA[5] + P[13][1]*SH_BETA[1]*SH_BETA[4]*SK_BETA[5]); -Kfusion[14] = SK_BETA[0]*(P[14][5]*SK_BETA[1] - P[14][2]*SK_BETA[4] - P[14][3]*SK_BETA[2] + P[14][4]*SK_BETA[3] + P[14][22]*SK_BETA[2] - P[14][23]*SK_BETA[3] + P[14][0]*SH_BETA[7]*SK_BETA[5] + P[14][1]*SH_BETA[1]*SH_BETA[4]*SK_BETA[5]); -Kfusion[15] = SK_BETA[0]*(P[15][5]*SK_BETA[1] - P[15][2]*SK_BETA[4] - P[15][3]*SK_BETA[2] + P[15][4]*SK_BETA[3] + P[15][22]*SK_BETA[2] - P[15][23]*SK_BETA[3] + P[15][0]*SH_BETA[7]*SK_BETA[5] + P[15][1]*SH_BETA[1]*SH_BETA[4]*SK_BETA[5]); -Kfusion[16] = SK_BETA[0]*(P[16][5]*SK_BETA[1] - P[16][2]*SK_BETA[4] - P[16][3]*SK_BETA[2] + P[16][4]*SK_BETA[3] + P[16][22]*SK_BETA[2] - P[16][23]*SK_BETA[3] + P[16][0]*SH_BETA[7]*SK_BETA[5] + P[16][1]*SH_BETA[1]*SH_BETA[4]*SK_BETA[5]); -Kfusion[17] = SK_BETA[0]*(P[17][5]*SK_BETA[1] - P[17][2]*SK_BETA[4] - P[17][3]*SK_BETA[2] + P[17][4]*SK_BETA[3] + P[17][22]*SK_BETA[2] - P[17][23]*SK_BETA[3] + P[17][0]*SH_BETA[7]*SK_BETA[5] + P[17][1]*SH_BETA[1]*SH_BETA[4]*SK_BETA[5]); -Kfusion[18] = SK_BETA[0]*(P[18][5]*SK_BETA[1] - P[18][2]*SK_BETA[4] - P[18][3]*SK_BETA[2] + P[18][4]*SK_BETA[3] + P[18][22]*SK_BETA[2] - P[18][23]*SK_BETA[3] + P[18][0]*SH_BETA[7]*SK_BETA[5] + P[18][1]*SH_BETA[1]*SH_BETA[4]*SK_BETA[5]); -Kfusion[19] = SK_BETA[0]*(P[19][5]*SK_BETA[1] - P[19][2]*SK_BETA[4] - P[19][3]*SK_BETA[2] + P[19][4]*SK_BETA[3] + P[19][22]*SK_BETA[2] - P[19][23]*SK_BETA[3] + P[19][0]*SH_BETA[7]*SK_BETA[5] + P[19][1]*SH_BETA[1]*SH_BETA[4]*SK_BETA[5]); -Kfusion[20] = SK_BETA[0]*(P[20][5]*SK_BETA[1] - P[20][2]*SK_BETA[4] - P[20][3]*SK_BETA[2] + P[20][4]*SK_BETA[3] + P[20][22]*SK_BETA[2] - P[20][23]*SK_BETA[3] + P[20][0]*SH_BETA[7]*SK_BETA[5] + P[20][1]*SH_BETA[1]*SH_BETA[4]*SK_BETA[5]); -Kfusion[21] = SK_BETA[0]*(P[21][5]*SK_BETA[1] - P[21][2]*SK_BETA[4] - P[21][3]*SK_BETA[2] + P[21][4]*SK_BETA[3] + P[21][22]*SK_BETA[2] - P[21][23]*SK_BETA[3] + P[21][0]*SH_BETA[7]*SK_BETA[5] + P[21][1]*SH_BETA[1]*SH_BETA[4]*SK_BETA[5]); -Kfusion[22] = SK_BETA[0]*(P[22][5]*SK_BETA[1] - P[22][2]*SK_BETA[4] - P[22][3]*SK_BETA[2] + P[22][4]*SK_BETA[3] + P[22][22]*SK_BETA[2] - P[22][23]*SK_BETA[3] + P[22][0]*SH_BETA[7]*SK_BETA[5] + P[22][1]*SH_BETA[1]*SH_BETA[4]*SK_BETA[5]); -Kfusion[23] = SK_BETA[0]*(P[23][5]*SK_BETA[1] - P[23][2]*SK_BETA[4] - P[23][3]*SK_BETA[2] + P[23][4]*SK_BETA[3] + P[23][22]*SK_BETA[2] - P[23][23]*SK_BETA[3] + P[23][0]*SH_BETA[7]*SK_BETA[5] + P[23][1]*SH_BETA[1]*SH_BETA[4]*SK_BETA[5]); +Kfusion[0] = SK_BETA[0]*(P[0][0]*SK_BETA[5] + P[0][1]*SK_BETA[4] - P[0][4]*SK_BETA[1] + P[0][5]*SK_BETA[2] + P[0][2]*SK_BETA[6] + P[0][6]*SK_BETA[3] - P[0][3]*SK_BETA[7] + P[0][22]*SK_BETA[1] - P[0][23]*SK_BETA[2]); +Kfusion[1] = SK_BETA[0]*(P[1][0]*SK_BETA[5] + P[1][1]*SK_BETA[4] - P[1][4]*SK_BETA[1] + P[1][5]*SK_BETA[2] + P[1][2]*SK_BETA[6] + P[1][6]*SK_BETA[3] - P[1][3]*SK_BETA[7] + P[1][22]*SK_BETA[1] - P[1][23]*SK_BETA[2]); +Kfusion[2] = SK_BETA[0]*(P[2][0]*SK_BETA[5] + P[2][1]*SK_BETA[4] - P[2][4]*SK_BETA[1] + P[2][5]*SK_BETA[2] + P[2][2]*SK_BETA[6] + P[2][6]*SK_BETA[3] - P[2][3]*SK_BETA[7] + P[2][22]*SK_BETA[1] - P[2][23]*SK_BETA[2]); +Kfusion[3] = SK_BETA[0]*(P[3][0]*SK_BETA[5] + P[3][1]*SK_BETA[4] - P[3][4]*SK_BETA[1] + P[3][5]*SK_BETA[2] + P[3][2]*SK_BETA[6] + P[3][6]*SK_BETA[3] - P[3][3]*SK_BETA[7] + P[3][22]*SK_BETA[1] - P[3][23]*SK_BETA[2]); +Kfusion[4] = SK_BETA[0]*(P[4][0]*SK_BETA[5] + P[4][1]*SK_BETA[4] - P[4][4]*SK_BETA[1] + P[4][5]*SK_BETA[2] + P[4][2]*SK_BETA[6] + P[4][6]*SK_BETA[3] - P[4][3]*SK_BETA[7] + P[4][22]*SK_BETA[1] - P[4][23]*SK_BETA[2]); +Kfusion[5] = SK_BETA[0]*(P[5][0]*SK_BETA[5] + P[5][1]*SK_BETA[4] - P[5][4]*SK_BETA[1] + P[5][5]*SK_BETA[2] + P[5][2]*SK_BETA[6] + P[5][6]*SK_BETA[3] - P[5][3]*SK_BETA[7] + P[5][22]*SK_BETA[1] - P[5][23]*SK_BETA[2]); +Kfusion[6] = SK_BETA[0]*(P[6][0]*SK_BETA[5] + P[6][1]*SK_BETA[4] - P[6][4]*SK_BETA[1] + P[6][5]*SK_BETA[2] + P[6][2]*SK_BETA[6] + P[6][6]*SK_BETA[3] - P[6][3]*SK_BETA[7] + P[6][22]*SK_BETA[1] - P[6][23]*SK_BETA[2]); +Kfusion[7] = SK_BETA[0]*(P[7][0]*SK_BETA[5] + P[7][1]*SK_BETA[4] - P[7][4]*SK_BETA[1] + P[7][5]*SK_BETA[2] + P[7][2]*SK_BETA[6] + P[7][6]*SK_BETA[3] - P[7][3]*SK_BETA[7] + P[7][22]*SK_BETA[1] - P[7][23]*SK_BETA[2]); +Kfusion[8] = SK_BETA[0]*(P[8][0]*SK_BETA[5] + P[8][1]*SK_BETA[4] - P[8][4]*SK_BETA[1] + P[8][5]*SK_BETA[2] + P[8][2]*SK_BETA[6] + P[8][6]*SK_BETA[3] - P[8][3]*SK_BETA[7] + P[8][22]*SK_BETA[1] - P[8][23]*SK_BETA[2]); +Kfusion[9] = SK_BETA[0]*(P[9][0]*SK_BETA[5] + P[9][1]*SK_BETA[4] - P[9][4]*SK_BETA[1] + P[9][5]*SK_BETA[2] + P[9][2]*SK_BETA[6] + P[9][6]*SK_BETA[3] - P[9][3]*SK_BETA[7] + P[9][22]*SK_BETA[1] - P[9][23]*SK_BETA[2]); +Kfusion[10] = SK_BETA[0]*(P[10][0]*SK_BETA[5] + P[10][1]*SK_BETA[4] - P[10][4]*SK_BETA[1] + P[10][5]*SK_BETA[2] + P[10][2]*SK_BETA[6] + P[10][6]*SK_BETA[3] - P[10][3]*SK_BETA[7] + P[10][22]*SK_BETA[1] - P[10][23]*SK_BETA[2]); +Kfusion[11] = SK_BETA[0]*(P[11][0]*SK_BETA[5] + P[11][1]*SK_BETA[4] - P[11][4]*SK_BETA[1] + P[11][5]*SK_BETA[2] + P[11][2]*SK_BETA[6] + P[11][6]*SK_BETA[3] - P[11][3]*SK_BETA[7] + P[11][22]*SK_BETA[1] - P[11][23]*SK_BETA[2]); +Kfusion[12] = SK_BETA[0]*(P[12][0]*SK_BETA[5] + P[12][1]*SK_BETA[4] - P[12][4]*SK_BETA[1] + P[12][5]*SK_BETA[2] + P[12][2]*SK_BETA[6] + P[12][6]*SK_BETA[3] - P[12][3]*SK_BETA[7] + P[12][22]*SK_BETA[1] - P[12][23]*SK_BETA[2]); +Kfusion[13] = SK_BETA[0]*(P[13][0]*SK_BETA[5] + P[13][1]*SK_BETA[4] - P[13][4]*SK_BETA[1] + P[13][5]*SK_BETA[2] + P[13][2]*SK_BETA[6] + P[13][6]*SK_BETA[3] - P[13][3]*SK_BETA[7] + P[13][22]*SK_BETA[1] - P[13][23]*SK_BETA[2]); +Kfusion[14] = SK_BETA[0]*(P[14][0]*SK_BETA[5] + P[14][1]*SK_BETA[4] - P[14][4]*SK_BETA[1] + P[14][5]*SK_BETA[2] + P[14][2]*SK_BETA[6] + P[14][6]*SK_BETA[3] - P[14][3]*SK_BETA[7] + P[14][22]*SK_BETA[1] - P[14][23]*SK_BETA[2]); +Kfusion[15] = SK_BETA[0]*(P[15][0]*SK_BETA[5] + P[15][1]*SK_BETA[4] - P[15][4]*SK_BETA[1] + P[15][5]*SK_BETA[2] + P[15][2]*SK_BETA[6] + P[15][6]*SK_BETA[3] - P[15][3]*SK_BETA[7] + P[15][22]*SK_BETA[1] - P[15][23]*SK_BETA[2]); +Kfusion[16] = SK_BETA[0]*(P[16][0]*SK_BETA[5] + P[16][1]*SK_BETA[4] - P[16][4]*SK_BETA[1] + P[16][5]*SK_BETA[2] + P[16][2]*SK_BETA[6] + P[16][6]*SK_BETA[3] - P[16][3]*SK_BETA[7] + P[16][22]*SK_BETA[1] - P[16][23]*SK_BETA[2]); +Kfusion[17] = SK_BETA[0]*(P[17][0]*SK_BETA[5] + P[17][1]*SK_BETA[4] - P[17][4]*SK_BETA[1] + P[17][5]*SK_BETA[2] + P[17][2]*SK_BETA[6] + P[17][6]*SK_BETA[3] - P[17][3]*SK_BETA[7] + P[17][22]*SK_BETA[1] - P[17][23]*SK_BETA[2]); +Kfusion[18] = SK_BETA[0]*(P[18][0]*SK_BETA[5] + P[18][1]*SK_BETA[4] - P[18][4]*SK_BETA[1] + P[18][5]*SK_BETA[2] + P[18][2]*SK_BETA[6] + P[18][6]*SK_BETA[3] - P[18][3]*SK_BETA[7] + P[18][22]*SK_BETA[1] - P[18][23]*SK_BETA[2]); +Kfusion[19] = SK_BETA[0]*(P[19][0]*SK_BETA[5] + P[19][1]*SK_BETA[4] - P[19][4]*SK_BETA[1] + P[19][5]*SK_BETA[2] + P[19][2]*SK_BETA[6] + P[19][6]*SK_BETA[3] - P[19][3]*SK_BETA[7] + P[19][22]*SK_BETA[1] - P[19][23]*SK_BETA[2]); +Kfusion[20] = SK_BETA[0]*(P[20][0]*SK_BETA[5] + P[20][1]*SK_BETA[4] - P[20][4]*SK_BETA[1] + P[20][5]*SK_BETA[2] + P[20][2]*SK_BETA[6] + P[20][6]*SK_BETA[3] - P[20][3]*SK_BETA[7] + P[20][22]*SK_BETA[1] - P[20][23]*SK_BETA[2]); +Kfusion[21] = SK_BETA[0]*(P[21][0]*SK_BETA[5] + P[21][1]*SK_BETA[4] - P[21][4]*SK_BETA[1] + P[21][5]*SK_BETA[2] + P[21][2]*SK_BETA[6] + P[21][6]*SK_BETA[3] - P[21][3]*SK_BETA[7] + P[21][22]*SK_BETA[1] - P[21][23]*SK_BETA[2]); +Kfusion[22] = SK_BETA[0]*(P[22][0]*SK_BETA[5] + P[22][1]*SK_BETA[4] - P[22][4]*SK_BETA[1] + P[22][5]*SK_BETA[2] + P[22][2]*SK_BETA[6] + P[22][6]*SK_BETA[3] - P[22][3]*SK_BETA[7] + P[22][22]*SK_BETA[1] - P[22][23]*SK_BETA[2]); +Kfusion[23] = SK_BETA[0]*(P[23][0]*SK_BETA[5] + P[23][1]*SK_BETA[4] - P[23][4]*SK_BETA[1] + P[23][5]*SK_BETA[2] + P[23][2]*SK_BETA[6] + P[23][6]*SK_BETA[3] - P[23][3]*SK_BETA[7] + P[23][22]*SK_BETA[1] - P[23][23]*SK_BETA[2]); float SH_MAG[9][1]; -SH_MAG[0] = sq(q0) - sq(q1) + sq(q2) - sq(q3); -SH_MAG[1] = sq(q0) + sq(q1) - sq(q2) - sq(q3); -SH_MAG[2] = sq(q0) - sq(q1) - sq(q2) + sq(q3); -SH_MAG[3] = 2*q0*q1 + 2*q2*q3; -SH_MAG[4] = 2*q0*q3 + 2*q1*q2; -SH_MAG[5] = 2*q0*q2 + 2*q1*q3; -SH_MAG[6] = magE*(2*q0*q1 - 2*q2*q3); -SH_MAG[7] = 2*q1*q3 - 2*q0*q2; -SH_MAG[8] = 2*q0*q3; +SH_MAG[0] = 2*magD*q3 + 2*magE*q2 + 2*magN*q1; +SH_MAG[1] = 2*magD*q0 - 2*magE*q1 + 2*magN*q2; +SH_MAG[2] = 2*magD*q1 + 2*magE*q0 - 2*magN*q3; +SH_MAG[3] = sq(q3); +SH_MAG[4] = sq(q2); +SH_MAG[5] = sq(q1); +SH_MAG[6] = sq(q0); +SH_MAG[7] = 2*magN*q0; +SH_MAG[8] = 2*magE*q3; float H_MAG[1][24]; -H_MAG[1] = SH_MAG[6] - magD*SH_MAG[2] - magN*SH_MAG[5]; -H_MAG[2] = magE*SH_MAG[0] + magD*SH_MAG[3] - magN*(SH_MAG[8] - 2*q1*q2); -H_MAG[16] = SH_MAG[1]; -H_MAG[17] = SH_MAG[4]; -H_MAG[18] = SH_MAG[7]; +H_MAG[0] = SH_MAG[7] + SH_MAG[8] - 2*magD*q2; +H_MAG[1] = SH_MAG[0]; +H_MAG[2] = -SH_MAG[1]; +H_MAG[3] = SH_MAG[2]; +H_MAG[16] = SH_MAG[5] - SH_MAG[4] - SH_MAG[3] + SH_MAG[6]; +H_MAG[17] = 2*q0*q3 + 2*q1*q2; +H_MAG[18] = 2*q1*q3 - 2*q0*q2; H_MAG[19] = 1; -float SK_MX[4][1]; -SK_MX[0] = 1/(P[19][19] + R_MAG - P[1][19]*(magD*SH_MAG[2] - SH_MAG[6] + magN*SH_MAG[5]) + P[16][19]*SH_MAG[1] + P[17][19]*SH_MAG[4] + P[18][19]*SH_MAG[7] + P[2][19]*(magE*SH_MAG[0] + magD*SH_MAG[3] - magN*(SH_MAG[8] - 2*q1*q2)) - (magD*SH_MAG[2] - SH_MAG[6] + magN*SH_MAG[5])*(P[19][1] - P[1][1]*(magD*SH_MAG[2] - SH_MAG[6] + magN*SH_MAG[5]) + P[16][1]*SH_MAG[1] + P[17][1]*SH_MAG[4] + P[18][1]*SH_MAG[7] + P[2][1]*(magE*SH_MAG[0] + magD*SH_MAG[3] - magN*(SH_MAG[8] - 2*q1*q2))) + SH_MAG[1]*(P[19][16] - P[1][16]*(magD*SH_MAG[2] - SH_MAG[6] + magN*SH_MAG[5]) + P[16][16]*SH_MAG[1] + P[17][16]*SH_MAG[4] + P[18][16]*SH_MAG[7] + P[2][16]*(magE*SH_MAG[0] + magD*SH_MAG[3] - magN*(SH_MAG[8] - 2*q1*q2))) + SH_MAG[4]*(P[19][17] - P[1][17]*(magD*SH_MAG[2] - SH_MAG[6] + magN*SH_MAG[5]) + P[16][17]*SH_MAG[1] + P[17][17]*SH_MAG[4] + P[18][17]*SH_MAG[7] + P[2][17]*(magE*SH_MAG[0] + magD*SH_MAG[3] - magN*(SH_MAG[8] - 2*q1*q2))) + SH_MAG[7]*(P[19][18] - P[1][18]*(magD*SH_MAG[2] - SH_MAG[6] + magN*SH_MAG[5]) + P[16][18]*SH_MAG[1] + P[17][18]*SH_MAG[4] + P[18][18]*SH_MAG[7] + P[2][18]*(magE*SH_MAG[0] + magD*SH_MAG[3] - magN*(SH_MAG[8] - 2*q1*q2))) + (magE*SH_MAG[0] + magD*SH_MAG[3] - magN*(SH_MAG[8] - 2*q1*q2))*(P[19][2] - P[1][2]*(magD*SH_MAG[2] - SH_MAG[6] + magN*SH_MAG[5]) + P[16][2]*SH_MAG[1] + P[17][2]*SH_MAG[4] + P[18][2]*SH_MAG[7] + P[2][2]*(magE*SH_MAG[0] + magD*SH_MAG[3] - magN*(SH_MAG[8] - 2*q1*q2)))); -SK_MX[1] = magE*SH_MAG[0] + magD*SH_MAG[3] - magN*(SH_MAG[8] - 2*q1*q2); -SK_MX[2] = magD*SH_MAG[2] - SH_MAG[6] + magN*SH_MAG[5]; -SK_MX[3] = SH_MAG[7]; +float SK_MX[5][1]; +SK_MX[0] = 1/(P[19][19] + R_MAG + P[1][19]*SH_MAG[0] - P[2][19]*SH_MAG[1] + P[3][19]*SH_MAG[2] - P[16][19]*(SH_MAG[3] + SH_MAG[4] - SH_MAG[5] - SH_MAG[6]) + (2*q0*q3 + 2*q1*q2)*(P[19][17] + P[1][17]*SH_MAG[0] - P[2][17]*SH_MAG[1] + P[3][17]*SH_MAG[2] - P[16][17]*(SH_MAG[3] + SH_MAG[4] - SH_MAG[5] - SH_MAG[6]) + P[17][17]*(2*q0*q3 + 2*q1*q2) - P[18][17]*(2*q0*q2 - 2*q1*q3) + P[0][17]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) - (2*q0*q2 - 2*q1*q3)*(P[19][18] + P[1][18]*SH_MAG[0] - P[2][18]*SH_MAG[1] + P[3][18]*SH_MAG[2] - P[16][18]*(SH_MAG[3] + SH_MAG[4] - SH_MAG[5] - SH_MAG[6]) + P[17][18]*(2*q0*q3 + 2*q1*q2) - P[18][18]*(2*q0*q2 - 2*q1*q3) + P[0][18]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) + (SH_MAG[7] + SH_MAG[8] - 2*magD*q2)*(P[19][0] + P[1][0]*SH_MAG[0] - P[2][0]*SH_MAG[1] + P[3][0]*SH_MAG[2] - P[16][0]*(SH_MAG[3] + SH_MAG[4] - SH_MAG[5] - SH_MAG[6]) + P[17][0]*(2*q0*q3 + 2*q1*q2) - P[18][0]*(2*q0*q2 - 2*q1*q3) + P[0][0]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) + P[17][19]*(2*q0*q3 + 2*q1*q2) - P[18][19]*(2*q0*q2 - 2*q1*q3) + SH_MAG[0]*(P[19][1] + P[1][1]*SH_MAG[0] - P[2][1]*SH_MAG[1] + P[3][1]*SH_MAG[2] - P[16][1]*(SH_MAG[3] + SH_MAG[4] - SH_MAG[5] - SH_MAG[6]) + P[17][1]*(2*q0*q3 + 2*q1*q2) - P[18][1]*(2*q0*q2 - 2*q1*q3) + P[0][1]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) - SH_MAG[1]*(P[19][2] + P[1][2]*SH_MAG[0] - P[2][2]*SH_MAG[1] + P[3][2]*SH_MAG[2] - P[16][2]*(SH_MAG[3] + SH_MAG[4] - SH_MAG[5] - SH_MAG[6]) + P[17][2]*(2*q0*q3 + 2*q1*q2) - P[18][2]*(2*q0*q2 - 2*q1*q3) + P[0][2]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) + SH_MAG[2]*(P[19][3] + P[1][3]*SH_MAG[0] - P[2][3]*SH_MAG[1] + P[3][3]*SH_MAG[2] - P[16][3]*(SH_MAG[3] + SH_MAG[4] - SH_MAG[5] - SH_MAG[6]) + P[17][3]*(2*q0*q3 + 2*q1*q2) - P[18][3]*(2*q0*q2 - 2*q1*q3) + P[0][3]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) - (SH_MAG[3] + SH_MAG[4] - SH_MAG[5] - SH_MAG[6])*(P[19][16] + P[1][16]*SH_MAG[0] - P[2][16]*SH_MAG[1] + P[3][16]*SH_MAG[2] - P[16][16]*(SH_MAG[3] + SH_MAG[4] - SH_MAG[5] - SH_MAG[6]) + P[17][16]*(2*q0*q3 + 2*q1*q2) - P[18][16]*(2*q0*q2 - 2*q1*q3) + P[0][16]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) + P[0][19]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)); +SK_MX[1] = SH_MAG[3] + SH_MAG[4] - SH_MAG[5] - SH_MAG[6]; +SK_MX[2] = SH_MAG[7] + SH_MAG[8] - 2*magD*q2; +SK_MX[3] = 2*q0*q2 - 2*q1*q3; +SK_MX[4] = 2*q0*q3 + 2*q1*q2; float Kfusion[24][1]; float Kfusion[1][1]; -Kfusion[0] = SK_MX[0]*(P[0][19] + P[0][16]*SH_MAG[1] + P[0][17]*SH_MAG[4] - P[0][1]*SK_MX[2] + P[0][2]*SK_MX[1] + P[0][18]*SK_MX[3]); -Kfusion[1] = SK_MX[0]*(P[1][19] + P[1][16]*SH_MAG[1] + P[1][17]*SH_MAG[4] - P[1][1]*SK_MX[2] + P[1][2]*SK_MX[1] + P[1][18]*SK_MX[3]); -Kfusion[2] = SK_MX[0]*(P[2][19] + P[2][16]*SH_MAG[1] + P[2][17]*SH_MAG[4] - P[2][1]*SK_MX[2] + P[2][2]*SK_MX[1] + P[2][18]*SK_MX[3]); -Kfusion[3] = SK_MX[0]*(P[3][19] + P[3][16]*SH_MAG[1] + P[3][17]*SH_MAG[4] - P[3][1]*SK_MX[2] + P[3][2]*SK_MX[1] + P[3][18]*SK_MX[3]); -Kfusion[4] = SK_MX[0]*(P[4][19] + P[4][16]*SH_MAG[1] + P[4][17]*SH_MAG[4] - P[4][1]*SK_MX[2] + P[4][2]*SK_MX[1] + P[4][18]*SK_MX[3]); -Kfusion[5] = SK_MX[0]*(P[5][19] + P[5][16]*SH_MAG[1] + P[5][17]*SH_MAG[4] - P[5][1]*SK_MX[2] + P[5][2]*SK_MX[1] + P[5][18]*SK_MX[3]); -Kfusion[6] = SK_MX[0]*(P[6][19] + P[6][16]*SH_MAG[1] + P[6][17]*SH_MAG[4] - P[6][1]*SK_MX[2] + P[6][2]*SK_MX[1] + P[6][18]*SK_MX[3]); -Kfusion[7] = SK_MX[0]*(P[7][19] + P[7][16]*SH_MAG[1] + P[7][17]*SH_MAG[4] - P[7][1]*SK_MX[2] + P[7][2]*SK_MX[1] + P[7][18]*SK_MX[3]); -Kfusion[8] = SK_MX[0]*(P[8][19] + P[8][16]*SH_MAG[1] + P[8][17]*SH_MAG[4] - P[8][1]*SK_MX[2] + P[8][2]*SK_MX[1] + P[8][18]*SK_MX[3]); -Kfusion[9] = SK_MX[0]*(P[9][19] + P[9][16]*SH_MAG[1] + P[9][17]*SH_MAG[4] - P[9][1]*SK_MX[2] + P[9][2]*SK_MX[1] + P[9][18]*SK_MX[3]); -Kfusion[10] = SK_MX[0]*(P[10][19] + P[10][16]*SH_MAG[1] + P[10][17]*SH_MAG[4] - P[10][1]*SK_MX[2] + P[10][2]*SK_MX[1] + P[10][18]*SK_MX[3]); -Kfusion[11] = SK_MX[0]*(P[11][19] + P[11][16]*SH_MAG[1] + P[11][17]*SH_MAG[4] - P[11][1]*SK_MX[2] + P[11][2]*SK_MX[1] + P[11][18]*SK_MX[3]); -Kfusion[12] = SK_MX[0]*(P[12][19] + P[12][16]*SH_MAG[1] + P[12][17]*SH_MAG[4] - P[12][1]*SK_MX[2] + P[12][2]*SK_MX[1] + P[12][18]*SK_MX[3]); -Kfusion[13] = SK_MX[0]*(P[13][19] + P[13][16]*SH_MAG[1] + P[13][17]*SH_MAG[4] - P[13][1]*SK_MX[2] + P[13][2]*SK_MX[1] + P[13][18]*SK_MX[3]); -Kfusion[14] = SK_MX[0]*(P[14][19] + P[14][16]*SH_MAG[1] + P[14][17]*SH_MAG[4] - P[14][1]*SK_MX[2] + P[14][2]*SK_MX[1] + P[14][18]*SK_MX[3]); -Kfusion[15] = SK_MX[0]*(P[15][19] + P[15][16]*SH_MAG[1] + P[15][17]*SH_MAG[4] - P[15][1]*SK_MX[2] + P[15][2]*SK_MX[1] + P[15][18]*SK_MX[3]); -Kfusion[16] = SK_MX[0]*(P[16][19] + P[16][16]*SH_MAG[1] + P[16][17]*SH_MAG[4] - P[16][1]*SK_MX[2] + P[16][2]*SK_MX[1] + P[16][18]*SK_MX[3]); -Kfusion[17] = SK_MX[0]*(P[17][19] + P[17][16]*SH_MAG[1] + P[17][17]*SH_MAG[4] - P[17][1]*SK_MX[2] + P[17][2]*SK_MX[1] + P[17][18]*SK_MX[3]); -Kfusion[18] = SK_MX[0]*(P[18][19] + P[18][16]*SH_MAG[1] + P[18][17]*SH_MAG[4] - P[18][1]*SK_MX[2] + P[18][2]*SK_MX[1] + P[18][18]*SK_MX[3]); -Kfusion[19] = SK_MX[0]*(P[19][19] + P[19][16]*SH_MAG[1] + P[19][17]*SH_MAG[4] - P[19][1]*SK_MX[2] + P[19][2]*SK_MX[1] + P[19][18]*SK_MX[3]); -Kfusion[20] = SK_MX[0]*(P[20][19] + P[20][16]*SH_MAG[1] + P[20][17]*SH_MAG[4] - P[20][1]*SK_MX[2] + P[20][2]*SK_MX[1] + P[20][18]*SK_MX[3]); -Kfusion[21] = SK_MX[0]*(P[21][19] + P[21][16]*SH_MAG[1] + P[21][17]*SH_MAG[4] - P[21][1]*SK_MX[2] + P[21][2]*SK_MX[1] + P[21][18]*SK_MX[3]); -Kfusion[22] = SK_MX[0]*(P[22][19] + P[22][16]*SH_MAG[1] + P[22][17]*SH_MAG[4] - P[22][1]*SK_MX[2] + P[22][2]*SK_MX[1] + P[22][18]*SK_MX[3]); -Kfusion[23] = SK_MX[0]*(P[23][19] + P[23][16]*SH_MAG[1] + P[23][17]*SH_MAG[4] - P[23][1]*SK_MX[2] + P[23][2]*SK_MX[1] + P[23][18]*SK_MX[3]); +Kfusion[0] = SK_MX[0]*(P[0][19] + P[0][1]*SH_MAG[0] - P[0][2]*SH_MAG[1] + P[0][3]*SH_MAG[2] + P[0][0]*SK_MX[2] - P[0][16]*SK_MX[1] + P[0][17]*SK_MX[4] - P[0][18]*SK_MX[3]); +Kfusion[1] = SK_MX[0]*(P[1][19] + P[1][1]*SH_MAG[0] - P[1][2]*SH_MAG[1] + P[1][3]*SH_MAG[2] + P[1][0]*SK_MX[2] - P[1][16]*SK_MX[1] + P[1][17]*SK_MX[4] - P[1][18]*SK_MX[3]); +Kfusion[2] = SK_MX[0]*(P[2][19] + P[2][1]*SH_MAG[0] - P[2][2]*SH_MAG[1] + P[2][3]*SH_MAG[2] + P[2][0]*SK_MX[2] - P[2][16]*SK_MX[1] + P[2][17]*SK_MX[4] - P[2][18]*SK_MX[3]); +Kfusion[3] = SK_MX[0]*(P[3][19] + P[3][1]*SH_MAG[0] - P[3][2]*SH_MAG[1] + P[3][3]*SH_MAG[2] + P[3][0]*SK_MX[2] - P[3][16]*SK_MX[1] + P[3][17]*SK_MX[4] - P[3][18]*SK_MX[3]); +Kfusion[4] = SK_MX[0]*(P[4][19] + P[4][1]*SH_MAG[0] - P[4][2]*SH_MAG[1] + P[4][3]*SH_MAG[2] + P[4][0]*SK_MX[2] - P[4][16]*SK_MX[1] + P[4][17]*SK_MX[4] - P[4][18]*SK_MX[3]); +Kfusion[5] = SK_MX[0]*(P[5][19] + P[5][1]*SH_MAG[0] - P[5][2]*SH_MAG[1] + P[5][3]*SH_MAG[2] + P[5][0]*SK_MX[2] - P[5][16]*SK_MX[1] + P[5][17]*SK_MX[4] - P[5][18]*SK_MX[3]); +Kfusion[6] = SK_MX[0]*(P[6][19] + P[6][1]*SH_MAG[0] - P[6][2]*SH_MAG[1] + P[6][3]*SH_MAG[2] + P[6][0]*SK_MX[2] - P[6][16]*SK_MX[1] + P[6][17]*SK_MX[4] - P[6][18]*SK_MX[3]); +Kfusion[7] = SK_MX[0]*(P[7][19] + P[7][1]*SH_MAG[0] - P[7][2]*SH_MAG[1] + P[7][3]*SH_MAG[2] + P[7][0]*SK_MX[2] - P[7][16]*SK_MX[1] + P[7][17]*SK_MX[4] - P[7][18]*SK_MX[3]); +Kfusion[8] = SK_MX[0]*(P[8][19] + P[8][1]*SH_MAG[0] - P[8][2]*SH_MAG[1] + P[8][3]*SH_MAG[2] + P[8][0]*SK_MX[2] - P[8][16]*SK_MX[1] + P[8][17]*SK_MX[4] - P[8][18]*SK_MX[3]); +Kfusion[9] = SK_MX[0]*(P[9][19] + P[9][1]*SH_MAG[0] - P[9][2]*SH_MAG[1] + P[9][3]*SH_MAG[2] + P[9][0]*SK_MX[2] - P[9][16]*SK_MX[1] + P[9][17]*SK_MX[4] - P[9][18]*SK_MX[3]); +Kfusion[10] = SK_MX[0]*(P[10][19] + P[10][1]*SH_MAG[0] - P[10][2]*SH_MAG[1] + P[10][3]*SH_MAG[2] + P[10][0]*SK_MX[2] - P[10][16]*SK_MX[1] + P[10][17]*SK_MX[4] - P[10][18]*SK_MX[3]); +Kfusion[11] = SK_MX[0]*(P[11][19] + P[11][1]*SH_MAG[0] - P[11][2]*SH_MAG[1] + P[11][3]*SH_MAG[2] + P[11][0]*SK_MX[2] - P[11][16]*SK_MX[1] + P[11][17]*SK_MX[4] - P[11][18]*SK_MX[3]); +Kfusion[12] = SK_MX[0]*(P[12][19] + P[12][1]*SH_MAG[0] - P[12][2]*SH_MAG[1] + P[12][3]*SH_MAG[2] + P[12][0]*SK_MX[2] - P[12][16]*SK_MX[1] + P[12][17]*SK_MX[4] - P[12][18]*SK_MX[3]); +Kfusion[13] = SK_MX[0]*(P[13][19] + P[13][1]*SH_MAG[0] - P[13][2]*SH_MAG[1] + P[13][3]*SH_MAG[2] + P[13][0]*SK_MX[2] - P[13][16]*SK_MX[1] + P[13][17]*SK_MX[4] - P[13][18]*SK_MX[3]); +Kfusion[14] = SK_MX[0]*(P[14][19] + P[14][1]*SH_MAG[0] - P[14][2]*SH_MAG[1] + P[14][3]*SH_MAG[2] + P[14][0]*SK_MX[2] - P[14][16]*SK_MX[1] + P[14][17]*SK_MX[4] - P[14][18]*SK_MX[3]); +Kfusion[15] = SK_MX[0]*(P[15][19] + P[15][1]*SH_MAG[0] - P[15][2]*SH_MAG[1] + P[15][3]*SH_MAG[2] + P[15][0]*SK_MX[2] - P[15][16]*SK_MX[1] + P[15][17]*SK_MX[4] - P[15][18]*SK_MX[3]); +Kfusion[16] = SK_MX[0]*(P[16][19] + P[16][1]*SH_MAG[0] - P[16][2]*SH_MAG[1] + P[16][3]*SH_MAG[2] + P[16][0]*SK_MX[2] - P[16][16]*SK_MX[1] + P[16][17]*SK_MX[4] - P[16][18]*SK_MX[3]); +Kfusion[17] = SK_MX[0]*(P[17][19] + P[17][1]*SH_MAG[0] - P[17][2]*SH_MAG[1] + P[17][3]*SH_MAG[2] + P[17][0]*SK_MX[2] - P[17][16]*SK_MX[1] + P[17][17]*SK_MX[4] - P[17][18]*SK_MX[3]); +Kfusion[18] = SK_MX[0]*(P[18][19] + P[18][1]*SH_MAG[0] - P[18][2]*SH_MAG[1] + P[18][3]*SH_MAG[2] + P[18][0]*SK_MX[2] - P[18][16]*SK_MX[1] + P[18][17]*SK_MX[4] - P[18][18]*SK_MX[3]); +Kfusion[19] = SK_MX[0]*(P[19][19] + P[19][1]*SH_MAG[0] - P[19][2]*SH_MAG[1] + P[19][3]*SH_MAG[2] + P[19][0]*SK_MX[2] - P[19][16]*SK_MX[1] + P[19][17]*SK_MX[4] - P[19][18]*SK_MX[3]); +Kfusion[20] = SK_MX[0]*(P[20][19] + P[20][1]*SH_MAG[0] - P[20][2]*SH_MAG[1] + P[20][3]*SH_MAG[2] + P[20][0]*SK_MX[2] - P[20][16]*SK_MX[1] + P[20][17]*SK_MX[4] - P[20][18]*SK_MX[3]); +Kfusion[21] = SK_MX[0]*(P[21][19] + P[21][1]*SH_MAG[0] - P[21][2]*SH_MAG[1] + P[21][3]*SH_MAG[2] + P[21][0]*SK_MX[2] - P[21][16]*SK_MX[1] + P[21][17]*SK_MX[4] - P[21][18]*SK_MX[3]); +Kfusion[22] = SK_MX[0]*(P[22][19] + P[22][1]*SH_MAG[0] - P[22][2]*SH_MAG[1] + P[22][3]*SH_MAG[2] + P[22][0]*SK_MX[2] - P[22][16]*SK_MX[1] + P[22][17]*SK_MX[4] - P[22][18]*SK_MX[3]); +Kfusion[23] = SK_MX[0]*(P[23][19] + P[23][1]*SH_MAG[0] - P[23][2]*SH_MAG[1] + P[23][3]*SH_MAG[2] + P[23][0]*SK_MX[2] - P[23][16]*SK_MX[1] + P[23][17]*SK_MX[4] - P[23][18]*SK_MX[3]); float H_MAG[1][24]; -H_MAG[0] = magD*SH_MAG[2] - SH_MAG[6] + magN*SH_MAG[5]; -H_MAG[2] = - magE*SH_MAG[4] - magD*SH_MAG[7] - magN*SH_MAG[1]; -H_MAG[16] = 2*q1*q2 - SH_MAG[8]; -H_MAG[17] = SH_MAG[0]; -H_MAG[18] = SH_MAG[3]; +H_MAG[0] = SH_MAG[2]; +H_MAG[1] = SH_MAG[1]; +H_MAG[2] = SH_MAG[0]; +H_MAG[3] = 2*magD*q2 - SH_MAG[8] - SH_MAG[7]; +H_MAG[16] = 2*q1*q2 - 2*q0*q3; +H_MAG[17] = SH_MAG[4] - SH_MAG[3] - SH_MAG[5] + SH_MAG[6]; +H_MAG[18] = 2*q0*q1 + 2*q2*q3; H_MAG[20] = 1; -float SK_MY[4][1]; -SK_MY[0] = 1/(P[20][20] + R_MAG + P[0][20]*(magD*SH_MAG[2] - SH_MAG[6] + magN*SH_MAG[5]) + P[17][20]*SH_MAG[0] + P[18][20]*SH_MAG[3] - (SH_MAG[8] - 2*q1*q2)*(P[20][16] + P[0][16]*(magD*SH_MAG[2] - SH_MAG[6] + magN*SH_MAG[5]) + P[17][16]*SH_MAG[0] + P[18][16]*SH_MAG[3] - P[2][16]*(magE*SH_MAG[4] + magD*SH_MAG[7] + magN*SH_MAG[1]) - P[16][16]*(SH_MAG[8] - 2*q1*q2)) - P[2][20]*(magE*SH_MAG[4] + magD*SH_MAG[7] + magN*SH_MAG[1]) + (magD*SH_MAG[2] - SH_MAG[6] + magN*SH_MAG[5])*(P[20][0] + P[0][0]*(magD*SH_MAG[2] - SH_MAG[6] + magN*SH_MAG[5]) + P[17][0]*SH_MAG[0] + P[18][0]*SH_MAG[3] - P[2][0]*(magE*SH_MAG[4] + magD*SH_MAG[7] + magN*SH_MAG[1]) - P[16][0]*(SH_MAG[8] - 2*q1*q2)) + SH_MAG[0]*(P[20][17] + P[0][17]*(magD*SH_MAG[2] - SH_MAG[6] + magN*SH_MAG[5]) + P[17][17]*SH_MAG[0] + P[18][17]*SH_MAG[3] - P[2][17]*(magE*SH_MAG[4] + magD*SH_MAG[7] + magN*SH_MAG[1]) - P[16][17]*(SH_MAG[8] - 2*q1*q2)) + SH_MAG[3]*(P[20][18] + P[0][18]*(magD*SH_MAG[2] - SH_MAG[6] + magN*SH_MAG[5]) + P[17][18]*SH_MAG[0] + P[18][18]*SH_MAG[3] - P[2][18]*(magE*SH_MAG[4] + magD*SH_MAG[7] + magN*SH_MAG[1]) - P[16][18]*(SH_MAG[8] - 2*q1*q2)) - P[16][20]*(SH_MAG[8] - 2*q1*q2) - (magE*SH_MAG[4] + magD*SH_MAG[7] + magN*SH_MAG[1])*(P[20][2] + P[0][2]*(magD*SH_MAG[2] - SH_MAG[6] + magN*SH_MAG[5]) + P[17][2]*SH_MAG[0] + P[18][2]*SH_MAG[3] - P[2][2]*(magE*SH_MAG[4] + magD*SH_MAG[7] + magN*SH_MAG[1]) - P[16][2]*(SH_MAG[8] - 2*q1*q2))); -SK_MY[1] = magE*SH_MAG[4] + magD*SH_MAG[7] + magN*SH_MAG[1]; -SK_MY[2] = magD*SH_MAG[2] - SH_MAG[6] + magN*SH_MAG[5]; -SK_MY[3] = SH_MAG[8] - 2*q1*q2; +float SK_MY[5][1]; +SK_MY[0] = 1/(P[20][20] + R_MAG + P[0][20]*SH_MAG[2] + P[1][20]*SH_MAG[1] + P[2][20]*SH_MAG[0] - P[17][20]*(SH_MAG[3] - SH_MAG[4] + SH_MAG[5] - SH_MAG[6]) - (2*q0*q3 - 2*q1*q2)*(P[20][16] + P[0][16]*SH_MAG[2] + P[1][16]*SH_MAG[1] + P[2][16]*SH_MAG[0] - P[17][16]*(SH_MAG[3] - SH_MAG[4] + SH_MAG[5] - SH_MAG[6]) - P[16][16]*(2*q0*q3 - 2*q1*q2) + P[18][16]*(2*q0*q1 + 2*q2*q3) - P[3][16]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) + (2*q0*q1 + 2*q2*q3)*(P[20][18] + P[0][18]*SH_MAG[2] + P[1][18]*SH_MAG[1] + P[2][18]*SH_MAG[0] - P[17][18]*(SH_MAG[3] - SH_MAG[4] + SH_MAG[5] - SH_MAG[6]) - P[16][18]*(2*q0*q3 - 2*q1*q2) + P[18][18]*(2*q0*q1 + 2*q2*q3) - P[3][18]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) - (SH_MAG[7] + SH_MAG[8] - 2*magD*q2)*(P[20][3] + P[0][3]*SH_MAG[2] + P[1][3]*SH_MAG[1] + P[2][3]*SH_MAG[0] - P[17][3]*(SH_MAG[3] - SH_MAG[4] + SH_MAG[5] - SH_MAG[6]) - P[16][3]*(2*q0*q3 - 2*q1*q2) + P[18][3]*(2*q0*q1 + 2*q2*q3) - P[3][3]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) - P[16][20]*(2*q0*q3 - 2*q1*q2) + P[18][20]*(2*q0*q1 + 2*q2*q3) + SH_MAG[2]*(P[20][0] + P[0][0]*SH_MAG[2] + P[1][0]*SH_MAG[1] + P[2][0]*SH_MAG[0] - P[17][0]*(SH_MAG[3] - SH_MAG[4] + SH_MAG[5] - SH_MAG[6]) - P[16][0]*(2*q0*q3 - 2*q1*q2) + P[18][0]*(2*q0*q1 + 2*q2*q3) - P[3][0]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) + SH_MAG[1]*(P[20][1] + P[0][1]*SH_MAG[2] + P[1][1]*SH_MAG[1] + P[2][1]*SH_MAG[0] - P[17][1]*(SH_MAG[3] - SH_MAG[4] + SH_MAG[5] - SH_MAG[6]) - P[16][1]*(2*q0*q3 - 2*q1*q2) + P[18][1]*(2*q0*q1 + 2*q2*q3) - P[3][1]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) + SH_MAG[0]*(P[20][2] + P[0][2]*SH_MAG[2] + P[1][2]*SH_MAG[1] + P[2][2]*SH_MAG[0] - P[17][2]*(SH_MAG[3] - SH_MAG[4] + SH_MAG[5] - SH_MAG[6]) - P[16][2]*(2*q0*q3 - 2*q1*q2) + P[18][2]*(2*q0*q1 + 2*q2*q3) - P[3][2]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) - (SH_MAG[3] - SH_MAG[4] + SH_MAG[5] - SH_MAG[6])*(P[20][17] + P[0][17]*SH_MAG[2] + P[1][17]*SH_MAG[1] + P[2][17]*SH_MAG[0] - P[17][17]*(SH_MAG[3] - SH_MAG[4] + SH_MAG[5] - SH_MAG[6]) - P[16][17]*(2*q0*q3 - 2*q1*q2) + P[18][17]*(2*q0*q1 + 2*q2*q3) - P[3][17]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) - P[3][20]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)); +SK_MY[1] = SH_MAG[3] - SH_MAG[4] + SH_MAG[5] - SH_MAG[6]; +SK_MY[2] = SH_MAG[7] + SH_MAG[8] - 2*magD*q2; +SK_MY[3] = 2*q0*q3 - 2*q1*q2; +SK_MY[4] = 2*q0*q1 + 2*q2*q3; float Kfusion[24][1]; float Kfusion[1][1]; -Kfusion[0] = SK_MY[0]*(P[0][20] + P[0][17]*SH_MAG[0] + P[0][18]*SH_MAG[3] + P[0][0]*SK_MY[2] - P[0][2]*SK_MY[1] - P[0][16]*SK_MY[3]); -Kfusion[1] = SK_MY[0]*(P[1][20] + P[1][17]*SH_MAG[0] + P[1][18]*SH_MAG[3] + P[1][0]*SK_MY[2] - P[1][2]*SK_MY[1] - P[1][16]*SK_MY[3]); -Kfusion[2] = SK_MY[0]*(P[2][20] + P[2][17]*SH_MAG[0] + P[2][18]*SH_MAG[3] + P[2][0]*SK_MY[2] - P[2][2]*SK_MY[1] - P[2][16]*SK_MY[3]); -Kfusion[3] = SK_MY[0]*(P[3][20] + P[3][17]*SH_MAG[0] + P[3][18]*SH_MAG[3] + P[3][0]*SK_MY[2] - P[3][2]*SK_MY[1] - P[3][16]*SK_MY[3]); -Kfusion[4] = SK_MY[0]*(P[4][20] + P[4][17]*SH_MAG[0] + P[4][18]*SH_MAG[3] + P[4][0]*SK_MY[2] - P[4][2]*SK_MY[1] - P[4][16]*SK_MY[3]); -Kfusion[5] = SK_MY[0]*(P[5][20] + P[5][17]*SH_MAG[0] + P[5][18]*SH_MAG[3] + P[5][0]*SK_MY[2] - P[5][2]*SK_MY[1] - P[5][16]*SK_MY[3]); -Kfusion[6] = SK_MY[0]*(P[6][20] + P[6][17]*SH_MAG[0] + P[6][18]*SH_MAG[3] + P[6][0]*SK_MY[2] - P[6][2]*SK_MY[1] - P[6][16]*SK_MY[3]); -Kfusion[7] = SK_MY[0]*(P[7][20] + P[7][17]*SH_MAG[0] + P[7][18]*SH_MAG[3] + P[7][0]*SK_MY[2] - P[7][2]*SK_MY[1] - P[7][16]*SK_MY[3]); -Kfusion[8] = SK_MY[0]*(P[8][20] + P[8][17]*SH_MAG[0] + P[8][18]*SH_MAG[3] + P[8][0]*SK_MY[2] - P[8][2]*SK_MY[1] - P[8][16]*SK_MY[3]); -Kfusion[9] = SK_MY[0]*(P[9][20] + P[9][17]*SH_MAG[0] + P[9][18]*SH_MAG[3] + P[9][0]*SK_MY[2] - P[9][2]*SK_MY[1] - P[9][16]*SK_MY[3]); -Kfusion[10] = SK_MY[0]*(P[10][20] + P[10][17]*SH_MAG[0] + P[10][18]*SH_MAG[3] + P[10][0]*SK_MY[2] - P[10][2]*SK_MY[1] - P[10][16]*SK_MY[3]); -Kfusion[11] = SK_MY[0]*(P[11][20] + P[11][17]*SH_MAG[0] + P[11][18]*SH_MAG[3] + P[11][0]*SK_MY[2] - P[11][2]*SK_MY[1] - P[11][16]*SK_MY[3]); -Kfusion[12] = SK_MY[0]*(P[12][20] + P[12][17]*SH_MAG[0] + P[12][18]*SH_MAG[3] + P[12][0]*SK_MY[2] - P[12][2]*SK_MY[1] - P[12][16]*SK_MY[3]); -Kfusion[13] = SK_MY[0]*(P[13][20] + P[13][17]*SH_MAG[0] + P[13][18]*SH_MAG[3] + P[13][0]*SK_MY[2] - P[13][2]*SK_MY[1] - P[13][16]*SK_MY[3]); -Kfusion[14] = SK_MY[0]*(P[14][20] + P[14][17]*SH_MAG[0] + P[14][18]*SH_MAG[3] + P[14][0]*SK_MY[2] - P[14][2]*SK_MY[1] - P[14][16]*SK_MY[3]); -Kfusion[15] = SK_MY[0]*(P[15][20] + P[15][17]*SH_MAG[0] + P[15][18]*SH_MAG[3] + P[15][0]*SK_MY[2] - P[15][2]*SK_MY[1] - P[15][16]*SK_MY[3]); -Kfusion[16] = SK_MY[0]*(P[16][20] + P[16][17]*SH_MAG[0] + P[16][18]*SH_MAG[3] + P[16][0]*SK_MY[2] - P[16][2]*SK_MY[1] - P[16][16]*SK_MY[3]); -Kfusion[17] = SK_MY[0]*(P[17][20] + P[17][17]*SH_MAG[0] + P[17][18]*SH_MAG[3] + P[17][0]*SK_MY[2] - P[17][2]*SK_MY[1] - P[17][16]*SK_MY[3]); -Kfusion[18] = SK_MY[0]*(P[18][20] + P[18][17]*SH_MAG[0] + P[18][18]*SH_MAG[3] + P[18][0]*SK_MY[2] - P[18][2]*SK_MY[1] - P[18][16]*SK_MY[3]); -Kfusion[19] = SK_MY[0]*(P[19][20] + P[19][17]*SH_MAG[0] + P[19][18]*SH_MAG[3] + P[19][0]*SK_MY[2] - P[19][2]*SK_MY[1] - P[19][16]*SK_MY[3]); -Kfusion[20] = SK_MY[0]*(P[20][20] + P[20][17]*SH_MAG[0] + P[20][18]*SH_MAG[3] + P[20][0]*SK_MY[2] - P[20][2]*SK_MY[1] - P[20][16]*SK_MY[3]); -Kfusion[21] = SK_MY[0]*(P[21][20] + P[21][17]*SH_MAG[0] + P[21][18]*SH_MAG[3] + P[21][0]*SK_MY[2] - P[21][2]*SK_MY[1] - P[21][16]*SK_MY[3]); -Kfusion[22] = SK_MY[0]*(P[22][20] + P[22][17]*SH_MAG[0] + P[22][18]*SH_MAG[3] + P[22][0]*SK_MY[2] - P[22][2]*SK_MY[1] - P[22][16]*SK_MY[3]); -Kfusion[23] = SK_MY[0]*(P[23][20] + P[23][17]*SH_MAG[0] + P[23][18]*SH_MAG[3] + P[23][0]*SK_MY[2] - P[23][2]*SK_MY[1] - P[23][16]*SK_MY[3]); +Kfusion[0] = SK_MY[0]*(P[0][20] + P[0][0]*SH_MAG[2] + P[0][1]*SH_MAG[1] + P[0][2]*SH_MAG[0] - P[0][3]*SK_MY[2] - P[0][17]*SK_MY[1] - P[0][16]*SK_MY[3] + P[0][18]*SK_MY[4]); +Kfusion[1] = SK_MY[0]*(P[1][20] + P[1][0]*SH_MAG[2] + P[1][1]*SH_MAG[1] + P[1][2]*SH_MAG[0] - P[1][3]*SK_MY[2] - P[1][17]*SK_MY[1] - P[1][16]*SK_MY[3] + P[1][18]*SK_MY[4]); +Kfusion[2] = SK_MY[0]*(P[2][20] + P[2][0]*SH_MAG[2] + P[2][1]*SH_MAG[1] + P[2][2]*SH_MAG[0] - P[2][3]*SK_MY[2] - P[2][17]*SK_MY[1] - P[2][16]*SK_MY[3] + P[2][18]*SK_MY[4]); +Kfusion[3] = SK_MY[0]*(P[3][20] + P[3][0]*SH_MAG[2] + P[3][1]*SH_MAG[1] + P[3][2]*SH_MAG[0] - P[3][3]*SK_MY[2] - P[3][17]*SK_MY[1] - P[3][16]*SK_MY[3] + P[3][18]*SK_MY[4]); +Kfusion[4] = SK_MY[0]*(P[4][20] + P[4][0]*SH_MAG[2] + P[4][1]*SH_MAG[1] + P[4][2]*SH_MAG[0] - P[4][3]*SK_MY[2] - P[4][17]*SK_MY[1] - P[4][16]*SK_MY[3] + P[4][18]*SK_MY[4]); +Kfusion[5] = SK_MY[0]*(P[5][20] + P[5][0]*SH_MAG[2] + P[5][1]*SH_MAG[1] + P[5][2]*SH_MAG[0] - P[5][3]*SK_MY[2] - P[5][17]*SK_MY[1] - P[5][16]*SK_MY[3] + P[5][18]*SK_MY[4]); +Kfusion[6] = SK_MY[0]*(P[6][20] + P[6][0]*SH_MAG[2] + P[6][1]*SH_MAG[1] + P[6][2]*SH_MAG[0] - P[6][3]*SK_MY[2] - P[6][17]*SK_MY[1] - P[6][16]*SK_MY[3] + P[6][18]*SK_MY[4]); +Kfusion[7] = SK_MY[0]*(P[7][20] + P[7][0]*SH_MAG[2] + P[7][1]*SH_MAG[1] + P[7][2]*SH_MAG[0] - P[7][3]*SK_MY[2] - P[7][17]*SK_MY[1] - P[7][16]*SK_MY[3] + P[7][18]*SK_MY[4]); +Kfusion[8] = SK_MY[0]*(P[8][20] + P[8][0]*SH_MAG[2] + P[8][1]*SH_MAG[1] + P[8][2]*SH_MAG[0] - P[8][3]*SK_MY[2] - P[8][17]*SK_MY[1] - P[8][16]*SK_MY[3] + P[8][18]*SK_MY[4]); +Kfusion[9] = SK_MY[0]*(P[9][20] + P[9][0]*SH_MAG[2] + P[9][1]*SH_MAG[1] + P[9][2]*SH_MAG[0] - P[9][3]*SK_MY[2] - P[9][17]*SK_MY[1] - P[9][16]*SK_MY[3] + P[9][18]*SK_MY[4]); +Kfusion[10] = SK_MY[0]*(P[10][20] + P[10][0]*SH_MAG[2] + P[10][1]*SH_MAG[1] + P[10][2]*SH_MAG[0] - P[10][3]*SK_MY[2] - P[10][17]*SK_MY[1] - P[10][16]*SK_MY[3] + P[10][18]*SK_MY[4]); +Kfusion[11] = SK_MY[0]*(P[11][20] + P[11][0]*SH_MAG[2] + P[11][1]*SH_MAG[1] + P[11][2]*SH_MAG[0] - P[11][3]*SK_MY[2] - P[11][17]*SK_MY[1] - P[11][16]*SK_MY[3] + P[11][18]*SK_MY[4]); +Kfusion[12] = SK_MY[0]*(P[12][20] + P[12][0]*SH_MAG[2] + P[12][1]*SH_MAG[1] + P[12][2]*SH_MAG[0] - P[12][3]*SK_MY[2] - P[12][17]*SK_MY[1] - P[12][16]*SK_MY[3] + P[12][18]*SK_MY[4]); +Kfusion[13] = SK_MY[0]*(P[13][20] + P[13][0]*SH_MAG[2] + P[13][1]*SH_MAG[1] + P[13][2]*SH_MAG[0] - P[13][3]*SK_MY[2] - P[13][17]*SK_MY[1] - P[13][16]*SK_MY[3] + P[13][18]*SK_MY[4]); +Kfusion[14] = SK_MY[0]*(P[14][20] + P[14][0]*SH_MAG[2] + P[14][1]*SH_MAG[1] + P[14][2]*SH_MAG[0] - P[14][3]*SK_MY[2] - P[14][17]*SK_MY[1] - P[14][16]*SK_MY[3] + P[14][18]*SK_MY[4]); +Kfusion[15] = SK_MY[0]*(P[15][20] + P[15][0]*SH_MAG[2] + P[15][1]*SH_MAG[1] + P[15][2]*SH_MAG[0] - P[15][3]*SK_MY[2] - P[15][17]*SK_MY[1] - P[15][16]*SK_MY[3] + P[15][18]*SK_MY[4]); +Kfusion[16] = SK_MY[0]*(P[16][20] + P[16][0]*SH_MAG[2] + P[16][1]*SH_MAG[1] + P[16][2]*SH_MAG[0] - P[16][3]*SK_MY[2] - P[16][17]*SK_MY[1] - P[16][16]*SK_MY[3] + P[16][18]*SK_MY[4]); +Kfusion[17] = SK_MY[0]*(P[17][20] + P[17][0]*SH_MAG[2] + P[17][1]*SH_MAG[1] + P[17][2]*SH_MAG[0] - P[17][3]*SK_MY[2] - P[17][17]*SK_MY[1] - P[17][16]*SK_MY[3] + P[17][18]*SK_MY[4]); +Kfusion[18] = SK_MY[0]*(P[18][20] + P[18][0]*SH_MAG[2] + P[18][1]*SH_MAG[1] + P[18][2]*SH_MAG[0] - P[18][3]*SK_MY[2] - P[18][17]*SK_MY[1] - P[18][16]*SK_MY[3] + P[18][18]*SK_MY[4]); +Kfusion[19] = SK_MY[0]*(P[19][20] + P[19][0]*SH_MAG[2] + P[19][1]*SH_MAG[1] + P[19][2]*SH_MAG[0] - P[19][3]*SK_MY[2] - P[19][17]*SK_MY[1] - P[19][16]*SK_MY[3] + P[19][18]*SK_MY[4]); +Kfusion[20] = SK_MY[0]*(P[20][20] + P[20][0]*SH_MAG[2] + P[20][1]*SH_MAG[1] + P[20][2]*SH_MAG[0] - P[20][3]*SK_MY[2] - P[20][17]*SK_MY[1] - P[20][16]*SK_MY[3] + P[20][18]*SK_MY[4]); +Kfusion[21] = SK_MY[0]*(P[21][20] + P[21][0]*SH_MAG[2] + P[21][1]*SH_MAG[1] + P[21][2]*SH_MAG[0] - P[21][3]*SK_MY[2] - P[21][17]*SK_MY[1] - P[21][16]*SK_MY[3] + P[21][18]*SK_MY[4]); +Kfusion[22] = SK_MY[0]*(P[22][20] + P[22][0]*SH_MAG[2] + P[22][1]*SH_MAG[1] + P[22][2]*SH_MAG[0] - P[22][3]*SK_MY[2] - P[22][17]*SK_MY[1] - P[22][16]*SK_MY[3] + P[22][18]*SK_MY[4]); +Kfusion[23] = SK_MY[0]*(P[23][20] + P[23][0]*SH_MAG[2] + P[23][1]*SH_MAG[1] + P[23][2]*SH_MAG[0] - P[23][3]*SK_MY[2] - P[23][17]*SK_MY[1] - P[23][16]*SK_MY[3] + P[23][18]*SK_MY[4]); float H_MAG[1][24]; -H_MAG[0] = magN*(SH_MAG[8] - 2*q1*q2) - magD*SH_MAG[3] - magE*SH_MAG[0]; -H_MAG[1] = magE*SH_MAG[4] + magD*SH_MAG[7] + magN*SH_MAG[1]; -H_MAG[16] = SH_MAG[5]; +H_MAG[0] = SH_MAG[1]; +H_MAG[1] = -SH_MAG[2]; +H_MAG[2] = SH_MAG[7] + SH_MAG[8] - 2*magD*q2; +H_MAG[3] = SH_MAG[0]; +H_MAG[16] = 2*q0*q2 + 2*q1*q3; H_MAG[17] = 2*q2*q3 - 2*q0*q1; -H_MAG[18] = SH_MAG[2]; +H_MAG[18] = SH_MAG[3] - SH_MAG[4] - SH_MAG[5] + SH_MAG[6]; H_MAG[21] = 1; -float SK_MZ[4][1]; -SK_MZ[0] = 1/(P[21][21] + R_MAG + P[16][21]*SH_MAG[5] + P[18][21]*SH_MAG[2] - (2*q0*q1 - 2*q2*q3)*(P[21][17] + P[16][17]*SH_MAG[5] + P[18][17]*SH_MAG[2] - P[0][17]*(magE*SH_MAG[0] + magD*SH_MAG[3] - magN*(SH_MAG[8] - 2*q1*q2)) + P[1][17]*(magE*SH_MAG[4] + magD*SH_MAG[7] + magN*SH_MAG[1]) - P[17][17]*(2*q0*q1 - 2*q2*q3)) - P[0][21]*(magE*SH_MAG[0] + magD*SH_MAG[3] - magN*(SH_MAG[8] - 2*q1*q2)) + P[1][21]*(magE*SH_MAG[4] + magD*SH_MAG[7] + magN*SH_MAG[1]) + SH_MAG[5]*(P[21][16] + P[16][16]*SH_MAG[5] + P[18][16]*SH_MAG[2] - P[0][16]*(magE*SH_MAG[0] + magD*SH_MAG[3] - magN*(SH_MAG[8] - 2*q1*q2)) + P[1][16]*(magE*SH_MAG[4] + magD*SH_MAG[7] + magN*SH_MAG[1]) - P[17][16]*(2*q0*q1 - 2*q2*q3)) + SH_MAG[2]*(P[21][18] + P[16][18]*SH_MAG[5] + P[18][18]*SH_MAG[2] - P[0][18]*(magE*SH_MAG[0] + magD*SH_MAG[3] - magN*(SH_MAG[8] - 2*q1*q2)) + P[1][18]*(magE*SH_MAG[4] + magD*SH_MAG[7] + magN*SH_MAG[1]) - P[17][18]*(2*q0*q1 - 2*q2*q3)) - (magE*SH_MAG[0] + magD*SH_MAG[3] - magN*(SH_MAG[8] - 2*q1*q2))*(P[21][0] + P[16][0]*SH_MAG[5] + P[18][0]*SH_MAG[2] - P[0][0]*(magE*SH_MAG[0] + magD*SH_MAG[3] - magN*(SH_MAG[8] - 2*q1*q2)) + P[1][0]*(magE*SH_MAG[4] + magD*SH_MAG[7] + magN*SH_MAG[1]) - P[17][0]*(2*q0*q1 - 2*q2*q3)) - P[17][21]*(2*q0*q1 - 2*q2*q3) + (magE*SH_MAG[4] + magD*SH_MAG[7] + magN*SH_MAG[1])*(P[21][1] + P[16][1]*SH_MAG[5] + P[18][1]*SH_MAG[2] - P[0][1]*(magE*SH_MAG[0] + magD*SH_MAG[3] - magN*(SH_MAG[8] - 2*q1*q2)) + P[1][1]*(magE*SH_MAG[4] + magD*SH_MAG[7] + magN*SH_MAG[1]) - P[17][1]*(2*q0*q1 - 2*q2*q3))); -SK_MZ[1] = magE*SH_MAG[0] + magD*SH_MAG[3] - magN*(SH_MAG[8] - 2*q1*q2); -SK_MZ[2] = magE*SH_MAG[4] + magD*SH_MAG[7] + magN*SH_MAG[1]; +float SK_MZ[5][1]; +SK_MZ[0] = 1/(P[21][21] + R_MAG + P[0][21]*SH_MAG[1] - P[1][21]*SH_MAG[2] + P[3][21]*SH_MAG[0] + P[18][21]*(SH_MAG[3] - SH_MAG[4] - SH_MAG[5] + SH_MAG[6]) + (2*q0*q2 + 2*q1*q3)*(P[21][16] + P[0][16]*SH_MAG[1] - P[1][16]*SH_MAG[2] + P[3][16]*SH_MAG[0] + P[18][16]*(SH_MAG[3] - SH_MAG[4] - SH_MAG[5] + SH_MAG[6]) + P[16][16]*(2*q0*q2 + 2*q1*q3) - P[17][16]*(2*q0*q1 - 2*q2*q3) + P[2][16]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) - (2*q0*q1 - 2*q2*q3)*(P[21][17] + P[0][17]*SH_MAG[1] - P[1][17]*SH_MAG[2] + P[3][17]*SH_MAG[0] + P[18][17]*(SH_MAG[3] - SH_MAG[4] - SH_MAG[5] + SH_MAG[6]) + P[16][17]*(2*q0*q2 + 2*q1*q3) - P[17][17]*(2*q0*q1 - 2*q2*q3) + P[2][17]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) + (SH_MAG[7] + SH_MAG[8] - 2*magD*q2)*(P[21][2] + P[0][2]*SH_MAG[1] - P[1][2]*SH_MAG[2] + P[3][2]*SH_MAG[0] + P[18][2]*(SH_MAG[3] - SH_MAG[4] - SH_MAG[5] + SH_MAG[6]) + P[16][2]*(2*q0*q2 + 2*q1*q3) - P[17][2]*(2*q0*q1 - 2*q2*q3) + P[2][2]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) + P[16][21]*(2*q0*q2 + 2*q1*q3) - P[17][21]*(2*q0*q1 - 2*q2*q3) + SH_MAG[1]*(P[21][0] + P[0][0]*SH_MAG[1] - P[1][0]*SH_MAG[2] + P[3][0]*SH_MAG[0] + P[18][0]*(SH_MAG[3] - SH_MAG[4] - SH_MAG[5] + SH_MAG[6]) + P[16][0]*(2*q0*q2 + 2*q1*q3) - P[17][0]*(2*q0*q1 - 2*q2*q3) + P[2][0]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) - SH_MAG[2]*(P[21][1] + P[0][1]*SH_MAG[1] - P[1][1]*SH_MAG[2] + P[3][1]*SH_MAG[0] + P[18][1]*(SH_MAG[3] - SH_MAG[4] - SH_MAG[5] + SH_MAG[6]) + P[16][1]*(2*q0*q2 + 2*q1*q3) - P[17][1]*(2*q0*q1 - 2*q2*q3) + P[2][1]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) + SH_MAG[0]*(P[21][3] + P[0][3]*SH_MAG[1] - P[1][3]*SH_MAG[2] + P[3][3]*SH_MAG[0] + P[18][3]*(SH_MAG[3] - SH_MAG[4] - SH_MAG[5] + SH_MAG[6]) + P[16][3]*(2*q0*q2 + 2*q1*q3) - P[17][3]*(2*q0*q1 - 2*q2*q3) + P[2][3]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) + (SH_MAG[3] - SH_MAG[4] - SH_MAG[5] + SH_MAG[6])*(P[21][18] + P[0][18]*SH_MAG[1] - P[1][18]*SH_MAG[2] + P[3][18]*SH_MAG[0] + P[18][18]*(SH_MAG[3] - SH_MAG[4] - SH_MAG[5] + SH_MAG[6]) + P[16][18]*(2*q0*q2 + 2*q1*q3) - P[17][18]*(2*q0*q1 - 2*q2*q3) + P[2][18]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) + P[2][21]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)); +SK_MZ[1] = SH_MAG[3] - SH_MAG[4] - SH_MAG[5] + SH_MAG[6]; +SK_MZ[2] = SH_MAG[7] + SH_MAG[8] - 2*magD*q2; SK_MZ[3] = 2*q0*q1 - 2*q2*q3; +SK_MZ[4] = 2*q0*q2 + 2*q1*q3; float Kfusion[24][1]; float Kfusion[1][1]; -Kfusion[0] = SK_MZ[0]*(P[0][21] + P[0][18]*SH_MAG[2] + P[0][16]*SH_MAG[5] - P[0][0]*SK_MZ[1] + P[0][1]*SK_MZ[2] - P[0][17]*SK_MZ[3]); -Kfusion[1] = SK_MZ[0]*(P[1][21] + P[1][18]*SH_MAG[2] + P[1][16]*SH_MAG[5] - P[1][0]*SK_MZ[1] + P[1][1]*SK_MZ[2] - P[1][17]*SK_MZ[3]); -Kfusion[2] = SK_MZ[0]*(P[2][21] + P[2][18]*SH_MAG[2] + P[2][16]*SH_MAG[5] - P[2][0]*SK_MZ[1] + P[2][1]*SK_MZ[2] - P[2][17]*SK_MZ[3]); -Kfusion[3] = SK_MZ[0]*(P[3][21] + P[3][18]*SH_MAG[2] + P[3][16]*SH_MAG[5] - P[3][0]*SK_MZ[1] + P[3][1]*SK_MZ[2] - P[3][17]*SK_MZ[3]); -Kfusion[4] = SK_MZ[0]*(P[4][21] + P[4][18]*SH_MAG[2] + P[4][16]*SH_MAG[5] - P[4][0]*SK_MZ[1] + P[4][1]*SK_MZ[2] - P[4][17]*SK_MZ[3]); -Kfusion[5] = SK_MZ[0]*(P[5][21] + P[5][18]*SH_MAG[2] + P[5][16]*SH_MAG[5] - P[5][0]*SK_MZ[1] + P[5][1]*SK_MZ[2] - P[5][17]*SK_MZ[3]); -Kfusion[6] = SK_MZ[0]*(P[6][21] + P[6][18]*SH_MAG[2] + P[6][16]*SH_MAG[5] - P[6][0]*SK_MZ[1] + P[6][1]*SK_MZ[2] - P[6][17]*SK_MZ[3]); -Kfusion[7] = SK_MZ[0]*(P[7][21] + P[7][18]*SH_MAG[2] + P[7][16]*SH_MAG[5] - P[7][0]*SK_MZ[1] + P[7][1]*SK_MZ[2] - P[7][17]*SK_MZ[3]); -Kfusion[8] = SK_MZ[0]*(P[8][21] + P[8][18]*SH_MAG[2] + P[8][16]*SH_MAG[5] - P[8][0]*SK_MZ[1] + P[8][1]*SK_MZ[2] - P[8][17]*SK_MZ[3]); -Kfusion[9] = SK_MZ[0]*(P[9][21] + P[9][18]*SH_MAG[2] + P[9][16]*SH_MAG[5] - P[9][0]*SK_MZ[1] + P[9][1]*SK_MZ[2] - P[9][17]*SK_MZ[3]); -Kfusion[10] = SK_MZ[0]*(P[10][21] + P[10][18]*SH_MAG[2] + P[10][16]*SH_MAG[5] - P[10][0]*SK_MZ[1] + P[10][1]*SK_MZ[2] - P[10][17]*SK_MZ[3]); -Kfusion[11] = SK_MZ[0]*(P[11][21] + P[11][18]*SH_MAG[2] + P[11][16]*SH_MAG[5] - P[11][0]*SK_MZ[1] + P[11][1]*SK_MZ[2] - P[11][17]*SK_MZ[3]); -Kfusion[12] = SK_MZ[0]*(P[12][21] + P[12][18]*SH_MAG[2] + P[12][16]*SH_MAG[5] - P[12][0]*SK_MZ[1] + P[12][1]*SK_MZ[2] - P[12][17]*SK_MZ[3]); -Kfusion[13] = SK_MZ[0]*(P[13][21] + P[13][18]*SH_MAG[2] + P[13][16]*SH_MAG[5] - P[13][0]*SK_MZ[1] + P[13][1]*SK_MZ[2] - P[13][17]*SK_MZ[3]); -Kfusion[14] = SK_MZ[0]*(P[14][21] + P[14][18]*SH_MAG[2] + P[14][16]*SH_MAG[5] - P[14][0]*SK_MZ[1] + P[14][1]*SK_MZ[2] - P[14][17]*SK_MZ[3]); -Kfusion[15] = SK_MZ[0]*(P[15][21] + P[15][18]*SH_MAG[2] + P[15][16]*SH_MAG[5] - P[15][0]*SK_MZ[1] + P[15][1]*SK_MZ[2] - P[15][17]*SK_MZ[3]); -Kfusion[16] = SK_MZ[0]*(P[16][21] + P[16][18]*SH_MAG[2] + P[16][16]*SH_MAG[5] - P[16][0]*SK_MZ[1] + P[16][1]*SK_MZ[2] - P[16][17]*SK_MZ[3]); -Kfusion[17] = SK_MZ[0]*(P[17][21] + P[17][18]*SH_MAG[2] + P[17][16]*SH_MAG[5] - P[17][0]*SK_MZ[1] + P[17][1]*SK_MZ[2] - P[17][17]*SK_MZ[3]); -Kfusion[18] = SK_MZ[0]*(P[18][21] + P[18][18]*SH_MAG[2] + P[18][16]*SH_MAG[5] - P[18][0]*SK_MZ[1] + P[18][1]*SK_MZ[2] - P[18][17]*SK_MZ[3]); -Kfusion[19] = SK_MZ[0]*(P[19][21] + P[19][18]*SH_MAG[2] + P[19][16]*SH_MAG[5] - P[19][0]*SK_MZ[1] + P[19][1]*SK_MZ[2] - P[19][17]*SK_MZ[3]); -Kfusion[20] = SK_MZ[0]*(P[20][21] + P[20][18]*SH_MAG[2] + P[20][16]*SH_MAG[5] - P[20][0]*SK_MZ[1] + P[20][1]*SK_MZ[2] - P[20][17]*SK_MZ[3]); -Kfusion[21] = SK_MZ[0]*(P[21][21] + P[21][18]*SH_MAG[2] + P[21][16]*SH_MAG[5] - P[21][0]*SK_MZ[1] + P[21][1]*SK_MZ[2] - P[21][17]*SK_MZ[3]); -Kfusion[22] = SK_MZ[0]*(P[22][21] + P[22][18]*SH_MAG[2] + P[22][16]*SH_MAG[5] - P[22][0]*SK_MZ[1] + P[22][1]*SK_MZ[2] - P[22][17]*SK_MZ[3]); -Kfusion[23] = SK_MZ[0]*(P[23][21] + P[23][18]*SH_MAG[2] + P[23][16]*SH_MAG[5] - P[23][0]*SK_MZ[1] + P[23][1]*SK_MZ[2] - P[23][17]*SK_MZ[3]); -float SH_ACCX[7][1]; +Kfusion[0] = SK_MZ[0]*(P[0][21] + P[0][0]*SH_MAG[1] - P[0][1]*SH_MAG[2] + P[0][3]*SH_MAG[0] + P[0][2]*SK_MZ[2] + P[0][18]*SK_MZ[1] + P[0][16]*SK_MZ[4] - P[0][17]*SK_MZ[3]); +Kfusion[1] = SK_MZ[0]*(P[1][21] + P[1][0]*SH_MAG[1] - P[1][1]*SH_MAG[2] + P[1][3]*SH_MAG[0] + P[1][2]*SK_MZ[2] + P[1][18]*SK_MZ[1] + P[1][16]*SK_MZ[4] - P[1][17]*SK_MZ[3]); +Kfusion[2] = SK_MZ[0]*(P[2][21] + P[2][0]*SH_MAG[1] - P[2][1]*SH_MAG[2] + P[2][3]*SH_MAG[0] + P[2][2]*SK_MZ[2] + P[2][18]*SK_MZ[1] + P[2][16]*SK_MZ[4] - P[2][17]*SK_MZ[3]); +Kfusion[3] = SK_MZ[0]*(P[3][21] + P[3][0]*SH_MAG[1] - P[3][1]*SH_MAG[2] + P[3][3]*SH_MAG[0] + P[3][2]*SK_MZ[2] + P[3][18]*SK_MZ[1] + P[3][16]*SK_MZ[4] - P[3][17]*SK_MZ[3]); +Kfusion[4] = SK_MZ[0]*(P[4][21] + P[4][0]*SH_MAG[1] - P[4][1]*SH_MAG[2] + P[4][3]*SH_MAG[0] + P[4][2]*SK_MZ[2] + P[4][18]*SK_MZ[1] + P[4][16]*SK_MZ[4] - P[4][17]*SK_MZ[3]); +Kfusion[5] = SK_MZ[0]*(P[5][21] + P[5][0]*SH_MAG[1] - P[5][1]*SH_MAG[2] + P[5][3]*SH_MAG[0] + P[5][2]*SK_MZ[2] + P[5][18]*SK_MZ[1] + P[5][16]*SK_MZ[4] - P[5][17]*SK_MZ[3]); +Kfusion[6] = SK_MZ[0]*(P[6][21] + P[6][0]*SH_MAG[1] - P[6][1]*SH_MAG[2] + P[6][3]*SH_MAG[0] + P[6][2]*SK_MZ[2] + P[6][18]*SK_MZ[1] + P[6][16]*SK_MZ[4] - P[6][17]*SK_MZ[3]); +Kfusion[7] = SK_MZ[0]*(P[7][21] + P[7][0]*SH_MAG[1] - P[7][1]*SH_MAG[2] + P[7][3]*SH_MAG[0] + P[7][2]*SK_MZ[2] + P[7][18]*SK_MZ[1] + P[7][16]*SK_MZ[4] - P[7][17]*SK_MZ[3]); +Kfusion[8] = SK_MZ[0]*(P[8][21] + P[8][0]*SH_MAG[1] - P[8][1]*SH_MAG[2] + P[8][3]*SH_MAG[0] + P[8][2]*SK_MZ[2] + P[8][18]*SK_MZ[1] + P[8][16]*SK_MZ[4] - P[8][17]*SK_MZ[3]); +Kfusion[9] = SK_MZ[0]*(P[9][21] + P[9][0]*SH_MAG[1] - P[9][1]*SH_MAG[2] + P[9][3]*SH_MAG[0] + P[9][2]*SK_MZ[2] + P[9][18]*SK_MZ[1] + P[9][16]*SK_MZ[4] - P[9][17]*SK_MZ[3]); +Kfusion[10] = SK_MZ[0]*(P[10][21] + P[10][0]*SH_MAG[1] - P[10][1]*SH_MAG[2] + P[10][3]*SH_MAG[0] + P[10][2]*SK_MZ[2] + P[10][18]*SK_MZ[1] + P[10][16]*SK_MZ[4] - P[10][17]*SK_MZ[3]); +Kfusion[11] = SK_MZ[0]*(P[11][21] + P[11][0]*SH_MAG[1] - P[11][1]*SH_MAG[2] + P[11][3]*SH_MAG[0] + P[11][2]*SK_MZ[2] + P[11][18]*SK_MZ[1] + P[11][16]*SK_MZ[4] - P[11][17]*SK_MZ[3]); +Kfusion[12] = SK_MZ[0]*(P[12][21] + P[12][0]*SH_MAG[1] - P[12][1]*SH_MAG[2] + P[12][3]*SH_MAG[0] + P[12][2]*SK_MZ[2] + P[12][18]*SK_MZ[1] + P[12][16]*SK_MZ[4] - P[12][17]*SK_MZ[3]); +Kfusion[13] = SK_MZ[0]*(P[13][21] + P[13][0]*SH_MAG[1] - P[13][1]*SH_MAG[2] + P[13][3]*SH_MAG[0] + P[13][2]*SK_MZ[2] + P[13][18]*SK_MZ[1] + P[13][16]*SK_MZ[4] - P[13][17]*SK_MZ[3]); +Kfusion[14] = SK_MZ[0]*(P[14][21] + P[14][0]*SH_MAG[1] - P[14][1]*SH_MAG[2] + P[14][3]*SH_MAG[0] + P[14][2]*SK_MZ[2] + P[14][18]*SK_MZ[1] + P[14][16]*SK_MZ[4] - P[14][17]*SK_MZ[3]); +Kfusion[15] = SK_MZ[0]*(P[15][21] + P[15][0]*SH_MAG[1] - P[15][1]*SH_MAG[2] + P[15][3]*SH_MAG[0] + P[15][2]*SK_MZ[2] + P[15][18]*SK_MZ[1] + P[15][16]*SK_MZ[4] - P[15][17]*SK_MZ[3]); +Kfusion[16] = SK_MZ[0]*(P[16][21] + P[16][0]*SH_MAG[1] - P[16][1]*SH_MAG[2] + P[16][3]*SH_MAG[0] + P[16][2]*SK_MZ[2] + P[16][18]*SK_MZ[1] + P[16][16]*SK_MZ[4] - P[16][17]*SK_MZ[3]); +Kfusion[17] = SK_MZ[0]*(P[17][21] + P[17][0]*SH_MAG[1] - P[17][1]*SH_MAG[2] + P[17][3]*SH_MAG[0] + P[17][2]*SK_MZ[2] + P[17][18]*SK_MZ[1] + P[17][16]*SK_MZ[4] - P[17][17]*SK_MZ[3]); +Kfusion[18] = SK_MZ[0]*(P[18][21] + P[18][0]*SH_MAG[1] - P[18][1]*SH_MAG[2] + P[18][3]*SH_MAG[0] + P[18][2]*SK_MZ[2] + P[18][18]*SK_MZ[1] + P[18][16]*SK_MZ[4] - P[18][17]*SK_MZ[3]); +Kfusion[19] = SK_MZ[0]*(P[19][21] + P[19][0]*SH_MAG[1] - P[19][1]*SH_MAG[2] + P[19][3]*SH_MAG[0] + P[19][2]*SK_MZ[2] + P[19][18]*SK_MZ[1] + P[19][16]*SK_MZ[4] - P[19][17]*SK_MZ[3]); +Kfusion[20] = SK_MZ[0]*(P[20][21] + P[20][0]*SH_MAG[1] - P[20][1]*SH_MAG[2] + P[20][3]*SH_MAG[0] + P[20][2]*SK_MZ[2] + P[20][18]*SK_MZ[1] + P[20][16]*SK_MZ[4] - P[20][17]*SK_MZ[3]); +Kfusion[21] = SK_MZ[0]*(P[21][21] + P[21][0]*SH_MAG[1] - P[21][1]*SH_MAG[2] + P[21][3]*SH_MAG[0] + P[21][2]*SK_MZ[2] + P[21][18]*SK_MZ[1] + P[21][16]*SK_MZ[4] - P[21][17]*SK_MZ[3]); +Kfusion[22] = SK_MZ[0]*(P[22][21] + P[22][0]*SH_MAG[1] - P[22][1]*SH_MAG[2] + P[22][3]*SH_MAG[0] + P[22][2]*SK_MZ[2] + P[22][18]*SK_MZ[1] + P[22][16]*SK_MZ[4] - P[22][17]*SK_MZ[3]); +Kfusion[23] = SK_MZ[0]*(P[23][21] + P[23][0]*SH_MAG[1] - P[23][1]*SH_MAG[2] + P[23][3]*SH_MAG[0] + P[23][2]*SK_MZ[2] + P[23][18]*SK_MZ[1] + P[23][16]*SK_MZ[4] - P[23][17]*SK_MZ[3]); +float SH_ACCX[4][1]; SH_ACCX[0] = sq(q0) + sq(q1) - sq(q2) - sq(q3); -SH_ACCX[1] = 2*q0*q3 + 2*q1*q2; -SH_ACCX[2] = vn - vwn; -SH_ACCX[3] = ve - vwe; -SH_ACCX[4] = sq(q3); -SH_ACCX[5] = 2*q0*q2; -SH_ACCX[6] = 2*q0*q1; +SH_ACCX[1] = vn - vwn; +SH_ACCX[2] = ve - vwe; +SH_ACCX[3] = 2*q0*q3 + 2*q1*q2; float H_ACCX[1][24]; -H_ACCX[0][1] = Kaccx*(SH_ACCX[2]*(SH_ACCX[5] + 2*q1*q3) - SH_ACCX[3]*(SH_ACCX[6] - 2*q2*q3) + vd*(SH_ACCX[4] + sq(q0) - sq(q1) - sq(q2))); -H_ACCX[0][2] = Kaccx*(SH_ACCX[2]*(2*q0*q3 - 2*q1*q2) + SH_ACCX[3]*(SH_ACCX[4] - sq(q0) + sq(q1) - sq(q2)) - vd*(SH_ACCX[6] + 2*q2*q3)); -H_ACCX[0][3] = -Kaccx*SH_ACCX[0]; -H_ACCX[0][4] = -Kaccx*SH_ACCX[1]; -H_ACCX[0][5] = Kaccx*(SH_ACCX[5] - 2*q1*q3); +H_ACCX[0][0] = -Kaccx*(2*q0*SH_ACCX[1] + 2*q3*SH_ACCX[2] - 2*q2*vd); +H_ACCX[0][1] = -Kaccx*(2*q1*SH_ACCX[1] + 2*q2*SH_ACCX[2] + 2*q3*vd); +H_ACCX[0][2] = Kaccx*(2*q2*SH_ACCX[1] - 2*q1*SH_ACCX[2] + 2*q0*vd); +H_ACCX[0][3] = -Kaccx*(2*q0*SH_ACCX[2] - 2*q3*SH_ACCX[1] + 2*q1*vd); +H_ACCX[0][4] = -Kaccx*SH_ACCX[0]; +H_ACCX[0][5] = -Kaccx*SH_ACCX[3]; +H_ACCX[0][6] = Kaccx*(2*q0*q2 - 2*q1*q3); H_ACCX[0][22] = Kaccx*SH_ACCX[0]; -H_ACCX[0][23] = Kaccx*SH_ACCX[1]; -float SK_ACCX[5][1]; -SK_ACCX[0] = 1/(R_ACC - Kaccx*SH_ACCX[0]*(Kaccx*P[22][3]*SH_ACCX[0] - Kaccx*P[4][3]*SH_ACCX[1] - Kaccx*P[3][3]*SH_ACCX[0] + Kaccx*P[23][3]*SH_ACCX[1] + Kaccx*P[2][3]*(SH_ACCX[2]*(2*q0*q3 - 2*q1*q2) + SH_ACCX[3]*(SH_ACCX[4] - sq(q0) + sq(q1) - sq(q2)) - vd*(SH_ACCX[6] + 2*q2*q3)) + Kaccx*P[1][3]*(SH_ACCX[2]*(SH_ACCX[5] + 2*q1*q3) - SH_ACCX[3]*(SH_ACCX[6] - 2*q2*q3) + vd*(SH_ACCX[4] + sq(q0) - sq(q1) - sq(q2))) + Kaccx*P[5][3]*(SH_ACCX[5] - 2*q1*q3)) - Kaccx*SH_ACCX[1]*(Kaccx*P[22][4]*SH_ACCX[0] - Kaccx*P[4][4]*SH_ACCX[1] - Kaccx*P[3][4]*SH_ACCX[0] + Kaccx*P[23][4]*SH_ACCX[1] + Kaccx*P[2][4]*(SH_ACCX[2]*(2*q0*q3 - 2*q1*q2) + SH_ACCX[3]*(SH_ACCX[4] - sq(q0) + sq(q1) - sq(q2)) - vd*(SH_ACCX[6] + 2*q2*q3)) + Kaccx*P[1][4]*(SH_ACCX[2]*(SH_ACCX[5] + 2*q1*q3) - SH_ACCX[3]*(SH_ACCX[6] - 2*q2*q3) + vd*(SH_ACCX[4] + sq(q0) - sq(q1) - sq(q2))) + Kaccx*P[5][4]*(SH_ACCX[5] - 2*q1*q3)) + Kaccx*SH_ACCX[0]*(Kaccx*P[22][22]*SH_ACCX[0] - Kaccx*P[4][22]*SH_ACCX[1] - Kaccx*P[3][22]*SH_ACCX[0] + Kaccx*P[23][22]*SH_ACCX[1] + Kaccx*P[2][22]*(SH_ACCX[2]*(2*q0*q3 - 2*q1*q2) + SH_ACCX[3]*(SH_ACCX[4] - sq(q0) + sq(q1) - sq(q2)) - vd*(SH_ACCX[6] + 2*q2*q3)) + Kaccx*P[1][22]*(SH_ACCX[2]*(SH_ACCX[5] + 2*q1*q3) - SH_ACCX[3]*(SH_ACCX[6] - 2*q2*q3) + vd*(SH_ACCX[4] + sq(q0) - sq(q1) - sq(q2))) + Kaccx*P[5][22]*(SH_ACCX[5] - 2*q1*q3)) + Kaccx*SH_ACCX[1]*(Kaccx*P[22][23]*SH_ACCX[0] - Kaccx*P[4][23]*SH_ACCX[1] - Kaccx*P[3][23]*SH_ACCX[0] + Kaccx*P[23][23]*SH_ACCX[1] + Kaccx*P[2][23]*(SH_ACCX[2]*(2*q0*q3 - 2*q1*q2) + SH_ACCX[3]*(SH_ACCX[4] - sq(q0) + sq(q1) - sq(q2)) - vd*(SH_ACCX[6] + 2*q2*q3)) + Kaccx*P[1][23]*(SH_ACCX[2]*(SH_ACCX[5] + 2*q1*q3) - SH_ACCX[3]*(SH_ACCX[6] - 2*q2*q3) + vd*(SH_ACCX[4] + sq(q0) - sq(q1) - sq(q2))) + Kaccx*P[5][23]*(SH_ACCX[5] - 2*q1*q3)) + Kaccx*(SH_ACCX[2]*(2*q0*q3 - 2*q1*q2) + SH_ACCX[3]*(SH_ACCX[4] - sq(q0) + sq(q1) - sq(q2)) - vd*(SH_ACCX[6] + 2*q2*q3))*(Kaccx*P[22][2]*SH_ACCX[0] - Kaccx*P[4][2]*SH_ACCX[1] - Kaccx*P[3][2]*SH_ACCX[0] + Kaccx*P[23][2]*SH_ACCX[1] + Kaccx*P[2][2]*(SH_ACCX[2]*(2*q0*q3 - 2*q1*q2) + SH_ACCX[3]*(SH_ACCX[4] - sq(q0) + sq(q1) - sq(q2)) - vd*(SH_ACCX[6] + 2*q2*q3)) + Kaccx*P[1][2]*(SH_ACCX[2]*(SH_ACCX[5] + 2*q1*q3) - SH_ACCX[3]*(SH_ACCX[6] - 2*q2*q3) + vd*(SH_ACCX[4] + sq(q0) - sq(q1) - sq(q2))) + Kaccx*P[5][2]*(SH_ACCX[5] - 2*q1*q3)) + Kaccx*(SH_ACCX[2]*(SH_ACCX[5] + 2*q1*q3) - SH_ACCX[3]*(SH_ACCX[6] - 2*q2*q3) + vd*(SH_ACCX[4] + sq(q0) - sq(q1) - sq(q2)))*(Kaccx*P[22][1]*SH_ACCX[0] - Kaccx*P[4][1]*SH_ACCX[1] - Kaccx*P[3][1]*SH_ACCX[0] + Kaccx*P[23][1]*SH_ACCX[1] + Kaccx*P[2][1]*(SH_ACCX[2]*(2*q0*q3 - 2*q1*q2) + SH_ACCX[3]*(SH_ACCX[4] - sq(q0) + sq(q1) - sq(q2)) - vd*(SH_ACCX[6] + 2*q2*q3)) + Kaccx*P[1][1]*(SH_ACCX[2]*(SH_ACCX[5] + 2*q1*q3) - SH_ACCX[3]*(SH_ACCX[6] - 2*q2*q3) + vd*(SH_ACCX[4] + sq(q0) - sq(q1) - sq(q2))) + Kaccx*P[5][1]*(SH_ACCX[5] - 2*q1*q3)) + Kaccx*(SH_ACCX[5] - 2*q1*q3)*(Kaccx*P[22][5]*SH_ACCX[0] - Kaccx*P[4][5]*SH_ACCX[1] - Kaccx*P[3][5]*SH_ACCX[0] + Kaccx*P[23][5]*SH_ACCX[1] + Kaccx*P[2][5]*(SH_ACCX[2]*(2*q0*q3 - 2*q1*q2) + SH_ACCX[3]*(SH_ACCX[4] - sq(q0) + sq(q1) - sq(q2)) - vd*(SH_ACCX[6] + 2*q2*q3)) + Kaccx*P[1][5]*(SH_ACCX[2]*(SH_ACCX[5] + 2*q1*q3) - SH_ACCX[3]*(SH_ACCX[6] - 2*q2*q3) + vd*(SH_ACCX[4] + sq(q0) - sq(q1) - sq(q2))) + Kaccx*P[5][5]*(SH_ACCX[5] - 2*q1*q3))); -SK_ACCX[1] = SH_ACCX[2]*(2*q0*q3 - 2*q1*q2) + SH_ACCX[3]*(SH_ACCX[4] - sq(q0) + sq(q1) - sq(q2)) - vd*(SH_ACCX[6] + 2*q2*q3); -SK_ACCX[2] = SH_ACCX[2]*(SH_ACCX[5] + 2*q1*q3) - SH_ACCX[3]*(SH_ACCX[6] - 2*q2*q3) + vd*(SH_ACCX[4] + sq(q0) - sq(q1) - sq(q2)); -SK_ACCX[3] = SH_ACCX[5] - 2*q1*q3; -SK_ACCX[4] = SH_ACCX[1]; +H_ACCX[0][23] = Kaccx*SH_ACCX[3]; +float SK_ACCX[7][1]; +SK_ACCX[0] = 1/(R_ACC + Kaccx*SH_ACCX[0]*(Kaccx*P[4][4]*SH_ACCX[0] + Kaccx*P[5][4]*SH_ACCX[3] - Kaccx*P[22][4]*SH_ACCX[0] - Kaccx*P[23][4]*SH_ACCX[3] - Kaccx*P[6][4]*(2*q0*q2 - 2*q1*q3) + Kaccx*P[0][4]*(2*q0*SH_ACCX[1] + 2*q3*SH_ACCX[2] - 2*q2*vd) + Kaccx*P[1][4]*(2*q1*SH_ACCX[1] + 2*q2*SH_ACCX[2] + 2*q3*vd) - Kaccx*P[2][4]*(2*q2*SH_ACCX[1] - 2*q1*SH_ACCX[2] + 2*q0*vd) + Kaccx*P[3][4]*(2*q0*SH_ACCX[2] - 2*q3*SH_ACCX[1] + 2*q1*vd)) + Kaccx*SH_ACCX[3]*(Kaccx*P[4][5]*SH_ACCX[0] + Kaccx*P[5][5]*SH_ACCX[3] - Kaccx*P[22][5]*SH_ACCX[0] - Kaccx*P[23][5]*SH_ACCX[3] - Kaccx*P[6][5]*(2*q0*q2 - 2*q1*q3) + Kaccx*P[0][5]*(2*q0*SH_ACCX[1] + 2*q3*SH_ACCX[2] - 2*q2*vd) + Kaccx*P[1][5]*(2*q1*SH_ACCX[1] + 2*q2*SH_ACCX[2] + 2*q3*vd) - Kaccx*P[2][5]*(2*q2*SH_ACCX[1] - 2*q1*SH_ACCX[2] + 2*q0*vd) + Kaccx*P[3][5]*(2*q0*SH_ACCX[2] - 2*q3*SH_ACCX[1] + 2*q1*vd)) - Kaccx*SH_ACCX[0]*(Kaccx*P[4][22]*SH_ACCX[0] + Kaccx*P[5][22]*SH_ACCX[3] - Kaccx*P[22][22]*SH_ACCX[0] - Kaccx*P[23][22]*SH_ACCX[3] - Kaccx*P[6][22]*(2*q0*q2 - 2*q1*q3) + Kaccx*P[0][22]*(2*q0*SH_ACCX[1] + 2*q3*SH_ACCX[2] - 2*q2*vd) + Kaccx*P[1][22]*(2*q1*SH_ACCX[1] + 2*q2*SH_ACCX[2] + 2*q3*vd) - Kaccx*P[2][22]*(2*q2*SH_ACCX[1] - 2*q1*SH_ACCX[2] + 2*q0*vd) + Kaccx*P[3][22]*(2*q0*SH_ACCX[2] - 2*q3*SH_ACCX[1] + 2*q1*vd)) - Kaccx*SH_ACCX[3]*(Kaccx*P[4][23]*SH_ACCX[0] + Kaccx*P[5][23]*SH_ACCX[3] - Kaccx*P[22][23]*SH_ACCX[0] - Kaccx*P[23][23]*SH_ACCX[3] - Kaccx*P[6][23]*(2*q0*q2 - 2*q1*q3) + Kaccx*P[0][23]*(2*q0*SH_ACCX[1] + 2*q3*SH_ACCX[2] - 2*q2*vd) + Kaccx*P[1][23]*(2*q1*SH_ACCX[1] + 2*q2*SH_ACCX[2] + 2*q3*vd) - Kaccx*P[2][23]*(2*q2*SH_ACCX[1] - 2*q1*SH_ACCX[2] + 2*q0*vd) + Kaccx*P[3][23]*(2*q0*SH_ACCX[2] - 2*q3*SH_ACCX[1] + 2*q1*vd)) - Kaccx*(2*q0*q2 - 2*q1*q3)*(Kaccx*P[4][6]*SH_ACCX[0] + Kaccx*P[5][6]*SH_ACCX[3] - Kaccx*P[22][6]*SH_ACCX[0] - Kaccx*P[23][6]*SH_ACCX[3] - Kaccx*P[6][6]*(2*q0*q2 - 2*q1*q3) + Kaccx*P[0][6]*(2*q0*SH_ACCX[1] + 2*q3*SH_ACCX[2] - 2*q2*vd) + Kaccx*P[1][6]*(2*q1*SH_ACCX[1] + 2*q2*SH_ACCX[2] + 2*q3*vd) - Kaccx*P[2][6]*(2*q2*SH_ACCX[1] - 2*q1*SH_ACCX[2] + 2*q0*vd) + Kaccx*P[3][6]*(2*q0*SH_ACCX[2] - 2*q3*SH_ACCX[1] + 2*q1*vd)) + Kaccx*(2*q0*SH_ACCX[1] + 2*q3*SH_ACCX[2] - 2*q2*vd)*(Kaccx*P[4][0]*SH_ACCX[0] + Kaccx*P[5][0]*SH_ACCX[3] - Kaccx*P[22][0]*SH_ACCX[0] - Kaccx*P[23][0]*SH_ACCX[3] - Kaccx*P[6][0]*(2*q0*q2 - 2*q1*q3) + Kaccx*P[0][0]*(2*q0*SH_ACCX[1] + 2*q3*SH_ACCX[2] - 2*q2*vd) + Kaccx*P[1][0]*(2*q1*SH_ACCX[1] + 2*q2*SH_ACCX[2] + 2*q3*vd) - Kaccx*P[2][0]*(2*q2*SH_ACCX[1] - 2*q1*SH_ACCX[2] + 2*q0*vd) + Kaccx*P[3][0]*(2*q0*SH_ACCX[2] - 2*q3*SH_ACCX[1] + 2*q1*vd)) + Kaccx*(2*q1*SH_ACCX[1] + 2*q2*SH_ACCX[2] + 2*q3*vd)*(Kaccx*P[4][1]*SH_ACCX[0] + Kaccx*P[5][1]*SH_ACCX[3] - Kaccx*P[22][1]*SH_ACCX[0] - Kaccx*P[23][1]*SH_ACCX[3] - Kaccx*P[6][1]*(2*q0*q2 - 2*q1*q3) + Kaccx*P[0][1]*(2*q0*SH_ACCX[1] + 2*q3*SH_ACCX[2] - 2*q2*vd) + Kaccx*P[1][1]*(2*q1*SH_ACCX[1] + 2*q2*SH_ACCX[2] + 2*q3*vd) - Kaccx*P[2][1]*(2*q2*SH_ACCX[1] - 2*q1*SH_ACCX[2] + 2*q0*vd) + Kaccx*P[3][1]*(2*q0*SH_ACCX[2] - 2*q3*SH_ACCX[1] + 2*q1*vd)) - Kaccx*(2*q2*SH_ACCX[1] - 2*q1*SH_ACCX[2] + 2*q0*vd)*(Kaccx*P[4][2]*SH_ACCX[0] + Kaccx*P[5][2]*SH_ACCX[3] - Kaccx*P[22][2]*SH_ACCX[0] - Kaccx*P[23][2]*SH_ACCX[3] - Kaccx*P[6][2]*(2*q0*q2 - 2*q1*q3) + Kaccx*P[0][2]*(2*q0*SH_ACCX[1] + 2*q3*SH_ACCX[2] - 2*q2*vd) + Kaccx*P[1][2]*(2*q1*SH_ACCX[1] + 2*q2*SH_ACCX[2] + 2*q3*vd) - Kaccx*P[2][2]*(2*q2*SH_ACCX[1] - 2*q1*SH_ACCX[2] + 2*q0*vd) + Kaccx*P[3][2]*(2*q0*SH_ACCX[2] - 2*q3*SH_ACCX[1] + 2*q1*vd)) + Kaccx*(2*q0*SH_ACCX[2] - 2*q3*SH_ACCX[1] + 2*q1*vd)*(Kaccx*P[4][3]*SH_ACCX[0] + Kaccx*P[5][3]*SH_ACCX[3] - Kaccx*P[22][3]*SH_ACCX[0] - Kaccx*P[23][3]*SH_ACCX[3] - Kaccx*P[6][3]*(2*q0*q2 - 2*q1*q3) + Kaccx*P[0][3]*(2*q0*SH_ACCX[1] + 2*q3*SH_ACCX[2] - 2*q2*vd) + Kaccx*P[1][3]*(2*q1*SH_ACCX[1] + 2*q2*SH_ACCX[2] + 2*q3*vd) - Kaccx*P[2][3]*(2*q2*SH_ACCX[1] - 2*q1*SH_ACCX[2] + 2*q0*vd) + Kaccx*P[3][3]*(2*q0*SH_ACCX[2] - 2*q3*SH_ACCX[1] + 2*q1*vd))); +SK_ACCX[1] = 2*q0*SH_ACCX[2] - 2*q3*SH_ACCX[1] + 2*q1*vd; +SK_ACCX[2] = 2*q2*SH_ACCX[1] - 2*q1*SH_ACCX[2] + 2*q0*vd; +SK_ACCX[3] = 2*q0*SH_ACCX[1] + 2*q3*SH_ACCX[2] - 2*q2*vd; +SK_ACCX[4] = 2*q1*SH_ACCX[1] + 2*q2*SH_ACCX[2] + 2*q3*vd; +SK_ACCX[5] = 2*q0*q2 - 2*q1*q3; +SK_ACCX[6] = SH_ACCX[3]; float Kfusion[24][1]; float Kfusion[1][1]; -Kfusion[0] = SK_ACCX[0]*(Kaccx*P[0][22]*SH_ACCX[0] - Kaccx*P[0][3]*SH_ACCX[0] + Kaccx*P[0][1]*SK_ACCX[2] + Kaccx*P[0][2]*SK_ACCX[1] - Kaccx*P[0][4]*SK_ACCX[4] + Kaccx*P[0][5]*SK_ACCX[3] + Kaccx*P[0][23]*SK_ACCX[4]); -Kfusion[1] = SK_ACCX[0]*(Kaccx*P[1][22]*SH_ACCX[0] - Kaccx*P[1][3]*SH_ACCX[0] + Kaccx*P[1][1]*SK_ACCX[2] + Kaccx*P[1][2]*SK_ACCX[1] - Kaccx*P[1][4]*SK_ACCX[4] + Kaccx*P[1][5]*SK_ACCX[3] + Kaccx*P[1][23]*SK_ACCX[4]); -Kfusion[2] = SK_ACCX[0]*(Kaccx*P[2][22]*SH_ACCX[0] - Kaccx*P[2][3]*SH_ACCX[0] + Kaccx*P[2][1]*SK_ACCX[2] + Kaccx*P[2][2]*SK_ACCX[1] - Kaccx*P[2][4]*SK_ACCX[4] + Kaccx*P[2][5]*SK_ACCX[3] + Kaccx*P[2][23]*SK_ACCX[4]); -Kfusion[3] = SK_ACCX[0]*(Kaccx*P[3][22]*SH_ACCX[0] - Kaccx*P[3][3]*SH_ACCX[0] + Kaccx*P[3][1]*SK_ACCX[2] + Kaccx*P[3][2]*SK_ACCX[1] - Kaccx*P[3][4]*SK_ACCX[4] + Kaccx*P[3][5]*SK_ACCX[3] + Kaccx*P[3][23]*SK_ACCX[4]); -Kfusion[4] = SK_ACCX[0]*(Kaccx*P[4][22]*SH_ACCX[0] - Kaccx*P[4][3]*SH_ACCX[0] + Kaccx*P[4][1]*SK_ACCX[2] + Kaccx*P[4][2]*SK_ACCX[1] - Kaccx*P[4][4]*SK_ACCX[4] + Kaccx*P[4][5]*SK_ACCX[3] + Kaccx*P[4][23]*SK_ACCX[4]); -Kfusion[5] = SK_ACCX[0]*(Kaccx*P[5][22]*SH_ACCX[0] - Kaccx*P[5][3]*SH_ACCX[0] + Kaccx*P[5][1]*SK_ACCX[2] + Kaccx*P[5][2]*SK_ACCX[1] - Kaccx*P[5][4]*SK_ACCX[4] + Kaccx*P[5][5]*SK_ACCX[3] + Kaccx*P[5][23]*SK_ACCX[4]); -Kfusion[6] = SK_ACCX[0]*(Kaccx*P[6][22]*SH_ACCX[0] - Kaccx*P[6][3]*SH_ACCX[0] + Kaccx*P[6][1]*SK_ACCX[2] + Kaccx*P[6][2]*SK_ACCX[1] - Kaccx*P[6][4]*SK_ACCX[4] + Kaccx*P[6][5]*SK_ACCX[3] + Kaccx*P[6][23]*SK_ACCX[4]); -Kfusion[7] = SK_ACCX[0]*(Kaccx*P[7][22]*SH_ACCX[0] - Kaccx*P[7][3]*SH_ACCX[0] + Kaccx*P[7][1]*SK_ACCX[2] + Kaccx*P[7][2]*SK_ACCX[1] - Kaccx*P[7][4]*SK_ACCX[4] + Kaccx*P[7][5]*SK_ACCX[3] + Kaccx*P[7][23]*SK_ACCX[4]); -Kfusion[8] = SK_ACCX[0]*(Kaccx*P[8][22]*SH_ACCX[0] - Kaccx*P[8][3]*SH_ACCX[0] + Kaccx*P[8][1]*SK_ACCX[2] + Kaccx*P[8][2]*SK_ACCX[1] - Kaccx*P[8][4]*SK_ACCX[4] + Kaccx*P[8][5]*SK_ACCX[3] + Kaccx*P[8][23]*SK_ACCX[4]); -Kfusion[9] = SK_ACCX[0]*(Kaccx*P[9][22]*SH_ACCX[0] - Kaccx*P[9][3]*SH_ACCX[0] + Kaccx*P[9][1]*SK_ACCX[2] + Kaccx*P[9][2]*SK_ACCX[1] - Kaccx*P[9][4]*SK_ACCX[4] + Kaccx*P[9][5]*SK_ACCX[3] + Kaccx*P[9][23]*SK_ACCX[4]); -Kfusion[10] = SK_ACCX[0]*(Kaccx*P[10][22]*SH_ACCX[0] - Kaccx*P[10][3]*SH_ACCX[0] + Kaccx*P[10][1]*SK_ACCX[2] + Kaccx*P[10][2]*SK_ACCX[1] - Kaccx*P[10][4]*SK_ACCX[4] + Kaccx*P[10][5]*SK_ACCX[3] + Kaccx*P[10][23]*SK_ACCX[4]); -Kfusion[11] = SK_ACCX[0]*(Kaccx*P[11][22]*SH_ACCX[0] - Kaccx*P[11][3]*SH_ACCX[0] + Kaccx*P[11][1]*SK_ACCX[2] + Kaccx*P[11][2]*SK_ACCX[1] - Kaccx*P[11][4]*SK_ACCX[4] + Kaccx*P[11][5]*SK_ACCX[3] + Kaccx*P[11][23]*SK_ACCX[4]); -Kfusion[12] = SK_ACCX[0]*(Kaccx*P[12][22]*SH_ACCX[0] - Kaccx*P[12][3]*SH_ACCX[0] + Kaccx*P[12][1]*SK_ACCX[2] + Kaccx*P[12][2]*SK_ACCX[1] - Kaccx*P[12][4]*SK_ACCX[4] + Kaccx*P[12][5]*SK_ACCX[3] + Kaccx*P[12][23]*SK_ACCX[4]); -Kfusion[13] = SK_ACCX[0]*(Kaccx*P[13][22]*SH_ACCX[0] - Kaccx*P[13][3]*SH_ACCX[0] + Kaccx*P[13][1]*SK_ACCX[2] + Kaccx*P[13][2]*SK_ACCX[1] - Kaccx*P[13][4]*SK_ACCX[4] + Kaccx*P[13][5]*SK_ACCX[3] + Kaccx*P[13][23]*SK_ACCX[4]); -Kfusion[14] = SK_ACCX[0]*(Kaccx*P[14][22]*SH_ACCX[0] - Kaccx*P[14][3]*SH_ACCX[0] + Kaccx*P[14][1]*SK_ACCX[2] + Kaccx*P[14][2]*SK_ACCX[1] - Kaccx*P[14][4]*SK_ACCX[4] + Kaccx*P[14][5]*SK_ACCX[3] + Kaccx*P[14][23]*SK_ACCX[4]); -Kfusion[15] = SK_ACCX[0]*(Kaccx*P[15][22]*SH_ACCX[0] - Kaccx*P[15][3]*SH_ACCX[0] + Kaccx*P[15][1]*SK_ACCX[2] + Kaccx*P[15][2]*SK_ACCX[1] - Kaccx*P[15][4]*SK_ACCX[4] + Kaccx*P[15][5]*SK_ACCX[3] + Kaccx*P[15][23]*SK_ACCX[4]); -Kfusion[16] = SK_ACCX[0]*(Kaccx*P[16][22]*SH_ACCX[0] - Kaccx*P[16][3]*SH_ACCX[0] + Kaccx*P[16][1]*SK_ACCX[2] + Kaccx*P[16][2]*SK_ACCX[1] - Kaccx*P[16][4]*SK_ACCX[4] + Kaccx*P[16][5]*SK_ACCX[3] + Kaccx*P[16][23]*SK_ACCX[4]); -Kfusion[17] = SK_ACCX[0]*(Kaccx*P[17][22]*SH_ACCX[0] - Kaccx*P[17][3]*SH_ACCX[0] + Kaccx*P[17][1]*SK_ACCX[2] + Kaccx*P[17][2]*SK_ACCX[1] - Kaccx*P[17][4]*SK_ACCX[4] + Kaccx*P[17][5]*SK_ACCX[3] + Kaccx*P[17][23]*SK_ACCX[4]); -Kfusion[18] = SK_ACCX[0]*(Kaccx*P[18][22]*SH_ACCX[0] - Kaccx*P[18][3]*SH_ACCX[0] + Kaccx*P[18][1]*SK_ACCX[2] + Kaccx*P[18][2]*SK_ACCX[1] - Kaccx*P[18][4]*SK_ACCX[4] + Kaccx*P[18][5]*SK_ACCX[3] + Kaccx*P[18][23]*SK_ACCX[4]); -Kfusion[19] = SK_ACCX[0]*(Kaccx*P[19][22]*SH_ACCX[0] - Kaccx*P[19][3]*SH_ACCX[0] + Kaccx*P[19][1]*SK_ACCX[2] + Kaccx*P[19][2]*SK_ACCX[1] - Kaccx*P[19][4]*SK_ACCX[4] + Kaccx*P[19][5]*SK_ACCX[3] + Kaccx*P[19][23]*SK_ACCX[4]); -Kfusion[20] = SK_ACCX[0]*(Kaccx*P[20][22]*SH_ACCX[0] - Kaccx*P[20][3]*SH_ACCX[0] + Kaccx*P[20][1]*SK_ACCX[2] + Kaccx*P[20][2]*SK_ACCX[1] - Kaccx*P[20][4]*SK_ACCX[4] + Kaccx*P[20][5]*SK_ACCX[3] + Kaccx*P[20][23]*SK_ACCX[4]); -Kfusion[21] = SK_ACCX[0]*(Kaccx*P[21][22]*SH_ACCX[0] - Kaccx*P[21][3]*SH_ACCX[0] + Kaccx*P[21][1]*SK_ACCX[2] + Kaccx*P[21][2]*SK_ACCX[1] - Kaccx*P[21][4]*SK_ACCX[4] + Kaccx*P[21][5]*SK_ACCX[3] + Kaccx*P[21][23]*SK_ACCX[4]); -Kfusion[22] = SK_ACCX[0]*(Kaccx*P[22][22]*SH_ACCX[0] - Kaccx*P[22][3]*SH_ACCX[0] + Kaccx*P[22][1]*SK_ACCX[2] + Kaccx*P[22][2]*SK_ACCX[1] - Kaccx*P[22][4]*SK_ACCX[4] + Kaccx*P[22][5]*SK_ACCX[3] + Kaccx*P[22][23]*SK_ACCX[4]); -Kfusion[23] = SK_ACCX[0]*(Kaccx*P[23][22]*SH_ACCX[0] - Kaccx*P[23][3]*SH_ACCX[0] + Kaccx*P[23][1]*SK_ACCX[2] + Kaccx*P[23][2]*SK_ACCX[1] - Kaccx*P[23][4]*SK_ACCX[4] + Kaccx*P[23][5]*SK_ACCX[3] + Kaccx*P[23][23]*SK_ACCX[4]); -float SH_ACCY[6][1]; +Kfusion[0] = -SK_ACCX[0]*(Kaccx*P[0][4]*SH_ACCX[0] - Kaccx*P[0][22]*SH_ACCX[0] + Kaccx*P[0][0]*SK_ACCX[3] - Kaccx*P[0][2]*SK_ACCX[2] + Kaccx*P[0][3]*SK_ACCX[1] + Kaccx*P[0][1]*SK_ACCX[4] + Kaccx*P[0][5]*SK_ACCX[6] - Kaccx*P[0][6]*SK_ACCX[5] - Kaccx*P[0][23]*SK_ACCX[6]); +Kfusion[1] = -SK_ACCX[0]*(Kaccx*P[1][4]*SH_ACCX[0] - Kaccx*P[1][22]*SH_ACCX[0] + Kaccx*P[1][0]*SK_ACCX[3] - Kaccx*P[1][2]*SK_ACCX[2] + Kaccx*P[1][3]*SK_ACCX[1] + Kaccx*P[1][1]*SK_ACCX[4] + Kaccx*P[1][5]*SK_ACCX[6] - Kaccx*P[1][6]*SK_ACCX[5] - Kaccx*P[1][23]*SK_ACCX[6]); +Kfusion[2] = -SK_ACCX[0]*(Kaccx*P[2][4]*SH_ACCX[0] - Kaccx*P[2][22]*SH_ACCX[0] + Kaccx*P[2][0]*SK_ACCX[3] - Kaccx*P[2][2]*SK_ACCX[2] + Kaccx*P[2][3]*SK_ACCX[1] + Kaccx*P[2][1]*SK_ACCX[4] + Kaccx*P[2][5]*SK_ACCX[6] - Kaccx*P[2][6]*SK_ACCX[5] - Kaccx*P[2][23]*SK_ACCX[6]); +Kfusion[3] = -SK_ACCX[0]*(Kaccx*P[3][4]*SH_ACCX[0] - Kaccx*P[3][22]*SH_ACCX[0] + Kaccx*P[3][0]*SK_ACCX[3] - Kaccx*P[3][2]*SK_ACCX[2] + Kaccx*P[3][3]*SK_ACCX[1] + Kaccx*P[3][1]*SK_ACCX[4] + Kaccx*P[3][5]*SK_ACCX[6] - Kaccx*P[3][6]*SK_ACCX[5] - Kaccx*P[3][23]*SK_ACCX[6]); +Kfusion[4] = -SK_ACCX[0]*(Kaccx*P[4][4]*SH_ACCX[0] - Kaccx*P[4][22]*SH_ACCX[0] + Kaccx*P[4][0]*SK_ACCX[3] - Kaccx*P[4][2]*SK_ACCX[2] + Kaccx*P[4][3]*SK_ACCX[1] + Kaccx*P[4][1]*SK_ACCX[4] + Kaccx*P[4][5]*SK_ACCX[6] - Kaccx*P[4][6]*SK_ACCX[5] - Kaccx*P[4][23]*SK_ACCX[6]); +Kfusion[5] = -SK_ACCX[0]*(Kaccx*P[5][4]*SH_ACCX[0] - Kaccx*P[5][22]*SH_ACCX[0] + Kaccx*P[5][0]*SK_ACCX[3] - Kaccx*P[5][2]*SK_ACCX[2] + Kaccx*P[5][3]*SK_ACCX[1] + Kaccx*P[5][1]*SK_ACCX[4] + Kaccx*P[5][5]*SK_ACCX[6] - Kaccx*P[5][6]*SK_ACCX[5] - Kaccx*P[5][23]*SK_ACCX[6]); +Kfusion[6] = -SK_ACCX[0]*(Kaccx*P[6][4]*SH_ACCX[0] - Kaccx*P[6][22]*SH_ACCX[0] + Kaccx*P[6][0]*SK_ACCX[3] - Kaccx*P[6][2]*SK_ACCX[2] + Kaccx*P[6][3]*SK_ACCX[1] + Kaccx*P[6][1]*SK_ACCX[4] + Kaccx*P[6][5]*SK_ACCX[6] - Kaccx*P[6][6]*SK_ACCX[5] - Kaccx*P[6][23]*SK_ACCX[6]); +Kfusion[7] = -SK_ACCX[0]*(Kaccx*P[7][4]*SH_ACCX[0] - Kaccx*P[7][22]*SH_ACCX[0] + Kaccx*P[7][0]*SK_ACCX[3] - Kaccx*P[7][2]*SK_ACCX[2] + Kaccx*P[7][3]*SK_ACCX[1] + Kaccx*P[7][1]*SK_ACCX[4] + Kaccx*P[7][5]*SK_ACCX[6] - Kaccx*P[7][6]*SK_ACCX[5] - Kaccx*P[7][23]*SK_ACCX[6]); +Kfusion[8] = -SK_ACCX[0]*(Kaccx*P[8][4]*SH_ACCX[0] - Kaccx*P[8][22]*SH_ACCX[0] + Kaccx*P[8][0]*SK_ACCX[3] - Kaccx*P[8][2]*SK_ACCX[2] + Kaccx*P[8][3]*SK_ACCX[1] + Kaccx*P[8][1]*SK_ACCX[4] + Kaccx*P[8][5]*SK_ACCX[6] - Kaccx*P[8][6]*SK_ACCX[5] - Kaccx*P[8][23]*SK_ACCX[6]); +Kfusion[9] = -SK_ACCX[0]*(Kaccx*P[9][4]*SH_ACCX[0] - Kaccx*P[9][22]*SH_ACCX[0] + Kaccx*P[9][0]*SK_ACCX[3] - Kaccx*P[9][2]*SK_ACCX[2] + Kaccx*P[9][3]*SK_ACCX[1] + Kaccx*P[9][1]*SK_ACCX[4] + Kaccx*P[9][5]*SK_ACCX[6] - Kaccx*P[9][6]*SK_ACCX[5] - Kaccx*P[9][23]*SK_ACCX[6]); +Kfusion[10] = -SK_ACCX[0]*(Kaccx*P[10][4]*SH_ACCX[0] - Kaccx*P[10][22]*SH_ACCX[0] + Kaccx*P[10][0]*SK_ACCX[3] - Kaccx*P[10][2]*SK_ACCX[2] + Kaccx*P[10][3]*SK_ACCX[1] + Kaccx*P[10][1]*SK_ACCX[4] + Kaccx*P[10][5]*SK_ACCX[6] - Kaccx*P[10][6]*SK_ACCX[5] - Kaccx*P[10][23]*SK_ACCX[6]); +Kfusion[11] = -SK_ACCX[0]*(Kaccx*P[11][4]*SH_ACCX[0] - Kaccx*P[11][22]*SH_ACCX[0] + Kaccx*P[11][0]*SK_ACCX[3] - Kaccx*P[11][2]*SK_ACCX[2] + Kaccx*P[11][3]*SK_ACCX[1] + Kaccx*P[11][1]*SK_ACCX[4] + Kaccx*P[11][5]*SK_ACCX[6] - Kaccx*P[11][6]*SK_ACCX[5] - Kaccx*P[11][23]*SK_ACCX[6]); +Kfusion[12] = -SK_ACCX[0]*(Kaccx*P[12][4]*SH_ACCX[0] - Kaccx*P[12][22]*SH_ACCX[0] + Kaccx*P[12][0]*SK_ACCX[3] - Kaccx*P[12][2]*SK_ACCX[2] + Kaccx*P[12][3]*SK_ACCX[1] + Kaccx*P[12][1]*SK_ACCX[4] + Kaccx*P[12][5]*SK_ACCX[6] - Kaccx*P[12][6]*SK_ACCX[5] - Kaccx*P[12][23]*SK_ACCX[6]); +Kfusion[13] = -SK_ACCX[0]*(Kaccx*P[13][4]*SH_ACCX[0] - Kaccx*P[13][22]*SH_ACCX[0] + Kaccx*P[13][0]*SK_ACCX[3] - Kaccx*P[13][2]*SK_ACCX[2] + Kaccx*P[13][3]*SK_ACCX[1] + Kaccx*P[13][1]*SK_ACCX[4] + Kaccx*P[13][5]*SK_ACCX[6] - Kaccx*P[13][6]*SK_ACCX[5] - Kaccx*P[13][23]*SK_ACCX[6]); +Kfusion[14] = -SK_ACCX[0]*(Kaccx*P[14][4]*SH_ACCX[0] - Kaccx*P[14][22]*SH_ACCX[0] + Kaccx*P[14][0]*SK_ACCX[3] - Kaccx*P[14][2]*SK_ACCX[2] + Kaccx*P[14][3]*SK_ACCX[1] + Kaccx*P[14][1]*SK_ACCX[4] + Kaccx*P[14][5]*SK_ACCX[6] - Kaccx*P[14][6]*SK_ACCX[5] - Kaccx*P[14][23]*SK_ACCX[6]); +Kfusion[15] = -SK_ACCX[0]*(Kaccx*P[15][4]*SH_ACCX[0] - Kaccx*P[15][22]*SH_ACCX[0] + Kaccx*P[15][0]*SK_ACCX[3] - Kaccx*P[15][2]*SK_ACCX[2] + Kaccx*P[15][3]*SK_ACCX[1] + Kaccx*P[15][1]*SK_ACCX[4] + Kaccx*P[15][5]*SK_ACCX[6] - Kaccx*P[15][6]*SK_ACCX[5] - Kaccx*P[15][23]*SK_ACCX[6]); +Kfusion[16] = -SK_ACCX[0]*(Kaccx*P[16][4]*SH_ACCX[0] - Kaccx*P[16][22]*SH_ACCX[0] + Kaccx*P[16][0]*SK_ACCX[3] - Kaccx*P[16][2]*SK_ACCX[2] + Kaccx*P[16][3]*SK_ACCX[1] + Kaccx*P[16][1]*SK_ACCX[4] + Kaccx*P[16][5]*SK_ACCX[6] - Kaccx*P[16][6]*SK_ACCX[5] - Kaccx*P[16][23]*SK_ACCX[6]); +Kfusion[17] = -SK_ACCX[0]*(Kaccx*P[17][4]*SH_ACCX[0] - Kaccx*P[17][22]*SH_ACCX[0] + Kaccx*P[17][0]*SK_ACCX[3] - Kaccx*P[17][2]*SK_ACCX[2] + Kaccx*P[17][3]*SK_ACCX[1] + Kaccx*P[17][1]*SK_ACCX[4] + Kaccx*P[17][5]*SK_ACCX[6] - Kaccx*P[17][6]*SK_ACCX[5] - Kaccx*P[17][23]*SK_ACCX[6]); +Kfusion[18] = -SK_ACCX[0]*(Kaccx*P[18][4]*SH_ACCX[0] - Kaccx*P[18][22]*SH_ACCX[0] + Kaccx*P[18][0]*SK_ACCX[3] - Kaccx*P[18][2]*SK_ACCX[2] + Kaccx*P[18][3]*SK_ACCX[1] + Kaccx*P[18][1]*SK_ACCX[4] + Kaccx*P[18][5]*SK_ACCX[6] - Kaccx*P[18][6]*SK_ACCX[5] - Kaccx*P[18][23]*SK_ACCX[6]); +Kfusion[19] = -SK_ACCX[0]*(Kaccx*P[19][4]*SH_ACCX[0] - Kaccx*P[19][22]*SH_ACCX[0] + Kaccx*P[19][0]*SK_ACCX[3] - Kaccx*P[19][2]*SK_ACCX[2] + Kaccx*P[19][3]*SK_ACCX[1] + Kaccx*P[19][1]*SK_ACCX[4] + Kaccx*P[19][5]*SK_ACCX[6] - Kaccx*P[19][6]*SK_ACCX[5] - Kaccx*P[19][23]*SK_ACCX[6]); +Kfusion[20] = -SK_ACCX[0]*(Kaccx*P[20][4]*SH_ACCX[0] - Kaccx*P[20][22]*SH_ACCX[0] + Kaccx*P[20][0]*SK_ACCX[3] - Kaccx*P[20][2]*SK_ACCX[2] + Kaccx*P[20][3]*SK_ACCX[1] + Kaccx*P[20][1]*SK_ACCX[4] + Kaccx*P[20][5]*SK_ACCX[6] - Kaccx*P[20][6]*SK_ACCX[5] - Kaccx*P[20][23]*SK_ACCX[6]); +Kfusion[21] = -SK_ACCX[0]*(Kaccx*P[21][4]*SH_ACCX[0] - Kaccx*P[21][22]*SH_ACCX[0] + Kaccx*P[21][0]*SK_ACCX[3] - Kaccx*P[21][2]*SK_ACCX[2] + Kaccx*P[21][3]*SK_ACCX[1] + Kaccx*P[21][1]*SK_ACCX[4] + Kaccx*P[21][5]*SK_ACCX[6] - Kaccx*P[21][6]*SK_ACCX[5] - Kaccx*P[21][23]*SK_ACCX[6]); +Kfusion[22] = -SK_ACCX[0]*(Kaccx*P[22][4]*SH_ACCX[0] - Kaccx*P[22][22]*SH_ACCX[0] + Kaccx*P[22][0]*SK_ACCX[3] - Kaccx*P[22][2]*SK_ACCX[2] + Kaccx*P[22][3]*SK_ACCX[1] + Kaccx*P[22][1]*SK_ACCX[4] + Kaccx*P[22][5]*SK_ACCX[6] - Kaccx*P[22][6]*SK_ACCX[5] - Kaccx*P[22][23]*SK_ACCX[6]); +Kfusion[23] = -SK_ACCX[0]*(Kaccx*P[23][4]*SH_ACCX[0] - Kaccx*P[23][22]*SH_ACCX[0] + Kaccx*P[23][0]*SK_ACCX[3] - Kaccx*P[23][2]*SK_ACCX[2] + Kaccx*P[23][3]*SK_ACCX[1] + Kaccx*P[23][1]*SK_ACCX[4] + Kaccx*P[23][5]*SK_ACCX[6] - Kaccx*P[23][6]*SK_ACCX[5] - Kaccx*P[23][23]*SK_ACCX[6]); +float SH_ACCY[3][1]; SH_ACCY[0] = sq(q0) - sq(q1) + sq(q2) - sq(q3); -SH_ACCY[1] = ve - vwe; -SH_ACCY[2] = vn - vwn; -SH_ACCY[3] = sq(q1); -SH_ACCY[4] = 2*q0*q1; -SH_ACCY[5] = 2*q0*q3; +SH_ACCY[1] = vn - vwn; +SH_ACCY[2] = ve - vwe; float H_ACCY[1][24]; -H_ACCY[0][0] = Kaccy*(SH_ACCY[1]*(SH_ACCY[4] - 2*q2*q3) - SH_ACCY[2]*(2*q0*q2 + 2*q1*q3) + vd*(SH_ACCY[3] - sq(q0) + sq(q2) - sq(q3))); -H_ACCY[0][2] = Kaccy*(SH_ACCY[2]*(SH_ACCY[3] + sq(q0) - sq(q2) - sq(q3)) + SH_ACCY[1]*(SH_ACCY[5] + 2*q1*q2) - 2*vd*(q0*q2 - q1*q3)); -H_ACCY[0][3] = Kaccy*(SH_ACCY[5] - 2*q1*q2); -H_ACCY[0][4] = -Kaccy*SH_ACCY[0]; -H_ACCY[0][5] = -Kaccy*(SH_ACCY[4] + 2*q2*q3); +H_ACCY[0][0] = -Kaccy*(2*q0*SH_ACCY[2] - 2*q3*SH_ACCY[1] + 2*q1*vd); +H_ACCY[0][1] = -Kaccy*(2*q2*SH_ACCY[1] - 2*q1*SH_ACCY[2] + 2*q0*vd); +H_ACCY[0][2] = -Kaccy*(2*q1*SH_ACCY[1] + 2*q2*SH_ACCY[2] + 2*q3*vd); +H_ACCY[0][3] = Kaccy*(2*q0*SH_ACCY[1] + 2*q3*SH_ACCY[2] - 2*q2*vd); +H_ACCY[0][4] = Kaccy*(2*q0*q3 - 2*q1*q2); +H_ACCY[0][5] = -Kaccy*SH_ACCY[0]; +H_ACCY[0][6] = -Kaccy*(2*q0*q1 + 2*q2*q3); H_ACCY[0][22] = -2*Kaccy*(q0*q3 - q1*q2); H_ACCY[0][23] = Kaccy*SH_ACCY[0]; -float SK_ACCY[7][1]; -SK_ACCY[0] = 1/(R_ACC - Kaccy*SH_ACCY[0]*(Kaccy*P[23][4]*SH_ACCY[0] - Kaccy*P[4][4]*SH_ACCY[0] + Kaccy*P[0][4]*(SH_ACCY[1]*(SH_ACCY[4] - 2*q2*q3) - SH_ACCY[2]*(2*q0*q2 + 2*q1*q3) + vd*(SH_ACCY[3] - sq(q0) + sq(q2) - sq(q3))) + Kaccy*P[2][4]*(SH_ACCY[2]*(SH_ACCY[3] + sq(q0) - sq(q2) - sq(q3)) + SH_ACCY[1]*(SH_ACCY[5] + 2*q1*q2) - 2*vd*(q0*q2 - q1*q3)) - 2*Kaccy*P[22][4]*(q0*q3 - q1*q2) + Kaccy*P[3][4]*(SH_ACCY[5] - 2*q1*q2) - Kaccy*P[5][4]*(SH_ACCY[4] + 2*q2*q3)) + Kaccy*SH_ACCY[0]*(Kaccy*P[23][23]*SH_ACCY[0] - Kaccy*P[4][23]*SH_ACCY[0] + Kaccy*P[0][23]*(SH_ACCY[1]*(SH_ACCY[4] - 2*q2*q3) - SH_ACCY[2]*(2*q0*q2 + 2*q1*q3) + vd*(SH_ACCY[3] - sq(q0) + sq(q2) - sq(q3))) + Kaccy*P[2][23]*(SH_ACCY[2]*(SH_ACCY[3] + sq(q0) - sq(q2) - sq(q3)) + SH_ACCY[1]*(SH_ACCY[5] + 2*q1*q2) - 2*vd*(q0*q2 - q1*q3)) - 2*Kaccy*P[22][23]*(q0*q3 - q1*q2) + Kaccy*P[3][23]*(SH_ACCY[5] - 2*q1*q2) - Kaccy*P[5][23]*(SH_ACCY[4] + 2*q2*q3)) + Kaccy*(SH_ACCY[1]*(SH_ACCY[4] - 2*q2*q3) - SH_ACCY[2]*(2*q0*q2 + 2*q1*q3) + vd*(SH_ACCY[3] - sq(q0) + sq(q2) - sq(q3)))*(Kaccy*P[23][0]*SH_ACCY[0] - Kaccy*P[4][0]*SH_ACCY[0] + Kaccy*P[0][0]*(SH_ACCY[1]*(SH_ACCY[4] - 2*q2*q3) - SH_ACCY[2]*(2*q0*q2 + 2*q1*q3) + vd*(SH_ACCY[3] - sq(q0) + sq(q2) - sq(q3))) + Kaccy*P[2][0]*(SH_ACCY[2]*(SH_ACCY[3] + sq(q0) - sq(q2) - sq(q3)) + SH_ACCY[1]*(SH_ACCY[5] + 2*q1*q2) - 2*vd*(q0*q2 - q1*q3)) - 2*Kaccy*P[22][0]*(q0*q3 - q1*q2) + Kaccy*P[3][0]*(SH_ACCY[5] - 2*q1*q2) - Kaccy*P[5][0]*(SH_ACCY[4] + 2*q2*q3)) + Kaccy*(SH_ACCY[2]*(SH_ACCY[3] + sq(q0) - sq(q2) - sq(q3)) + SH_ACCY[1]*(SH_ACCY[5] + 2*q1*q2) - 2*vd*(q0*q2 - q1*q3))*(Kaccy*P[23][2]*SH_ACCY[0] - Kaccy*P[4][2]*SH_ACCY[0] + Kaccy*P[0][2]*(SH_ACCY[1]*(SH_ACCY[4] - 2*q2*q3) - SH_ACCY[2]*(2*q0*q2 + 2*q1*q3) + vd*(SH_ACCY[3] - sq(q0) + sq(q2) - sq(q3))) + Kaccy*P[2][2]*(SH_ACCY[2]*(SH_ACCY[3] + sq(q0) - sq(q2) - sq(q3)) + SH_ACCY[1]*(SH_ACCY[5] + 2*q1*q2) - 2*vd*(q0*q2 - q1*q3)) - 2*Kaccy*P[22][2]*(q0*q3 - q1*q2) + Kaccy*P[3][2]*(SH_ACCY[5] - 2*q1*q2) - Kaccy*P[5][2]*(SH_ACCY[4] + 2*q2*q3)) - 2*Kaccy*(q0*q3 - q1*q2)*(Kaccy*P[23][22]*SH_ACCY[0] - Kaccy*P[4][22]*SH_ACCY[0] + Kaccy*P[0][22]*(SH_ACCY[1]*(SH_ACCY[4] - 2*q2*q3) - SH_ACCY[2]*(2*q0*q2 + 2*q1*q3) + vd*(SH_ACCY[3] - sq(q0) + sq(q2) - sq(q3))) + Kaccy*P[2][22]*(SH_ACCY[2]*(SH_ACCY[3] + sq(q0) - sq(q2) - sq(q3)) + SH_ACCY[1]*(SH_ACCY[5] + 2*q1*q2) - 2*vd*(q0*q2 - q1*q3)) - 2*Kaccy*P[22][22]*(q0*q3 - q1*q2) + Kaccy*P[3][22]*(SH_ACCY[5] - 2*q1*q2) - Kaccy*P[5][22]*(SH_ACCY[4] + 2*q2*q3)) + Kaccy*(SH_ACCY[5] - 2*q1*q2)*(Kaccy*P[23][3]*SH_ACCY[0] - Kaccy*P[4][3]*SH_ACCY[0] + Kaccy*P[0][3]*(SH_ACCY[1]*(SH_ACCY[4] - 2*q2*q3) - SH_ACCY[2]*(2*q0*q2 + 2*q1*q3) + vd*(SH_ACCY[3] - sq(q0) + sq(q2) - sq(q3))) + Kaccy*P[2][3]*(SH_ACCY[2]*(SH_ACCY[3] + sq(q0) - sq(q2) - sq(q3)) + SH_ACCY[1]*(SH_ACCY[5] + 2*q1*q2) - 2*vd*(q0*q2 - q1*q3)) - 2*Kaccy*P[22][3]*(q0*q3 - q1*q2) + Kaccy*P[3][3]*(SH_ACCY[5] - 2*q1*q2) - Kaccy*P[5][3]*(SH_ACCY[4] + 2*q2*q3)) - Kaccy*(SH_ACCY[4] + 2*q2*q3)*(Kaccy*P[23][5]*SH_ACCY[0] - Kaccy*P[4][5]*SH_ACCY[0] + Kaccy*P[0][5]*(SH_ACCY[1]*(SH_ACCY[4] - 2*q2*q3) - SH_ACCY[2]*(2*q0*q2 + 2*q1*q3) + vd*(SH_ACCY[3] - sq(q0) + sq(q2) - sq(q3))) + Kaccy*P[2][5]*(SH_ACCY[2]*(SH_ACCY[3] + sq(q0) - sq(q2) - sq(q3)) + SH_ACCY[1]*(SH_ACCY[5] + 2*q1*q2) - 2*vd*(q0*q2 - q1*q3)) - 2*Kaccy*P[22][5]*(q0*q3 - q1*q2) + Kaccy*P[3][5]*(SH_ACCY[5] - 2*q1*q2) - Kaccy*P[5][5]*(SH_ACCY[4] + 2*q2*q3))); -SK_ACCY[1] = SH_ACCY[2]*(SH_ACCY[3] + sq(q0) - sq(q2) - sq(q3)) + SH_ACCY[1]*(SH_ACCY[5] + 2*q1*q2) - 2*vd*(q0*q2 - q1*q3); -SK_ACCY[2] = SH_ACCY[1]*(SH_ACCY[4] - 2*q2*q3) - SH_ACCY[2]*(2*q0*q2 + 2*q1*q3) + vd*(SH_ACCY[3] - sq(q0) + sq(q2) - sq(q3)); -SK_ACCY[3] = q0*q3 - q1*q2; -SK_ACCY[4] = SH_ACCY[5] - 2*q1*q2; -SK_ACCY[5] = SH_ACCY[4] + 2*q2*q3; -SK_ACCY[6] = SH_ACCY[0]; +float SK_ACCY[9][1]; +SK_ACCY[0] = 1/(R_ACC + Kaccy*SH_ACCY[0]*(Kaccy*P[5][5]*SH_ACCY[0] - Kaccy*P[23][5]*SH_ACCY[0] - Kaccy*P[4][5]*(2*q0*q3 - 2*q1*q2) + Kaccy*P[6][5]*(2*q0*q1 + 2*q2*q3) + 2*Kaccy*P[22][5]*(q0*q3 - q1*q2) + Kaccy*P[0][5]*(2*q0*SH_ACCY[2] - 2*q3*SH_ACCY[1] + 2*q1*vd) + Kaccy*P[1][5]*(2*q2*SH_ACCY[1] - 2*q1*SH_ACCY[2] + 2*q0*vd) + Kaccy*P[2][5]*(2*q1*SH_ACCY[1] + 2*q2*SH_ACCY[2] + 2*q3*vd) - Kaccy*P[3][5]*(2*q0*SH_ACCY[1] + 2*q3*SH_ACCY[2] - 2*q2*vd)) - Kaccy*SH_ACCY[0]*(Kaccy*P[5][23]*SH_ACCY[0] - Kaccy*P[23][23]*SH_ACCY[0] - Kaccy*P[4][23]*(2*q0*q3 - 2*q1*q2) + Kaccy*P[6][23]*(2*q0*q1 + 2*q2*q3) + 2*Kaccy*P[22][23]*(q0*q3 - q1*q2) + Kaccy*P[0][23]*(2*q0*SH_ACCY[2] - 2*q3*SH_ACCY[1] + 2*q1*vd) + Kaccy*P[1][23]*(2*q2*SH_ACCY[1] - 2*q1*SH_ACCY[2] + 2*q0*vd) + Kaccy*P[2][23]*(2*q1*SH_ACCY[1] + 2*q2*SH_ACCY[2] + 2*q3*vd) - Kaccy*P[3][23]*(2*q0*SH_ACCY[1] + 2*q3*SH_ACCY[2] - 2*q2*vd)) - Kaccy*(2*q0*q3 - 2*q1*q2)*(Kaccy*P[5][4]*SH_ACCY[0] - Kaccy*P[23][4]*SH_ACCY[0] - Kaccy*P[4][4]*(2*q0*q3 - 2*q1*q2) + Kaccy*P[6][4]*(2*q0*q1 + 2*q2*q3) + 2*Kaccy*P[22][4]*(q0*q3 - q1*q2) + Kaccy*P[0][4]*(2*q0*SH_ACCY[2] - 2*q3*SH_ACCY[1] + 2*q1*vd) + Kaccy*P[1][4]*(2*q2*SH_ACCY[1] - 2*q1*SH_ACCY[2] + 2*q0*vd) + Kaccy*P[2][4]*(2*q1*SH_ACCY[1] + 2*q2*SH_ACCY[2] + 2*q3*vd) - Kaccy*P[3][4]*(2*q0*SH_ACCY[1] + 2*q3*SH_ACCY[2] - 2*q2*vd)) + Kaccy*(2*q0*q1 + 2*q2*q3)*(Kaccy*P[5][6]*SH_ACCY[0] - Kaccy*P[23][6]*SH_ACCY[0] - Kaccy*P[4][6]*(2*q0*q3 - 2*q1*q2) + Kaccy*P[6][6]*(2*q0*q1 + 2*q2*q3) + 2*Kaccy*P[22][6]*(q0*q3 - q1*q2) + Kaccy*P[0][6]*(2*q0*SH_ACCY[2] - 2*q3*SH_ACCY[1] + 2*q1*vd) + Kaccy*P[1][6]*(2*q2*SH_ACCY[1] - 2*q1*SH_ACCY[2] + 2*q0*vd) + Kaccy*P[2][6]*(2*q1*SH_ACCY[1] + 2*q2*SH_ACCY[2] + 2*q3*vd) - Kaccy*P[3][6]*(2*q0*SH_ACCY[1] + 2*q3*SH_ACCY[2] - 2*q2*vd)) + 2*Kaccy*(q0*q3 - q1*q2)*(Kaccy*P[5][22]*SH_ACCY[0] - Kaccy*P[23][22]*SH_ACCY[0] - Kaccy*P[4][22]*(2*q0*q3 - 2*q1*q2) + Kaccy*P[6][22]*(2*q0*q1 + 2*q2*q3) + 2*Kaccy*P[22][22]*(q0*q3 - q1*q2) + Kaccy*P[0][22]*(2*q0*SH_ACCY[2] - 2*q3*SH_ACCY[1] + 2*q1*vd) + Kaccy*P[1][22]*(2*q2*SH_ACCY[1] - 2*q1*SH_ACCY[2] + 2*q0*vd) + Kaccy*P[2][22]*(2*q1*SH_ACCY[1] + 2*q2*SH_ACCY[2] + 2*q3*vd) - Kaccy*P[3][22]*(2*q0*SH_ACCY[1] + 2*q3*SH_ACCY[2] - 2*q2*vd)) + Kaccy*(2*q0*SH_ACCY[2] - 2*q3*SH_ACCY[1] + 2*q1*vd)*(Kaccy*P[5][0]*SH_ACCY[0] - Kaccy*P[23][0]*SH_ACCY[0] - Kaccy*P[4][0]*(2*q0*q3 - 2*q1*q2) + Kaccy*P[6][0]*(2*q0*q1 + 2*q2*q3) + 2*Kaccy*P[22][0]*(q0*q3 - q1*q2) + Kaccy*P[0][0]*(2*q0*SH_ACCY[2] - 2*q3*SH_ACCY[1] + 2*q1*vd) + Kaccy*P[1][0]*(2*q2*SH_ACCY[1] - 2*q1*SH_ACCY[2] + 2*q0*vd) + Kaccy*P[2][0]*(2*q1*SH_ACCY[1] + 2*q2*SH_ACCY[2] + 2*q3*vd) - Kaccy*P[3][0]*(2*q0*SH_ACCY[1] + 2*q3*SH_ACCY[2] - 2*q2*vd)) + Kaccy*(2*q2*SH_ACCY[1] - 2*q1*SH_ACCY[2] + 2*q0*vd)*(Kaccy*P[5][1]*SH_ACCY[0] - Kaccy*P[23][1]*SH_ACCY[0] - Kaccy*P[4][1]*(2*q0*q3 - 2*q1*q2) + Kaccy*P[6][1]*(2*q0*q1 + 2*q2*q3) + 2*Kaccy*P[22][1]*(q0*q3 - q1*q2) + Kaccy*P[0][1]*(2*q0*SH_ACCY[2] - 2*q3*SH_ACCY[1] + 2*q1*vd) + Kaccy*P[1][1]*(2*q2*SH_ACCY[1] - 2*q1*SH_ACCY[2] + 2*q0*vd) + Kaccy*P[2][1]*(2*q1*SH_ACCY[1] + 2*q2*SH_ACCY[2] + 2*q3*vd) - Kaccy*P[3][1]*(2*q0*SH_ACCY[1] + 2*q3*SH_ACCY[2] - 2*q2*vd)) + Kaccy*(2*q1*SH_ACCY[1] + 2*q2*SH_ACCY[2] + 2*q3*vd)*(Kaccy*P[5][2]*SH_ACCY[0] - Kaccy*P[23][2]*SH_ACCY[0] - Kaccy*P[4][2]*(2*q0*q3 - 2*q1*q2) + Kaccy*P[6][2]*(2*q0*q1 + 2*q2*q3) + 2*Kaccy*P[22][2]*(q0*q3 - q1*q2) + Kaccy*P[0][2]*(2*q0*SH_ACCY[2] - 2*q3*SH_ACCY[1] + 2*q1*vd) + Kaccy*P[1][2]*(2*q2*SH_ACCY[1] - 2*q1*SH_ACCY[2] + 2*q0*vd) + Kaccy*P[2][2]*(2*q1*SH_ACCY[1] + 2*q2*SH_ACCY[2] + 2*q3*vd) - Kaccy*P[3][2]*(2*q0*SH_ACCY[1] + 2*q3*SH_ACCY[2] - 2*q2*vd)) - Kaccy*(2*q0*SH_ACCY[1] + 2*q3*SH_ACCY[2] - 2*q2*vd)*(Kaccy*P[5][3]*SH_ACCY[0] - Kaccy*P[23][3]*SH_ACCY[0] - Kaccy*P[4][3]*(2*q0*q3 - 2*q1*q2) + Kaccy*P[6][3]*(2*q0*q1 + 2*q2*q3) + 2*Kaccy*P[22][3]*(q0*q3 - q1*q2) + Kaccy*P[0][3]*(2*q0*SH_ACCY[2] - 2*q3*SH_ACCY[1] + 2*q1*vd) + Kaccy*P[1][3]*(2*q2*SH_ACCY[1] - 2*q1*SH_ACCY[2] + 2*q0*vd) + Kaccy*P[2][3]*(2*q1*SH_ACCY[1] + 2*q2*SH_ACCY[2] + 2*q3*vd) - Kaccy*P[3][3]*(2*q0*SH_ACCY[1] + 2*q3*SH_ACCY[2] - 2*q2*vd))); +SK_ACCY[1] = 2*q0*SH_ACCY[1] + 2*q3*SH_ACCY[2] - 2*q2*vd; +SK_ACCY[2] = 2*q2*SH_ACCY[1] - 2*q1*SH_ACCY[2] + 2*q0*vd; +SK_ACCY[3] = 2*q0*SH_ACCY[2] - 2*q3*SH_ACCY[1] + 2*q1*vd; +SK_ACCY[4] = 2*q1*SH_ACCY[1] + 2*q2*SH_ACCY[2] + 2*q3*vd; +SK_ACCY[5] = 2*q0*q3 - 2*q1*q2; +SK_ACCY[6] = q0*q3 - q1*q2; +SK_ACCY[7] = 2*q0*q1 + 2*q2*q3; +SK_ACCY[8] = SH_ACCY[0]; float Kfusion[24][1]; float Kfusion[1][1]; -Kfusion[0] = SK_ACCY[0]*(Kaccy*P[0][0]*SK_ACCY[2] + Kaccy*P[0][2]*SK_ACCY[1] + Kaccy*P[0][3]*SK_ACCY[4] - Kaccy*P[0][4]*SK_ACCY[6] - Kaccy*P[0][5]*SK_ACCY[5] - 2*Kaccy*P[0][22]*SK_ACCY[3] + Kaccy*P[0][23]*SK_ACCY[6]); -Kfusion[1] = SK_ACCY[0]*(Kaccy*P[1][0]*SK_ACCY[2] + Kaccy*P[1][2]*SK_ACCY[1] + Kaccy*P[1][3]*SK_ACCY[4] - Kaccy*P[1][4]*SK_ACCY[6] - Kaccy*P[1][5]*SK_ACCY[5] - 2*Kaccy*P[1][22]*SK_ACCY[3] + Kaccy*P[1][23]*SK_ACCY[6]); -Kfusion[2] = SK_ACCY[0]*(Kaccy*P[2][0]*SK_ACCY[2] + Kaccy*P[2][2]*SK_ACCY[1] + Kaccy*P[2][3]*SK_ACCY[4] - Kaccy*P[2][4]*SK_ACCY[6] - Kaccy*P[2][5]*SK_ACCY[5] - 2*Kaccy*P[2][22]*SK_ACCY[3] + Kaccy*P[2][23]*SK_ACCY[6]); -Kfusion[3] = SK_ACCY[0]*(Kaccy*P[3][0]*SK_ACCY[2] + Kaccy*P[3][2]*SK_ACCY[1] + Kaccy*P[3][3]*SK_ACCY[4] - Kaccy*P[3][4]*SK_ACCY[6] - Kaccy*P[3][5]*SK_ACCY[5] - 2*Kaccy*P[3][22]*SK_ACCY[3] + Kaccy*P[3][23]*SK_ACCY[6]); -Kfusion[4] = SK_ACCY[0]*(Kaccy*P[4][0]*SK_ACCY[2] + Kaccy*P[4][2]*SK_ACCY[1] + Kaccy*P[4][3]*SK_ACCY[4] - Kaccy*P[4][4]*SK_ACCY[6] - Kaccy*P[4][5]*SK_ACCY[5] - 2*Kaccy*P[4][22]*SK_ACCY[3] + Kaccy*P[4][23]*SK_ACCY[6]); -Kfusion[5] = SK_ACCY[0]*(Kaccy*P[5][0]*SK_ACCY[2] + Kaccy*P[5][2]*SK_ACCY[1] + Kaccy*P[5][3]*SK_ACCY[4] - Kaccy*P[5][4]*SK_ACCY[6] - Kaccy*P[5][5]*SK_ACCY[5] - 2*Kaccy*P[5][22]*SK_ACCY[3] + Kaccy*P[5][23]*SK_ACCY[6]); -Kfusion[6] = SK_ACCY[0]*(Kaccy*P[6][0]*SK_ACCY[2] + Kaccy*P[6][2]*SK_ACCY[1] + Kaccy*P[6][3]*SK_ACCY[4] - Kaccy*P[6][4]*SK_ACCY[6] - Kaccy*P[6][5]*SK_ACCY[5] - 2*Kaccy*P[6][22]*SK_ACCY[3] + Kaccy*P[6][23]*SK_ACCY[6]); -Kfusion[7] = SK_ACCY[0]*(Kaccy*P[7][0]*SK_ACCY[2] + Kaccy*P[7][2]*SK_ACCY[1] + Kaccy*P[7][3]*SK_ACCY[4] - Kaccy*P[7][4]*SK_ACCY[6] - Kaccy*P[7][5]*SK_ACCY[5] - 2*Kaccy*P[7][22]*SK_ACCY[3] + Kaccy*P[7][23]*SK_ACCY[6]); -Kfusion[8] = SK_ACCY[0]*(Kaccy*P[8][0]*SK_ACCY[2] + Kaccy*P[8][2]*SK_ACCY[1] + Kaccy*P[8][3]*SK_ACCY[4] - Kaccy*P[8][4]*SK_ACCY[6] - Kaccy*P[8][5]*SK_ACCY[5] - 2*Kaccy*P[8][22]*SK_ACCY[3] + Kaccy*P[8][23]*SK_ACCY[6]); -Kfusion[9] = SK_ACCY[0]*(Kaccy*P[9][0]*SK_ACCY[2] + Kaccy*P[9][2]*SK_ACCY[1] + Kaccy*P[9][3]*SK_ACCY[4] - Kaccy*P[9][4]*SK_ACCY[6] - Kaccy*P[9][5]*SK_ACCY[5] - 2*Kaccy*P[9][22]*SK_ACCY[3] + Kaccy*P[9][23]*SK_ACCY[6]); -Kfusion[10] = SK_ACCY[0]*(Kaccy*P[10][0]*SK_ACCY[2] + Kaccy*P[10][2]*SK_ACCY[1] + Kaccy*P[10][3]*SK_ACCY[4] - Kaccy*P[10][4]*SK_ACCY[6] - Kaccy*P[10][5]*SK_ACCY[5] - 2*Kaccy*P[10][22]*SK_ACCY[3] + Kaccy*P[10][23]*SK_ACCY[6]); -Kfusion[11] = SK_ACCY[0]*(Kaccy*P[11][0]*SK_ACCY[2] + Kaccy*P[11][2]*SK_ACCY[1] + Kaccy*P[11][3]*SK_ACCY[4] - Kaccy*P[11][4]*SK_ACCY[6] - Kaccy*P[11][5]*SK_ACCY[5] - 2*Kaccy*P[11][22]*SK_ACCY[3] + Kaccy*P[11][23]*SK_ACCY[6]); -Kfusion[12] = SK_ACCY[0]*(Kaccy*P[12][0]*SK_ACCY[2] + Kaccy*P[12][2]*SK_ACCY[1] + Kaccy*P[12][3]*SK_ACCY[4] - Kaccy*P[12][4]*SK_ACCY[6] - Kaccy*P[12][5]*SK_ACCY[5] - 2*Kaccy*P[12][22]*SK_ACCY[3] + Kaccy*P[12][23]*SK_ACCY[6]); -Kfusion[13] = SK_ACCY[0]*(Kaccy*P[13][0]*SK_ACCY[2] + Kaccy*P[13][2]*SK_ACCY[1] + Kaccy*P[13][3]*SK_ACCY[4] - Kaccy*P[13][4]*SK_ACCY[6] - Kaccy*P[13][5]*SK_ACCY[5] - 2*Kaccy*P[13][22]*SK_ACCY[3] + Kaccy*P[13][23]*SK_ACCY[6]); -Kfusion[14] = SK_ACCY[0]*(Kaccy*P[14][0]*SK_ACCY[2] + Kaccy*P[14][2]*SK_ACCY[1] + Kaccy*P[14][3]*SK_ACCY[4] - Kaccy*P[14][4]*SK_ACCY[6] - Kaccy*P[14][5]*SK_ACCY[5] - 2*Kaccy*P[14][22]*SK_ACCY[3] + Kaccy*P[14][23]*SK_ACCY[6]); -Kfusion[15] = SK_ACCY[0]*(Kaccy*P[15][0]*SK_ACCY[2] + Kaccy*P[15][2]*SK_ACCY[1] + Kaccy*P[15][3]*SK_ACCY[4] - Kaccy*P[15][4]*SK_ACCY[6] - Kaccy*P[15][5]*SK_ACCY[5] - 2*Kaccy*P[15][22]*SK_ACCY[3] + Kaccy*P[15][23]*SK_ACCY[6]); -Kfusion[16] = SK_ACCY[0]*(Kaccy*P[16][0]*SK_ACCY[2] + Kaccy*P[16][2]*SK_ACCY[1] + Kaccy*P[16][3]*SK_ACCY[4] - Kaccy*P[16][4]*SK_ACCY[6] - Kaccy*P[16][5]*SK_ACCY[5] - 2*Kaccy*P[16][22]*SK_ACCY[3] + Kaccy*P[16][23]*SK_ACCY[6]); -Kfusion[17] = SK_ACCY[0]*(Kaccy*P[17][0]*SK_ACCY[2] + Kaccy*P[17][2]*SK_ACCY[1] + Kaccy*P[17][3]*SK_ACCY[4] - Kaccy*P[17][4]*SK_ACCY[6] - Kaccy*P[17][5]*SK_ACCY[5] - 2*Kaccy*P[17][22]*SK_ACCY[3] + Kaccy*P[17][23]*SK_ACCY[6]); -Kfusion[18] = SK_ACCY[0]*(Kaccy*P[18][0]*SK_ACCY[2] + Kaccy*P[18][2]*SK_ACCY[1] + Kaccy*P[18][3]*SK_ACCY[4] - Kaccy*P[18][4]*SK_ACCY[6] - Kaccy*P[18][5]*SK_ACCY[5] - 2*Kaccy*P[18][22]*SK_ACCY[3] + Kaccy*P[18][23]*SK_ACCY[6]); -Kfusion[19] = SK_ACCY[0]*(Kaccy*P[19][0]*SK_ACCY[2] + Kaccy*P[19][2]*SK_ACCY[1] + Kaccy*P[19][3]*SK_ACCY[4] - Kaccy*P[19][4]*SK_ACCY[6] - Kaccy*P[19][5]*SK_ACCY[5] - 2*Kaccy*P[19][22]*SK_ACCY[3] + Kaccy*P[19][23]*SK_ACCY[6]); -Kfusion[20] = SK_ACCY[0]*(Kaccy*P[20][0]*SK_ACCY[2] + Kaccy*P[20][2]*SK_ACCY[1] + Kaccy*P[20][3]*SK_ACCY[4] - Kaccy*P[20][4]*SK_ACCY[6] - Kaccy*P[20][5]*SK_ACCY[5] - 2*Kaccy*P[20][22]*SK_ACCY[3] + Kaccy*P[20][23]*SK_ACCY[6]); -Kfusion[21] = SK_ACCY[0]*(Kaccy*P[21][0]*SK_ACCY[2] + Kaccy*P[21][2]*SK_ACCY[1] + Kaccy*P[21][3]*SK_ACCY[4] - Kaccy*P[21][4]*SK_ACCY[6] - Kaccy*P[21][5]*SK_ACCY[5] - 2*Kaccy*P[21][22]*SK_ACCY[3] + Kaccy*P[21][23]*SK_ACCY[6]); -Kfusion[22] = SK_ACCY[0]*(Kaccy*P[22][0]*SK_ACCY[2] + Kaccy*P[22][2]*SK_ACCY[1] + Kaccy*P[22][3]*SK_ACCY[4] - Kaccy*P[22][4]*SK_ACCY[6] - Kaccy*P[22][5]*SK_ACCY[5] - 2*Kaccy*P[22][22]*SK_ACCY[3] + Kaccy*P[22][23]*SK_ACCY[6]); -Kfusion[23] = SK_ACCY[0]*(Kaccy*P[23][0]*SK_ACCY[2] + Kaccy*P[23][2]*SK_ACCY[1] + Kaccy*P[23][3]*SK_ACCY[4] - Kaccy*P[23][4]*SK_ACCY[6] - Kaccy*P[23][5]*SK_ACCY[5] - 2*Kaccy*P[23][22]*SK_ACCY[3] + Kaccy*P[23][23]*SK_ACCY[6]); +Kfusion[0] = -SK_ACCY[0]*(Kaccy*P[0][0]*SK_ACCY[3] + Kaccy*P[0][1]*SK_ACCY[2] - Kaccy*P[0][3]*SK_ACCY[1] + Kaccy*P[0][2]*SK_ACCY[4] - Kaccy*P[0][4]*SK_ACCY[5] + Kaccy*P[0][5]*SK_ACCY[8] + Kaccy*P[0][6]*SK_ACCY[7] + 2*Kaccy*P[0][22]*SK_ACCY[6] - Kaccy*P[0][23]*SK_ACCY[8]); +Kfusion[1] = -SK_ACCY[0]*(Kaccy*P[1][0]*SK_ACCY[3] + Kaccy*P[1][1]*SK_ACCY[2] - Kaccy*P[1][3]*SK_ACCY[1] + Kaccy*P[1][2]*SK_ACCY[4] - Kaccy*P[1][4]*SK_ACCY[5] + Kaccy*P[1][5]*SK_ACCY[8] + Kaccy*P[1][6]*SK_ACCY[7] + 2*Kaccy*P[1][22]*SK_ACCY[6] - Kaccy*P[1][23]*SK_ACCY[8]); +Kfusion[2] = -SK_ACCY[0]*(Kaccy*P[2][0]*SK_ACCY[3] + Kaccy*P[2][1]*SK_ACCY[2] - Kaccy*P[2][3]*SK_ACCY[1] + Kaccy*P[2][2]*SK_ACCY[4] - Kaccy*P[2][4]*SK_ACCY[5] + Kaccy*P[2][5]*SK_ACCY[8] + Kaccy*P[2][6]*SK_ACCY[7] + 2*Kaccy*P[2][22]*SK_ACCY[6] - Kaccy*P[2][23]*SK_ACCY[8]); +Kfusion[3] = -SK_ACCY[0]*(Kaccy*P[3][0]*SK_ACCY[3] + Kaccy*P[3][1]*SK_ACCY[2] - Kaccy*P[3][3]*SK_ACCY[1] + Kaccy*P[3][2]*SK_ACCY[4] - Kaccy*P[3][4]*SK_ACCY[5] + Kaccy*P[3][5]*SK_ACCY[8] + Kaccy*P[3][6]*SK_ACCY[7] + 2*Kaccy*P[3][22]*SK_ACCY[6] - Kaccy*P[3][23]*SK_ACCY[8]); +Kfusion[4] = -SK_ACCY[0]*(Kaccy*P[4][0]*SK_ACCY[3] + Kaccy*P[4][1]*SK_ACCY[2] - Kaccy*P[4][3]*SK_ACCY[1] + Kaccy*P[4][2]*SK_ACCY[4] - Kaccy*P[4][4]*SK_ACCY[5] + Kaccy*P[4][5]*SK_ACCY[8] + Kaccy*P[4][6]*SK_ACCY[7] + 2*Kaccy*P[4][22]*SK_ACCY[6] - Kaccy*P[4][23]*SK_ACCY[8]); +Kfusion[5] = -SK_ACCY[0]*(Kaccy*P[5][0]*SK_ACCY[3] + Kaccy*P[5][1]*SK_ACCY[2] - Kaccy*P[5][3]*SK_ACCY[1] + Kaccy*P[5][2]*SK_ACCY[4] - Kaccy*P[5][4]*SK_ACCY[5] + Kaccy*P[5][5]*SK_ACCY[8] + Kaccy*P[5][6]*SK_ACCY[7] + 2*Kaccy*P[5][22]*SK_ACCY[6] - Kaccy*P[5][23]*SK_ACCY[8]); +Kfusion[6] = -SK_ACCY[0]*(Kaccy*P[6][0]*SK_ACCY[3] + Kaccy*P[6][1]*SK_ACCY[2] - Kaccy*P[6][3]*SK_ACCY[1] + Kaccy*P[6][2]*SK_ACCY[4] - Kaccy*P[6][4]*SK_ACCY[5] + Kaccy*P[6][5]*SK_ACCY[8] + Kaccy*P[6][6]*SK_ACCY[7] + 2*Kaccy*P[6][22]*SK_ACCY[6] - Kaccy*P[6][23]*SK_ACCY[8]); +Kfusion[7] = -SK_ACCY[0]*(Kaccy*P[7][0]*SK_ACCY[3] + Kaccy*P[7][1]*SK_ACCY[2] - Kaccy*P[7][3]*SK_ACCY[1] + Kaccy*P[7][2]*SK_ACCY[4] - Kaccy*P[7][4]*SK_ACCY[5] + Kaccy*P[7][5]*SK_ACCY[8] + Kaccy*P[7][6]*SK_ACCY[7] + 2*Kaccy*P[7][22]*SK_ACCY[6] - Kaccy*P[7][23]*SK_ACCY[8]); +Kfusion[8] = -SK_ACCY[0]*(Kaccy*P[8][0]*SK_ACCY[3] + Kaccy*P[8][1]*SK_ACCY[2] - Kaccy*P[8][3]*SK_ACCY[1] + Kaccy*P[8][2]*SK_ACCY[4] - Kaccy*P[8][4]*SK_ACCY[5] + Kaccy*P[8][5]*SK_ACCY[8] + Kaccy*P[8][6]*SK_ACCY[7] + 2*Kaccy*P[8][22]*SK_ACCY[6] - Kaccy*P[8][23]*SK_ACCY[8]); +Kfusion[9] = -SK_ACCY[0]*(Kaccy*P[9][0]*SK_ACCY[3] + Kaccy*P[9][1]*SK_ACCY[2] - Kaccy*P[9][3]*SK_ACCY[1] + Kaccy*P[9][2]*SK_ACCY[4] - Kaccy*P[9][4]*SK_ACCY[5] + Kaccy*P[9][5]*SK_ACCY[8] + Kaccy*P[9][6]*SK_ACCY[7] + 2*Kaccy*P[9][22]*SK_ACCY[6] - Kaccy*P[9][23]*SK_ACCY[8]); +Kfusion[10] = -SK_ACCY[0]*(Kaccy*P[10][0]*SK_ACCY[3] + Kaccy*P[10][1]*SK_ACCY[2] - Kaccy*P[10][3]*SK_ACCY[1] + Kaccy*P[10][2]*SK_ACCY[4] - Kaccy*P[10][4]*SK_ACCY[5] + Kaccy*P[10][5]*SK_ACCY[8] + Kaccy*P[10][6]*SK_ACCY[7] + 2*Kaccy*P[10][22]*SK_ACCY[6] - Kaccy*P[10][23]*SK_ACCY[8]); +Kfusion[11] = -SK_ACCY[0]*(Kaccy*P[11][0]*SK_ACCY[3] + Kaccy*P[11][1]*SK_ACCY[2] - Kaccy*P[11][3]*SK_ACCY[1] + Kaccy*P[11][2]*SK_ACCY[4] - Kaccy*P[11][4]*SK_ACCY[5] + Kaccy*P[11][5]*SK_ACCY[8] + Kaccy*P[11][6]*SK_ACCY[7] + 2*Kaccy*P[11][22]*SK_ACCY[6] - Kaccy*P[11][23]*SK_ACCY[8]); +Kfusion[12] = -SK_ACCY[0]*(Kaccy*P[12][0]*SK_ACCY[3] + Kaccy*P[12][1]*SK_ACCY[2] - Kaccy*P[12][3]*SK_ACCY[1] + Kaccy*P[12][2]*SK_ACCY[4] - Kaccy*P[12][4]*SK_ACCY[5] + Kaccy*P[12][5]*SK_ACCY[8] + Kaccy*P[12][6]*SK_ACCY[7] + 2*Kaccy*P[12][22]*SK_ACCY[6] - Kaccy*P[12][23]*SK_ACCY[8]); +Kfusion[13] = -SK_ACCY[0]*(Kaccy*P[13][0]*SK_ACCY[3] + Kaccy*P[13][1]*SK_ACCY[2] - Kaccy*P[13][3]*SK_ACCY[1] + Kaccy*P[13][2]*SK_ACCY[4] - Kaccy*P[13][4]*SK_ACCY[5] + Kaccy*P[13][5]*SK_ACCY[8] + Kaccy*P[13][6]*SK_ACCY[7] + 2*Kaccy*P[13][22]*SK_ACCY[6] - Kaccy*P[13][23]*SK_ACCY[8]); +Kfusion[14] = -SK_ACCY[0]*(Kaccy*P[14][0]*SK_ACCY[3] + Kaccy*P[14][1]*SK_ACCY[2] - Kaccy*P[14][3]*SK_ACCY[1] + Kaccy*P[14][2]*SK_ACCY[4] - Kaccy*P[14][4]*SK_ACCY[5] + Kaccy*P[14][5]*SK_ACCY[8] + Kaccy*P[14][6]*SK_ACCY[7] + 2*Kaccy*P[14][22]*SK_ACCY[6] - Kaccy*P[14][23]*SK_ACCY[8]); +Kfusion[15] = -SK_ACCY[0]*(Kaccy*P[15][0]*SK_ACCY[3] + Kaccy*P[15][1]*SK_ACCY[2] - Kaccy*P[15][3]*SK_ACCY[1] + Kaccy*P[15][2]*SK_ACCY[4] - Kaccy*P[15][4]*SK_ACCY[5] + Kaccy*P[15][5]*SK_ACCY[8] + Kaccy*P[15][6]*SK_ACCY[7] + 2*Kaccy*P[15][22]*SK_ACCY[6] - Kaccy*P[15][23]*SK_ACCY[8]); +Kfusion[16] = -SK_ACCY[0]*(Kaccy*P[16][0]*SK_ACCY[3] + Kaccy*P[16][1]*SK_ACCY[2] - Kaccy*P[16][3]*SK_ACCY[1] + Kaccy*P[16][2]*SK_ACCY[4] - Kaccy*P[16][4]*SK_ACCY[5] + Kaccy*P[16][5]*SK_ACCY[8] + Kaccy*P[16][6]*SK_ACCY[7] + 2*Kaccy*P[16][22]*SK_ACCY[6] - Kaccy*P[16][23]*SK_ACCY[8]); +Kfusion[17] = -SK_ACCY[0]*(Kaccy*P[17][0]*SK_ACCY[3] + Kaccy*P[17][1]*SK_ACCY[2] - Kaccy*P[17][3]*SK_ACCY[1] + Kaccy*P[17][2]*SK_ACCY[4] - Kaccy*P[17][4]*SK_ACCY[5] + Kaccy*P[17][5]*SK_ACCY[8] + Kaccy*P[17][6]*SK_ACCY[7] + 2*Kaccy*P[17][22]*SK_ACCY[6] - Kaccy*P[17][23]*SK_ACCY[8]); +Kfusion[18] = -SK_ACCY[0]*(Kaccy*P[18][0]*SK_ACCY[3] + Kaccy*P[18][1]*SK_ACCY[2] - Kaccy*P[18][3]*SK_ACCY[1] + Kaccy*P[18][2]*SK_ACCY[4] - Kaccy*P[18][4]*SK_ACCY[5] + Kaccy*P[18][5]*SK_ACCY[8] + Kaccy*P[18][6]*SK_ACCY[7] + 2*Kaccy*P[18][22]*SK_ACCY[6] - Kaccy*P[18][23]*SK_ACCY[8]); +Kfusion[19] = -SK_ACCY[0]*(Kaccy*P[19][0]*SK_ACCY[3] + Kaccy*P[19][1]*SK_ACCY[2] - Kaccy*P[19][3]*SK_ACCY[1] + Kaccy*P[19][2]*SK_ACCY[4] - Kaccy*P[19][4]*SK_ACCY[5] + Kaccy*P[19][5]*SK_ACCY[8] + Kaccy*P[19][6]*SK_ACCY[7] + 2*Kaccy*P[19][22]*SK_ACCY[6] - Kaccy*P[19][23]*SK_ACCY[8]); +Kfusion[20] = -SK_ACCY[0]*(Kaccy*P[20][0]*SK_ACCY[3] + Kaccy*P[20][1]*SK_ACCY[2] - Kaccy*P[20][3]*SK_ACCY[1] + Kaccy*P[20][2]*SK_ACCY[4] - Kaccy*P[20][4]*SK_ACCY[5] + Kaccy*P[20][5]*SK_ACCY[8] + Kaccy*P[20][6]*SK_ACCY[7] + 2*Kaccy*P[20][22]*SK_ACCY[6] - Kaccy*P[20][23]*SK_ACCY[8]); +Kfusion[21] = -SK_ACCY[0]*(Kaccy*P[21][0]*SK_ACCY[3] + Kaccy*P[21][1]*SK_ACCY[2] - Kaccy*P[21][3]*SK_ACCY[1] + Kaccy*P[21][2]*SK_ACCY[4] - Kaccy*P[21][4]*SK_ACCY[5] + Kaccy*P[21][5]*SK_ACCY[8] + Kaccy*P[21][6]*SK_ACCY[7] + 2*Kaccy*P[21][22]*SK_ACCY[6] - Kaccy*P[21][23]*SK_ACCY[8]); +Kfusion[22] = -SK_ACCY[0]*(Kaccy*P[22][0]*SK_ACCY[3] + Kaccy*P[22][1]*SK_ACCY[2] - Kaccy*P[22][3]*SK_ACCY[1] + Kaccy*P[22][2]*SK_ACCY[4] - Kaccy*P[22][4]*SK_ACCY[5] + Kaccy*P[22][5]*SK_ACCY[8] + Kaccy*P[22][6]*SK_ACCY[7] + 2*Kaccy*P[22][22]*SK_ACCY[6] - Kaccy*P[22][23]*SK_ACCY[8]); +Kfusion[23] = -SK_ACCY[0]*(Kaccy*P[23][0]*SK_ACCY[3] + Kaccy*P[23][1]*SK_ACCY[2] - Kaccy*P[23][3]*SK_ACCY[1] + Kaccy*P[23][2]*SK_ACCY[4] - Kaccy*P[23][4]*SK_ACCY[5] + Kaccy*P[23][5]*SK_ACCY[8] + Kaccy*P[23][6]*SK_ACCY[7] + 2*Kaccy*P[23][22]*SK_ACCY[6] - Kaccy*P[23][23]*SK_ACCY[8]); diff --git a/matlab/scripts/Inertial Nav EKF/Drag.mat b/matlab/scripts/Inertial Nav EKF/Drag.mat index 7b9b77124a0f79ddbbbc3c5cd816a9f6d0b91645..bf456947ab10d41d468ceb4b1d8783c7d319390d 100644 GIT binary patch delta 17749 zcmV(=K-s_Ajseh*0gyKoO<{Q;ATb~@G&(deIx#RHGB7bVkx?U&UtxdMNmL;wJI zoUEA14(vvjo+Y)ax(kK{d)v!imB9t)sexW(a-NwalhdY}V{)G7r|@HV=_l}W_%Xcn z(!A1@OMOvlZydlu5}-1evMekp(W>VJRR@vpzs zU&;?({qMe)v@iZoxBbt*{PlnOAO6PmzuGVHAAkPu`>$;@#;||A&wu^Reg5;;_TT^C z`p2K!e)0d~ZG72e-V_Z(HvQ!-~TH>96DcPhb6eHS}@y&;OiHeQPgM*?s=}PnmqBLJe;yXF>IX zyzpLoy_FS`EsuYd0R4Y@a*5Y)O)U3Fw8)Hr)yX%WS0?k!s^08#aNDc$oyOHa1k z`#R=<2beqzS)y~`QQ>bXD~q0eTX#g6-DHrACeu)w6k7!q*o1VDddd5${WobEdE=}gr5 z^0e zurkMGN6*}$B_peE8TN*XeF*QY&qYp%6e8bVp`}^n_KH zFm@?MeC7FcUT)}T@$};Sx-(sSg?MudhDLv5_7v-p5^|tede3c{*L2FBA@U}oNlj*J z9!~85r_!w-CkYs-2b|p;X>yGLm|y9Sg}1P3SSUjubNqibU0T-hea@}2)xXTq4`HO^ zedgSPPnhrEwz*&fonDW0aRiw-ns<%A7nx=>65acaQA%l(?1177WniQCdyrmW$Fb*t zvE0HA6C!WT%<*C8Ap|c7r6CxFq%|Tp_&mGmwVpErfOk_=Rc#fBG|RW|&d5hZ6TLV#@h2tKVf%eb{eXC^>qD2$8`O^E@!3=27+>&cm;Ga|C#R;8lr71uiTh3+80e)lv+Oz00e0$NO z6>z}|fRYb`5LSS}&oz(L1qrN=FUk~4$%0_`=^}sDr8`*YSmBE)tI#2qQ*o{gdz@&A zk1&@Y3JyneEwfPmMD+l?eCgaA>vNIQA+ zgovH%rNoU_8n1dv&Fv!d#2EZuwI>W6(QUlf+Es!}0v&_~Iepdn*hE9>momjROJ!6PDPV9sVX>mk%Y}1X&7Sw;a@^r3c*^Cotu$A(4p2>j5;k4p-ndA1`a(9KN|<##U75nY{rP=nh_%1?h|4*()m z5id>)GF~UM@vK<%^F_tiy}+D)eWJ+FGuC!(VKfnF_eod~e&J*DVov>KYYf}$jl+k!~A6;!YZ)dLLl(l`C(p^=w79E1Ma0U4zmOv@MT zlVZ<-T!lIIS&Y+PY-M&Yk3)a3_^966hX+2fwB=^WWy|Fg3Z~J>%gs@z5m35+J>5lQ z(9@E`i`>=1Ubom*^A`_Z`CFsjSOEyRE7k+z`Yw3tbQ=4V1Gm8I=>xu5kTNzayb-7E zipIe;JYuyF`P|AMAFxv*aI?LLA7P}gL3i)qxP~9zaP|46yWG7`?6`m9)h1d102b8_ zOJ5E+&)^}KfJV_-Z`e5sddB_$I5nM~&pfUTqIQ98pemCFeL@VS-dzXvlauy14^N5< z@K5ewY8+4jS!Jrc0_0_Euue)D7v=+iYFDx}3sslZM6``J90rX*_Y8M0p^KDxOM$18 zf0lzl27GO-Nct3cFEM`?@L<+m00oB(4+c~>9 zemQk8+j2R83|&K68D?JK{OPT|0*mZs6W~dF3gMY?1(Bbd3xFIv^-Ih!Q{g=X?9<;ivLo#=XIO#pue!Y|r==o=uFUKIW5 z>6M%Hep;Ain_rkl-B={O;Po=Ikps>cEYQb&OTRo;3eQ@^ub(l%_o!3PI5dN%Iq<<#I_=odNKy~DZ*xh zK@n@|HuTd~=jyp4uM@!0b8AzGl59&n4FM%p;3XbQms6f9n^S}2CJxB$B83L^4ABSk zQAjM2cNE-tw3iKt-iSo)(pU_=h<@p0Jm{cTEk{a5=JbDIVtUQqh*_zWUsbYLHhF=o zQea`Bjy?JFiD7PUYG6Dsd7X2og|3v0&Vxtj8@UUbeK`jKHvZ%NX6fYZR7#4kB$-lY z;dHA#BY33PSf|lB$C7}B0nP+I@cy1x$D$3j(TsQ&uv1;4mzQb9rgA{t?LkKiX_#|{ zLpx!mN-%%cX3T=ebBVNoPD>V%2LO7NkJN^MD>PDUY?!+5*>%j_WqZK*&>@Q#Fmh&ZNDwQ4qYRVFh=oBSYv@Qlv3`!P^%zP;a z%0+6eh>`US@4HAFfWg|{dz1>gqz7CbXHVK-H>rO<5nKVCHg+}~O}PK60p9{L*njdE zM)n=?$!tU}TI+Ixc~fQ*P0YOD#TF~JQDq9k!N#Yo&rSCs83gL0>ENChQa?qguS<1? zLTrXU;CnkX8tCHr47r<4DzjRUy57_RN^^fSPLY!d;27lR7Ff@!sOK+e&k8N%*hlhyu8P9Qh^f zqYIdLDoj3s$Vpb^t$boUm2)CsnUb^+Wx4sFELo_02R_0C&tnu5pmpMT@1CpSU}Ep+ znl_SlHhP6LelnWTc~Rce$RzBBBzN`hgfagYGzyC$jDjSn-bApB|7TU z9C_Aq0WHTbN;RdF*2X3~SZtz0*an_R)DAcVU$+mO*~^ErB|TfDnU`tvbe5`!AX$H< zo+t&Wh~A??!fW=zWglBx+FB(D4)j}iNIVs9Hze$aX2ZyiFGrhd30j7u|Ic$>o3Za>Yb9x#`i(A#vOjL4zekK%-J8GX0X(3|eFT zc~1GKG)QzxYX9bnLH;azach~EV!A*l;;1?EWRdNih(HP}o=7@(gc-pR|MX3xr2@cY z{kgq5n5ow#KqRn_#@@s$O?L#_kKGh@kS_}1j6E~D7J=TMV?n?QErd67(y4#VvMPq0 z)(Q?2l+FFe+#w@XPzOFJ?HamOA}rbxCzOCo$O0{hg~g6CZwZ*mSt?{QeB++zUeV0SDJA1x^qQCEN5^DHfaKjXF!5?Nhg#o1leqzH&)t^Gn~@O&;&d-)*? zsLHkuRz@Z3^=TWkZKKZ{!kXH50Kl}F*fOD`~2!5%-coeh%nK*{_2fr5W;=pn@vi6G-u zqQQa!mDz(s^uita&975&1hlsx1eT_iS{Kd2B`I}tC{MB8MnX+ngiAijW^=E24^OjV zObC&>T#J*Sx`PiJ_sSe43kC-s=o@N<7450$Q-kNj5f?dJ{T zoyD0QUVGstA1TgG znjLy1vI#t53P67gOqzzrJU!5BP8ix2B#GM+-Cbpu`;32-HT0PAddpJwu~J@jNEC*) z5F`|c&*mM@Aug7bB=Z)hVb#uygaB)9p~u3QBFQ0}ECiM1IuIkV6p}?FXb};l7wP8_ zin>#Ln)qybe!amV0yf3bRdCfQp_tt1vp!!Kqj$}kuO@VAxX5K_-tmo5U^)4@XzhU_ zj|((96dr%+^++}+pyN8L0{;tn$;2>M-c0$p*9hVS1FeJ`Zl%cYRVT{hMtR44V*zyl z15h3a1XkFCbmr*Nn~nu^2p7CND=-2~6$i1QVaMfdgemGC0jfP6OJIhe93U4EosqdL zq)B=}+68M^Llv<+Asy*FkeoQxh`VSB-yd+a@Z5hKGPeU90zmWi9`!2>wG4rUAe?m_ z&k1Z5vBJ1WHFX%Ft?n%F#BPzTzpxJY2vZWj&(Igvv@ii^x>Lp5Y361;@>#gCENNf? zj8}29E054FYFJZHGZ3?7ppDOSuN<`o5l`Kp&Kz_sAXNpWc9=-!q4l{ty^#TVpCEqM~i<8y#*jwQP9?V6LXO7mEcAZ-6Ot8bGL1lk=H7LOt?9 z^M23MW|6f}CPnz!E|A|{dFsY0x2!m}lz|)9mVE*F=#sE!mkMc%z-3xC$At)zS3m9K!E6pb`&xxty8N*>d) z1jWd%X;MXHxVS#7G<3)ld?IZ_Kzas+!@%cagu@fgEFg(ty%Tn`5BXq!L)?vZbobg2 z{X<+Q(cRK1!N5#GS8!%J3C`dcFjAteIO_nO$4$nxKZ{oOLbouZ<|BX0-{b)^Ai?DC zK3S(cjSG(y0gtGBX<1mhAfKs6di0yx>9m{eo$k#0L`i6G+^{Eb$zHTW8xm}nobtIQ zc7&6lgn#ZBc~(9ruCphMsD3$UTG@aHyuk)`0F639!y;vbcMKiV0c=f(FW={~a~nB| z7Gd|^F59ij2t3kM*J z1-k-dQh_sTxu9R=U2fx-5jx`T;3LvXAP+g#o8%WB0dZb2X?%C$>EJs=Z9lIfx0=ib zbfxpD9hZ)GllU19AD#N?kI<1xnTQ37(U8zmcyLz08b0<=D5J%n>gy1@ySJ zG1)uh%PQ*v+BAPQqJnZu)9!g#6FCAZ0J+610$U>h6K;BU?wv;&Qt|NKf)aGLIsiG`|NFlLORL zM(~+*lyGumt+G!R_@NUv5glsc5mb7=0g&$^EB;J1z9$^=s2T3Lqi}fAm zQH&frOI-gC00030|HN3w4(!TteFkhp1_Z<3pp^_Rn3Di67>8+?^KO`jIj1l1clo0X zFUkg7)^h(_TbFz@X=Sw3D;g z)8+(tpMI|zx!?ComzAQuQxbY>8!q=cytmznj%jZ*Xk_|?OS0Z&RLYqxr^=M3SbWC#TY{v{T#WagXK~M(MVV-3Y?v1h&pghO zN(I4O%13{WiM8tag3Uj`mpW+?uSu=e&@kY)jpEY`d*S4z+$aJ)^NybRMc1$V@#h$c z`Hd@>r*E1+^-Y`~Pv2Nl*O%<=J~e-%kO77x0YVhwLLyP;6gX&4&$fU!0Un|@;QfO*j&EU+J1~)8i4d7?3=cAQZW)rch8V*z&fr*;Ya(jfqvRC_X?jmc)T$?$ zP$b!bA$BLg@fHM);KKf}3l)8@94dp&onqf+$E2nZX{4`DzS>GV@oYns+S#1 z%=X{A?q~xz7IhcepdU8-a?4~F@ni3eD6!uYd2fAMr{l-@9J&B7Jq>@DpL~=Mivlx= zTrp;O1(wtstaKH;n+HJCLWLU89T?aL_f9_Z__BgXLmcwqPwRl z;I3)KCeOWGWK|BbqrDPlt2ebJQ@{13YeyPG_cS;?)yWIHOy`B7QBO`GOHOSQsYHuS zI~?+|sx?7L0ooeD(^r2-cH@WRlasaq$@6kMc}=j)d}tml%G*sLVurKQ0!6c;>*^~4 zR%X`Z!if{df2F=Far$G#j5e>l(t$jeF+i=C0|vda%5*H`>g!W$jgy-o;> zGe|iXM0s521^n|>yA2HIT;~W9InNpp@M{HL>zm)PT}}D}*|r`!;vksj6VD407UTG$ zcK<`|A-rLkLS`+6D92e!RgPymVkrku-s5_J!Zm=9JX&lOov!3h{DB^2?Oo@E#UcM-5y1T zJxs$;pB7{)3RQm*at7N;9mYZ>k&;-fC(`-}qa{2A?U|fQ zBLjTWV9;XY-;l3DhnU0m!?IfoXxXqlBuF>

5$d%XabwaVm9(^&Y0m8oN&D6%G7y z^yK0`+uUzH74;{n6gE}8zzP-4nW&^F^+yK;9-#J;#zFV2cU2~f$)}VSz&c@0~ zO*7)0Z8!xdFD;I)5BX{bPHa8?VJigqYdC1Nt<0!xjf02Rwcl z)Vce4^qJSn(<+~=hJGGwyv_0CFv7by!XoUIvRgH`z_Dr#&~`5gQpCG) z2@iiM*{HC4B@gV83N`@#H^Pa<*CCkhJ`2o_`IpT@=Vpt1==vL)k%F$%AwuI_-x@tAQ|VFYMXcwbh3ACH>6Fh2frc-?uWU?lgTw*x z0bGH|pHfAS`7GUb}lc$ya{M^&ehLMNUHHVjoi+-&~^v zZL>S@Gd#h_B$92u1CRsi;2aFlv1vW(`3c5Un%Jvs7nL%(EA}}%x&esHm%I<#pMu0HUx+@JTSQLxkV3`6p78nskV(c z^mX#AHG}#DC?ZhFO=EpF84SFmhAm_Q-67#H*SX6LlIR3`I^Z^V%mM-JWL4u!jUXs( zo!>J%nCI+Bfh>?8lT}2-+=_pbQlWGv-ZId_&}RQdeK)_x$c{8eJDkV@-i77Kk3A_x8g;{_%W&V@kg5*h1m*?E6 z*yJ!XMyF*dJ4u)OIH(2|##KPkC^@qyA%b~7YeYSU902^ehoUf+mB#8)9?yaiXCV4s zm#(Be&sKG+;iDVv81E`+C}BB+TKPCpIx@DZii+^|3agH& zSBf~zW~T=R0^ETUD+1OJa{lrQ@4LN$sJ5J8LVY1Wo&>_q66>P zpo!(xMxQyOsogBPA_b$^Q{->Vks-;0PTw{XxFx1HeM7vVCG08?`?$__w>aV`7jfGN z150`!S_v(n;jnl(I*cTw$f6m$A**BJ6|Up^XPrO}!RtnccbY=qRMfeUZDOGC0eC`Z zF>zk_(^`M+0`JiLgT4WN9X49*my9ip*Q8?JLo8?gMNb_i!ukNR!!I9+`~2=u~m| zWlXu68qof25%E^0kAtQO~h8C`e_v^%iF6mltD zKSEgoG%=5AsM+}eM%C;oOJ36V0h{qo!TnIfUMmhddFc9|-A%*U0ec(BVT~0rjP!Wo zo7;bgQg!y7M621=h=&;@&xH+E*^q6KGq*HBQlH3VN;d~10jS8&P49!<-pcq?V z1ACe0n=V{`xnjm#k}p_4XXU%mI(RGQ2eTwWxqwqy`K%IxbdueNi-&l=Mtp$+?Bq%W6!YmZ-A^XRmw#{kd)j^nriF z_Tcdp0;HDRRWL}Cfo-x+2J4&#&jIOvzxx5cd?dD06|%2pO-35Xl4Mv_T8zBH06iME z04C4E>b%_W3t&Y#<8eFD-yX7#1{ezgh`Ja@(E89Yd*v?`;M;k5){}=VuGAJe?A=|<|>B#zC%(>jiY819b`98`}eKe zPfZc`jYAcwfref{okMAL`ilt^yNZ(sDA@a+eXVt%ZJ!8l#ykjlDSkKrEF06hjM z(@D{9FE{{FpG64lZs^lNC07ZW}oada5E59|ppnTt4&+0j3lZVdA@KS@7HG5lfqa2I#!Xn4ZInQ=2v*Awjx48;E9nGd) zeuo_W4YGRnl+Xx1z8V0U9;m`69OZD~{6(WoXrw50o`LY4Q^N-c$T zDE^B`idVeo4_(7y)PVa&o~&^sz&+K8X>Jz0qI!?a^IFZ{!UgYA%^^f9^>h3jOH9qc zGTjsW$b6~-^zE(7yAXebLg<@WTC{D>-B4Y_U|TCMVoi$ zK;^poA-PlrdrQisr)(sDuFt9z9h7oo1;R^nw>IgM-g_j1d}x0ylto?_SHRjj1Ow`u zxdiH{57$|xMDGRAc4+d-Af~WoYtUp(^}JrsqyE<0b};!ZW;TKs23H~^;*IRT>z0&y*M;4c~ApWR=}Jxkp^VjnW{pimWKgviKoSJ+HhSNB>q{J0`eL+2;5VQBNDCxmx`M1K2c7+ z&O%e<16%~Se2Bhdp9HM~Rv31v@$h=n6Yv-olJ#N!msyylc?ntazR9J6as#x$D#|uP z^*=))otA$&z-vTiwKTf$DyuO47<=NCN1K2E^x(>pjEOyontF8X?vn2ybD znD-_Lk3NQgO4fk^_|V4NUgod?@-vnZ?8&oquuts|F7YLg6>w1FJlzqD$!ZQpv3xq( zR1<$&Q?=eayi~CqQ$A;t3gdk~VQZ}GB0!@-!~-t`=8B<*odzG?_w|r)B-bH-cwgX6 z2A@D*(&@$UJIyLBj|u>}gWbQRGj7auk3N^2EByn-3Mpjk!~1f7lmKIWKu;RJE0Vmm zAH2_lS$Ty+a$O^K*JS{K<3`ObY-n`{`wV|L|50NBG{3>VXI(`PIrAZ>Oj_$L;It}t zmgLolv1FWR-OI%~lCL_)A3R16%+~B67omq*yw^St7+~z-^W&(kEf~U#%*{4^qA%$C zuZ92d!BT8J`sv*yA-(6&DQ=`1qS5WYmNN&00e+Rx@2hJRA_7&pgea2OdeRl0l1I>UhhfFo-3uMXIai~qQaUhQ* zIkozkl$z#6SAu954p9A|ePd$lnz(ZD>$|_VSMMHl*$*(|fM}^pb-m5?gRF0Qg?kSz zEz+LB`u0Z_*IrRO5?~hIW~PS1I>Ue2EWI8f$O9ywi=)wtnmEY(1~JUro*kN@CFH3P z+b$)WV6;S0&r?lO04bu>s+rA52+4Ccl|smmDVP458ov)RPe?cE*_x1<$aP4^A=7s zrx{A6RMY*wz`C7xue(;i&Bzl=pyCJV6D7|&8BIlfBwtY|j2~LLpp$-by=Jf9&MQNp zq5~flz*F-{t%KV5nnzO4xhH>3-~R>x0RR8Qnb{7jT65>m7p0@Vh@w10uDZ1@7V{7( z7X}QN**0dnGxI#pPn5?DXP>i`d|OGn`>K)3RV-mxK&`6(&t``w<&bEd5DEb>IZGZr zQQ-P%p_Y}jZ%?+XG8xVy6sm7(EbiAoRbjd(lEmJtea$r~6HkW|$lZU8KHI2RNClJa z`DknJp<3#zpOP~yqXIX=DPaRjOyYjLCzF9o)=3Xb&t*M+ODgJ(j(B@aOo0&7GP7@} zinaq(EKw+eMpeqv2bktexgtD@OvITJJ}Z}VYoe#8EtGNJ2fR1|6W003ymt-BDfzk5 zcZW6DFHXKky_u)Q?CF1@)fXgYD`WzA`!&u?KxO2Mn)>-v0*YGix3vrvi3ZL3a`)l} z<0T@TWgW}IZfz^Fk@F}luf{;G7V!<6is7+$=}CxekoW-DILt z<}5W8P5haU=lEFK67j1FWNAN|s%QZ+ePiobpvz&MMZ@E7>213wH#0>kH6U zWN|WY#=x4~a5aMIjP9I+v+)+p>6wB-Oq+iYPDa+WJzkshmkEKBDDXp6a6o9s zlt8TO>>4CWP|Tk9-Pmy`kA2m80^-0y>VW^J|NYx<|M1&yzcJUx-(CKHUiP=Y{jvRz zKllG~+28%cAO834AOGB+j;0ICfBxrm?3(vH7H#&w{wYz;xQ#FiV|-`Rsxgd%(WGcw zX{CS2Y>MxQOpDa@sU33}?zxe+90o&+w@<-89``kxUxVV@vw?Z_9gzkf-rIsYFNb!GwMVcR$kQrE#$lwFtkMam}`o*RVf;2CB z7Az!}xI>3WPqOh!PtOs-tc1D~m`K5|$0Wn}V7rwBPM_oyoA$hEi#`-yTA6fHf<|`@ zHKkQg3Hb6UkiJxtw)Lbi>XipELr5-`ue^jXPn25a8kg3lCn7BaQ_*_1i>)W-?d*RD z&U#D25XATlfX*f7L$R>0haiEGlJms$qjfQ*2t9X zc*bEd;tOoi0Op^aAkghJ0|lkXf!ZRF#5?j#*_vvaRrk#xTd<)m z1XmktX=RtvnbfEc1}x=lT7n(%+?~ak=Hl=U2QW4U-P=@JKByX+4ViwDtlo1xv6k)8 zqmQtfSOcu@oc_!w_MDF7g(hOud!o>}dn6re)$04yZlKtFiFf9VBH12?J<+evgmBJ`BNst}n%D(&+<$ow{r#sgKDF zY592D3OQp1i53$jpb_h~Wo5t2!KLKmg*EwJ;21ejZm}3W>$_!@{(UHx&m4IFc_iHbMm|XLVT*g z(`--Y*Q`X&gKp7V6=QB|N6;B%ab9+6E}m}K#qZM$$C@U+;$weO?-pD=AtCQZtoi-H zdYC4Y2ne_UPvV zN1(lEcXs0iq(dZ(L-WQ;y`3NS8Szcfm#%G?>UoeJCWa%r?@4=F{?xayKtO>q#_l{J zFtaayQZhNP0A+uZ0d_D_n}?X-A&^oEYo!-=2>of7Y&5;gg6tBWrGldZJx;H8tB|4p zq~c4|;zy5|%vJY*^9`l+h8IhR&)7ib4Y0boK4SUf5Gc9S8Y-}jH+}js(d(q;fdV^C zK`>@OSGG93T3-Cn4;Y7EAo`3j)+6Y-hOHrzHWX-OEhm3}H%M`1kRYcn0i(@-t6of)q_2$qTJFq{XA zw#TzGI|~(%I7WS_;U?v5pBn_#*I!AOv(4M&0w=U*kFbxHjHd}1q96f0*N8Wd4Do8@ zKKltKi8p`HIFvoUc{glvd4DlRKG@-^)M^GFuZW zIp;rA>W~KnM9*9r%`@GYa~PnGHKcdj&)q~gQ{2PU)(vo`u4R_Z+5pA(7aG5TSBuVE z*tLT6lm+%sMRC03EWAim6gj6g7NL~)n+Q+YPhO{Kj0n< zhm-fr?Lm4>wv)>ccrq|+1}GHEddWjBAI>Y)fkn#BQ%bkxVTZ?P0Ae{Gly!%m z$**amxwVDmRz%$x38XVdg{wJwF-4GM&pv;B7U^b+R+>Ujm)7Lz8A?F0+LOfbE*UZdyfO5Qq#8AL5_NI zzPNrwpOrAGjL^@g{CTEhwX`zNgR}3uFY8f>QSXo3s{k%V{`o;edkJu%489o9(toX(MjImsvAf$_{IN>g+xwn zOZdZ{zxY4mFLR%!Sr*F6JdiWlL=Wo$yrKI4f9!u)IhW=@ zJRn26961s!&JOVcDn_4f1I|NrChda)uM6q1Wg3w`#!&CLo9g)Vy<~d#}6xh z@jqkiB`mxx;GB}v*|f2@) z`A8PGfBBc6{P?eb|KIcD`uBg$kH7E#7yRhB3}%V<&u3)OtF(tCdcS`?^G8v5T0wZ& z##irc(WKKCoeaCbEWTIT-gEkP>C#1RIK?na<P`Ryac`>VLDGAyTGSmdl_+%){HT) zJ#3@OIr`-;uX`1y!^D3~F^i}61MNp{j(|Bki!rASMG3P>V_wujwUqD3#8&4a+TCfY4K@nTt%yqJC=p77u&-%+w=65dfTgoDuZ-mx(5FNYcC}0J>O}>?)eQBu!gwei%aDGId z?@0d4NV91_3g)`FrCe&SFUcp0t=34dz1abr2oBytFEpeEOj@u9Z|bHB-Zepv^Q$<_ z3|46IuJR3?UXt|bJwpta%g7&qq}i8Q#+*yRH(=rN2aKU;vDbpxEO zMeT3e@OE5p3vaM~XTh()pb!$r`c6Y{&!kjzSRS&GW8d58Mq(-m$M=SrbFpsPya6u- z(E6Nzxejx%QD6b%-B9_Oph+<{*Lr`a)Cb>PM0d{f zu`}v%amQv*3=h{RwV&Lz#5$yZtW#8sA3l+%zQ-i4V9k|9(m+330UV6|eh@edwKKzs z2F>cVx3CYBZq#x=h<9*f`y%iuq!djDv;0Li%+dc|3mFTE)B1w*QitXRbR3<|tL_aQ zJ|J#4n~^%W>$l0)Gl(~!Lzq&i-4&P)lJsf}pvChKhG{8^u0MSa>pOv8BQ*c^1f9ZKoOnt@R-z3exEZU-o zhy@crns+c`vHI;;1vk^9AH3sO_=I7>{k#f!6u?kFzGuJN%VKX0=`a#|wvd0fP#;U{ zVp$cqCSi~txvfX_M&f9H%Jdiv;1EJwrbE$#xJYu#1gVm}t_{!~6WAR#;Q$#T#Vu3@ zajM){#3z}lUd}pm+c0r?YQ?K-RmX`u3AGe$!eGIPe99lWGsv46uUZB(sN?l5IN)K^ zS@HIw>?E_T^;6xDQ!C@IYdz9T?@sI)XK=K94im7(+=P!sNMPfCKPz(wH`84Qc<}*} zHVM97^S|W83y%Ny^H0`cWyL6h^p?}hj^SlG9&pjqdGcf0Q%DY1Eie%=jdGN5jgt+d zv*&zCnpOr%D_a!SS?q3N(HqVxI5T-nWqBd@!1f%UqqdTx4pL{1uh%pC{rD!_PTa)zbBR(qrma|T*V2We zfa)s_eQ>8)x)CcZ1soH-)FAqIUit0cdF3y^@XFu(Irek>$Nyvh;rPG#Px$7yzdFy~ z{y%;H-v9sr|NmoTfB;4)&C0+6X2bY=K->YuY(UHb#GG&~br3#CT?CSPCMchQ(bE^E g-vdcM6Bhl*_JQnYh4MkPud{zJ%p4E^0IV?^k6cD)mH+?% delta 17630 zcmV(yKtxdMMFL;wJI zoUEAH4(v#BSZ}v_MjG21$iJYcG5ElJ6CeS_;!YOH;$8$Sf&0Gi{1SbJKF{!jVczLG z?$*W3JUM|tRs=JXxkNBe)bGE1`BMDrmoLA)>%Y6@cVB)kzxk&Ba0~UXKi6N&kKgn! zKS-~y`tNV~_y74z{~!NM|381p&-S1G`0R&oZC+2^`qMbZug3ZB-`fB1|LULq*!HXb z_qXt6lX_D)4C(Z5|Mso_Km4lyFYo(V|F7T8<7@jr{P>sG{l9+r&+UKwX8ZBmZ|LiM zzsVnN`+xlK^YcHI`OAE^U;cdg@h{kaU4Hm8`VW7`{-^nTZ~vQb^1Xlkr*HDT{Wss_ zd;4#{$@liZ{U+br|L&XorFsAGSLDa<^uPH||LHsZH{a>M{Z9YeFaQ6_?|)T8|K%6I z`RSYe*Z%&$fA`CJ|KXc{dqW>p|MXAU)VJ0$m0kXae@x}85o*NXIS&fj)C=CC4?7Q! zV@z)K8M9)ryl&vmOUi%!xhv5raXS$pgWwM2+GnfSGLoiO^7-QXib)J~I(v{3BDo-F zD&MG*=QgHk$+24ybUFw>aV{g;)}yXRh@b$pN$H80R;ktIN)^ct%D};s3&R*ABd$vS z;t6z^DHAn5gHSLs`F!pIfz8vhWis8r!)%x$j7AX*(XkmO`v8AI(*Q7xB##g>TL-z< zE~Mi(53CJStX_L+;h1`wBWColSX#@zF)YkOUPR;Lvx1SCrso2gBp29%7O1yi zd(6iL^FenybijY49L0${dxAMDlzr(x6H)1kML+l1dyLu@;K^a4^YRh9nq~f~o4X#UK{@yJk^u@O*9-GCSso_M$y|`OY{s{OQS4NCA)~ombk5>(s{tz-StYbgApmZHFvNQ`kk7ep zBTIS3R!4uEEa89-(h`D#%60Ti{aMqy0)C+8m^a{@TZY&rzA%WixUAb}#3dutvNCm3 zc7;X7;*Mw|sU5|23@@q0C5YAMTPo!UeE@vUci%5+YZkIz**pqRksed7T%V8-hraiW z8exvr@h}z}iC&*Wtx}pn9#^%=Gh$Pra(0tDV6cC9Rye=0{!PR?5$}_)o<{GIIsxHY_>Ug(Rp8z*NmG<_`Vy%72;Lagi<*cC2p-s8Wdyzj9Y%J z0!HY4Vzj<=H{OE#%kYFgS-^GSip&)%r^ebw!EVRPfuE6S$WObU%TpcSOsYe{sdBIPOX1z2q-#xm(={O*p_+h)*L;&VRG9lr| z@<~TDTh$(dT&TDZ+an+S_5xlhSyTx70f2*M2al{1N=rNx&ke0z@)bF8*hc(N2hM-U zGoob?z?0=!c;x}@+L?eD>*xVi;UH9Hy9KqtxfBwhldlMqap3cdM%C89be0>Nq{|z!clSv zPw1m#kc-`-xCkfybm@I^Pz!MbfFXZ`czfFYVy6f0j?-SC*wu_H=Vos{+PCm*GZG48 z5@s*86(dFPWIi7kQV*$*r$xau4>a2tsDpK>?wh+EsKnsqf{`W>4*_#k=N(Z1?cC2M z_;D%K!n4+GOdyU=A$f$dX1|0EEs~nht&~o8GMbePQ4{V$_6RtqO6?Q(fiHik+o6-y z7sOFbAPxzJlJUDj!HZ&PfJ;VlOe~(7Wztqg6>DDy-{3rK!@kG|eqPfOMrUl1SBW>H zD}{aJ5*uHk3qu$Q*cxTn@{V8zp$ke1h%tks{rj3e5rYHojWte8@byOkutU{~6j_D) z<6U)Yq(9_JbUOy}esRdGL z?D_C-|B0`IT~&;s1|c4hD(XRA2iA1~xXNrGDIpr0N(o(bM<_(2seln?&b8nu4s`eT zk4m1%grDwM1++b=1|1KHhbQ?m#G{B^e4xCKy6H{oz%d>q<-!!Q*K3XgCvA`VrNaa(K~Y)a@yVryh-HYqJ`@R=jwc+#?X+k1JXg&QVM{`5J_~29 zwffT~%pIWwD7A)LR%?G4y%yN4ogbrVR?s^e9$hlXM|RL-9)8mL^*u%hm!8%bN~HpY zFQ{eQqWx5Or!aK$g6JD%OjFSr5&&RI3DT@Hsq3ME6o*RSAeAeCCHUY&^IP$7hkBCd zlQ^NN>-GbZjN`hNoWWfBIv%qG;-tx(1zAi}@J^~jQi%zND#AHQ(p@VmdxjsNl; zH~!0C=0;bjmrZ|wT#Tz$EHxj`uy8G>;d)w=RQ@FteBiMVZb_@;yi1c9y<#EB=Q$@h znk1$yK5|zt8SMQO#o~}4m0|!ak1aDqDdx!wt0jmnf;tq~21u~Na8KFR$*u-@byG8qFj|Sn20S6Mm8SGx*PmclgTPdnklY` z*3vnRkyyDci4Rwm$LMdYBr8zPZr z0ch}uNrZpKaKu9=kj(ljNw4O+N{Y@y9Arw6L9_GxgRO7I`J5-8KBv<)*rY}%^w^50 zagidD#&34?I)r>28z1)$uQ3Z8kxBU0(lDSWx6KD!udFj%e&)sS=0#DML5Jk2%b{`_ zb_g+w;`-^|p&EPIaawv(WybRj+9smi_ZOEW6Z3y5z2^*EaslYLs>Lq`w6`jUnno$5 z?6ZZsMU4E-i-D8(H+x8p@q9oZiN6uzTNEf-|& zwy1xAQllCKOBLntyat?~Ka5rs+#I@q$qE8xS!QOpMLtZ`GC?nKsvw~oHd5VEQi{VA zer3!}FRQ-28>$o|ts~+P7Mwx4f(6V71#k&D1RH(LRN&aAk#y(1!{7FeWyh)97v&>m zIS<|5>YG;F57#>sw9XIYX+Ly4`E&@5YtMhzr#ZklkEFmvYdB;`p^O_F4pZG+IN-HF zA;$PuzRIY-b028L@n~`6XT53gB9RA*6;S^I{iRteCxE(hd+JO@ZRIl_)i6%DN4L&> zkTP0wb0haEfY)@#HSYEmB)`NP7hlT)aZOsx%GPJF5x7RFFY0leHaho`fhE+7XwrYf z#(H|7O~52RZ9pQu*m$Hyk;S$X;RLI5=> zn!V){`TA8f)qc;Wlq%-9m=+ic*%#nIO}CvNZg?fFO$-<8w1|wAC<%_pc-K0cT`$m^ zEi?;iTd&P?&>O;F?(;rxSPY~jXEA>a?&DIA84Ce9uj(_2xz4VlY+NJIyJsClE2 zZdjC;V?9t>ol|-s_%sWQ;xz*`!3TT>I7X+C3%xwb<1mP9o-RsJ zy5JE7UIAR{nKSzmw1#3^D&ZQEQAeoyQ%vDXv%ib z#GACpL(ft$hx(5j_nKZ9i?Dwu^G+g&v$*B(++t;%mdFh-6SD-b2q4c*A$)|*;XxCx zAe;)>hvcQd^I^N9iFAEY58A>DxM3rXK^=?ULL~5L|1-@Ez~70igKak~1_v+O_|W#e zrpo~jfm`L|Eo9TL;BW@8Gf1y#$(ei?6t+}LU34{{UlI6}wadYk2}gg~WCavZ6tRGu zlWc3Vx*QNlY#=R6k^~r)_MONe0usAwShl#EJG9KKn1$r3#OLObG0=msrnF60s@l%G zH@y3J;J;^3!oZk4>O3Ju(HCNaGp)8=)L^FDjL1f2M{kVdDUTwSnd$W8UV=6X;-P~x z`Ka*uWYApbx{pSoYqx(tA}$*~drk(To@CS zor8GeqR{}wSDZ$Zh{W5S?&^Lw8`vw!pWtV=Nf@_>o;N!D^NA>se_ji&D_h`?aV@Na zJf70)D6*>5wk{5t%pvXp%QQoIai({(C%_BXtOt!_Rd5;yVt`hE9R!pkp|);0f1Q9b z@9Hdx%yN_V>;UxD2SCu+K6!2*Z9$5aaUGLOJU&d1&r9! zrB>xmRw2bn?YfD)#sev~QUj!6{`sH3vezH~ulxJI&Ru{1=fC}D?)s|#CGP58@P=}4 zXMbjLQQ34~GwSoO4<{{~20KvFMf&%nksmM@JzA(vYvyx}ge`Q@a%92N*&9cHa+t)h z<=)p34=^D1_*f=E($D=VbBFxoU*Ly`Nxi!BTf|4I^yy6EvR(L$L^L{I7?Lzh$w5`Z zE)%YUP0)W1NNO8*2GxTxRO4rQQNTOUI6x2CS}|VsiE7 z4gMft6jKI-I2n2Eq%-1dWiHGrCuw$uSXY*3dQwC;SHle2doqS+FUEFEo6R{r-bp`y zMFuc2F&vh6f^K13+}NO74LuXg+MTLPU3?DIEi!*0rC|L`)x!tf7-~ES;EPObQL>CM z3hJ7_e&NmJuTtN-oZ%trWj+KQ?IhJ+8ibTd>Kir^JsgjTnvcZ ziE{Sp&>hTC-C>128ad^oxVD94IcCgCdBah+J5ST=|tVKTEI2_)($aW>eS%@Mus%%?009RM;6 z77^tb{Uw+n2WeTgIyZt2?b=K5v@!V)2F{@BX#|os2tqDT5VqrP$oeCW6SyLwr#d_Z zOf?eoIwAc|VAh>!!(Hde>hwOXp8CQ*3eQQUUzH$Di@B)1|1q( z7+vE+n9{ANJ48ZL;|io5XjjmJkm3P9Kh0G}+2;XY*~p>XXp#BazQKWhV^$>c9A_B; z4q+bhdT_JQ+zW1iI91L9bdIyj$`ygP5||jEa_~DjsDQb3>ZnE1?g{`G8$-mc(CB|& zrtdFskPTq8<5cvRnciPh1ee551aHYYlY4te{lE_DgC}tvvX{9*%Z%vy_^m?gi@eua zCK|2*6fTt8oDwq-*t>OvL1PmXaNEQv@5p@Kz(YpgK z&k91qV^f_ZvsW8@lgZARLd7UxLS^IHs1{8x=g+Y;Fad5I!EX>*A)|*NREK}KFEzb^ zndOEYJhQ-M?u#%~4_eJk%8ITAN5XTs$aMv%&ZEfB=4B<82L0IuY9wfP_*Ar%aGH_^ z!dfKIKEM(bV-YCt_p!n};IBsgoU;bBOxQAvD$kOLE>8Cn*PXz9z;DCl)HV$bUo1H; z1yjk}1C(ZZ-6tl3mN;3}gJTsXM_?@j)Mih!{_0KxlpBs9A(ulD9;F z1L<&!lw)~z<4Gm+GQj3%Mu$fkq|WOw5r6YnCL{8WsL_ePW1CGA$Ox0g1Qabz5JI#Y z!-Rz#1=LC+aLRv>hr2i?rRF$x<41Nb8)7OTwFmN69ehWqV;+A1y4kEIBo_7n=!o)i zHQ(K0@?*oh^QkAa7&1!92H>OPWuBgyY$Of3lRJf;=B4g1tI`HI1`iPhCEa@TklxYx zHlr5sU?Z`OlOveZD9gbSvJlB_a*CuC(7a(r&tkyY=tWqSG401~k=}0S@f)qx6We`I zrHC}hr)h30ZohxJnienN3wPlaq9~4l72GoR0 zLxIP|Iy2*{pp(hhD4)*zB|_&2Pr<1W{Z%XPG!asdmS~~MJ|kadUvM}8+m#8va2$9- zK?lAZCwNgwWMcL}5)1V(l*f`LuUR{M|1IlLrz6JeLSujDbIqIJE`=YHkb=;f9%nHI zIz{xpYVAcz-T4B}mGnD+oNN`35O4-65SLo}B46AH`lmw}nAzJy#>K^8pGF$VTEhHa z00030|9qH74#Z4zo<9S&VM%~t_y}6r;(|E|(1JM(^Kh6}X3jbDXg-yXV15ezt%XFO z!08%-?5=-i)%z6bl57D&6Q;p6`n}>q%1Pk{xStts*T#@i0EWffKVYB*z-{Vsq{9Js z{?Zb1ptZcC`=K9Rr{>fr$284NqzI2|=~zK2Mw8g+Hw22&XoQgB2Q0*Qz9|p|0%P!U zoSNv=1Z@&o@Z4!UFZu9hfLIC+PTOrQ27CY+P33>9&i`;ZUU)+1d?dQdhsmVaSkt`# z9 zCGUSdr6S-b7gV7jJnVTeGIug5$uN&DaZ!o+CEtY~CY1rcr)7gj7`{{R)VOT($EPjd z#lV-@%0jW-F;{c09HX9R8%E}R#*|hjHQwh#4BwBU@a6Y8Hsg{{VMfMh#(V@Z)6WbJ z8FE&0nSs`uWz)ad6tz5um;8L&Y5$Mw68?W;@7zO1eb*HWB|i21$Un$ZN{=8Iy<)~u ziO(l{|5O#wjXZbtfB_`i8rnxZt*Tp|I%_cbytTFkB>yl~#3~D3k^aRGPnUJAJRXVn zx8OB@5J2g)x|Ub}+5dU>5xZH6>M`~8FMMA#iu~M8iT#tm3)2US7$A44P&QTEI!vo-7;~viN1qxb`c?;Po?=bmm_ye;0u1??d%=;20w?nbIAYlfBB3-{8v0ZoPL#o!`JK?I0+blBxJhH1&ohw*ezqW*k8Vq0c%|aGW0?y~bz$k( z;6MgU8B=qG>8-@OJvf~JvV?U=T*F*gNo4fF3l zs74)3p-cg|RmQ=+p#Ub*+tFHpH5&R9PUINJL5$6ZChHdKdiu`*=i?4TXtF)w2AxP@ zISPn8=3$R?;x2j~$W*sin4%BqZPv7yf(@=$ZKTEE1eh$*JA~$r$47tvB{h2E#KO)% zj6j#<|EL?_DHg*eHoRpf1P4MEff+#JchzZ5wf7uPE!kIk1B!qiM>62$9DrJl9<_Pj zeFr5z%;hjC`eq?-G?wVAQI$MUxkR1T`b@xWpv!r+QY_15Z;@rPPH2?Z#AUIRCyWfy zE`=5+a`$_5l^xJEp|XEv;0a~|mTCveyuO||=b(6sd&s?9uF@c~2^M$W?LPDkIC!!( z8})9@Yk=^^S=SShs70I-Ea;cYnNwYI63aU$LT=xlC^rs>^iYP3Pktx)a!84z59HQ+taEe;u5$~`bi z6JoW#HunfYD6^PF&^;5<_!UNO@+tT?hkt&mn~+n4o|HLf0J36u{tUF!8u$k2?bB}7 zFx+R4RXCR|YaTO6eYW7ld8q@8)lOq|S)<5DR$7q0fX0S7b z$)?0*a6qej9MOLb=)^xx<;L*=-n2t>TTtO!Fl~j8;){K($9%r!M!;`AIC>7#B%Vab z!@N|${yb=|o>h3NTc1vC-?-RG*B7gNspl9r@IJ|L$uY94_r+aWAZktxHBiNp3LSqtJc)4998T1}LnM&?JJ%JpEt3o8MK=JD2hv^BQM?D!NDxmq|7_ca1 zUM|3>fsNUk=*)7KvX zwwsO)_=x!-+#?@Cv#ig@zCx??FX87Lk-xF0gcICD@8?urVu5uOnM)ky*0pj2@}rPe zzC9;KCL9S3r03Pc=pYpul!XQCh%hMac2VUDAK!m{Xx;OQl6BrM)n}{o5^tlSi=6;# zGjX(n9D$0g8PL)66-?o*xvvvEQ+mb?2-^s>cClOl8yzIy$hrCTs9+^-t`+Ejr=KcD zs!a%PKXaqmM9{Jf*9wH4Un#G4%{zJ3?1yAd7^E&~f={-IrQ1RdafqBaIG`v*l91?q z|AT+X=og%P!_pD2aKm|E(_8WQ<^l}}OodF~c*K0IO_@Au~9oy76e@JM_;Q4YeFTcA2}ehM%k+%rknKyo3MKB3-5MFgq=G{rYL_X ze(8e2>68-AOwK&n$mBgvtcxu9iYed@V3M<5ON`zYy84tHs%QX3F09L327WwAZnlaK z7)akx4>iE}MN_6Bt<^91X4wTCI#H+bP;MbtDB%oYl{=Tq-1Xd--*m_4%aJXxY zfIXog17|5kmB}nMdq(jJ_fN}^?QE&R&mc3~*IBy7aVcEoM@4*yH<>ec8IJ0kTl+2# zsWgNKdl z!XH&bZ}jAS)Zh$@A9(<$g;_Sv>PPH*1?C3~LjeZ4w-SF$vL9Pr(-AK4 zvZ(kZTMJ9ClobZF`(~D-F{;er1unPgU<{Qp^oat$1@funoI2U=**t(xKm ziNLwcsEl<1cZ$}nqmO@64w40>X{eFv1EiScKIb{?$>o{t!MT8|T7&KYQ~#EQw*5Nj zP^o5!Du5Y$ATk7RP%@3K@7c{Xt;H3NIZ9bAiJ@hFr5?iqW}hNTR3Dl4;~td3+^Q*U zW+_hG7;56!;(N^Y7zk(3FuPDp1ZG=^tK7H^G(*iC9?EtPM2LTQ8azK3)36WjWo>Z# zTlEaEmuW-?(M46P!$D%738#wy3rO=^_uS||Cl$1%EU{F*enngtvGdamx4x$q*jDGB z76XBu7LrXNSmReL*L2HbZ_0SLy+`FCvA+;>;HL!F))JqF24#)~t}Us~qY$TehvuT_ z-`~df-X0OeWa58=pFH-D%>U={C-=*L{qJ-CfB)-$&HaCl{|)Z%q;@+b$irlQdo?Vy zNAXu|pAQ5H>+xg0ve((FyBU(}O^O0b?Yt#Yu&f#Z!^2xDe%+5_1wxToK}}6rZkXeg zlbXG7V=5Ts^N}m2?4lvcisUf}0EWrmH}r=N^rPW8vL%07GKFK?CNeh-=%`s-lL-Yb zM>v2FZQ)GXfY0C=$~9T*KGcJlRlhVLP|T=wkJrdVnJoy#_A4#M4rm@EZ-1^$o9bqUKfr2Q zD+0I(@60Z2&z25ZK$y6SVyOcYhU({Nm$iP5Eq8R(pm?Hq0m3E#Gh|`SMWplC?-B7l zc3h}q&F1$SdqS43chpE~zC_xduy+xy{ir}9ZaIIBd#kShR zNx{z_0w@jeB0Y4ob~9|$NBBa~u$sN3klp$`yH&^JE{FB>WB7ATUsXixM-Pb4@pEFh z0d%j^I|BA^08*$oAoTJTH2gwGnZ)oU6{JzKj4y=5MP%2@Dyx87@yf^g2GtM$N$$%& zdewi4+nB>%9m;)C>Y4q`zX$I$H=pyTp1U~`56MbI%%K|BaUtN>HNF^?7fBt|a;p-+ zIjQV{*55`_!%HJ-p-3*372ht|bTrdMc>9cZ%Z}3?(0@OfU-pG3B@91^W#8A-ecM{n zA`2T$#{1W#K0+71M0da^KFBEDlb2eD1{Qw?V4uf$`$-n^V2JP|Y%Er9Y z-V&B}mLMh$%YZ}*CT#^VzBBc+*Au07v$TPq=pGkD`P_z9Av{_ZE(d%%C> zh9Alyge{qHdtDbq&}cF23Wkbv@)MSpr70AyCV-P#m{I>||G=tRpbYayOk>Y zq;$xEjjSSIR9VtP`vN^;`;h#DpwwwVAw?woJLE@9;@W!TwV#_3j`Yhl=+UGfa&n&s z7DzdK6EAXE(aZYeaYxoy0gVB1$$5W5SNC~}qiV6Cb_;AxB2? z3yqA47gh^!0b6dHep?h8Q+4o z822I7h;8l+=_9m3-|BD@?(jHDL0;R+PBd*BZ{^T3x!_%I1;XZumQbVj{1w1Y#II=& zHwfz6=uze)Fhq7!q>Nw8laHbTQh!N=mp3G=`hq9Y7zQfh0e8~XG75iyVMT6_0w^<9 zzz|?*dD|?_!?P%*fB3n&+=qYO(Nh~d*G5h^#AZznR4l~$7dLib(S;RwC%a+UYJPe_ zUtkofFdwn$C;0~RmEw8&Sr;SmBZMW;cCVjt^WQE5nTMD!@Lm&BO9M&`U^S$JWeEaO z9Hv3dm-F^z{h7r*Vka(qo0}{6^ZTr7;qDCsINgZ)SK18tw``J`XD@&2;}hGKhgc!= zssIs)!<6>jlFn;AAYE_iy+kvVpP?TgV)~^$9@DmIDFV3dgesaBPQS#17U5En$+0k* z?|rpJG6#CFQ)))Fa=WG&)l=>OV3nTXaHFXP(01Lhtkw@O-?M&n)>U~OoJ|9RX#X|f z7%H;pyuTvmr_i!&5D$O4^r^e}iC_iJP#p@9rMXjFoX-^{llX_yLAi`#j6E=Ea4G9C zwS!?fGsRboJui@_$eOe{>@ zcAlk(H9_zOmAr4Rz!UW+NAr3ZJiQY$0HI+o2mvXgg!{R*6i9#lBUu{LlZJ+#&hpoo z`^n^w_@dxdAY9`QL0!y$_D47!;`0Z2Z=bokjd<>gEAir)!?!9^OQ(?2Eg^IfPe*A zku9Wkzyi@*x^;h0WHQXX6DyGd0ORB>-)Mk8V@#>ZTU;iGeuW=INjmNQJ&*}Gd^sx` za3fQKV>6-x8$Jq#6u2p#1wEocHyX2J%^`-&c0{MU4FA5ps!#&i9>&+z>j-a|sM zh64*d1l_;jgVz8>0iaU$@th6tB=VePPcbz3WnU-)vzl$G7Jm=#?L)Yq?Bi1xMRd)tB=_Vu%n!6B zS2A%wngCG?iRU8t9DRgv*nQb)f*h3vUa7{kR-GIv_YEL{8lb(noD)&H<5y4TnD#4> z$+A081C0|#dHwl|lKclh`KaOmOArhv>m9$>eL)Ts|EUO2b{6V0-s zr4WCpLU4U*P%$>{r)E^6X$Xm3>j%Qpy*ZfhN(^RL05=sK$71a9jZ*Tq<5DdIb$L)u zlxe?gSSbXiY-<;d23L=}k)peZV}3fnQ!AnN0?ni=bNsoCGstWzfVg8Iv+lj!)=ui( zi%ZO-85M}FS+&_LP|0m<6wNkO zgY?r_`Zs8bkrq)vG7&IF&NBf zwNy~St*N#WkD`Wlo*<8}>NCc*N_^IY_yk26cLQKkdxuZ7eEQQwsS7~c2Pa|}G0T5Q z#oB~fA>NaZmZtqIgV_fSx)Tr+Eh!sP!}ot@To7g+|NZyCT3>Y~g}6CZK7Eh%Wh`*4%;A zv9rTsqzu{F0NFVQqwpmJ_~INwI=g>R>}SHUHG=-m(O;)uV*G$T>Os^P5#gzDS!6@r z8kJQR_Y!5NTp!a(EauDqeE4w5AFX+jkfx=+uMEQZ>)Xx3*7hKQ{&H;t&`zKL?xC(Q zkEkM%@Uu>ZO%hQ;LV6ejHcXmqqpu#e#$*5zw$V+I!R$z)a{{6aTmwKk5s zEUnVr@W5{)OWFE7QIR=Zld&6Ilj;CYpuy_l(!M$bgk~6S?w=c$K1YAb`oW_0Pg?vm zOmxurNst~`S$x#JElWr^sBJZx93X#4vB2a}z37&%FYFi+m3I3nXrOF*qC>VG;v&_S zpzA?fdZV)N&oYM?JY0wWe*pjh|NqTd$qvNIRegy90znWfJ|HVlEj&+=vgmG4?e^53 z?Vaa&p8W-U3g5)n;75O6k{84vAr_Q$RjTS5x^C4y_Z(Rgqk#D|)MwdJKY_S;0Bzb->QiRFo)qFVBDRnd2S}OU5`?)zF3kHdt*R4do*jG`cNf!aJW=hv0vE5KRPqh zZFs?u)$oxGdnt-EX;a$M@F?gpPsJ*^dk7OkLiNHmCP;_?7dwA!!*wm>;FZ0a3zK6$ zk^!@v{4j6%g}oLlkprhgbo+Y($;}a!lFPyIdIj?_%%P>6q?Hx%OucGgP+N1Z_F*x&<78{C$*pV|r2FMV5 z0}{bd$1Bd-z%YM0w~>q={3?i&m#%cA!fJ-sU`@kbN&E|H5dp>GqMELD>YGOsJdv)W z@aPpIz5*%Du175K<9riqGuobqM?Czb-Y?WUR!bn zr1+BK4X4WPTY^5S_1VK!zMm1g0NR|A(v*IJ$+em#FN+9BbxqM{w|y5EQL*)FLZY_~ zgtN)Y8|pRFPsqjAQ;}XUXSb3fKZ4{Gv!TZ8b!wQ59@mwk!$t07*0Q5GIU8KzAqJfY z)EP@0F(-dnUy>nlapx;2DS#qzhfOPYTQCd?QfZ(zp~>vHqbi&W|Csr#eSGdC}Qg&fDp|O z09Qg6u4RSbFdlbN_5yt>jlpW?`l=1hx0wYHlFxrUg9+l#wtJ_gA^47yDg6>=9;FL@ zJ*WYa#mb(uc<`psRFKFO#(f%j6k8@|Ge03U%nQ}Wi<-RS_u6#0c<5Bar+WH^Aj*Dw z72Hs(67C)wk!k9YE&Yb;X>L3M-HX<%hCLDi*pJDfq6Mu>R2@rl@}#*cpj zI^sDk>mg|EvD+uOFn;P_$fVz*r=+7+r8S^vNvQ@iZL|^Jw>jPPr}XH~s$Z)X6(4Oq zpj$Os2iO2w@99VZYhwVRKb1=&G$gd(m|l|-Gh!s(qANHS4wzkY=w_qqC=IJ5^a3<0 z@hFPQc4Qzmz_@Eg=&f@gdE#+f3xt2%pD}%=`wyKna{gsd91EIrjeDGhFa@EkYLH0H z8hlSIB(|$RUY$WZ`kt+vrs8P2@|~<9yhDh|J29uhBYObb?58?SK+kHVT*Z+28Zk%n z%(~SYg%XMg&PubjR)>JSxZp-f6qr*CD6RLR0Qb76Mv)_x&^ zwj>j*LbccK2L$Lu?hmntsR@5x&`3I3dkb4FrkDdY0LM&y(j(vkd&7MRM-{?kYH7pk zQWBj7EJHUh)~S_bAR~ah%kI2|CHj|zf4CCg{Ssy164qnK8~EnMig1CR-%Z&^p9x!( zKi=hu$V^I%>Ws?i6i;I2dsv`49m8cGO>;@n^{~|-PYmGxSp*2XNp_Aqe?d05>hr$>sZpV#KZ?geE}gK`gETlLn(UEK?0~4 zF_agDIm(nq^qz1-&X8H)1WcQ*GQ&uFT~!fq2sA_o3Xh)#)VVZ1r>e}CG-h-fTDWy$ zC3CgBlT;P%DA|e(u1Vdt6PY_jj3>RB=lhn{dJg6$yR*+pT<;Kg z0Si&%$Im=;3bbc3A&Bs8+ATG*3O8faFH;7X{G<`$ z0wHeEN6mU5J)p!&(LI~J#3S~>uMx`FxJ)IAN-z%a40fzy=02>>Jxa&hw}f|*F&_7t z{=S0cPLzdV1V>PE)SPbC$cWne=HZqTPZ zPe@L0X2iz}G_NnZM-W!jpLGy1%mqEy3w=>Z7F?DaL;ESW=}W52Ys*-Dhd<&M1&NLc z=xCi>mUy*yK=cWsg#CQTNT9P#KPwqhw0F8-&+QOAVKX#kg|Y1$0X!7!%I| z@FG7sFt300!9!JDCX*nILB44`icsEt5iC9i2^ZQ9ojf^%YUcxC-BW9_V}|xQd_F}= zX5*WmhGGWx;Z4I$?4$v43G&&4zRXoKaw4=4>NGlqe9|5{3_}e9 zu$gxXttUpZw}AeZhb`-y@JafHmM3#F3(SBAXlyq&sw%rPz=^7!q@v=adf3xn8?T%Q zoQhnAWM9g@9(Wmb1slEz>X7SG9G7t0K3>cDVnLc@hbHrkGX&RF-lqTx;@Ng$cN03b zVWWRhIx-Y;7v5M7zEF&gq1S=6`9c!OFkY*O-P_(XBd^J7?8~ep=EG|VnpS*lNfj#k ztj*Coj2p)Ff=ggy$)S`(>+CK%nH}}qGE{37Xj!S$qI8|8!XUyvq=jdLH$Z~-@~KH_ zFfH3BDhp&zTe>92j;zVz$(!UK^Jp?RDN=ut;LtwNQZMocq6T?ntSLJvhB~PgtkA;t zZ5NqQbHUTL2_S4%*t{gFYS=w$(r7jjs=KNxJ7sl_Qq_=kiR{Ap0w14|Tc@00J5eBJ zoxfOYh_L~q&6O~Ve2XP3+Nd^UXUf#tOHCx!6LxGMUgQEJx=PX}GzHWUNUktXh1P!s zjb=`V4H^P-t<_A-Sq(!kGPB!rJ1AbnM;oSxkud&?B6t3R^Qi0Jm~I##EGzopx6_H4_lqDO_m5w_?fXnIz91+M z{NyRrjWzBSgFjmNClk=(F^lcb?fVB?JIT53KmI2>|7a&Hsf3!Rdcw0+YWaU+g&AK0 zt5E}IU|UNF)ji~GnAs!B`En&2KiFt_SGkVM^_3>VGd&=T^Hs>bI5Sj>b9FX+ z^ps0pDDQLtUwRW+H3?nwkdA+>(L@TXQywGdQ#bSfj)P9pnZ_6YpZt6Iaw?RsdvBg7 zWx0BIp8H+bxrh@7-idiD`PF0Pq2^{$lp4>ChFgbrfyMonhaS|r|_&WCU(F?BtoJ+s} zx{X8+Yi#RuMxFAyY=g42l91v%=ihf0-};f1cic5_AzQge2Nk`3WeHEvk3AUh6eEl_ z4H#!hrfz~df=u~E4S;{X6kd3(kz*_9O>ieeQLziP^1B_|i7F3>@A*8SGFhhzCj-h`>l$fT@&!Ns0Ptv@a5>UYdUp6dd)_!}5y0+a>y{ zj$2`Y*Q=v;DBfHyKhK;wdun+CvQ2pKnQEFp@U&n*W=pHJubX#xy;yyFd$-i}RPr%^ zsc1o-RtE0qT*$k#6-u}?n2n!Y(O8x1xAk51@GfUrdWE0UYQ>$tReV%F9x{rH8Q$aC z$g-t|!n*R1dq{ta*;y;HK2rBO>l)k-LbKa(B@ubCPmF-%nR0CR=VWJl#U^UgFUAn% z9X?`DLL}Z2QBbk25vRLz+ItOyr%3eF%?Q?h?&SFKQP@*C&+U_2Rs5U@B6HCzazeSd zL4q}?hg1(~tLkmrK!QO^7dZy%B~=}B)GDE2oJo-0LS=uMSW2bWD`@(h#-r7rtUF7{ z@FY(XhD%iVVDFpRUI4RD?P-hXISLdVvY6I&mL&)>$)W<{3-GS#BQ*fqN|v`~a=weA z6GLxyGRWbLTOV@uke0lKO42YM_cC{JO@jqS?dMKsX=YJ(lw1Wc2?Kq|f+TI0B6M&W z@g4V-hMRvgBs8%AS4^6V;$z$EV#e&QI(>CtIV3YemmZml+7^cqe1lM*so>7fh5-J` zvkQSA(U`Wk#IkPfjOB@3PCbkV_@GMT!ouant}Fh`w2<^x|?%FRR7CT8#Pqu(w?bAX==6-)waur3shRlkHnskt+_aoi(91Opgg8#^ zUDSVXxDQJ;dL6@xIr^R&y4!rjn><#YSmHhfJ20WSUo_*T>R15A%ed~g&}*IH<)y&_ zfGUYW+;30SOs>{Ry@V>tjoWn zS8XxTmZDuBl8)JxVfX?Wi&*G0V`9 z&&*(ZNqJHFkfiTGS_#A>XL?d(MDLve%zq%=E!dq}f7}|(L#uke-`|6aEBK~5P&8A2 z??;5kfzP}!k{+T4iuTMe;#e3VSf==IFdu-W&6uHim$4B`)x$jSsVi6E?$!2pDA1Fx zCoAg}N2(Cmm1x-maEVe-lCwj;PDbl=RY~zZh6on3!6v!Iy8Ss<@q$7h%w9}k-mQQF za{rav^O(rp8H=DL7H%7H3oM7KHkSK;-GpciUgGugyP6*tcw25y^z@7NA=aw0;EA!I za)*g-`RsCzU4G_imM9K5S$eE=9Zmb|qNj{qHNZ#xd9_TyVs|LsAaLV!B4d`IxLJRR zpNUDbs&(2BSUsR_ygmJh3IrL>?6(JojU$P4R8H?iX`_&D9@oyF%>&Q1$2fX_UdGF? zbN*V^E;Lv|9HlScI26v9XEaU@(ss|F0R?3ZIWcY0659;+0@L2mB0AIroj~tOX4{gi zmM|)6rfOmPg@~kA9XUniQr}u7R`>5nPaWHU}OSW5X_*iLv+W@a8T=>nRW?CL- z-k|1DWXjvUQX^DDBOx7#o(#d!eGceP660+8V^Kr5xH1xljiWhX_rm#q;K1zl8i34i z=21fRrNm#dUBk2!L4C>0tESt1W9q>IucM>)r0pbG*E4*?DF@Aju!A5PZ?;=KGf!rS z??}b+@Oi_x&a=r==C)FMLGi59NQsG-ALLQgO3cuDWS~f@CDZi~(7Z|M{M7!j RR$iLoed}ww90dRX diff --git a/matlab/scripts/Inertial Nav EKF/H_LOSX.c b/matlab/scripts/Inertial Nav EKF/H_LOSX.c index c7ba63108e..e2223cc9e4 100644 --- a/matlab/scripts/Inertial Nav EKF/H_LOSX.c +++ b/matlab/scripts/Inertial Nav EKF/H_LOSX.c @@ -1,15 +1,8 @@ t2 = 1.0/range; -t3 = q0*q0; -t4 = q1*q1; -t5 = q2*q2; -t6 = q3*q3; -t7 = q0*q2*2.0; -t8 = q1*q3*2.0; -t9 = q0*q3*2.0; -t10 = q1*q2*2.0; -t11 = q0*q1*2.0; -A0[0][0] = t2*(vn*(t7+t8)+vd*(t3-t4-t5+t6)-ve*(t11-q2*q3*2.0)); -A0[0][2] = -t2*(ve*(t9+t10)-vd*(t7-t8)+vn*(t3+t4-t5-t6)); -A0[0][3] = -t2*(t9-t10); -A0[0][4] = t2*(t3-t4+t5-t6); -A0[0][5] = t2*(t11+q2*q3*2.0); +A0[0][0] = t2*(q1*vd*2.0+q0*ve*2.0-q3*vn*2.0); +A0[0][1] = t2*(q0*vd*2.0-q1*ve*2.0+q2*vn*2.0); +A0[0][2] = t2*(q3*vd*2.0+q2*ve*2.0+q1*vn*2.0); +A0[0][3] = -t2*(q2*vd*-2.0+q3*ve*2.0+q0*vn*2.0); +A0[0][4] = -t2*(q0*q3*2.0-q1*q2*2.0); +A0[0][5] = t2*(q0*q0-q1*q1+q2*q2-q3*q3); +A0[0][6] = t2*(q0*q1*2.0+q2*q3*2.0); diff --git a/matlab/scripts/Inertial Nav EKF/H_LOSY.c b/matlab/scripts/Inertial Nav EKF/H_LOSY.c index 1c7ee5be18..306eed204b 100644 --- a/matlab/scripts/Inertial Nav EKF/H_LOSY.c +++ b/matlab/scripts/Inertial Nav EKF/H_LOSY.c @@ -1,14 +1,8 @@ t2 = 1.0/range; -t3 = q0*q0; -t4 = q1*q1; -t5 = q2*q2; -t6 = q3*q3; -t7 = q0*q1*2.0; -t8 = q0*q3*2.0; -t9 = q0*q2*2.0; -t10 = q1*q3*2.0; -A0[0][1] = t2*(vn*(t9+t10)+vd*(t3-t4-t5+t6)-ve*(t7-q2*q3*2.0)); -A0[0][2] = -t2*(ve*(t3-t4+t5-t6)+vd*(t7+q2*q3*2.0)-vn*(t8-q1*q2*2.0)); -A0[0][3] = -t2*(t3+t4-t5-t6); -A0[0][4] = -t2*(t8+q1*q2*2.0); -A0[0][5] = t2*(t9-t10); +A0[0][0] = -t2*(q2*vd*-2.0+q3*ve*2.0+q0*vn*2.0); +A0[0][1] = -t2*(q3*vd*2.0+q2*ve*2.0+q1*vn*2.0); +A0[0][2] = t2*(q0*vd*2.0-q1*ve*2.0+q2*vn*2.0); +A0[0][3] = -t2*(q1*vd*2.0+q0*ve*2.0-q3*vn*2.0); +A0[0][4] = -t2*(q0*q0+q1*q1-q2*q2-q3*q3); +A0[0][5] = -t2*(q0*q3*2.0+q1*q2*2.0); +A0[0][6] = t2*(q0*q2*2.0-q1*q3*2.0); diff --git a/matlab/scripts/Inertial Nav EKF/K_LOSX.c b/matlab/scripts/Inertial Nav EKF/K_LOSX.c index fe44362016..5044d0cc6e 100644 --- a/matlab/scripts/Inertial Nav EKF/K_LOSX.c +++ b/matlab/scripts/Inertial Nav EKF/K_LOSX.c @@ -1,89 +1,117 @@ t2 = 1.0/range; -t3 = q0*q1*2.0; -t4 = q2*q3*2.0; -t5 = q0*q0; -t6 = q1*q1; -t7 = q2*q2; -t8 = q3*q3; -t9 = q0*q2*2.0; -t10 = q1*q3*2.0; -t11 = q0*q3*2.0; -t12 = q1*q2*2.0; -t13 = t11-t12; -t14 = t3+t4; -t15 = t5-t6-t7+t8; -t16 = t15*vd; -t17 = t3-t4; -t18 = t9+t10; -t19 = t18*vn; -t28 = t17*ve; -t20 = t16+t19-t28; -t21 = t5+t6-t7-t8; -t22 = t21*vn; -t23 = t9-t10; -t24 = t11+t12; -t25 = t24*ve; -t29 = t23*vd; -t26 = t22+t25-t29; -t27 = t5-t6+t7-t8; -t30 = P[0][0]*t2*t20; -t31 = P[5][3]*t2*t14; -t32 = P[0][3]*t2*t20; -t33 = P[4][3]*t2*t27; -t56 = P[3][3]*t2*t13; -t57 = P[2][3]*t2*t26; -t34 = t31+t32+t33-t56-t57; -t35 = P[5][5]*t2*t14; -t36 = P[0][5]*t2*t20; -t37 = P[4][5]*t2*t27; -t59 = P[3][5]*t2*t13; -t60 = P[2][5]*t2*t26; -t38 = t35+t36+t37-t59-t60; -t39 = t2*t14*t38; -t40 = P[5][0]*t2*t14; -t41 = P[4][0]*t2*t27; -t61 = P[3][0]*t2*t13; -t62 = P[2][0]*t2*t26; -t42 = t30+t40+t41-t61-t62; -t43 = t2*t20*t42; -t44 = P[5][2]*t2*t14; -t45 = P[0][2]*t2*t20; -t46 = P[4][2]*t2*t27; -t55 = P[2][2]*t2*t26; -t63 = P[3][2]*t2*t13; -t47 = t44+t45+t46-t55-t63; -t48 = P[5][4]*t2*t14; -t49 = P[0][4]*t2*t20; -t50 = P[4][4]*t2*t27; -t65 = P[3][4]*t2*t13; -t66 = P[2][4]*t2*t26; -t51 = t48+t49+t50-t65-t66; -t52 = t2*t27*t51; -t58 = t2*t13*t34; -t64 = t2*t26*t47; -t53 = R_LOS+t39+t43+t52-t58-t64; -t54 = 1.0/t53; -A0[0][0] = t54*(t30-P[0][3]*t2*(t11-q1*q2*2.0)+P[0][5]*t2*t14-P[0][2]*t2*t26+P[0][4]*t2*t27); -A0[1][0] = t54*(-P[1][3]*t2*t13+P[1][5]*t2*t14+P[1][0]*t2*t20-P[1][2]*t2*t26+P[1][4]*t2*t27); -A0[2][0] = t54*(-t55-P[2][3]*t2*t13+P[2][5]*t2*t14+P[2][0]*t2*t20+P[2][4]*t2*t27); -A0[3][0] = t54*(-t56+P[3][5]*t2*t14+P[3][0]*t2*t20-P[3][2]*t2*t26+P[3][4]*t2*t27); -A0[4][0] = t54*(t50-P[4][3]*t2*t13+P[4][5]*t2*t14+P[4][0]*t2*t20-P[4][2]*t2*t26); -A0[5][0] = t54*(t35-P[5][3]*t2*t13+P[5][0]*t2*t20-P[5][2]*t2*t26+P[5][4]*t2*t27); -A0[6][0] = t54*(-P[6][3]*t2*t13+P[6][5]*t2*t14+P[6][0]*t2*t20-P[6][2]*t2*t26+P[6][4]*t2*t27); -A0[7][0] = t54*(-P[7][3]*t2*t13+P[7][5]*t2*t14+P[7][0]*t2*t20-P[7][2]*t2*t26+P[7][4]*t2*t27); -A0[8][0] = t54*(-P[8][3]*t2*t13+P[8][5]*t2*t14+P[8][0]*t2*t20-P[8][2]*t2*t26+P[8][4]*t2*t27); -A0[9][0] = t54*(-P[9][3]*t2*t13+P[9][5]*t2*t14+P[9][0]*t2*t20-P[9][2]*t2*t26+P[9][4]*t2*t27); -A0[10][0] = t54*(-P[10][3]*t2*t13+P[10][5]*t2*t14+P[10][0]*t2*t20-P[10][2]*t2*t26+P[10][4]*t2*t27); -A0[11][0] = t54*(-P[11][3]*t2*t13+P[11][5]*t2*t14+P[11][0]*t2*t20-P[11][2]*t2*t26+P[11][4]*t2*t27); -A0[12][0] = t54*(-P[12][3]*t2*t13+P[12][5]*t2*t14+P[12][0]*t2*t20-P[12][2]*t2*t26+P[12][4]*t2*t27); -A0[13][0] = t54*(-P[13][3]*t2*t13+P[13][5]*t2*t14+P[13][0]*t2*t20-P[13][2]*t2*t26+P[13][4]*t2*t27); -A0[14][0] = t54*(-P[14][3]*t2*t13+P[14][5]*t2*t14+P[14][0]*t2*t20-P[14][2]*t2*t26+P[14][4]*t2*t27); -A0[15][0] = t54*(-P[15][3]*t2*t13+P[15][5]*t2*t14+P[15][0]*t2*t20-P[15][2]*t2*t26+P[15][4]*t2*t27); -A0[16][0] = t54*(-P[16][3]*t2*t13+P[16][5]*t2*t14+P[16][0]*t2*t20-P[16][2]*t2*t26+P[16][4]*t2*t27); -A0[17][0] = t54*(-P[17][3]*t2*t13+P[17][5]*t2*t14+P[17][0]*t2*t20-P[17][2]*t2*t26+P[17][4]*t2*t27); -A0[18][0] = t54*(-P[18][3]*t2*t13+P[18][5]*t2*t14+P[18][0]*t2*t20-P[18][2]*t2*t26+P[18][4]*t2*t27); -A0[19][0] = t54*(-P[19][3]*t2*t13+P[19][5]*t2*t14+P[19][0]*t2*t20-P[19][2]*t2*t26+P[19][4]*t2*t27); -A0[20][0] = t54*(-P[20][3]*t2*t13+P[20][5]*t2*t14+P[20][0]*t2*t20-P[20][2]*t2*t26+P[20][4]*t2*t27); -A0[21][0] = t54*(-P[21][3]*t2*t13+P[21][5]*t2*t14+P[21][0]*t2*t20-P[21][2]*t2*t26+P[21][4]*t2*t27); -A0[22][0] = t54*(-P[22][3]*t2*t13+P[22][5]*t2*t14+P[22][0]*t2*t20-P[22][2]*t2*t26+P[22][4]*t2*t27); -A0[23][0] = t54*(-P[23][3]*t2*t13+P[23][5]*t2*t14+P[23][0]*t2*t20-P[23][2]*t2*t26+P[23][4]*t2*t27); +t3 = q1*vd*2.0; +t4 = q0*ve*2.0; +t11 = q3*vn*2.0; +t5 = t3+t4-t11; +t6 = q0*q3*2.0; +t29 = q1*q2*2.0; +t7 = t6-t29; +t8 = q0*q1*2.0; +t9 = q2*q3*2.0; +t10 = t8+t9; +t12 = P[0][0]*t2*t5; +t13 = q0*vd*2.0; +t14 = q2*vn*2.0; +t28 = q1*ve*2.0; +t15 = t13+t14-t28; +t16 = q3*vd*2.0; +t17 = q2*ve*2.0; +t18 = q1*vn*2.0; +t19 = t16+t17+t18; +t20 = q3*ve*2.0; +t21 = q0*vn*2.0; +t30 = q2*vd*2.0; +t22 = t20+t21-t30; +t23 = q0*q0; +t24 = q1*q1; +t25 = q2*q2; +t26 = q3*q3; +t27 = t23-t24+t25-t26; +t31 = P[1][1]*t2*t15; +t32 = P[6][0]*t2*t10; +t33 = P[1][0]*t2*t15; +t34 = P[2][0]*t2*t19; +t35 = P[5][0]*t2*t27; +t79 = P[4][0]*t2*t7; +t80 = P[3][0]*t2*t22; +t36 = t12+t32+t33+t34+t35-t79-t80; +t37 = t2*t5*t36; +t38 = P[6][1]*t2*t10; +t39 = P[0][1]*t2*t5; +t40 = P[2][1]*t2*t19; +t41 = P[5][1]*t2*t27; +t81 = P[4][1]*t2*t7; +t82 = P[3][1]*t2*t22; +t42 = t31+t38+t39+t40+t41-t81-t82; +t43 = t2*t15*t42; +t44 = P[6][2]*t2*t10; +t45 = P[0][2]*t2*t5; +t46 = P[1][2]*t2*t15; +t47 = P[2][2]*t2*t19; +t48 = P[5][2]*t2*t27; +t83 = P[4][2]*t2*t7; +t84 = P[3][2]*t2*t22; +t49 = t44+t45+t46+t47+t48-t83-t84; +t50 = t2*t19*t49; +t51 = P[6][3]*t2*t10; +t52 = P[0][3]*t2*t5; +t53 = P[1][3]*t2*t15; +t54 = P[2][3]*t2*t19; +t55 = P[5][3]*t2*t27; +t85 = P[4][3]*t2*t7; +t86 = P[3][3]*t2*t22; +t56 = t51+t52+t53+t54+t55-t85-t86; +t57 = P[6][5]*t2*t10; +t58 = P[0][5]*t2*t5; +t59 = P[1][5]*t2*t15; +t60 = P[2][5]*t2*t19; +t61 = P[5][5]*t2*t27; +t88 = P[4][5]*t2*t7; +t89 = P[3][5]*t2*t22; +t62 = t57+t58+t59+t60+t61-t88-t89; +t63 = t2*t27*t62; +t64 = P[6][4]*t2*t10; +t65 = P[0][4]*t2*t5; +t66 = P[1][4]*t2*t15; +t67 = P[2][4]*t2*t19; +t68 = P[5][4]*t2*t27; +t90 = P[4][4]*t2*t7; +t91 = P[3][4]*t2*t22; +t69 = t64+t65+t66+t67+t68-t90-t91; +t70 = P[6][6]*t2*t10; +t71 = P[0][6]*t2*t5; +t72 = P[1][6]*t2*t15; +t73 = P[2][6]*t2*t19; +t74 = P[5][6]*t2*t27; +t93 = P[4][6]*t2*t7; +t94 = P[3][6]*t2*t22; +t75 = t70+t71+t72+t73+t74-t93-t94; +t76 = t2*t10*t75; +t87 = t2*t22*t56; +t92 = t2*t7*t69; +t77 = R_LOS+t37+t43+t50+t63+t76-t87-t92; +t78 = 1.0/t77; +A0[0][0] = t78*(t12-P[0][4]*t2*t7+P[0][1]*t2*t15+P[0][6]*t2*t10+P[0][2]*t2*t19-P[0][3]*t2*t22+P[0][5]*t2*t27); +A0[1][0] = t78*(t31+P[1][0]*t2*t5-P[1][4]*t2*t7+P[1][6]*t2*t10+P[1][2]*t2*t19-P[1][3]*t2*t22+P[1][5]*t2*t27); +A0[2][0] = t78*(t47+P[2][0]*t2*t5-P[2][4]*t2*t7+P[2][1]*t2*t15+P[2][6]*t2*t10-P[2][3]*t2*t22+P[2][5]*t2*t27); +A0[3][0] = t78*(-t86+P[3][0]*t2*t5-P[3][4]*t2*t7+P[3][1]*t2*t15+P[3][6]*t2*t10+P[3][2]*t2*t19+P[3][5]*t2*t27); +A0[4][0] = t78*(-t90+P[4][0]*t2*t5+P[4][1]*t2*t15+P[4][6]*t2*t10+P[4][2]*t2*t19-P[4][3]*t2*t22+P[4][5]*t2*t27); +A0[5][0] = t78*(t61+P[5][0]*t2*t5-P[5][4]*t2*t7+P[5][1]*t2*t15+P[5][6]*t2*t10+P[5][2]*t2*t19-P[5][3]*t2*t22); +A0[6][0] = t78*(t70+P[6][0]*t2*t5-P[6][4]*t2*t7+P[6][1]*t2*t15+P[6][2]*t2*t19-P[6][3]*t2*t22+P[6][5]*t2*t27); +A0[7][0] = t78*(P[7][0]*t2*t5-P[7][4]*t2*t7+P[7][1]*t2*t15+P[7][6]*t2*t10+P[7][2]*t2*t19-P[7][3]*t2*t22+P[7][5]*t2*t27); +A0[8][0] = t78*(P[8][0]*t2*t5-P[8][4]*t2*t7+P[8][1]*t2*t15+P[8][6]*t2*t10+P[8][2]*t2*t19-P[8][3]*t2*t22+P[8][5]*t2*t27); +A0[9][0] = t78*(P[9][0]*t2*t5-P[9][4]*t2*t7+P[9][1]*t2*t15+P[9][6]*t2*t10+P[9][2]*t2*t19-P[9][3]*t2*t22+P[9][5]*t2*t27); +A0[10][0] = t78*(P[10][0]*t2*t5-P[10][4]*t2*t7+P[10][1]*t2*t15+P[10][6]*t2*t10+P[10][2]*t2*t19-P[10][3]*t2*t22+P[10][5]*t2*t27); +A0[11][0] = t78*(P[11][0]*t2*t5-P[11][4]*t2*t7+P[11][1]*t2*t15+P[11][6]*t2*t10+P[11][2]*t2*t19-P[11][3]*t2*t22+P[11][5]*t2*t27); +A0[12][0] = t78*(P[12][0]*t2*t5-P[12][4]*t2*t7+P[12][1]*t2*t15+P[12][6]*t2*t10+P[12][2]*t2*t19-P[12][3]*t2*t22+P[12][5]*t2*t27); +A0[13][0] = t78*(P[13][0]*t2*t5-P[13][4]*t2*t7+P[13][1]*t2*t15+P[13][6]*t2*t10+P[13][2]*t2*t19-P[13][3]*t2*t22+P[13][5]*t2*t27); +A0[14][0] = t78*(P[14][0]*t2*t5-P[14][4]*t2*t7+P[14][1]*t2*t15+P[14][6]*t2*t10+P[14][2]*t2*t19-P[14][3]*t2*t22+P[14][5]*t2*t27); +A0[15][0] = t78*(P[15][0]*t2*t5-P[15][4]*t2*t7+P[15][1]*t2*t15+P[15][6]*t2*t10+P[15][2]*t2*t19-P[15][3]*t2*t22+P[15][5]*t2*t27); +A0[16][0] = t78*(P[16][0]*t2*t5-P[16][4]*t2*t7+P[16][1]*t2*t15+P[16][6]*t2*t10+P[16][2]*t2*t19-P[16][3]*t2*t22+P[16][5]*t2*t27); +A0[17][0] = t78*(P[17][0]*t2*t5-P[17][4]*t2*t7+P[17][1]*t2*t15+P[17][6]*t2*t10+P[17][2]*t2*t19-P[17][3]*t2*t22+P[17][5]*t2*t27); +A0[18][0] = t78*(P[18][0]*t2*t5-P[18][4]*t2*t7+P[18][1]*t2*t15+P[18][6]*t2*t10+P[18][2]*t2*t19-P[18][3]*t2*t22+P[18][5]*t2*t27); +A0[19][0] = t78*(P[19][0]*t2*t5-P[19][4]*t2*t7+P[19][1]*t2*t15+P[19][6]*t2*t10+P[19][2]*t2*t19-P[19][3]*t2*t22+P[19][5]*t2*t27); +A0[20][0] = t78*(P[20][0]*t2*t5-P[20][4]*t2*t7+P[20][1]*t2*t15+P[20][6]*t2*t10+P[20][2]*t2*t19-P[20][3]*t2*t22+P[20][5]*t2*t27); +A0[21][0] = t78*(P[21][0]*t2*t5-P[21][4]*t2*t7+P[21][1]*t2*t15+P[21][6]*t2*t10+P[21][2]*t2*t19-P[21][3]*t2*t22+P[21][5]*t2*t27); +A0[22][0] = t78*(P[22][0]*t2*t5-P[22][4]*t2*t7+P[22][1]*t2*t15+P[22][6]*t2*t10+P[22][2]*t2*t19-P[22][3]*t2*t22+P[22][5]*t2*t27); +A0[23][0] = t78*(P[23][0]*t2*t5-P[23][4]*t2*t7+P[23][1]*t2*t15+P[23][6]*t2*t10+P[23][2]*t2*t19-P[23][3]*t2*t22+P[23][5]*t2*t27); diff --git a/matlab/scripts/Inertial Nav EKF/K_LOSY.c b/matlab/scripts/Inertial Nav EKF/K_LOSY.c index abd0c8f983..8abde33643 100644 --- a/matlab/scripts/Inertial Nav EKF/K_LOSY.c +++ b/matlab/scripts/Inertial Nav EKF/K_LOSY.c @@ -1,89 +1,117 @@ t2 = 1.0/range; -t3 = q0*q2*2.0; -t4 = q0*q0; -t5 = q1*q1; -t6 = q2*q2; -t7 = q3*q3; -t8 = q0*q1*2.0; -t9 = q0*q3*2.0; -t10 = q1*q2*2.0; -t11 = t9+t10; -t12 = q1*q3*2.0; -t13 = t4-t5-t6+t7; -t14 = t13*vd; -t15 = q2*q3*2.0; -t16 = t3+t12; -t17 = t16*vn; -t18 = t4-t5+t6-t7; -t19 = t18*ve; -t20 = t8+t15; -t21 = t20*vd; -t22 = t9-t10; -t28 = t22*vn; -t23 = t19+t21-t28; -t24 = t4+t5-t6-t7; -t25 = t3-t12; -t26 = t8-t15; -t29 = t26*ve; -t27 = t14+t17-t29; -t30 = P[4][4]*t2*t11; -t31 = P[2][4]*t2*t23; -t32 = P[3][4]*t2*t24; -t56 = P[5][4]*t2*t25; -t57 = P[1][4]*t2*t27; -t33 = t30+t31+t32-t56-t57; -t34 = t2*t11*t33; -t35 = P[4][5]*t2*t11; -t36 = P[2][5]*t2*t23; -t37 = P[3][5]*t2*t24; -t58 = P[5][5]*t2*t25; -t59 = P[1][5]*t2*t27; -t38 = t35+t36+t37-t58-t59; -t39 = P[4][1]*t2*t11; -t40 = P[2][1]*t2*t23; -t41 = P[3][1]*t2*t24; -t55 = P[1][1]*t2*t27; -t61 = P[5][1]*t2*t25; -t42 = t39+t40+t41-t55-t61; -t43 = P[4][2]*t2*t11; -t44 = P[2][2]*t2*t23; -t45 = P[3][2]*t2*t24; -t63 = P[5][2]*t2*t25; -t64 = P[1][2]*t2*t27; -t46 = t43+t44+t45-t63-t64; -t47 = t2*t23*t46; -t48 = P[4][3]*t2*t11; -t49 = P[2][3]*t2*t23; -t50 = P[3][3]*t2*t24; -t65 = P[5][3]*t2*t25; -t66 = P[1][3]*t2*t27; -t51 = t48+t49+t50-t65-t66; -t52 = t2*t24*t51; -t60 = t2*t25*t38; -t62 = t2*t27*t42; -t53 = R_LOS+t34+t47+t52-t60-t62; -t54 = 1.0/t53; -A0[0][0] = -t54*(P[0][4]*t2*t11+P[0][2]*t2*t23+P[0][3]*t2*t24-P[0][1]*t2*t27-P[0][5]*t2*t25); -A0[1][0] = -t54*(-t55+P[1][4]*t2*t11+P[1][2]*t2*t23+P[1][3]*t2*t24-P[1][5]*t2*t25); -A0[2][0] = -t54*(t44+P[2][4]*t2*t11+P[2][3]*t2*t24-P[2][1]*t2*t27-P[2][5]*t2*t25); -A0[3][0] = -t54*(t50+P[3][4]*t2*t11+P[3][2]*t2*t23-P[3][1]*t2*t27-P[3][5]*t2*t25); -A0[4][0] = -t54*(t30+P[4][2]*t2*t23+P[4][3]*t2*t24-P[4][1]*t2*t27-P[4][5]*t2*t25); -A0[5][0] = -t54*(-t58+P[5][4]*t2*t11+P[5][2]*t2*t23+P[5][3]*t2*t24-P[5][1]*t2*t27); -A0[6][0] = -t54*(P[6][4]*t2*t11+P[6][2]*t2*t23+P[6][3]*t2*t24-P[6][1]*t2*t27-P[6][5]*t2*t25); -A0[7][0] = -t54*(P[7][4]*t2*t11+P[7][2]*t2*t23+P[7][3]*t2*t24-P[7][1]*t2*t27-P[7][5]*t2*t25); -A0[8][0] = -t54*(P[8][4]*t2*t11+P[8][2]*t2*t23+P[8][3]*t2*t24-P[8][1]*t2*t27-P[8][5]*t2*t25); -A0[9][0] = -t54*(P[9][4]*t2*t11+P[9][2]*t2*t23+P[9][3]*t2*t24-P[9][1]*t2*t27-P[9][5]*t2*t25); -A0[10][0] = -t54*(P[10][4]*t2*t11+P[10][2]*t2*t23+P[10][3]*t2*t24-P[10][1]*t2*t27-P[10][5]*t2*t25); -A0[11][0] = -t54*(P[11][4]*t2*t11+P[11][2]*t2*t23+P[11][3]*t2*t24-P[11][1]*t2*t27-P[11][5]*t2*t25); -A0[12][0] = -t54*(P[12][4]*t2*t11+P[12][2]*t2*t23+P[12][3]*t2*t24-P[12][1]*t2*t27-P[12][5]*t2*t25); -A0[13][0] = -t54*(P[13][4]*t2*t11+P[13][2]*t2*t23+P[13][3]*t2*t24-P[13][1]*t2*t27-P[13][5]*t2*t25); -A0[14][0] = -t54*(P[14][4]*t2*t11+P[14][2]*t2*t23+P[14][3]*t2*t24-P[14][1]*t2*t27-P[14][5]*t2*t25); -A0[15][0] = -t54*(P[15][4]*t2*t11+P[15][2]*t2*t23+P[15][3]*t2*t24-P[15][1]*t2*t27-P[15][5]*t2*t25); -A0[16][0] = -t54*(P[16][4]*t2*t11+P[16][2]*t2*t23+P[16][3]*t2*t24-P[16][1]*t2*t27-P[16][5]*t2*t25); -A0[17][0] = -t54*(P[17][4]*t2*t11+P[17][2]*t2*t23+P[17][3]*t2*t24-P[17][1]*t2*t27-P[17][5]*t2*t25); -A0[18][0] = -t54*(P[18][4]*t2*t11+P[18][2]*t2*t23+P[18][3]*t2*t24-P[18][1]*t2*t27-P[18][5]*t2*t25); -A0[19][0] = -t54*(P[19][4]*t2*t11+P[19][2]*t2*t23+P[19][3]*t2*t24-P[19][1]*t2*t27-P[19][5]*t2*t25); -A0[20][0] = -t54*(P[20][4]*t2*t11+P[20][2]*t2*t23+P[20][3]*t2*t24-P[20][1]*t2*t27-P[20][5]*t2*t25); -A0[21][0] = -t54*(P[21][4]*t2*t11+P[21][2]*t2*t23+P[21][3]*t2*t24-P[21][1]*t2*t27-P[21][5]*t2*t25); -A0[22][0] = -t54*(P[22][4]*t2*t11+P[22][2]*t2*t23+P[22][3]*t2*t24-P[22][1]*t2*t27-P[22][5]*t2*t25); -A0[23][0] = -t54*(P[23][4]*t2*t11+P[23][2]*t2*t23+P[23][3]*t2*t24-P[23][1]*t2*t27-P[23][5]*t2*t25); +t3 = q3*ve*2.0; +t4 = q0*vn*2.0; +t11 = q2*vd*2.0; +t5 = t3+t4-t11; +t6 = q0*q3*2.0; +t7 = q1*q2*2.0; +t8 = t6+t7; +t9 = q0*q2*2.0; +t28 = q1*q3*2.0; +t10 = t9-t28; +t12 = P[0][0]*t2*t5; +t13 = q3*vd*2.0; +t14 = q2*ve*2.0; +t15 = q1*vn*2.0; +t16 = t13+t14+t15; +t17 = q0*vd*2.0; +t18 = q2*vn*2.0; +t29 = q1*ve*2.0; +t19 = t17+t18-t29; +t20 = q1*vd*2.0; +t21 = q0*ve*2.0; +t30 = q3*vn*2.0; +t22 = t20+t21-t30; +t23 = q0*q0; +t24 = q1*q1; +t25 = q2*q2; +t26 = q3*q3; +t27 = t23+t24-t25-t26; +t31 = P[1][1]*t2*t16; +t32 = P[5][0]*t2*t8; +t33 = P[1][0]*t2*t16; +t34 = P[3][0]*t2*t22; +t35 = P[4][0]*t2*t27; +t80 = P[6][0]*t2*t10; +t81 = P[2][0]*t2*t19; +t36 = t12+t32+t33+t34+t35-t80-t81; +t37 = t2*t5*t36; +t38 = P[5][1]*t2*t8; +t39 = P[0][1]*t2*t5; +t40 = P[3][1]*t2*t22; +t41 = P[4][1]*t2*t27; +t82 = P[6][1]*t2*t10; +t83 = P[2][1]*t2*t19; +t42 = t31+t38+t39+t40+t41-t82-t83; +t43 = t2*t16*t42; +t44 = P[5][2]*t2*t8; +t45 = P[0][2]*t2*t5; +t46 = P[1][2]*t2*t16; +t47 = P[3][2]*t2*t22; +t48 = P[4][2]*t2*t27; +t79 = P[2][2]*t2*t19; +t84 = P[6][2]*t2*t10; +t49 = t44+t45+t46+t47+t48-t79-t84; +t50 = P[5][3]*t2*t8; +t51 = P[0][3]*t2*t5; +t52 = P[1][3]*t2*t16; +t53 = P[3][3]*t2*t22; +t54 = P[4][3]*t2*t27; +t86 = P[6][3]*t2*t10; +t87 = P[2][3]*t2*t19; +t55 = t50+t51+t52+t53+t54-t86-t87; +t56 = t2*t22*t55; +t57 = P[5][4]*t2*t8; +t58 = P[0][4]*t2*t5; +t59 = P[1][4]*t2*t16; +t60 = P[3][4]*t2*t22; +t61 = P[4][4]*t2*t27; +t88 = P[6][4]*t2*t10; +t89 = P[2][4]*t2*t19; +t62 = t57+t58+t59+t60+t61-t88-t89; +t63 = t2*t27*t62; +t64 = P[5][5]*t2*t8; +t65 = P[0][5]*t2*t5; +t66 = P[1][5]*t2*t16; +t67 = P[3][5]*t2*t22; +t68 = P[4][5]*t2*t27; +t90 = P[6][5]*t2*t10; +t91 = P[2][5]*t2*t19; +t69 = t64+t65+t66+t67+t68-t90-t91; +t70 = t2*t8*t69; +t71 = P[5][6]*t2*t8; +t72 = P[0][6]*t2*t5; +t73 = P[1][6]*t2*t16; +t74 = P[3][6]*t2*t22; +t75 = P[4][6]*t2*t27; +t92 = P[6][6]*t2*t10; +t93 = P[2][6]*t2*t19; +t76 = t71+t72+t73+t74+t75-t92-t93; +t85 = t2*t19*t49; +t94 = t2*t10*t76; +t77 = R_LOS+t37+t43+t56+t63+t70-t85-t94; +t78 = 1.0/t77; +A0[0][0] = -t78*(t12+P[0][5]*t2*t8-P[0][6]*t2*t10+P[0][1]*t2*t16-P[0][2]*t2*t19+P[0][3]*t2*t22+P[0][4]*t2*t27); +A0[1][0] = -t78*(t31+P[1][0]*t2*t5+P[1][5]*t2*t8-P[1][6]*t2*t10-P[1][2]*t2*t19+P[1][3]*t2*t22+P[1][4]*t2*t27); +A0[2][0] = -t78*(-t79+P[2][0]*t2*t5+P[2][5]*t2*t8-P[2][6]*t2*t10+P[2][1]*t2*t16+P[2][3]*t2*t22+P[2][4]*t2*t27); +A0[3][0] = -t78*(t53+P[3][0]*t2*t5+P[3][5]*t2*t8-P[3][6]*t2*t10+P[3][1]*t2*t16-P[3][2]*t2*t19+P[3][4]*t2*t27); +A0[4][0] = -t78*(t61+P[4][0]*t2*t5+P[4][5]*t2*t8-P[4][6]*t2*t10+P[4][1]*t2*t16-P[4][2]*t2*t19+P[4][3]*t2*t22); +A0[5][0] = -t78*(t64+P[5][0]*t2*t5-P[5][6]*t2*t10+P[5][1]*t2*t16-P[5][2]*t2*t19+P[5][3]*t2*t22+P[5][4]*t2*t27); +A0[6][0] = -t78*(-t92+P[6][0]*t2*t5+P[6][5]*t2*t8+P[6][1]*t2*t16-P[6][2]*t2*t19+P[6][3]*t2*t22+P[6][4]*t2*t27); +A0[7][0] = -t78*(P[7][0]*t2*t5+P[7][5]*t2*t8-P[7][6]*t2*t10+P[7][1]*t2*t16-P[7][2]*t2*t19+P[7][3]*t2*t22+P[7][4]*t2*t27); +A0[8][0] = -t78*(P[8][0]*t2*t5+P[8][5]*t2*t8-P[8][6]*t2*t10+P[8][1]*t2*t16-P[8][2]*t2*t19+P[8][3]*t2*t22+P[8][4]*t2*t27); +A0[9][0] = -t78*(P[9][0]*t2*t5+P[9][5]*t2*t8-P[9][6]*t2*t10+P[9][1]*t2*t16-P[9][2]*t2*t19+P[9][3]*t2*t22+P[9][4]*t2*t27); +A0[10][0] = -t78*(P[10][0]*t2*t5+P[10][5]*t2*t8-P[10][6]*t2*t10+P[10][1]*t2*t16-P[10][2]*t2*t19+P[10][3]*t2*t22+P[10][4]*t2*t27); +A0[11][0] = -t78*(P[11][0]*t2*t5+P[11][5]*t2*t8-P[11][6]*t2*t10+P[11][1]*t2*t16-P[11][2]*t2*t19+P[11][3]*t2*t22+P[11][4]*t2*t27); +A0[12][0] = -t78*(P[12][0]*t2*t5+P[12][5]*t2*t8-P[12][6]*t2*t10+P[12][1]*t2*t16-P[12][2]*t2*t19+P[12][3]*t2*t22+P[12][4]*t2*t27); +A0[13][0] = -t78*(P[13][0]*t2*t5+P[13][5]*t2*t8-P[13][6]*t2*t10+P[13][1]*t2*t16-P[13][2]*t2*t19+P[13][3]*t2*t22+P[13][4]*t2*t27); +A0[14][0] = -t78*(P[14][0]*t2*t5+P[14][5]*t2*t8-P[14][6]*t2*t10+P[14][1]*t2*t16-P[14][2]*t2*t19+P[14][3]*t2*t22+P[14][4]*t2*t27); +A0[15][0] = -t78*(P[15][0]*t2*t5+P[15][5]*t2*t8-P[15][6]*t2*t10+P[15][1]*t2*t16-P[15][2]*t2*t19+P[15][3]*t2*t22+P[15][4]*t2*t27); +A0[16][0] = -t78*(P[16][0]*t2*t5+P[16][5]*t2*t8-P[16][6]*t2*t10+P[16][1]*t2*t16-P[16][2]*t2*t19+P[16][3]*t2*t22+P[16][4]*t2*t27); +A0[17][0] = -t78*(P[17][0]*t2*t5+P[17][5]*t2*t8-P[17][6]*t2*t10+P[17][1]*t2*t16-P[17][2]*t2*t19+P[17][3]*t2*t22+P[17][4]*t2*t27); +A0[18][0] = -t78*(P[18][0]*t2*t5+P[18][5]*t2*t8-P[18][6]*t2*t10+P[18][1]*t2*t16-P[18][2]*t2*t19+P[18][3]*t2*t22+P[18][4]*t2*t27); +A0[19][0] = -t78*(P[19][0]*t2*t5+P[19][5]*t2*t8-P[19][6]*t2*t10+P[19][1]*t2*t16-P[19][2]*t2*t19+P[19][3]*t2*t22+P[19][4]*t2*t27); +A0[20][0] = -t78*(P[20][0]*t2*t5+P[20][5]*t2*t8-P[20][6]*t2*t10+P[20][1]*t2*t16-P[20][2]*t2*t19+P[20][3]*t2*t22+P[20][4]*t2*t27); +A0[21][0] = -t78*(P[21][0]*t2*t5+P[21][5]*t2*t8-P[21][6]*t2*t10+P[21][1]*t2*t16-P[21][2]*t2*t19+P[21][3]*t2*t22+P[21][4]*t2*t27); +A0[22][0] = -t78*(P[22][0]*t2*t5+P[22][5]*t2*t8-P[22][6]*t2*t10+P[22][1]*t2*t16-P[22][2]*t2*t19+P[22][3]*t2*t22+P[22][4]*t2*t27); +A0[23][0] = -t78*(P[23][0]*t2*t5+P[23][5]*t2*t8-P[23][6]*t2*t10+P[23][1]*t2*t16-P[23][2]*t2*t19+P[23][3]*t2*t22+P[23][4]*t2*t27); diff --git a/matlab/scripts/Inertial Nav EKF/M_code24.txt b/matlab/scripts/Inertial Nav EKF/M_code24.txt index 00527b0767..aa51c6ff7e 100644 --- a/matlab/scripts/Inertial Nav EKF/M_code24.txt +++ b/matlab/scripts/Inertial Nav EKF/M_code24.txt @@ -1,217 +1,205 @@ -SF = zeros(25,1); -SF(1) = daz_b/2 + dazNoise/2 - (daz*daz_s)/2; -SF(2) = day_b/2 + dayNoise/2 - (day*day_s)/2; -SF(3) = dax_b/2 + daxNoise/2 - (dax*dax_s)/2; -SF(4) = q3/2 - (q0*SF(1))/2 + (q1*SF(2))/2 - (q2*SF(3))/2; -SF(5) = q0/2 - (q1*SF(3))/2 - (q2*SF(2))/2 + (q3*SF(1))/2; -SF(6) = q1/2 + (q0*SF(3))/2 - (q2*SF(1))/2 - (q3*SF(2))/2; -SF(7) = q3/2 + (q0*SF(1))/2 - (q1*SF(2))/2 - (q2*SF(3))/2; -SF(8) = q0/2 - (q1*SF(3))/2 + (q2*SF(2))/2 - (q3*SF(1))/2; -SF(9) = q0/2 + (q1*SF(3))/2 - (q2*SF(2))/2 - (q3*SF(1))/2; -SF(10) = q2/2 + (q0*SF(2))/2 + (q1*SF(1))/2 + (q3*SF(3))/2; -SF(11) = q2/2 - (q0*SF(2))/2 - (q1*SF(1))/2 + (q3*SF(3))/2; -SF(12) = q2/2 + (q0*SF(2))/2 - (q1*SF(1))/2 - (q3*SF(3))/2; -SF(13) = q1/2 + (q0*SF(3))/2 + (q2*SF(1))/2 + (q3*SF(2))/2; -SF(14) = q1/2 - (q0*SF(3))/2 + (q2*SF(1))/2 - (q3*SF(2))/2; -SF(15) = q3/2 + (q0*SF(1))/2 + (q1*SF(2))/2 + (q2*SF(3))/2; -SF(16) = - q0^2 - q1^2 - q2^2 - q3^2; -SF(17) = dvz_b - dvz + dvzNoise; -SF(18) = dvx - dvxNoise; -SF(19) = dvy - dvyNoise; -SF(20) = q2^2; -SF(21) = SF(20) - q0^2 + q1^2 - q3^2; -SF(22) = SF(20) + q0^2 - q1^2 - q3^2; -SF(23) = 2*q0*q1 - 2*q2*q3; -SF(24) = SF(20) - q0^2 - q1^2 + q3^2; -SF(25) = 2*q1*q2; -SG = zeros(5,1); -SG(1) = - q0^2 - q1^2 - q2^2 - q3^2; +SF = zeros(21,1); +SF(1) = dvz - dvz_b; +SF(2) = dvy - dvy_b; +SF(3) = dvx - dvx_b; +SF(4) = 2*q1*SF(3) + 2*q2*SF(2) + 2*q3*SF(1); +SF(5) = 2*q0*SF(2) - 2*q1*SF(1) + 2*q3*SF(3); +SF(6) = 2*q0*SF(3) + 2*q2*SF(1) - 2*q3*SF(2); +SF(7) = day/2 - day_b/2; +SF(8) = daz/2 - daz_b/2; +SF(9) = dax/2 - dax_b/2; +SF(10) = dax_b/2 - dax/2; +SF(11) = daz_b/2 - daz/2; +SF(12) = day_b/2 - day/2; +SF(13) = 2*q1*SF(2); +SF(14) = 2*q0*SF(1); +SF(15) = q1/2; +SF(16) = q2/2; +SF(17) = q3/2; +SF(18) = q3^2; +SF(19) = q2^2; +SF(20) = q1^2; +SF(21) = q0^2; +SG = zeros(8,1); +SG(1) = q0/2; SG(2) = q3^2; SG(3) = q2^2; SG(4) = q1^2; SG(5) = q0^2; -SQ = zeros(10,1); -SQ(1) = - dvyNoise^2*(2*q0*q1 + 2*q2*q3)*(SG(2) - SG(3) + SG(4) - SG(5)) - dvzNoise^2*(2*q0*q1 - 2*q2*q3)*(SG(2) - SG(3) - SG(4) + SG(5)) - dvxNoise^2*(2*q0*q2 - 2*q1*q3)*(2*q0*q3 + 2*q1*q2); -SQ(2) = dvxNoise^2*(2*q0*q2 - 2*q1*q3)*(SG(2) + SG(3) - SG(4) - SG(5)) + dvzNoise^2*(2*q0*q2 + 2*q1*q3)*(SG(2) - SG(3) - SG(4) + SG(5)) - dvyNoise^2*(2*q0*q1 + 2*q2*q3)*(2*q0*q3 - 2*q1*q2); -SQ(3) = dvyNoise^2*(2*q0*q3 - 2*q1*q2)*(SG(2) - SG(3) + SG(4) - SG(5)) - dvxNoise^2*(2*q0*q3 + 2*q1*q2)*(SG(2) + SG(3) - SG(4) - SG(5)) - dvzNoise^2*(2*q0*q1 - 2*q2*q3)*(2*q0*q2 + 2*q1*q3); -SQ(4) = SG(1)^2; -SQ(5) = dvyNoise^2; -SQ(6) = dvzNoise^2; -SQ(7) = dvxNoise^2; -SQ(8) = 2*q2*q3; -SQ(9) = 2*q1*q3; -SQ(10) = 2*q1*q2; -SPP = zeros(23,1); -SPP(1) = SF(18)*(2*q0*q1 + 2*q2*q3) + SF(19)*(2*q0*q2 - 2*q1*q3); -SPP(2) = SF(19)*(2*q0*q2 + 2*q1*q3) + SF(17)*(SF(25) - 2*q0*q3); -SPP(3) = 2*q3*SF(9) + 2*q1*SF(12) - 2*q0*SF(15) - 2*q2*SF(14); -SPP(4) = 2*q1*SF(8) + 2*q2*SF(7) - 2*q0*SF(13) - 2*q3*SF(11); -SPP(5) = 2*q0*SF(7) - 2*q3*SF(8) - 2*q1*SF(11) + 2*q2*SF(13); -SPP(6) = 2*q0*SF(9) + 2*q2*SF(12) + 2*q1*SF(14) + 2*q3*SF(15); -SPP(7) = 2*q0*SF(8) + 2*q3*SF(7) + 2*q2*SF(11) + 2*q1*SF(13); -SPP(8) = 2*q1*SF(4) - 2*q2*SF(5) - 2*q3*SF(6) + 2*q0*SF(10); -SPP(9) = 2*q0*SF(6) - 2*q1*SF(5) - 2*q2*SF(4) + 2*q3*SF(10); -SPP(10) = SF(19)*SF(21) - SF(17)*(2*q0*q1 + 2*q2*q3); -SPP(11) = SF(18)*SF(21) + SF(17)*(2*q0*q2 - 2*q1*q3); -SPP(12) = SF(18)*SF(22) - SF(19)*(SF(25) + 2*q0*q3); -SPP(13) = SF(18)*SF(23) - SF(17)*(SF(25) + 2*q0*q3); -SPP(14) = 2*q0*SF(5) + 2*q1*SF(6) + 2*q3*SF(4) + 2*q2*SF(10); -SPP(15) = 2*q2*SF(9) - 2*q0*SF(12) - 2*q1*SF(15) + 2*q3*SF(14); -SPP(16) = SF(19)*SF(24) + SF(18)*(SF(25) - 2*q0*q3); -SPP(17) = daz*SF(20) + daz*q0^2 + daz*q1^2 + daz*q3^2; -SPP(18) = day*SF(20) + day*q0^2 + day*q1^2 + day*q3^2; -SPP(19) = dax*SF(20) + dax*q0^2 + dax*q1^2 + dax*q3^2; -SPP(20) = SF(17)*SF(24) - SF(18)*(2*q0*q2 + 2*q1*q3); -SPP(21) = SF(17)*SF(22) - SF(19)*SF(23); -SPP(22) = 2*q0*q2 + 2*q1*q3; -SPP(23) = SF(16); +SG(6) = 2*q2*q3; +SG(7) = 2*q1*q3; +SG(8) = 2*q1*q2; +SQ = zeros(11,1); +SQ(1) = dvzVar*(SG(6) - 2*q0*q1)*(SG(2) - SG(3) - SG(4) + SG(5)) - dvyVar*(SG(6) + 2*q0*q1)*(SG(2) - SG(3) + SG(4) - SG(5)) + dvxVar*(SG(7) - 2*q0*q2)*(SG(8) + 2*q0*q3); +SQ(2) = dvzVar*(SG(7) + 2*q0*q2)*(SG(2) - SG(3) - SG(4) + SG(5)) - dvxVar*(SG(7) - 2*q0*q2)*(SG(2) + SG(3) - SG(4) - SG(5)) + dvyVar*(SG(6) + 2*q0*q1)*(SG(8) - 2*q0*q3); +SQ(3) = dvzVar*(SG(6) - 2*q0*q1)*(SG(7) + 2*q0*q2) - dvyVar*(SG(8) - 2*q0*q3)*(SG(2) - SG(3) + SG(4) - SG(5)) - dvxVar*(SG(8) + 2*q0*q3)*(SG(2) + SG(3) - SG(4) - SG(5)); +SQ(4) = (dayVar*q1*SG(1))/2 - (dazVar*q1*SG(1))/2 - (daxVar*q2*q3)/4; +SQ(5) = (dazVar*q2*SG(1))/2 - (daxVar*q2*SG(1))/2 - (dayVar*q1*q3)/4; +SQ(6) = (daxVar*q3*SG(1))/2 - (dayVar*q3*SG(1))/2 - (dazVar*q1*q2)/4; +SQ(7) = (daxVar*q1*q2)/4 - (dazVar*q3*SG(1))/2 - (dayVar*q1*q2)/4; +SQ(8) = (dazVar*q1*q3)/4 - (daxVar*q1*q3)/4 - (dayVar*q2*SG(1))/2; +SQ(9) = (dayVar*q2*q3)/4 - (daxVar*q1*SG(1))/2 - (dazVar*q2*q3)/4; +SQ(10) = SG(1)^2; +SQ(11) = q1^2; +SPP = zeros(11,1); +SPP(1) = SF(13) + SF(14) - 2*q2*SF(3); +SPP(2) = SF(18) - SF(19) - SF(20) + SF(21); +SPP(3) = SF(18) - SF(19) + SF(20) - SF(21); +SPP(4) = SF(18) + SF(19) - SF(20) - SF(21); +SPP(5) = 2*q0*q2 - 2*q1*q3; +SPP(6) = 2*q0*q1 - 2*q2*q3; +SPP(7) = 2*q0*q3 - 2*q1*q2; +SPP(8) = 2*q0*q1 + 2*q2*q3; +SPP(9) = 2*q0*q3 + 2*q1*q2; +SPP(10) = 2*q0*q2 + 2*q1*q3; +SPP(11) = SF(17); nextP = zeros(24,24); -nextP(1,1) = SPP(6)*(OP(1,1)*SPP(6) - OP(2,1)*SPP(5) + OP(3,1)*SPP(8) + OP(10,1)*SPP(23) + OP(13,1)*SPP(19)) - SPP(5)*(OP(1,2)*SPP(6) - OP(2,2)*SPP(5) + OP(3,2)*SPP(8) + OP(10,2)*SPP(23) + OP(13,2)*SPP(19)) + SPP(8)*(OP(1,3)*SPP(6) - OP(2,3)*SPP(5) + OP(3,3)*SPP(8) + OP(10,3)*SPP(23) + OP(13,3)*SPP(19)) + SPP(23)*(OP(1,10)*SPP(6) - OP(2,10)*SPP(5) + OP(3,10)*SPP(8) + OP(10,10)*SPP(23) + OP(13,10)*SPP(19)) + SPP(19)*(OP(1,13)*SPP(6) - OP(2,13)*SPP(5) + OP(3,13)*SPP(8) + OP(10,13)*SPP(23) + OP(13,13)*SPP(19)) + daxNoise^2*SQ(4); -nextP(1,2) = SPP(7)*(OP(1,2)*SPP(6) - OP(2,2)*SPP(5) + OP(3,2)*SPP(8) + OP(10,2)*SPP(23) + OP(13,2)*SPP(19)) - SPP(3)*(OP(1,1)*SPP(6) - OP(2,1)*SPP(5) + OP(3,1)*SPP(8) + OP(10,1)*SPP(23) + OP(13,1)*SPP(19)) - SPP(9)*(OP(1,3)*SPP(6) - OP(2,3)*SPP(5) + OP(3,3)*SPP(8) + OP(10,3)*SPP(23) + OP(13,3)*SPP(19)) + SPP(23)*(OP(1,11)*SPP(6) - OP(2,11)*SPP(5) + OP(3,11)*SPP(8) + OP(10,11)*SPP(23) + OP(13,11)*SPP(19)) + SPP(18)*(OP(1,14)*SPP(6) - OP(2,14)*SPP(5) + OP(3,14)*SPP(8) + OP(10,14)*SPP(23) + OP(13,14)*SPP(19)); -nextP(2,2) = SPP(7)*(OP(2,2)*SPP(7) - OP(1,2)*SPP(3) - OP(3,2)*SPP(9) + OP(11,2)*SPP(23) + OP(14,2)*SPP(18)) - SPP(3)*(OP(2,1)*SPP(7) - OP(1,1)*SPP(3) - OP(3,1)*SPP(9) + OP(11,1)*SPP(23) + OP(14,1)*SPP(18)) - SPP(9)*(OP(2,3)*SPP(7) - OP(1,3)*SPP(3) - OP(3,3)*SPP(9) + OP(11,3)*SPP(23) + OP(14,3)*SPP(18)) + SPP(23)*(OP(2,11)*SPP(7) - OP(1,11)*SPP(3) - OP(3,11)*SPP(9) + OP(11,11)*SPP(23) + OP(14,11)*SPP(18)) + SPP(18)*(OP(2,14)*SPP(7) - OP(1,14)*SPP(3) - OP(3,14)*SPP(9) + OP(11,14)*SPP(23) + OP(14,14)*SPP(18)) + dayNoise^2*SQ(4); -nextP(1,3) = SPP(15)*(OP(1,1)*SPP(6) - OP(2,1)*SPP(5) + OP(3,1)*SPP(8) + OP(10,1)*SPP(23) + OP(13,1)*SPP(19)) - SPP(4)*(OP(1,2)*SPP(6) - OP(2,2)*SPP(5) + OP(3,2)*SPP(8) + OP(10,2)*SPP(23) + OP(13,2)*SPP(19)) + SPP(14)*(OP(1,3)*SPP(6) - OP(2,3)*SPP(5) + OP(3,3)*SPP(8) + OP(10,3)*SPP(23) + OP(13,3)*SPP(19)) + SPP(23)*(OP(1,12)*SPP(6) - OP(2,12)*SPP(5) + OP(3,12)*SPP(8) + OP(10,12)*SPP(23) + OP(13,12)*SPP(19)) + SPP(17)*(OP(1,15)*SPP(6) - OP(2,15)*SPP(5) + OP(3,15)*SPP(8) + OP(10,15)*SPP(23) + OP(13,15)*SPP(19)); -nextP(2,3) = SPP(15)*(OP(2,1)*SPP(7) - OP(1,1)*SPP(3) - OP(3,1)*SPP(9) + OP(11,1)*SPP(23) + OP(14,1)*SPP(18)) - SPP(4)*(OP(2,2)*SPP(7) - OP(1,2)*SPP(3) - OP(3,2)*SPP(9) + OP(11,2)*SPP(23) + OP(14,2)*SPP(18)) + SPP(14)*(OP(2,3)*SPP(7) - OP(1,3)*SPP(3) - OP(3,3)*SPP(9) + OP(11,3)*SPP(23) + OP(14,3)*SPP(18)) + SPP(23)*(OP(2,12)*SPP(7) - OP(1,12)*SPP(3) - OP(3,12)*SPP(9) + OP(11,12)*SPP(23) + OP(14,12)*SPP(18)) + SPP(17)*(OP(2,15)*SPP(7) - OP(1,15)*SPP(3) - OP(3,15)*SPP(9) + OP(11,15)*SPP(23) + OP(14,15)*SPP(18)); -nextP(3,3) = SPP(15)*(OP(1,1)*SPP(15) - OP(2,1)*SPP(4) + OP(3,1)*SPP(14) + OP(12,1)*SPP(23) + OP(15,1)*SPP(17)) - SPP(4)*(OP(1,2)*SPP(15) - OP(2,2)*SPP(4) + OP(3,2)*SPP(14) + OP(12,2)*SPP(23) + OP(15,2)*SPP(17)) + SPP(14)*(OP(1,3)*SPP(15) - OP(2,3)*SPP(4) + OP(3,3)*SPP(14) + OP(12,3)*SPP(23) + OP(15,3)*SPP(17)) + SPP(23)*(OP(1,12)*SPP(15) - OP(2,12)*SPP(4) + OP(3,12)*SPP(14) + OP(12,12)*SPP(23) + OP(15,12)*SPP(17)) + SPP(17)*(OP(1,15)*SPP(15) - OP(2,15)*SPP(4) + OP(3,15)*SPP(14) + OP(12,15)*SPP(23) + OP(15,15)*SPP(17)) + dazNoise^2*SQ(4); -nextP(1,4) = OP(1,4)*SPP(6) - OP(2,4)*SPP(5) + OP(3,4)*SPP(8) + OP(10,4)*SPP(23) + OP(13,4)*SPP(19) + SPP(2)*(OP(1,1)*SPP(6) - OP(2,1)*SPP(5) + OP(3,1)*SPP(8) + OP(10,1)*SPP(23) + OP(13,1)*SPP(19)) + SPP(20)*(OP(1,2)*SPP(6) - OP(2,2)*SPP(5) + OP(3,2)*SPP(8) + OP(10,2)*SPP(23) + OP(13,2)*SPP(19)) + SPP(16)*(OP(1,3)*SPP(6) - OP(2,3)*SPP(5) + OP(3,3)*SPP(8) + OP(10,3)*SPP(23) + OP(13,3)*SPP(19)) - SPP(22)*(OP(1,16)*SPP(6) - OP(2,16)*SPP(5) + OP(3,16)*SPP(8) + OP(10,16)*SPP(23) + OP(13,16)*SPP(19)); -nextP(2,4) = OP(2,4)*SPP(7) - OP(1,4)*SPP(3) - OP(3,4)*SPP(9) + OP(11,4)*SPP(23) + OP(14,4)*SPP(18) + SPP(2)*(OP(2,1)*SPP(7) - OP(1,1)*SPP(3) - OP(3,1)*SPP(9) + OP(11,1)*SPP(23) + OP(14,1)*SPP(18)) + SPP(20)*(OP(2,2)*SPP(7) - OP(1,2)*SPP(3) - OP(3,2)*SPP(9) + OP(11,2)*SPP(23) + OP(14,2)*SPP(18)) + SPP(16)*(OP(2,3)*SPP(7) - OP(1,3)*SPP(3) - OP(3,3)*SPP(9) + OP(11,3)*SPP(23) + OP(14,3)*SPP(18)) - SPP(22)*(OP(2,16)*SPP(7) - OP(1,16)*SPP(3) - OP(3,16)*SPP(9) + OP(11,16)*SPP(23) + OP(14,16)*SPP(18)); -nextP(3,4) = OP(1,4)*SPP(15) - OP(2,4)*SPP(4) + OP(3,4)*SPP(14) + OP(12,4)*SPP(23) + OP(15,4)*SPP(17) + SPP(2)*(OP(1,1)*SPP(15) - OP(2,1)*SPP(4) + OP(3,1)*SPP(14) + OP(12,1)*SPP(23) + OP(15,1)*SPP(17)) + SPP(20)*(OP(1,2)*SPP(15) - OP(2,2)*SPP(4) + OP(3,2)*SPP(14) + OP(12,2)*SPP(23) + OP(15,2)*SPP(17)) + SPP(16)*(OP(1,3)*SPP(15) - OP(2,3)*SPP(4) + OP(3,3)*SPP(14) + OP(12,3)*SPP(23) + OP(15,3)*SPP(17)) - SPP(22)*(OP(1,16)*SPP(15) - OP(2,16)*SPP(4) + OP(3,16)*SPP(14) + OP(12,16)*SPP(23) + OP(15,16)*SPP(17)); -nextP(4,4) = OP(4,4) + OP(1,4)*SPP(2) + OP(2,4)*SPP(20) + OP(3,4)*SPP(16) - OP(16,4)*SPP(22) + SQ(6)*(SQ(9) + 2*q0*q2)^2 + SQ(5)*(SQ(10) - 2*q0*q3)^2 + SPP(2)*(OP(4,1) + OP(1,1)*SPP(2) + OP(2,1)*SPP(20) + OP(3,1)*SPP(16) - OP(16,1)*SPP(22)) + SPP(20)*(OP(4,2) + OP(1,2)*SPP(2) + OP(2,2)*SPP(20) + OP(3,2)*SPP(16) - OP(16,2)*SPP(22)) + SPP(16)*(OP(4,3) + OP(1,3)*SPP(2) + OP(2,3)*SPP(20) + OP(3,3)*SPP(16) - OP(16,3)*SPP(22)) - SPP(22)*(OP(4,16) + OP(1,16)*SPP(2) + OP(2,16)*SPP(20) + OP(3,16)*SPP(16) - OP(16,16)*SPP(22)) + SQ(7)*(SG(2) + SG(3) - SG(4) - SG(5))^2; -nextP(1,5) = OP(1,5)*SPP(6) - OP(2,5)*SPP(5) + OP(3,5)*SPP(8) + OP(10,5)*SPP(23) + OP(13,5)*SPP(19) + SF(23)*(OP(1,16)*SPP(6) - OP(2,16)*SPP(5) + OP(3,16)*SPP(8) + OP(10,16)*SPP(23) + OP(13,16)*SPP(19)) + SPP(13)*(OP(1,2)*SPP(6) - OP(2,2)*SPP(5) + OP(3,2)*SPP(8) + OP(10,2)*SPP(23) + OP(13,2)*SPP(19)) + SPP(21)*(OP(1,1)*SPP(6) - OP(2,1)*SPP(5) + OP(3,1)*SPP(8) + OP(10,1)*SPP(23) + OP(13,1)*SPP(19)) + SPP(12)*(OP(1,3)*SPP(6) - OP(2,3)*SPP(5) + OP(3,3)*SPP(8) + OP(10,3)*SPP(23) + OP(13,3)*SPP(19)); -nextP(2,5) = OP(2,5)*SPP(7) - OP(1,5)*SPP(3) - OP(3,5)*SPP(9) + OP(11,5)*SPP(23) + OP(14,5)*SPP(18) + SF(23)*(OP(2,16)*SPP(7) - OP(1,16)*SPP(3) - OP(3,16)*SPP(9) + OP(11,16)*SPP(23) + OP(14,16)*SPP(18)) + SPP(13)*(OP(2,2)*SPP(7) - OP(1,2)*SPP(3) - OP(3,2)*SPP(9) + OP(11,2)*SPP(23) + OP(14,2)*SPP(18)) + SPP(21)*(OP(2,1)*SPP(7) - OP(1,1)*SPP(3) - OP(3,1)*SPP(9) + OP(11,1)*SPP(23) + OP(14,1)*SPP(18)) + SPP(12)*(OP(2,3)*SPP(7) - OP(1,3)*SPP(3) - OP(3,3)*SPP(9) + OP(11,3)*SPP(23) + OP(14,3)*SPP(18)); -nextP(3,5) = OP(1,5)*SPP(15) - OP(2,5)*SPP(4) + OP(3,5)*SPP(14) + OP(12,5)*SPP(23) + OP(15,5)*SPP(17) + SF(23)*(OP(1,16)*SPP(15) - OP(2,16)*SPP(4) + OP(3,16)*SPP(14) + OP(12,16)*SPP(23) + OP(15,16)*SPP(17)) + SPP(13)*(OP(1,2)*SPP(15) - OP(2,2)*SPP(4) + OP(3,2)*SPP(14) + OP(12,2)*SPP(23) + OP(15,2)*SPP(17)) + SPP(21)*(OP(1,1)*SPP(15) - OP(2,1)*SPP(4) + OP(3,1)*SPP(14) + OP(12,1)*SPP(23) + OP(15,1)*SPP(17)) + SPP(12)*(OP(1,3)*SPP(15) - OP(2,3)*SPP(4) + OP(3,3)*SPP(14) + OP(12,3)*SPP(23) + OP(15,3)*SPP(17)); -nextP(4,5) = OP(4,5) + SQ(3) + OP(1,5)*SPP(2) + OP(2,5)*SPP(20) + OP(3,5)*SPP(16) - OP(16,5)*SPP(22) + SF(23)*(OP(4,16) + OP(1,16)*SPP(2) + OP(2,16)*SPP(20) + OP(3,16)*SPP(16) - OP(16,16)*SPP(22)) + SPP(13)*(OP(4,2) + OP(1,2)*SPP(2) + OP(2,2)*SPP(20) + OP(3,2)*SPP(16) - OP(16,2)*SPP(22)) + SPP(21)*(OP(4,1) + OP(1,1)*SPP(2) + OP(2,1)*SPP(20) + OP(3,1)*SPP(16) - OP(16,1)*SPP(22)) + SPP(12)*(OP(4,3) + OP(1,3)*SPP(2) + OP(2,3)*SPP(20) + OP(3,3)*SPP(16) - OP(16,3)*SPP(22)); -nextP(5,5) = OP(5,5) + OP(16,5)*SF(23) + OP(1,5)*SPP(21) + OP(2,5)*SPP(13) + OP(3,5)*SPP(12) + SQ(6)*(SQ(8) - 2*q0*q1)^2 + SQ(7)*(SQ(10) + 2*q0*q3)^2 + SF(23)*(OP(5,16) + OP(16,16)*SF(23) + OP(1,16)*SPP(21) + OP(2,16)*SPP(13) + OP(3,16)*SPP(12)) + SPP(13)*(OP(5,2) + OP(16,2)*SF(23) + OP(1,2)*SPP(21) + OP(2,2)*SPP(13) + OP(3,2)*SPP(12)) + SPP(21)*(OP(5,1) + OP(16,1)*SF(23) + OP(1,1)*SPP(21) + OP(2,1)*SPP(13) + OP(3,1)*SPP(12)) + SPP(12)*(OP(5,3) + OP(16,3)*SF(23) + OP(1,3)*SPP(21) + OP(2,3)*SPP(13) + OP(3,3)*SPP(12)) + SQ(5)*(SG(2) - SG(3) + SG(4) - SG(5))^2; -nextP(1,6) = OP(1,6)*SPP(6) - OP(2,6)*SPP(5) + OP(3,6)*SPP(8) + OP(10,6)*SPP(23) + OP(13,6)*SPP(19) + SF(21)*(OP(1,16)*SPP(6) - OP(2,16)*SPP(5) + OP(3,16)*SPP(8) + OP(10,16)*SPP(23) + OP(13,16)*SPP(19)) - SPP(10)*(OP(1,1)*SPP(6) - OP(2,1)*SPP(5) + OP(3,1)*SPP(8) + OP(10,1)*SPP(23) + OP(13,1)*SPP(19)) + SPP(1)*(OP(1,3)*SPP(6) - OP(2,3)*SPP(5) + OP(3,3)*SPP(8) + OP(10,3)*SPP(23) + OP(13,3)*SPP(19)) + SPP(11)*(OP(1,2)*SPP(6) - OP(2,2)*SPP(5) + OP(3,2)*SPP(8) + OP(10,2)*SPP(23) + OP(13,2)*SPP(19)); -nextP(2,6) = OP(2,6)*SPP(7) - OP(1,6)*SPP(3) - OP(3,6)*SPP(9) + OP(11,6)*SPP(23) + OP(14,6)*SPP(18) + SF(21)*(OP(2,16)*SPP(7) - OP(1,16)*SPP(3) - OP(3,16)*SPP(9) + OP(11,16)*SPP(23) + OP(14,16)*SPP(18)) - SPP(10)*(OP(2,1)*SPP(7) - OP(1,1)*SPP(3) - OP(3,1)*SPP(9) + OP(11,1)*SPP(23) + OP(14,1)*SPP(18)) + SPP(1)*(OP(2,3)*SPP(7) - OP(1,3)*SPP(3) - OP(3,3)*SPP(9) + OP(11,3)*SPP(23) + OP(14,3)*SPP(18)) + SPP(11)*(OP(2,2)*SPP(7) - OP(1,2)*SPP(3) - OP(3,2)*SPP(9) + OP(11,2)*SPP(23) + OP(14,2)*SPP(18)); -nextP(3,6) = OP(1,6)*SPP(15) - OP(2,6)*SPP(4) + OP(3,6)*SPP(14) + OP(12,6)*SPP(23) + OP(15,6)*SPP(17) + SF(21)*(OP(1,16)*SPP(15) - OP(2,16)*SPP(4) + OP(3,16)*SPP(14) + OP(12,16)*SPP(23) + OP(15,16)*SPP(17)) - SPP(10)*(OP(1,1)*SPP(15) - OP(2,1)*SPP(4) + OP(3,1)*SPP(14) + OP(12,1)*SPP(23) + OP(15,1)*SPP(17)) + SPP(1)*(OP(1,3)*SPP(15) - OP(2,3)*SPP(4) + OP(3,3)*SPP(14) + OP(12,3)*SPP(23) + OP(15,3)*SPP(17)) + SPP(11)*(OP(1,2)*SPP(15) - OP(2,2)*SPP(4) + OP(3,2)*SPP(14) + OP(12,2)*SPP(23) + OP(15,2)*SPP(17)); -nextP(4,6) = OP(4,6) + SQ(2) + OP(1,6)*SPP(2) + OP(2,6)*SPP(20) + OP(3,6)*SPP(16) - OP(16,6)*SPP(22) + SF(21)*(OP(4,16) + OP(1,16)*SPP(2) + OP(2,16)*SPP(20) + OP(3,16)*SPP(16) - OP(16,16)*SPP(22)) - SPP(10)*(OP(4,1) + OP(1,1)*SPP(2) + OP(2,1)*SPP(20) + OP(3,1)*SPP(16) - OP(16,1)*SPP(22)) + SPP(1)*(OP(4,3) + OP(1,3)*SPP(2) + OP(2,3)*SPP(20) + OP(3,3)*SPP(16) - OP(16,3)*SPP(22)) + SPP(11)*(OP(4,2) + OP(1,2)*SPP(2) + OP(2,2)*SPP(20) + OP(3,2)*SPP(16) - OP(16,2)*SPP(22)); -nextP(5,6) = OP(5,6) + SQ(1) + OP(16,6)*SF(23) + OP(1,6)*SPP(21) + OP(2,6)*SPP(13) + OP(3,6)*SPP(12) + SF(21)*(OP(5,16) + OP(16,16)*SF(23) + OP(1,16)*SPP(21) + OP(2,16)*SPP(13) + OP(3,16)*SPP(12)) - SPP(10)*(OP(5,1) + OP(16,1)*SF(23) + OP(1,1)*SPP(21) + OP(2,1)*SPP(13) + OP(3,1)*SPP(12)) + SPP(1)*(OP(5,3) + OP(16,3)*SF(23) + OP(1,3)*SPP(21) + OP(2,3)*SPP(13) + OP(3,3)*SPP(12)) + SPP(11)*(OP(5,2) + OP(16,2)*SF(23) + OP(1,2)*SPP(21) + OP(2,2)*SPP(13) + OP(3,2)*SPP(12)); -nextP(6,6) = OP(6,6) + OP(16,6)*SF(21) - OP(1,6)*SPP(10) + OP(2,6)*SPP(11) + OP(3,6)*SPP(1) + SQ(5)*(SQ(8) + 2*q0*q1)^2 + SQ(7)*(SQ(9) - 2*q0*q2)^2 + SF(21)*(OP(6,16) + OP(16,16)*SF(21) - OP(1,16)*SPP(10) + OP(2,16)*SPP(11) + OP(3,16)*SPP(1)) - SPP(10)*(OP(6,1) + OP(16,1)*SF(21) - OP(1,1)*SPP(10) + OP(2,1)*SPP(11) + OP(3,1)*SPP(1)) + SPP(1)*(OP(6,3) + OP(16,3)*SF(21) - OP(1,3)*SPP(10) + OP(2,3)*SPP(11) + OP(3,3)*SPP(1)) + SPP(11)*(OP(6,2) + OP(16,2)*SF(21) - OP(1,2)*SPP(10) + OP(2,2)*SPP(11) + OP(3,2)*SPP(1)) + SQ(6)*(SG(2) - SG(3) - SG(4) + SG(5))^2; -nextP(1,7) = OP(1,7)*SPP(6) - OP(2,7)*SPP(5) + OP(3,7)*SPP(8) + OP(10,7)*SPP(23) + OP(13,7)*SPP(19) + dt*(OP(1,4)*SPP(6) - OP(2,4)*SPP(5) + OP(3,4)*SPP(8) + OP(10,4)*SPP(23) + OP(13,4)*SPP(19)); -nextP(2,7) = OP(2,7)*SPP(7) - OP(1,7)*SPP(3) - OP(3,7)*SPP(9) + OP(11,7)*SPP(23) + OP(14,7)*SPP(18) + dt*(OP(2,4)*SPP(7) - OP(1,4)*SPP(3) - OP(3,4)*SPP(9) + OP(11,4)*SPP(23) + OP(14,4)*SPP(18)); -nextP(3,7) = OP(1,7)*SPP(15) - OP(2,7)*SPP(4) + OP(3,7)*SPP(14) + OP(12,7)*SPP(23) + OP(15,7)*SPP(17) + dt*(OP(1,4)*SPP(15) - OP(2,4)*SPP(4) + OP(3,4)*SPP(14) + OP(12,4)*SPP(23) + OP(15,4)*SPP(17)); -nextP(4,7) = OP(4,7) + OP(1,7)*SPP(2) + OP(2,7)*SPP(20) + OP(3,7)*SPP(16) - OP(16,7)*SPP(22) + dt*(OP(4,4) + OP(1,4)*SPP(2) + OP(2,4)*SPP(20) + OP(3,4)*SPP(16) - OP(16,4)*SPP(22)); -nextP(5,7) = OP(5,7) + OP(16,7)*SF(23) + OP(1,7)*SPP(21) + OP(2,7)*SPP(13) + OP(3,7)*SPP(12) + dt*(OP(5,4) + OP(16,4)*SF(23) + OP(1,4)*SPP(21) + OP(2,4)*SPP(13) + OP(3,4)*SPP(12)); -nextP(6,7) = OP(6,7) + OP(16,7)*SF(21) - OP(1,7)*SPP(10) + OP(2,7)*SPP(11) + OP(3,7)*SPP(1) + dt*(OP(6,4) + OP(16,4)*SF(21) - OP(1,4)*SPP(10) + OP(2,4)*SPP(11) + OP(3,4)*SPP(1)); -nextP(7,7) = OP(7,7) + OP(4,7)*dt + dt*(OP(7,4) + OP(4,4)*dt); -nextP(1,8) = OP(1,8)*SPP(6) - OP(2,8)*SPP(5) + OP(3,8)*SPP(8) + OP(10,8)*SPP(23) + OP(13,8)*SPP(19) + dt*(OP(1,5)*SPP(6) - OP(2,5)*SPP(5) + OP(3,5)*SPP(8) + OP(10,5)*SPP(23) + OP(13,5)*SPP(19)); -nextP(2,8) = OP(2,8)*SPP(7) - OP(1,8)*SPP(3) - OP(3,8)*SPP(9) + OP(11,8)*SPP(23) + OP(14,8)*SPP(18) + dt*(OP(2,5)*SPP(7) - OP(1,5)*SPP(3) - OP(3,5)*SPP(9) + OP(11,5)*SPP(23) + OP(14,5)*SPP(18)); -nextP(3,8) = OP(1,8)*SPP(15) - OP(2,8)*SPP(4) + OP(3,8)*SPP(14) + OP(12,8)*SPP(23) + OP(15,8)*SPP(17) + dt*(OP(1,5)*SPP(15) - OP(2,5)*SPP(4) + OP(3,5)*SPP(14) + OP(12,5)*SPP(23) + OP(15,5)*SPP(17)); -nextP(4,8) = OP(4,8) + OP(1,8)*SPP(2) + OP(2,8)*SPP(20) + OP(3,8)*SPP(16) - OP(16,8)*SPP(22) + dt*(OP(4,5) + OP(1,5)*SPP(2) + OP(2,5)*SPP(20) + OP(3,5)*SPP(16) - OP(16,5)*SPP(22)); -nextP(5,8) = OP(5,8) + OP(16,8)*SF(23) + OP(1,8)*SPP(21) + OP(2,8)*SPP(13) + OP(3,8)*SPP(12) + dt*(OP(5,5) + OP(16,5)*SF(23) + OP(1,5)*SPP(21) + OP(2,5)*SPP(13) + OP(3,5)*SPP(12)); -nextP(6,8) = OP(6,8) + OP(16,8)*SF(21) - OP(1,8)*SPP(10) + OP(2,8)*SPP(11) + OP(3,8)*SPP(1) + dt*(OP(6,5) + OP(16,5)*SF(21) - OP(1,5)*SPP(10) + OP(2,5)*SPP(11) + OP(3,5)*SPP(1)); -nextP(7,8) = OP(7,8) + OP(4,8)*dt + dt*(OP(7,5) + OP(4,5)*dt); +nextP(1,1) = OP(1,1) + OP(2,1)*SF(10) + OP(3,1)*SF(12) + OP(4,1)*SF(11) + OP(11,1)*SF(15) + OP(12,1)*SF(16) + OP(13,1)*SPP(11) + (daxVar*SQ(11))/4 + SF(10)*(OP(1,2) + OP(2,2)*SF(10) + OP(3,2)*SF(12) + OP(4,2)*SF(11) + OP(11,2)*SF(15) + OP(12,2)*SF(16) + OP(13,2)*SPP(11)) + SF(12)*(OP(1,3) + OP(2,3)*SF(10) + OP(3,3)*SF(12) + OP(4,3)*SF(11) + OP(11,3)*SF(15) + OP(12,3)*SF(16) + OP(13,3)*SPP(11)) + SF(11)*(OP(1,4) + OP(2,4)*SF(10) + OP(3,4)*SF(12) + OP(4,4)*SF(11) + OP(11,4)*SF(15) + OP(12,4)*SF(16) + OP(13,4)*SPP(11)) + SF(15)*(OP(1,11) + OP(2,11)*SF(10) + OP(3,11)*SF(12) + OP(4,11)*SF(11) + OP(11,11)*SF(15) + OP(12,11)*SF(16) + OP(13,11)*SPP(11)) + SF(16)*(OP(1,12) + OP(2,12)*SF(10) + OP(3,12)*SF(12) + OP(4,12)*SF(11) + OP(11,12)*SF(15) + OP(12,12)*SF(16) + OP(13,12)*SPP(11)) + SPP(11)*(OP(1,13) + OP(2,13)*SF(10) + OP(3,13)*SF(12) + OP(4,13)*SF(11) + OP(11,13)*SF(15) + OP(12,13)*SF(16) + OP(13,13)*SPP(11)) + (dayVar*q2^2)/4 + (dazVar*q3^2)/4; +nextP(1,2) = OP(1,2) + SQ(9) + OP(2,2)*SF(10) + OP(3,2)*SF(12) + OP(4,2)*SF(11) + OP(11,2)*SF(15) + OP(12,2)*SF(16) + OP(13,2)*SPP(11) + SF(9)*(OP(1,1) + OP(2,1)*SF(10) + OP(3,1)*SF(12) + OP(4,1)*SF(11) + OP(11,1)*SF(15) + OP(12,1)*SF(16) + OP(13,1)*SPP(11)) + SF(8)*(OP(1,3) + OP(2,3)*SF(10) + OP(3,3)*SF(12) + OP(4,3)*SF(11) + OP(11,3)*SF(15) + OP(12,3)*SF(16) + OP(13,3)*SPP(11)) + SF(12)*(OP(1,4) + OP(2,4)*SF(10) + OP(3,4)*SF(12) + OP(4,4)*SF(11) + OP(11,4)*SF(15) + OP(12,4)*SF(16) + OP(13,4)*SPP(11)) - SF(16)*(OP(1,13) + OP(2,13)*SF(10) + OP(3,13)*SF(12) + OP(4,13)*SF(11) + OP(11,13)*SF(15) + OP(12,13)*SF(16) + OP(13,13)*SPP(11)) + SPP(11)*(OP(1,12) + OP(2,12)*SF(10) + OP(3,12)*SF(12) + OP(4,12)*SF(11) + OP(11,12)*SF(15) + OP(12,12)*SF(16) + OP(13,12)*SPP(11)) - (q0*(OP(1,11) + OP(2,11)*SF(10) + OP(3,11)*SF(12) + OP(4,11)*SF(11) + OP(11,11)*SF(15) + OP(12,11)*SF(16) + OP(13,11)*SPP(11)))/2; +nextP(2,2) = OP(2,2) + OP(1,2)*SF(9) + OP(3,2)*SF(8) + OP(4,2)*SF(12) - OP(13,2)*SF(16) + OP(12,2)*SPP(11) + daxVar*SQ(10) - (OP(11,2)*q0)/2 + SF(9)*(OP(2,1) + OP(1,1)*SF(9) + OP(3,1)*SF(8) + OP(4,1)*SF(12) - OP(13,1)*SF(16) + OP(12,1)*SPP(11) - (OP(11,1)*q0)/2) + SF(8)*(OP(2,3) + OP(1,3)*SF(9) + OP(3,3)*SF(8) + OP(4,3)*SF(12) - OP(13,3)*SF(16) + OP(12,3)*SPP(11) - (OP(11,3)*q0)/2) + SF(12)*(OP(2,4) + OP(1,4)*SF(9) + OP(3,4)*SF(8) + OP(4,4)*SF(12) - OP(13,4)*SF(16) + OP(12,4)*SPP(11) - (OP(11,4)*q0)/2) - SF(16)*(OP(2,13) + OP(1,13)*SF(9) + OP(3,13)*SF(8) + OP(4,13)*SF(12) - OP(13,13)*SF(16) + OP(12,13)*SPP(11) - (OP(11,13)*q0)/2) + SPP(11)*(OP(2,12) + OP(1,12)*SF(9) + OP(3,12)*SF(8) + OP(4,12)*SF(12) - OP(13,12)*SF(16) + OP(12,12)*SPP(11) - (OP(11,12)*q0)/2) + (dayVar*q3^2)/4 + (dazVar*q2^2)/4 - (q0*(OP(2,11) + OP(1,11)*SF(9) + OP(3,11)*SF(8) + OP(4,11)*SF(12) - OP(13,11)*SF(16) + OP(12,11)*SPP(11) - (OP(11,11)*q0)/2))/2; +nextP(1,3) = OP(1,3) + SQ(8) + OP(2,3)*SF(10) + OP(3,3)*SF(12) + OP(4,3)*SF(11) + OP(11,3)*SF(15) + OP(12,3)*SF(16) + OP(13,3)*SPP(11) + SF(7)*(OP(1,1) + OP(2,1)*SF(10) + OP(3,1)*SF(12) + OP(4,1)*SF(11) + OP(11,1)*SF(15) + OP(12,1)*SF(16) + OP(13,1)*SPP(11)) + SF(11)*(OP(1,2) + OP(2,2)*SF(10) + OP(3,2)*SF(12) + OP(4,2)*SF(11) + OP(11,2)*SF(15) + OP(12,2)*SF(16) + OP(13,2)*SPP(11)) + SF(9)*(OP(1,4) + OP(2,4)*SF(10) + OP(3,4)*SF(12) + OP(4,4)*SF(11) + OP(11,4)*SF(15) + OP(12,4)*SF(16) + OP(13,4)*SPP(11)) + SF(15)*(OP(1,13) + OP(2,13)*SF(10) + OP(3,13)*SF(12) + OP(4,13)*SF(11) + OP(11,13)*SF(15) + OP(12,13)*SF(16) + OP(13,13)*SPP(11)) - SPP(11)*(OP(1,11) + OP(2,11)*SF(10) + OP(3,11)*SF(12) + OP(4,11)*SF(11) + OP(11,11)*SF(15) + OP(12,11)*SF(16) + OP(13,11)*SPP(11)) - (q0*(OP(1,12) + OP(2,12)*SF(10) + OP(3,12)*SF(12) + OP(4,12)*SF(11) + OP(11,12)*SF(15) + OP(12,12)*SF(16) + OP(13,12)*SPP(11)))/2; +nextP(2,3) = OP(2,3) + SQ(6) + OP(1,3)*SF(9) + OP(3,3)*SF(8) + OP(4,3)*SF(12) - OP(13,3)*SF(16) + OP(12,3)*SPP(11) - (OP(11,3)*q0)/2 + SF(7)*(OP(2,1) + OP(1,1)*SF(9) + OP(3,1)*SF(8) + OP(4,1)*SF(12) - OP(13,1)*SF(16) + OP(12,1)*SPP(11) - (OP(11,1)*q0)/2) + SF(11)*(OP(2,2) + OP(1,2)*SF(9) + OP(3,2)*SF(8) + OP(4,2)*SF(12) - OP(13,2)*SF(16) + OP(12,2)*SPP(11) - (OP(11,2)*q0)/2) + SF(9)*(OP(2,4) + OP(1,4)*SF(9) + OP(3,4)*SF(8) + OP(4,4)*SF(12) - OP(13,4)*SF(16) + OP(12,4)*SPP(11) - (OP(11,4)*q0)/2) + SF(15)*(OP(2,13) + OP(1,13)*SF(9) + OP(3,13)*SF(8) + OP(4,13)*SF(12) - OP(13,13)*SF(16) + OP(12,13)*SPP(11) - (OP(11,13)*q0)/2) - SPP(11)*(OP(2,11) + OP(1,11)*SF(9) + OP(3,11)*SF(8) + OP(4,11)*SF(12) - OP(13,11)*SF(16) + OP(12,11)*SPP(11) - (OP(11,11)*q0)/2) - (q0*(OP(2,12) + OP(1,12)*SF(9) + OP(3,12)*SF(8) + OP(4,12)*SF(12) - OP(13,12)*SF(16) + OP(12,12)*SPP(11) - (OP(11,12)*q0)/2))/2; +nextP(3,3) = OP(3,3) + OP(1,3)*SF(7) + OP(2,3)*SF(11) + OP(4,3)*SF(9) + OP(13,3)*SF(15) - OP(11,3)*SPP(11) + dayVar*SQ(10) + (dazVar*SQ(11))/4 - (OP(12,3)*q0)/2 + SF(7)*(OP(3,1) + OP(1,1)*SF(7) + OP(2,1)*SF(11) + OP(4,1)*SF(9) + OP(13,1)*SF(15) - OP(11,1)*SPP(11) - (OP(12,1)*q0)/2) + SF(11)*(OP(3,2) + OP(1,2)*SF(7) + OP(2,2)*SF(11) + OP(4,2)*SF(9) + OP(13,2)*SF(15) - OP(11,2)*SPP(11) - (OP(12,2)*q0)/2) + SF(9)*(OP(3,4) + OP(1,4)*SF(7) + OP(2,4)*SF(11) + OP(4,4)*SF(9) + OP(13,4)*SF(15) - OP(11,4)*SPP(11) - (OP(12,4)*q0)/2) + SF(15)*(OP(3,13) + OP(1,13)*SF(7) + OP(2,13)*SF(11) + OP(4,13)*SF(9) + OP(13,13)*SF(15) - OP(11,13)*SPP(11) - (OP(12,13)*q0)/2) - SPP(11)*(OP(3,11) + OP(1,11)*SF(7) + OP(2,11)*SF(11) + OP(4,11)*SF(9) + OP(13,11)*SF(15) - OP(11,11)*SPP(11) - (OP(12,11)*q0)/2) + (daxVar*q3^2)/4 - (q0*(OP(3,12) + OP(1,12)*SF(7) + OP(2,12)*SF(11) + OP(4,12)*SF(9) + OP(13,12)*SF(15) - OP(11,12)*SPP(11) - (OP(12,12)*q0)/2))/2; +nextP(1,4) = OP(1,4) + SQ(7) + OP(2,4)*SF(10) + OP(3,4)*SF(12) + OP(4,4)*SF(11) + OP(11,4)*SF(15) + OP(12,4)*SF(16) + OP(13,4)*SPP(11) + SF(8)*(OP(1,1) + OP(2,1)*SF(10) + OP(3,1)*SF(12) + OP(4,1)*SF(11) + OP(11,1)*SF(15) + OP(12,1)*SF(16) + OP(13,1)*SPP(11)) + SF(7)*(OP(1,2) + OP(2,2)*SF(10) + OP(3,2)*SF(12) + OP(4,2)*SF(11) + OP(11,2)*SF(15) + OP(12,2)*SF(16) + OP(13,2)*SPP(11)) + SF(10)*(OP(1,3) + OP(2,3)*SF(10) + OP(3,3)*SF(12) + OP(4,3)*SF(11) + OP(11,3)*SF(15) + OP(12,3)*SF(16) + OP(13,3)*SPP(11)) + SF(16)*(OP(1,11) + OP(2,11)*SF(10) + OP(3,11)*SF(12) + OP(4,11)*SF(11) + OP(11,11)*SF(15) + OP(12,11)*SF(16) + OP(13,11)*SPP(11)) - SF(15)*(OP(1,12) + OP(2,12)*SF(10) + OP(3,12)*SF(12) + OP(4,12)*SF(11) + OP(11,12)*SF(15) + OP(12,12)*SF(16) + OP(13,12)*SPP(11)) - (q0*(OP(1,13) + OP(2,13)*SF(10) + OP(3,13)*SF(12) + OP(4,13)*SF(11) + OP(11,13)*SF(15) + OP(12,13)*SF(16) + OP(13,13)*SPP(11)))/2; +nextP(2,4) = OP(2,4) + SQ(5) + OP(1,4)*SF(9) + OP(3,4)*SF(8) + OP(4,4)*SF(12) - OP(13,4)*SF(16) + OP(12,4)*SPP(11) - (OP(11,4)*q0)/2 + SF(8)*(OP(2,1) + OP(1,1)*SF(9) + OP(3,1)*SF(8) + OP(4,1)*SF(12) - OP(13,1)*SF(16) + OP(12,1)*SPP(11) - (OP(11,1)*q0)/2) + SF(7)*(OP(2,2) + OP(1,2)*SF(9) + OP(3,2)*SF(8) + OP(4,2)*SF(12) - OP(13,2)*SF(16) + OP(12,2)*SPP(11) - (OP(11,2)*q0)/2) + SF(10)*(OP(2,3) + OP(1,3)*SF(9) + OP(3,3)*SF(8) + OP(4,3)*SF(12) - OP(13,3)*SF(16) + OP(12,3)*SPP(11) - (OP(11,3)*q0)/2) + SF(16)*(OP(2,11) + OP(1,11)*SF(9) + OP(3,11)*SF(8) + OP(4,11)*SF(12) - OP(13,11)*SF(16) + OP(12,11)*SPP(11) - (OP(11,11)*q0)/2) - SF(15)*(OP(2,12) + OP(1,12)*SF(9) + OP(3,12)*SF(8) + OP(4,12)*SF(12) - OP(13,12)*SF(16) + OP(12,12)*SPP(11) - (OP(11,12)*q0)/2) - (q0*(OP(2,13) + OP(1,13)*SF(9) + OP(3,13)*SF(8) + OP(4,13)*SF(12) - OP(13,13)*SF(16) + OP(12,13)*SPP(11) - (OP(11,13)*q0)/2))/2; +nextP(3,4) = OP(3,4) + SQ(4) + OP(1,4)*SF(7) + OP(2,4)*SF(11) + OP(4,4)*SF(9) + OP(13,4)*SF(15) - OP(11,4)*SPP(11) - (OP(12,4)*q0)/2 + SF(8)*(OP(3,1) + OP(1,1)*SF(7) + OP(2,1)*SF(11) + OP(4,1)*SF(9) + OP(13,1)*SF(15) - OP(11,1)*SPP(11) - (OP(12,1)*q0)/2) + SF(7)*(OP(3,2) + OP(1,2)*SF(7) + OP(2,2)*SF(11) + OP(4,2)*SF(9) + OP(13,2)*SF(15) - OP(11,2)*SPP(11) - (OP(12,2)*q0)/2) + SF(10)*(OP(3,3) + OP(1,3)*SF(7) + OP(2,3)*SF(11) + OP(4,3)*SF(9) + OP(13,3)*SF(15) - OP(11,3)*SPP(11) - (OP(12,3)*q0)/2) + SF(16)*(OP(3,11) + OP(1,11)*SF(7) + OP(2,11)*SF(11) + OP(4,11)*SF(9) + OP(13,11)*SF(15) - OP(11,11)*SPP(11) - (OP(12,11)*q0)/2) - SF(15)*(OP(3,12) + OP(1,12)*SF(7) + OP(2,12)*SF(11) + OP(4,12)*SF(9) + OP(13,12)*SF(15) - OP(11,12)*SPP(11) - (OP(12,12)*q0)/2) - (q0*(OP(3,13) + OP(1,13)*SF(7) + OP(2,13)*SF(11) + OP(4,13)*SF(9) + OP(13,13)*SF(15) - OP(11,13)*SPP(11) - (OP(12,13)*q0)/2))/2; +nextP(4,4) = OP(4,4) + OP(1,4)*SF(8) + OP(2,4)*SF(7) + OP(3,4)*SF(10) + OP(11,4)*SF(16) - OP(12,4)*SF(15) + (dayVar*SQ(11))/4 + dazVar*SQ(10) - (OP(13,4)*q0)/2 + SF(8)*(OP(4,1) + OP(1,1)*SF(8) + OP(2,1)*SF(7) + OP(3,1)*SF(10) + OP(11,1)*SF(16) - OP(12,1)*SF(15) - (OP(13,1)*q0)/2) + SF(7)*(OP(4,2) + OP(1,2)*SF(8) + OP(2,2)*SF(7) + OP(3,2)*SF(10) + OP(11,2)*SF(16) - OP(12,2)*SF(15) - (OP(13,2)*q0)/2) + SF(10)*(OP(4,3) + OP(1,3)*SF(8) + OP(2,3)*SF(7) + OP(3,3)*SF(10) + OP(11,3)*SF(16) - OP(12,3)*SF(15) - (OP(13,3)*q0)/2) + SF(16)*(OP(4,11) + OP(1,11)*SF(8) + OP(2,11)*SF(7) + OP(3,11)*SF(10) + OP(11,11)*SF(16) - OP(12,11)*SF(15) - (OP(13,11)*q0)/2) - SF(15)*(OP(4,12) + OP(1,12)*SF(8) + OP(2,12)*SF(7) + OP(3,12)*SF(10) + OP(11,12)*SF(16) - OP(12,12)*SF(15) - (OP(13,12)*q0)/2) + (daxVar*q2^2)/4 - (q0*(OP(4,13) + OP(1,13)*SF(8) + OP(2,13)*SF(7) + OP(3,13)*SF(10) + OP(11,13)*SF(16) - OP(12,13)*SF(15) - (OP(13,13)*q0)/2))/2; +nextP(1,5) = OP(1,5) + OP(2,5)*SF(10) + OP(3,5)*SF(12) + OP(4,5)*SF(11) + OP(11,5)*SF(15) + OP(12,5)*SF(16) + OP(13,5)*SPP(11) + SF(6)*(OP(1,1) + OP(2,1)*SF(10) + OP(3,1)*SF(12) + OP(4,1)*SF(11) + OP(11,1)*SF(15) + OP(12,1)*SF(16) + OP(13,1)*SPP(11)) + SF(4)*(OP(1,2) + OP(2,2)*SF(10) + OP(3,2)*SF(12) + OP(4,2)*SF(11) + OP(11,2)*SF(15) + OP(12,2)*SF(16) + OP(13,2)*SPP(11)) - SF(5)*(OP(1,4) + OP(2,4)*SF(10) + OP(3,4)*SF(12) + OP(4,4)*SF(11) + OP(11,4)*SF(15) + OP(12,4)*SF(16) + OP(13,4)*SPP(11)) + SPP(1)*(OP(1,3) + OP(2,3)*SF(10) + OP(3,3)*SF(12) + OP(4,3)*SF(11) + OP(11,3)*SF(15) + OP(12,3)*SF(16) + OP(13,3)*SPP(11)) + SPP(4)*(OP(1,14) + OP(2,14)*SF(10) + OP(3,14)*SF(12) + OP(4,14)*SF(11) + OP(11,14)*SF(15) + OP(12,14)*SF(16) + OP(13,14)*SPP(11)) + SPP(7)*(OP(1,15) + OP(2,15)*SF(10) + OP(3,15)*SF(12) + OP(4,15)*SF(11) + OP(11,15)*SF(15) + OP(12,15)*SF(16) + OP(13,15)*SPP(11)) - SPP(10)*(OP(1,16) + OP(2,16)*SF(10) + OP(3,16)*SF(12) + OP(4,16)*SF(11) + OP(11,16)*SF(15) + OP(12,16)*SF(16) + OP(13,16)*SPP(11)); +nextP(2,5) = OP(2,5) + OP(1,5)*SF(9) + OP(3,5)*SF(8) + OP(4,5)*SF(12) - OP(13,5)*SF(16) + OP(12,5)*SPP(11) - (OP(11,5)*q0)/2 + SF(6)*(OP(2,1) + OP(1,1)*SF(9) + OP(3,1)*SF(8) + OP(4,1)*SF(12) - OP(13,1)*SF(16) + OP(12,1)*SPP(11) - (OP(11,1)*q0)/2) + SF(4)*(OP(2,2) + OP(1,2)*SF(9) + OP(3,2)*SF(8) + OP(4,2)*SF(12) - OP(13,2)*SF(16) + OP(12,2)*SPP(11) - (OP(11,2)*q0)/2) - SF(5)*(OP(2,4) + OP(1,4)*SF(9) + OP(3,4)*SF(8) + OP(4,4)*SF(12) - OP(13,4)*SF(16) + OP(12,4)*SPP(11) - (OP(11,4)*q0)/2) + SPP(1)*(OP(2,3) + OP(1,3)*SF(9) + OP(3,3)*SF(8) + OP(4,3)*SF(12) - OP(13,3)*SF(16) + OP(12,3)*SPP(11) - (OP(11,3)*q0)/2) + SPP(4)*(OP(2,14) + OP(1,14)*SF(9) + OP(3,14)*SF(8) + OP(4,14)*SF(12) - OP(13,14)*SF(16) + OP(12,14)*SPP(11) - (OP(11,14)*q0)/2) + SPP(7)*(OP(2,15) + OP(1,15)*SF(9) + OP(3,15)*SF(8) + OP(4,15)*SF(12) - OP(13,15)*SF(16) + OP(12,15)*SPP(11) - (OP(11,15)*q0)/2) - SPP(10)*(OP(2,16) + OP(1,16)*SF(9) + OP(3,16)*SF(8) + OP(4,16)*SF(12) - OP(13,16)*SF(16) + OP(12,16)*SPP(11) - (OP(11,16)*q0)/2); +nextP(3,5) = OP(3,5) + OP(1,5)*SF(7) + OP(2,5)*SF(11) + OP(4,5)*SF(9) + OP(13,5)*SF(15) - OP(11,5)*SPP(11) - (OP(12,5)*q0)/2 + SF(6)*(OP(3,1) + OP(1,1)*SF(7) + OP(2,1)*SF(11) + OP(4,1)*SF(9) + OP(13,1)*SF(15) - OP(11,1)*SPP(11) - (OP(12,1)*q0)/2) + SF(4)*(OP(3,2) + OP(1,2)*SF(7) + OP(2,2)*SF(11) + OP(4,2)*SF(9) + OP(13,2)*SF(15) - OP(11,2)*SPP(11) - (OP(12,2)*q0)/2) - SF(5)*(OP(3,4) + OP(1,4)*SF(7) + OP(2,4)*SF(11) + OP(4,4)*SF(9) + OP(13,4)*SF(15) - OP(11,4)*SPP(11) - (OP(12,4)*q0)/2) + SPP(1)*(OP(3,3) + OP(1,3)*SF(7) + OP(2,3)*SF(11) + OP(4,3)*SF(9) + OP(13,3)*SF(15) - OP(11,3)*SPP(11) - (OP(12,3)*q0)/2) + SPP(4)*(OP(3,14) + OP(1,14)*SF(7) + OP(2,14)*SF(11) + OP(4,14)*SF(9) + OP(13,14)*SF(15) - OP(11,14)*SPP(11) - (OP(12,14)*q0)/2) + SPP(7)*(OP(3,15) + OP(1,15)*SF(7) + OP(2,15)*SF(11) + OP(4,15)*SF(9) + OP(13,15)*SF(15) - OP(11,15)*SPP(11) - (OP(12,15)*q0)/2) - SPP(10)*(OP(3,16) + OP(1,16)*SF(7) + OP(2,16)*SF(11) + OP(4,16)*SF(9) + OP(13,16)*SF(15) - OP(11,16)*SPP(11) - (OP(12,16)*q0)/2); +nextP(4,5) = OP(4,5) + OP(1,5)*SF(8) + OP(2,5)*SF(7) + OP(3,5)*SF(10) + OP(11,5)*SF(16) - OP(12,5)*SF(15) - (OP(13,5)*q0)/2 + SF(6)*(OP(4,1) + OP(1,1)*SF(8) + OP(2,1)*SF(7) + OP(3,1)*SF(10) + OP(11,1)*SF(16) - OP(12,1)*SF(15) - (OP(13,1)*q0)/2) + SF(4)*(OP(4,2) + OP(1,2)*SF(8) + OP(2,2)*SF(7) + OP(3,2)*SF(10) + OP(11,2)*SF(16) - OP(12,2)*SF(15) - (OP(13,2)*q0)/2) - SF(5)*(OP(4,4) + OP(1,4)*SF(8) + OP(2,4)*SF(7) + OP(3,4)*SF(10) + OP(11,4)*SF(16) - OP(12,4)*SF(15) - (OP(13,4)*q0)/2) + SPP(1)*(OP(4,3) + OP(1,3)*SF(8) + OP(2,3)*SF(7) + OP(3,3)*SF(10) + OP(11,3)*SF(16) - OP(12,3)*SF(15) - (OP(13,3)*q0)/2) + SPP(4)*(OP(4,14) + OP(1,14)*SF(8) + OP(2,14)*SF(7) + OP(3,14)*SF(10) + OP(11,14)*SF(16) - OP(12,14)*SF(15) - (OP(13,14)*q0)/2) + SPP(7)*(OP(4,15) + OP(1,15)*SF(8) + OP(2,15)*SF(7) + OP(3,15)*SF(10) + OP(11,15)*SF(16) - OP(12,15)*SF(15) - (OP(13,15)*q0)/2) - SPP(10)*(OP(4,16) + OP(1,16)*SF(8) + OP(2,16)*SF(7) + OP(3,16)*SF(10) + OP(11,16)*SF(16) - OP(12,16)*SF(15) - (OP(13,16)*q0)/2); +nextP(5,5) = OP(5,5) + OP(1,5)*SF(6) + OP(2,5)*SF(4) - OP(4,5)*SF(5) + OP(3,5)*SPP(1) + OP(14,5)*SPP(4) + OP(15,5)*SPP(7) - OP(16,5)*SPP(10) + dvyVar*(SG(8) - 2*q0*q3)^2 + dvzVar*(SG(7) + 2*q0*q2)^2 + SF(6)*(OP(5,1) + OP(1,1)*SF(6) + OP(2,1)*SF(4) - OP(4,1)*SF(5) + OP(3,1)*SPP(1) + OP(14,1)*SPP(4) + OP(15,1)*SPP(7) - OP(16,1)*SPP(10)) + SF(4)*(OP(5,2) + OP(1,2)*SF(6) + OP(2,2)*SF(4) - OP(4,2)*SF(5) + OP(3,2)*SPP(1) + OP(14,2)*SPP(4) + OP(15,2)*SPP(7) - OP(16,2)*SPP(10)) - SF(5)*(OP(5,4) + OP(1,4)*SF(6) + OP(2,4)*SF(4) - OP(4,4)*SF(5) + OP(3,4)*SPP(1) + OP(14,4)*SPP(4) + OP(15,4)*SPP(7) - OP(16,4)*SPP(10)) + SPP(1)*(OP(5,3) + OP(1,3)*SF(6) + OP(2,3)*SF(4) - OP(4,3)*SF(5) + OP(3,3)*SPP(1) + OP(14,3)*SPP(4) + OP(15,3)*SPP(7) - OP(16,3)*SPP(10)) + SPP(4)*(OP(5,14) + OP(1,14)*SF(6) + OP(2,14)*SF(4) - OP(4,14)*SF(5) + OP(3,14)*SPP(1) + OP(14,14)*SPP(4) + OP(15,14)*SPP(7) - OP(16,14)*SPP(10)) + SPP(7)*(OP(5,15) + OP(1,15)*SF(6) + OP(2,15)*SF(4) - OP(4,15)*SF(5) + OP(3,15)*SPP(1) + OP(14,15)*SPP(4) + OP(15,15)*SPP(7) - OP(16,15)*SPP(10)) - SPP(10)*(OP(5,16) + OP(1,16)*SF(6) + OP(2,16)*SF(4) - OP(4,16)*SF(5) + OP(3,16)*SPP(1) + OP(14,16)*SPP(4) + OP(15,16)*SPP(7) - OP(16,16)*SPP(10)) + dvxVar*(SG(2) + SG(3) - SG(4) - SG(5))^2; +nextP(1,6) = OP(1,6) + OP(2,6)*SF(10) + OP(3,6)*SF(12) + OP(4,6)*SF(11) + OP(11,6)*SF(15) + OP(12,6)*SF(16) + OP(13,6)*SPP(11) + SF(5)*(OP(1,1) + OP(2,1)*SF(10) + OP(3,1)*SF(12) + OP(4,1)*SF(11) + OP(11,1)*SF(15) + OP(12,1)*SF(16) + OP(13,1)*SPP(11)) + SF(4)*(OP(1,3) + OP(2,3)*SF(10) + OP(3,3)*SF(12) + OP(4,3)*SF(11) + OP(11,3)*SF(15) + OP(12,3)*SF(16) + OP(13,3)*SPP(11)) + SF(6)*(OP(1,4) + OP(2,4)*SF(10) + OP(3,4)*SF(12) + OP(4,4)*SF(11) + OP(11,4)*SF(15) + OP(12,4)*SF(16) + OP(13,4)*SPP(11)) - SPP(1)*(OP(1,2) + OP(2,2)*SF(10) + OP(3,2)*SF(12) + OP(4,2)*SF(11) + OP(11,2)*SF(15) + OP(12,2)*SF(16) + OP(13,2)*SPP(11)) - SPP(9)*(OP(1,14) + OP(2,14)*SF(10) + OP(3,14)*SF(12) + OP(4,14)*SF(11) + OP(11,14)*SF(15) + OP(12,14)*SF(16) + OP(13,14)*SPP(11)) + SPP(3)*(OP(1,15) + OP(2,15)*SF(10) + OP(3,15)*SF(12) + OP(4,15)*SF(11) + OP(11,15)*SF(15) + OP(12,15)*SF(16) + OP(13,15)*SPP(11)) + SPP(6)*(OP(1,16) + OP(2,16)*SF(10) + OP(3,16)*SF(12) + OP(4,16)*SF(11) + OP(11,16)*SF(15) + OP(12,16)*SF(16) + OP(13,16)*SPP(11)); +nextP(2,6) = OP(2,6) + OP(1,6)*SF(9) + OP(3,6)*SF(8) + OP(4,6)*SF(12) - OP(13,6)*SF(16) + OP(12,6)*SPP(11) - (OP(11,6)*q0)/2 + SF(5)*(OP(2,1) + OP(1,1)*SF(9) + OP(3,1)*SF(8) + OP(4,1)*SF(12) - OP(13,1)*SF(16) + OP(12,1)*SPP(11) - (OP(11,1)*q0)/2) + SF(4)*(OP(2,3) + OP(1,3)*SF(9) + OP(3,3)*SF(8) + OP(4,3)*SF(12) - OP(13,3)*SF(16) + OP(12,3)*SPP(11) - (OP(11,3)*q0)/2) + SF(6)*(OP(2,4) + OP(1,4)*SF(9) + OP(3,4)*SF(8) + OP(4,4)*SF(12) - OP(13,4)*SF(16) + OP(12,4)*SPP(11) - (OP(11,4)*q0)/2) - SPP(1)*(OP(2,2) + OP(1,2)*SF(9) + OP(3,2)*SF(8) + OP(4,2)*SF(12) - OP(13,2)*SF(16) + OP(12,2)*SPP(11) - (OP(11,2)*q0)/2) - SPP(9)*(OP(2,14) + OP(1,14)*SF(9) + OP(3,14)*SF(8) + OP(4,14)*SF(12) - OP(13,14)*SF(16) + OP(12,14)*SPP(11) - (OP(11,14)*q0)/2) + SPP(3)*(OP(2,15) + OP(1,15)*SF(9) + OP(3,15)*SF(8) + OP(4,15)*SF(12) - OP(13,15)*SF(16) + OP(12,15)*SPP(11) - (OP(11,15)*q0)/2) + SPP(6)*(OP(2,16) + OP(1,16)*SF(9) + OP(3,16)*SF(8) + OP(4,16)*SF(12) - OP(13,16)*SF(16) + OP(12,16)*SPP(11) - (OP(11,16)*q0)/2); +nextP(3,6) = OP(3,6) + OP(1,6)*SF(7) + OP(2,6)*SF(11) + OP(4,6)*SF(9) + OP(13,6)*SF(15) - OP(11,6)*SPP(11) - (OP(12,6)*q0)/2 + SF(5)*(OP(3,1) + OP(1,1)*SF(7) + OP(2,1)*SF(11) + OP(4,1)*SF(9) + OP(13,1)*SF(15) - OP(11,1)*SPP(11) - (OP(12,1)*q0)/2) + SF(4)*(OP(3,3) + OP(1,3)*SF(7) + OP(2,3)*SF(11) + OP(4,3)*SF(9) + OP(13,3)*SF(15) - OP(11,3)*SPP(11) - (OP(12,3)*q0)/2) + SF(6)*(OP(3,4) + OP(1,4)*SF(7) + OP(2,4)*SF(11) + OP(4,4)*SF(9) + OP(13,4)*SF(15) - OP(11,4)*SPP(11) - (OP(12,4)*q0)/2) - SPP(1)*(OP(3,2) + OP(1,2)*SF(7) + OP(2,2)*SF(11) + OP(4,2)*SF(9) + OP(13,2)*SF(15) - OP(11,2)*SPP(11) - (OP(12,2)*q0)/2) - SPP(9)*(OP(3,14) + OP(1,14)*SF(7) + OP(2,14)*SF(11) + OP(4,14)*SF(9) + OP(13,14)*SF(15) - OP(11,14)*SPP(11) - (OP(12,14)*q0)/2) + SPP(3)*(OP(3,15) + OP(1,15)*SF(7) + OP(2,15)*SF(11) + OP(4,15)*SF(9) + OP(13,15)*SF(15) - OP(11,15)*SPP(11) - (OP(12,15)*q0)/2) + SPP(6)*(OP(3,16) + OP(1,16)*SF(7) + OP(2,16)*SF(11) + OP(4,16)*SF(9) + OP(13,16)*SF(15) - OP(11,16)*SPP(11) - (OP(12,16)*q0)/2); +nextP(4,6) = OP(4,6) + OP(1,6)*SF(8) + OP(2,6)*SF(7) + OP(3,6)*SF(10) + OP(11,6)*SF(16) - OP(12,6)*SF(15) - (OP(13,6)*q0)/2 + SF(5)*(OP(4,1) + OP(1,1)*SF(8) + OP(2,1)*SF(7) + OP(3,1)*SF(10) + OP(11,1)*SF(16) - OP(12,1)*SF(15) - (OP(13,1)*q0)/2) + SF(4)*(OP(4,3) + OP(1,3)*SF(8) + OP(2,3)*SF(7) + OP(3,3)*SF(10) + OP(11,3)*SF(16) - OP(12,3)*SF(15) - (OP(13,3)*q0)/2) + SF(6)*(OP(4,4) + OP(1,4)*SF(8) + OP(2,4)*SF(7) + OP(3,4)*SF(10) + OP(11,4)*SF(16) - OP(12,4)*SF(15) - (OP(13,4)*q0)/2) - SPP(1)*(OP(4,2) + OP(1,2)*SF(8) + OP(2,2)*SF(7) + OP(3,2)*SF(10) + OP(11,2)*SF(16) - OP(12,2)*SF(15) - (OP(13,2)*q0)/2) - SPP(9)*(OP(4,14) + OP(1,14)*SF(8) + OP(2,14)*SF(7) + OP(3,14)*SF(10) + OP(11,14)*SF(16) - OP(12,14)*SF(15) - (OP(13,14)*q0)/2) + SPP(3)*(OP(4,15) + OP(1,15)*SF(8) + OP(2,15)*SF(7) + OP(3,15)*SF(10) + OP(11,15)*SF(16) - OP(12,15)*SF(15) - (OP(13,15)*q0)/2) + SPP(6)*(OP(4,16) + OP(1,16)*SF(8) + OP(2,16)*SF(7) + OP(3,16)*SF(10) + OP(11,16)*SF(16) - OP(12,16)*SF(15) - (OP(13,16)*q0)/2); +nextP(5,6) = OP(5,6) + SQ(3) + OP(1,6)*SF(6) + OP(2,6)*SF(4) - OP(4,6)*SF(5) + OP(3,6)*SPP(1) + OP(14,6)*SPP(4) + OP(15,6)*SPP(7) - OP(16,6)*SPP(10) + SF(5)*(OP(5,1) + OP(1,1)*SF(6) + OP(2,1)*SF(4) - OP(4,1)*SF(5) + OP(3,1)*SPP(1) + OP(14,1)*SPP(4) + OP(15,1)*SPP(7) - OP(16,1)*SPP(10)) + SF(4)*(OP(5,3) + OP(1,3)*SF(6) + OP(2,3)*SF(4) - OP(4,3)*SF(5) + OP(3,3)*SPP(1) + OP(14,3)*SPP(4) + OP(15,3)*SPP(7) - OP(16,3)*SPP(10)) + SF(6)*(OP(5,4) + OP(1,4)*SF(6) + OP(2,4)*SF(4) - OP(4,4)*SF(5) + OP(3,4)*SPP(1) + OP(14,4)*SPP(4) + OP(15,4)*SPP(7) - OP(16,4)*SPP(10)) - SPP(1)*(OP(5,2) + OP(1,2)*SF(6) + OP(2,2)*SF(4) - OP(4,2)*SF(5) + OP(3,2)*SPP(1) + OP(14,2)*SPP(4) + OP(15,2)*SPP(7) - OP(16,2)*SPP(10)) - SPP(9)*(OP(5,14) + OP(1,14)*SF(6) + OP(2,14)*SF(4) - OP(4,14)*SF(5) + OP(3,14)*SPP(1) + OP(14,14)*SPP(4) + OP(15,14)*SPP(7) - OP(16,14)*SPP(10)) + SPP(3)*(OP(5,15) + OP(1,15)*SF(6) + OP(2,15)*SF(4) - OP(4,15)*SF(5) + OP(3,15)*SPP(1) + OP(14,15)*SPP(4) + OP(15,15)*SPP(7) - OP(16,15)*SPP(10)) + SPP(6)*(OP(5,16) + OP(1,16)*SF(6) + OP(2,16)*SF(4) - OP(4,16)*SF(5) + OP(3,16)*SPP(1) + OP(14,16)*SPP(4) + OP(15,16)*SPP(7) - OP(16,16)*SPP(10)); +nextP(6,6) = OP(6,6) + OP(1,6)*SF(5) + OP(3,6)*SF(4) + OP(4,6)*SF(6) - OP(2,6)*SPP(1) - OP(14,6)*SPP(9) + OP(15,6)*SPP(3) + OP(16,6)*SPP(6) + dvxVar*(SG(8) + 2*q0*q3)^2 + dvzVar*(SG(6) - 2*q0*q1)^2 + SF(5)*(OP(6,1) + OP(1,1)*SF(5) + OP(3,1)*SF(4) + OP(4,1)*SF(6) - OP(2,1)*SPP(1) - OP(14,1)*SPP(9) + OP(15,1)*SPP(3) + OP(16,1)*SPP(6)) + SF(4)*(OP(6,3) + OP(1,3)*SF(5) + OP(3,3)*SF(4) + OP(4,3)*SF(6) - OP(2,3)*SPP(1) - OP(14,3)*SPP(9) + OP(15,3)*SPP(3) + OP(16,3)*SPP(6)) + SF(6)*(OP(6,4) + OP(1,4)*SF(5) + OP(3,4)*SF(4) + OP(4,4)*SF(6) - OP(2,4)*SPP(1) - OP(14,4)*SPP(9) + OP(15,4)*SPP(3) + OP(16,4)*SPP(6)) - SPP(1)*(OP(6,2) + OP(1,2)*SF(5) + OP(3,2)*SF(4) + OP(4,2)*SF(6) - OP(2,2)*SPP(1) - OP(14,2)*SPP(9) + OP(15,2)*SPP(3) + OP(16,2)*SPP(6)) - SPP(9)*(OP(6,14) + OP(1,14)*SF(5) + OP(3,14)*SF(4) + OP(4,14)*SF(6) - OP(2,14)*SPP(1) - OP(14,14)*SPP(9) + OP(15,14)*SPP(3) + OP(16,14)*SPP(6)) + SPP(3)*(OP(6,15) + OP(1,15)*SF(5) + OP(3,15)*SF(4) + OP(4,15)*SF(6) - OP(2,15)*SPP(1) - OP(14,15)*SPP(9) + OP(15,15)*SPP(3) + OP(16,15)*SPP(6)) + SPP(6)*(OP(6,16) + OP(1,16)*SF(5) + OP(3,16)*SF(4) + OP(4,16)*SF(6) - OP(2,16)*SPP(1) - OP(14,16)*SPP(9) + OP(15,16)*SPP(3) + OP(16,16)*SPP(6)) + dvyVar*(SG(2) - SG(3) + SG(4) - SG(5))^2; +nextP(1,7) = OP(1,7) + OP(2,7)*SF(10) + OP(3,7)*SF(12) + OP(4,7)*SF(11) + OP(11,7)*SF(15) + OP(12,7)*SF(16) + OP(13,7)*SPP(11) + SF(5)*(OP(1,2) + OP(2,2)*SF(10) + OP(3,2)*SF(12) + OP(4,2)*SF(11) + OP(11,2)*SF(15) + OP(12,2)*SF(16) + OP(13,2)*SPP(11)) - SF(6)*(OP(1,3) + OP(2,3)*SF(10) + OP(3,3)*SF(12) + OP(4,3)*SF(11) + OP(11,3)*SF(15) + OP(12,3)*SF(16) + OP(13,3)*SPP(11)) + SF(4)*(OP(1,4) + OP(2,4)*SF(10) + OP(3,4)*SF(12) + OP(4,4)*SF(11) + OP(11,4)*SF(15) + OP(12,4)*SF(16) + OP(13,4)*SPP(11)) + SPP(1)*(OP(1,1) + OP(2,1)*SF(10) + OP(3,1)*SF(12) + OP(4,1)*SF(11) + OP(11,1)*SF(15) + OP(12,1)*SF(16) + OP(13,1)*SPP(11)) + SPP(5)*(OP(1,14) + OP(2,14)*SF(10) + OP(3,14)*SF(12) + OP(4,14)*SF(11) + OP(11,14)*SF(15) + OP(12,14)*SF(16) + OP(13,14)*SPP(11)) - SPP(8)*(OP(1,15) + OP(2,15)*SF(10) + OP(3,15)*SF(12) + OP(4,15)*SF(11) + OP(11,15)*SF(15) + OP(12,15)*SF(16) + OP(13,15)*SPP(11)) - SPP(2)*(OP(1,16) + OP(2,16)*SF(10) + OP(3,16)*SF(12) + OP(4,16)*SF(11) + OP(11,16)*SF(15) + OP(12,16)*SF(16) + OP(13,16)*SPP(11)); +nextP(2,7) = OP(2,7) + OP(1,7)*SF(9) + OP(3,7)*SF(8) + OP(4,7)*SF(12) - OP(13,7)*SF(16) + OP(12,7)*SPP(11) - (OP(11,7)*q0)/2 + SF(5)*(OP(2,2) + OP(1,2)*SF(9) + OP(3,2)*SF(8) + OP(4,2)*SF(12) - OP(13,2)*SF(16) + OP(12,2)*SPP(11) - (OP(11,2)*q0)/2) - SF(6)*(OP(2,3) + OP(1,3)*SF(9) + OP(3,3)*SF(8) + OP(4,3)*SF(12) - OP(13,3)*SF(16) + OP(12,3)*SPP(11) - (OP(11,3)*q0)/2) + SF(4)*(OP(2,4) + OP(1,4)*SF(9) + OP(3,4)*SF(8) + OP(4,4)*SF(12) - OP(13,4)*SF(16) + OP(12,4)*SPP(11) - (OP(11,4)*q0)/2) + SPP(1)*(OP(2,1) + OP(1,1)*SF(9) + OP(3,1)*SF(8) + OP(4,1)*SF(12) - OP(13,1)*SF(16) + OP(12,1)*SPP(11) - (OP(11,1)*q0)/2) + SPP(5)*(OP(2,14) + OP(1,14)*SF(9) + OP(3,14)*SF(8) + OP(4,14)*SF(12) - OP(13,14)*SF(16) + OP(12,14)*SPP(11) - (OP(11,14)*q0)/2) - SPP(8)*(OP(2,15) + OP(1,15)*SF(9) + OP(3,15)*SF(8) + OP(4,15)*SF(12) - OP(13,15)*SF(16) + OP(12,15)*SPP(11) - (OP(11,15)*q0)/2) - SPP(2)*(OP(2,16) + OP(1,16)*SF(9) + OP(3,16)*SF(8) + OP(4,16)*SF(12) - OP(13,16)*SF(16) + OP(12,16)*SPP(11) - (OP(11,16)*q0)/2); +nextP(3,7) = OP(3,7) + OP(1,7)*SF(7) + OP(2,7)*SF(11) + OP(4,7)*SF(9) + OP(13,7)*SF(15) - OP(11,7)*SPP(11) - (OP(12,7)*q0)/2 + SF(5)*(OP(3,2) + OP(1,2)*SF(7) + OP(2,2)*SF(11) + OP(4,2)*SF(9) + OP(13,2)*SF(15) - OP(11,2)*SPP(11) - (OP(12,2)*q0)/2) - SF(6)*(OP(3,3) + OP(1,3)*SF(7) + OP(2,3)*SF(11) + OP(4,3)*SF(9) + OP(13,3)*SF(15) - OP(11,3)*SPP(11) - (OP(12,3)*q0)/2) + SF(4)*(OP(3,4) + OP(1,4)*SF(7) + OP(2,4)*SF(11) + OP(4,4)*SF(9) + OP(13,4)*SF(15) - OP(11,4)*SPP(11) - (OP(12,4)*q0)/2) + SPP(1)*(OP(3,1) + OP(1,1)*SF(7) + OP(2,1)*SF(11) + OP(4,1)*SF(9) + OP(13,1)*SF(15) - OP(11,1)*SPP(11) - (OP(12,1)*q0)/2) + SPP(5)*(OP(3,14) + OP(1,14)*SF(7) + OP(2,14)*SF(11) + OP(4,14)*SF(9) + OP(13,14)*SF(15) - OP(11,14)*SPP(11) - (OP(12,14)*q0)/2) - SPP(8)*(OP(3,15) + OP(1,15)*SF(7) + OP(2,15)*SF(11) + OP(4,15)*SF(9) + OP(13,15)*SF(15) - OP(11,15)*SPP(11) - (OP(12,15)*q0)/2) - SPP(2)*(OP(3,16) + OP(1,16)*SF(7) + OP(2,16)*SF(11) + OP(4,16)*SF(9) + OP(13,16)*SF(15) - OP(11,16)*SPP(11) - (OP(12,16)*q0)/2); +nextP(4,7) = OP(4,7) + OP(1,7)*SF(8) + OP(2,7)*SF(7) + OP(3,7)*SF(10) + OP(11,7)*SF(16) - OP(12,7)*SF(15) - (OP(13,7)*q0)/2 + SF(5)*(OP(4,2) + OP(1,2)*SF(8) + OP(2,2)*SF(7) + OP(3,2)*SF(10) + OP(11,2)*SF(16) - OP(12,2)*SF(15) - (OP(13,2)*q0)/2) - SF(6)*(OP(4,3) + OP(1,3)*SF(8) + OP(2,3)*SF(7) + OP(3,3)*SF(10) + OP(11,3)*SF(16) - OP(12,3)*SF(15) - (OP(13,3)*q0)/2) + SF(4)*(OP(4,4) + OP(1,4)*SF(8) + OP(2,4)*SF(7) + OP(3,4)*SF(10) + OP(11,4)*SF(16) - OP(12,4)*SF(15) - (OP(13,4)*q0)/2) + SPP(1)*(OP(4,1) + OP(1,1)*SF(8) + OP(2,1)*SF(7) + OP(3,1)*SF(10) + OP(11,1)*SF(16) - OP(12,1)*SF(15) - (OP(13,1)*q0)/2) + SPP(5)*(OP(4,14) + OP(1,14)*SF(8) + OP(2,14)*SF(7) + OP(3,14)*SF(10) + OP(11,14)*SF(16) - OP(12,14)*SF(15) - (OP(13,14)*q0)/2) - SPP(8)*(OP(4,15) + OP(1,15)*SF(8) + OP(2,15)*SF(7) + OP(3,15)*SF(10) + OP(11,15)*SF(16) - OP(12,15)*SF(15) - (OP(13,15)*q0)/2) - SPP(2)*(OP(4,16) + OP(1,16)*SF(8) + OP(2,16)*SF(7) + OP(3,16)*SF(10) + OP(11,16)*SF(16) - OP(12,16)*SF(15) - (OP(13,16)*q0)/2); +nextP(5,7) = OP(5,7) + SQ(2) + OP(1,7)*SF(6) + OP(2,7)*SF(4) - OP(4,7)*SF(5) + OP(3,7)*SPP(1) + OP(14,7)*SPP(4) + OP(15,7)*SPP(7) - OP(16,7)*SPP(10) + SF(5)*(OP(5,2) + OP(1,2)*SF(6) + OP(2,2)*SF(4) - OP(4,2)*SF(5) + OP(3,2)*SPP(1) + OP(14,2)*SPP(4) + OP(15,2)*SPP(7) - OP(16,2)*SPP(10)) - SF(6)*(OP(5,3) + OP(1,3)*SF(6) + OP(2,3)*SF(4) - OP(4,3)*SF(5) + OP(3,3)*SPP(1) + OP(14,3)*SPP(4) + OP(15,3)*SPP(7) - OP(16,3)*SPP(10)) + SF(4)*(OP(5,4) + OP(1,4)*SF(6) + OP(2,4)*SF(4) - OP(4,4)*SF(5) + OP(3,4)*SPP(1) + OP(14,4)*SPP(4) + OP(15,4)*SPP(7) - OP(16,4)*SPP(10)) + SPP(1)*(OP(5,1) + OP(1,1)*SF(6) + OP(2,1)*SF(4) - OP(4,1)*SF(5) + OP(3,1)*SPP(1) + OP(14,1)*SPP(4) + OP(15,1)*SPP(7) - OP(16,1)*SPP(10)) + SPP(5)*(OP(5,14) + OP(1,14)*SF(6) + OP(2,14)*SF(4) - OP(4,14)*SF(5) + OP(3,14)*SPP(1) + OP(14,14)*SPP(4) + OP(15,14)*SPP(7) - OP(16,14)*SPP(10)) - SPP(8)*(OP(5,15) + OP(1,15)*SF(6) + OP(2,15)*SF(4) - OP(4,15)*SF(5) + OP(3,15)*SPP(1) + OP(14,15)*SPP(4) + OP(15,15)*SPP(7) - OP(16,15)*SPP(10)) - SPP(2)*(OP(5,16) + OP(1,16)*SF(6) + OP(2,16)*SF(4) - OP(4,16)*SF(5) + OP(3,16)*SPP(1) + OP(14,16)*SPP(4) + OP(15,16)*SPP(7) - OP(16,16)*SPP(10)); +nextP(6,7) = OP(6,7) + SQ(1) + OP(1,7)*SF(5) + OP(3,7)*SF(4) + OP(4,7)*SF(6) - OP(2,7)*SPP(1) - OP(14,7)*SPP(9) + OP(15,7)*SPP(3) + OP(16,7)*SPP(6) + SF(5)*(OP(6,2) + OP(1,2)*SF(5) + OP(3,2)*SF(4) + OP(4,2)*SF(6) - OP(2,2)*SPP(1) - OP(14,2)*SPP(9) + OP(15,2)*SPP(3) + OP(16,2)*SPP(6)) - SF(6)*(OP(6,3) + OP(1,3)*SF(5) + OP(3,3)*SF(4) + OP(4,3)*SF(6) - OP(2,3)*SPP(1) - OP(14,3)*SPP(9) + OP(15,3)*SPP(3) + OP(16,3)*SPP(6)) + SF(4)*(OP(6,4) + OP(1,4)*SF(5) + OP(3,4)*SF(4) + OP(4,4)*SF(6) - OP(2,4)*SPP(1) - OP(14,4)*SPP(9) + OP(15,4)*SPP(3) + OP(16,4)*SPP(6)) + SPP(1)*(OP(6,1) + OP(1,1)*SF(5) + OP(3,1)*SF(4) + OP(4,1)*SF(6) - OP(2,1)*SPP(1) - OP(14,1)*SPP(9) + OP(15,1)*SPP(3) + OP(16,1)*SPP(6)) + SPP(5)*(OP(6,14) + OP(1,14)*SF(5) + OP(3,14)*SF(4) + OP(4,14)*SF(6) - OP(2,14)*SPP(1) - OP(14,14)*SPP(9) + OP(15,14)*SPP(3) + OP(16,14)*SPP(6)) - SPP(8)*(OP(6,15) + OP(1,15)*SF(5) + OP(3,15)*SF(4) + OP(4,15)*SF(6) - OP(2,15)*SPP(1) - OP(14,15)*SPP(9) + OP(15,15)*SPP(3) + OP(16,15)*SPP(6)) - SPP(2)*(OP(6,16) + OP(1,16)*SF(5) + OP(3,16)*SF(4) + OP(4,16)*SF(6) - OP(2,16)*SPP(1) - OP(14,16)*SPP(9) + OP(15,16)*SPP(3) + OP(16,16)*SPP(6)); +nextP(7,7) = OP(7,7) + OP(2,7)*SF(5) - OP(3,7)*SF(6) + OP(4,7)*SF(4) + OP(1,7)*SPP(1) + OP(14,7)*SPP(5) - OP(15,7)*SPP(8) - OP(16,7)*SPP(2) + dvxVar*(SG(7) - 2*q0*q2)^2 + dvyVar*(SG(6) + 2*q0*q1)^2 + SF(5)*(OP(7,2) + OP(2,2)*SF(5) - OP(3,2)*SF(6) + OP(4,2)*SF(4) + OP(1,2)*SPP(1) + OP(14,2)*SPP(5) - OP(15,2)*SPP(8) - OP(16,2)*SPP(2)) - SF(6)*(OP(7,3) + OP(2,3)*SF(5) - OP(3,3)*SF(6) + OP(4,3)*SF(4) + OP(1,3)*SPP(1) + OP(14,3)*SPP(5) - OP(15,3)*SPP(8) - OP(16,3)*SPP(2)) + SF(4)*(OP(7,4) + OP(2,4)*SF(5) - OP(3,4)*SF(6) + OP(4,4)*SF(4) + OP(1,4)*SPP(1) + OP(14,4)*SPP(5) - OP(15,4)*SPP(8) - OP(16,4)*SPP(2)) + SPP(1)*(OP(7,1) + OP(2,1)*SF(5) - OP(3,1)*SF(6) + OP(4,1)*SF(4) + OP(1,1)*SPP(1) + OP(14,1)*SPP(5) - OP(15,1)*SPP(8) - OP(16,1)*SPP(2)) + SPP(5)*(OP(7,14) + OP(2,14)*SF(5) - OP(3,14)*SF(6) + OP(4,14)*SF(4) + OP(1,14)*SPP(1) + OP(14,14)*SPP(5) - OP(15,14)*SPP(8) - OP(16,14)*SPP(2)) - SPP(8)*(OP(7,15) + OP(2,15)*SF(5) - OP(3,15)*SF(6) + OP(4,15)*SF(4) + OP(1,15)*SPP(1) + OP(14,15)*SPP(5) - OP(15,15)*SPP(8) - OP(16,15)*SPP(2)) - SPP(2)*(OP(7,16) + OP(2,16)*SF(5) - OP(3,16)*SF(6) + OP(4,16)*SF(4) + OP(1,16)*SPP(1) + OP(14,16)*SPP(5) - OP(15,16)*SPP(8) - OP(16,16)*SPP(2)) + dvzVar*(SG(2) - SG(3) - SG(4) + SG(5))^2; +nextP(1,8) = OP(1,8) + OP(2,8)*SF(10) + OP(3,8)*SF(12) + OP(4,8)*SF(11) + OP(11,8)*SF(15) + OP(12,8)*SF(16) + OP(13,8)*SPP(11) + dt*(OP(1,5) + OP(2,5)*SF(10) + OP(3,5)*SF(12) + OP(4,5)*SF(11) + OP(11,5)*SF(15) + OP(12,5)*SF(16) + OP(13,5)*SPP(11)); +nextP(2,8) = OP(2,8) + OP(1,8)*SF(9) + OP(3,8)*SF(8) + OP(4,8)*SF(12) - OP(13,8)*SF(16) + OP(12,8)*SPP(11) - (OP(11,8)*q0)/2 + dt*(OP(2,5) + OP(1,5)*SF(9) + OP(3,5)*SF(8) + OP(4,5)*SF(12) - OP(13,5)*SF(16) + OP(12,5)*SPP(11) - (OP(11,5)*q0)/2); +nextP(3,8) = OP(3,8) + OP(1,8)*SF(7) + OP(2,8)*SF(11) + OP(4,8)*SF(9) + OP(13,8)*SF(15) - OP(11,8)*SPP(11) - (OP(12,8)*q0)/2 + dt*(OP(3,5) + OP(1,5)*SF(7) + OP(2,5)*SF(11) + OP(4,5)*SF(9) + OP(13,5)*SF(15) - OP(11,5)*SPP(11) - (OP(12,5)*q0)/2); +nextP(4,8) = OP(4,8) + OP(1,8)*SF(8) + OP(2,8)*SF(7) + OP(3,8)*SF(10) + OP(11,8)*SF(16) - OP(12,8)*SF(15) - (OP(13,8)*q0)/2 + dt*(OP(4,5) + OP(1,5)*SF(8) + OP(2,5)*SF(7) + OP(3,5)*SF(10) + OP(11,5)*SF(16) - OP(12,5)*SF(15) - (OP(13,5)*q0)/2); +nextP(5,8) = OP(5,8) + OP(1,8)*SF(6) + OP(2,8)*SF(4) - OP(4,8)*SF(5) + OP(3,8)*SPP(1) + OP(14,8)*SPP(4) + OP(15,8)*SPP(7) - OP(16,8)*SPP(10) + dt*(OP(5,5) + OP(1,5)*SF(6) + OP(2,5)*SF(4) - OP(4,5)*SF(5) + OP(3,5)*SPP(1) + OP(14,5)*SPP(4) + OP(15,5)*SPP(7) - OP(16,5)*SPP(10)); +nextP(6,8) = OP(6,8) + OP(1,8)*SF(5) + OP(3,8)*SF(4) + OP(4,8)*SF(6) - OP(2,8)*SPP(1) - OP(14,8)*SPP(9) + OP(15,8)*SPP(3) + OP(16,8)*SPP(6) + dt*(OP(6,5) + OP(1,5)*SF(5) + OP(3,5)*SF(4) + OP(4,5)*SF(6) - OP(2,5)*SPP(1) - OP(14,5)*SPP(9) + OP(15,5)*SPP(3) + OP(16,5)*SPP(6)); +nextP(7,8) = OP(7,8) + OP(2,8)*SF(5) - OP(3,8)*SF(6) + OP(4,8)*SF(4) + OP(1,8)*SPP(1) + OP(14,8)*SPP(5) - OP(15,8)*SPP(8) - OP(16,8)*SPP(2) + dt*(OP(7,5) + OP(2,5)*SF(5) - OP(3,5)*SF(6) + OP(4,5)*SF(4) + OP(1,5)*SPP(1) + OP(14,5)*SPP(5) - OP(15,5)*SPP(8) - OP(16,5)*SPP(2)); nextP(8,8) = OP(8,8) + OP(5,8)*dt + dt*(OP(8,5) + OP(5,5)*dt); -nextP(1,9) = OP(1,9)*SPP(6) - OP(2,9)*SPP(5) + OP(3,9)*SPP(8) + OP(10,9)*SPP(23) + OP(13,9)*SPP(19) + dt*(OP(1,6)*SPP(6) - OP(2,6)*SPP(5) + OP(3,6)*SPP(8) + OP(10,6)*SPP(23) + OP(13,6)*SPP(19)); -nextP(2,9) = OP(2,9)*SPP(7) - OP(1,9)*SPP(3) - OP(3,9)*SPP(9) + OP(11,9)*SPP(23) + OP(14,9)*SPP(18) + dt*(OP(2,6)*SPP(7) - OP(1,6)*SPP(3) - OP(3,6)*SPP(9) + OP(11,6)*SPP(23) + OP(14,6)*SPP(18)); -nextP(3,9) = OP(1,9)*SPP(15) - OP(2,9)*SPP(4) + OP(3,9)*SPP(14) + OP(12,9)*SPP(23) + OP(15,9)*SPP(17) + dt*(OP(1,6)*SPP(15) - OP(2,6)*SPP(4) + OP(3,6)*SPP(14) + OP(12,6)*SPP(23) + OP(15,6)*SPP(17)); -nextP(4,9) = OP(4,9) + OP(1,9)*SPP(2) + OP(2,9)*SPP(20) + OP(3,9)*SPP(16) - OP(16,9)*SPP(22) + dt*(OP(4,6) + OP(1,6)*SPP(2) + OP(2,6)*SPP(20) + OP(3,6)*SPP(16) - OP(16,6)*SPP(22)); -nextP(5,9) = OP(5,9) + OP(16,9)*SF(23) + OP(1,9)*SPP(21) + OP(2,9)*SPP(13) + OP(3,9)*SPP(12) + dt*(OP(5,6) + OP(16,6)*SF(23) + OP(1,6)*SPP(21) + OP(2,6)*SPP(13) + OP(3,6)*SPP(12)); -nextP(6,9) = OP(6,9) + OP(16,9)*SF(21) - OP(1,9)*SPP(10) + OP(2,9)*SPP(11) + OP(3,9)*SPP(1) + dt*(OP(6,6) + OP(16,6)*SF(21) - OP(1,6)*SPP(10) + OP(2,6)*SPP(11) + OP(3,6)*SPP(1)); -nextP(7,9) = OP(7,9) + OP(4,9)*dt + dt*(OP(7,6) + OP(4,6)*dt); +nextP(1,9) = OP(1,9) + OP(2,9)*SF(10) + OP(3,9)*SF(12) + OP(4,9)*SF(11) + OP(11,9)*SF(15) + OP(12,9)*SF(16) + OP(13,9)*SPP(11) + dt*(OP(1,6) + OP(2,6)*SF(10) + OP(3,6)*SF(12) + OP(4,6)*SF(11) + OP(11,6)*SF(15) + OP(12,6)*SF(16) + OP(13,6)*SPP(11)); +nextP(2,9) = OP(2,9) + OP(1,9)*SF(9) + OP(3,9)*SF(8) + OP(4,9)*SF(12) - OP(13,9)*SF(16) + OP(12,9)*SPP(11) - (OP(11,9)*q0)/2 + dt*(OP(2,6) + OP(1,6)*SF(9) + OP(3,6)*SF(8) + OP(4,6)*SF(12) - OP(13,6)*SF(16) + OP(12,6)*SPP(11) - (OP(11,6)*q0)/2); +nextP(3,9) = OP(3,9) + OP(1,9)*SF(7) + OP(2,9)*SF(11) + OP(4,9)*SF(9) + OP(13,9)*SF(15) - OP(11,9)*SPP(11) - (OP(12,9)*q0)/2 + dt*(OP(3,6) + OP(1,6)*SF(7) + OP(2,6)*SF(11) + OP(4,6)*SF(9) + OP(13,6)*SF(15) - OP(11,6)*SPP(11) - (OP(12,6)*q0)/2); +nextP(4,9) = OP(4,9) + OP(1,9)*SF(8) + OP(2,9)*SF(7) + OP(3,9)*SF(10) + OP(11,9)*SF(16) - OP(12,9)*SF(15) - (OP(13,9)*q0)/2 + dt*(OP(4,6) + OP(1,6)*SF(8) + OP(2,6)*SF(7) + OP(3,6)*SF(10) + OP(11,6)*SF(16) - OP(12,6)*SF(15) - (OP(13,6)*q0)/2); +nextP(5,9) = OP(5,9) + OP(1,9)*SF(6) + OP(2,9)*SF(4) - OP(4,9)*SF(5) + OP(3,9)*SPP(1) + OP(14,9)*SPP(4) + OP(15,9)*SPP(7) - OP(16,9)*SPP(10) + dt*(OP(5,6) + OP(1,6)*SF(6) + OP(2,6)*SF(4) - OP(4,6)*SF(5) + OP(3,6)*SPP(1) + OP(14,6)*SPP(4) + OP(15,6)*SPP(7) - OP(16,6)*SPP(10)); +nextP(6,9) = OP(6,9) + OP(1,9)*SF(5) + OP(3,9)*SF(4) + OP(4,9)*SF(6) - OP(2,9)*SPP(1) - OP(14,9)*SPP(9) + OP(15,9)*SPP(3) + OP(16,9)*SPP(6) + dt*(OP(6,6) + OP(1,6)*SF(5) + OP(3,6)*SF(4) + OP(4,6)*SF(6) - OP(2,6)*SPP(1) - OP(14,6)*SPP(9) + OP(15,6)*SPP(3) + OP(16,6)*SPP(6)); +nextP(7,9) = OP(7,9) + OP(2,9)*SF(5) - OP(3,9)*SF(6) + OP(4,9)*SF(4) + OP(1,9)*SPP(1) + OP(14,9)*SPP(5) - OP(15,9)*SPP(8) - OP(16,9)*SPP(2) + dt*(OP(7,6) + OP(2,6)*SF(5) - OP(3,6)*SF(6) + OP(4,6)*SF(4) + OP(1,6)*SPP(1) + OP(14,6)*SPP(5) - OP(15,6)*SPP(8) - OP(16,6)*SPP(2)); nextP(8,9) = OP(8,9) + OP(5,9)*dt + dt*(OP(8,6) + OP(5,6)*dt); nextP(9,9) = OP(9,9) + OP(6,9)*dt + dt*(OP(9,6) + OP(6,6)*dt); -nextP(1,10) = OP(1,10)*SPP(6) - OP(2,10)*SPP(5) + OP(3,10)*SPP(8) + OP(10,10)*SPP(23) + OP(13,10)*SPP(19); -nextP(2,10) = OP(2,10)*SPP(7) - OP(1,10)*SPP(3) - OP(3,10)*SPP(9) + OP(11,10)*SPP(23) + OP(14,10)*SPP(18); -nextP(3,10) = OP(1,10)*SPP(15) - OP(2,10)*SPP(4) + OP(3,10)*SPP(14) + OP(12,10)*SPP(23) + OP(15,10)*SPP(17); -nextP(4,10) = OP(4,10) + OP(1,10)*SPP(2) + OP(2,10)*SPP(20) + OP(3,10)*SPP(16) - OP(16,10)*SPP(22); -nextP(5,10) = OP(5,10) + OP(16,10)*SF(23) + OP(1,10)*SPP(21) + OP(2,10)*SPP(13) + OP(3,10)*SPP(12); -nextP(6,10) = OP(6,10) + OP(16,10)*SF(21) - OP(1,10)*SPP(10) + OP(2,10)*SPP(11) + OP(3,10)*SPP(1); -nextP(7,10) = OP(7,10) + OP(4,10)*dt; -nextP(8,10) = OP(8,10) + OP(5,10)*dt; -nextP(9,10) = OP(9,10) + OP(6,10)*dt; -nextP(10,10) = OP(10,10); -nextP(1,11) = OP(1,11)*SPP(6) - OP(2,11)*SPP(5) + OP(3,11)*SPP(8) + OP(10,11)*SPP(23) + OP(13,11)*SPP(19); -nextP(2,11) = OP(2,11)*SPP(7) - OP(1,11)*SPP(3) - OP(3,11)*SPP(9) + OP(11,11)*SPP(23) + OP(14,11)*SPP(18); -nextP(3,11) = OP(1,11)*SPP(15) - OP(2,11)*SPP(4) + OP(3,11)*SPP(14) + OP(12,11)*SPP(23) + OP(15,11)*SPP(17); -nextP(4,11) = OP(4,11) + OP(1,11)*SPP(2) + OP(2,11)*SPP(20) + OP(3,11)*SPP(16) - OP(16,11)*SPP(22); -nextP(5,11) = OP(5,11) + OP(16,11)*SF(23) + OP(1,11)*SPP(21) + OP(2,11)*SPP(13) + OP(3,11)*SPP(12); -nextP(6,11) = OP(6,11) + OP(16,11)*SF(21) - OP(1,11)*SPP(10) + OP(2,11)*SPP(11) + OP(3,11)*SPP(1); -nextP(7,11) = OP(7,11) + OP(4,11)*dt; +nextP(1,10) = OP(1,10) + OP(2,10)*SF(10) + OP(3,10)*SF(12) + OP(4,10)*SF(11) + OP(11,10)*SF(15) + OP(12,10)*SF(16) + OP(13,10)*SPP(11) + dt*(OP(1,7) + OP(2,7)*SF(10) + OP(3,7)*SF(12) + OP(4,7)*SF(11) + OP(11,7)*SF(15) + OP(12,7)*SF(16) + OP(13,7)*SPP(11)); +nextP(2,10) = OP(2,10) + OP(1,10)*SF(9) + OP(3,10)*SF(8) + OP(4,10)*SF(12) - OP(13,10)*SF(16) + OP(12,10)*SPP(11) - (OP(11,10)*q0)/2 + dt*(OP(2,7) + OP(1,7)*SF(9) + OP(3,7)*SF(8) + OP(4,7)*SF(12) - OP(13,7)*SF(16) + OP(12,7)*SPP(11) - (OP(11,7)*q0)/2); +nextP(3,10) = OP(3,10) + OP(1,10)*SF(7) + OP(2,10)*SF(11) + OP(4,10)*SF(9) + OP(13,10)*SF(15) - OP(11,10)*SPP(11) - (OP(12,10)*q0)/2 + dt*(OP(3,7) + OP(1,7)*SF(7) + OP(2,7)*SF(11) + OP(4,7)*SF(9) + OP(13,7)*SF(15) - OP(11,7)*SPP(11) - (OP(12,7)*q0)/2); +nextP(4,10) = OP(4,10) + OP(1,10)*SF(8) + OP(2,10)*SF(7) + OP(3,10)*SF(10) + OP(11,10)*SF(16) - OP(12,10)*SF(15) - (OP(13,10)*q0)/2 + dt*(OP(4,7) + OP(1,7)*SF(8) + OP(2,7)*SF(7) + OP(3,7)*SF(10) + OP(11,7)*SF(16) - OP(12,7)*SF(15) - (OP(13,7)*q0)/2); +nextP(5,10) = OP(5,10) + OP(1,10)*SF(6) + OP(2,10)*SF(4) - OP(4,10)*SF(5) + OP(3,10)*SPP(1) + OP(14,10)*SPP(4) + OP(15,10)*SPP(7) - OP(16,10)*SPP(10) + dt*(OP(5,7) + OP(1,7)*SF(6) + OP(2,7)*SF(4) - OP(4,7)*SF(5) + OP(3,7)*SPP(1) + OP(14,7)*SPP(4) + OP(15,7)*SPP(7) - OP(16,7)*SPP(10)); +nextP(6,10) = OP(6,10) + OP(1,10)*SF(5) + OP(3,10)*SF(4) + OP(4,10)*SF(6) - OP(2,10)*SPP(1) - OP(14,10)*SPP(9) + OP(15,10)*SPP(3) + OP(16,10)*SPP(6) + dt*(OP(6,7) + OP(1,7)*SF(5) + OP(3,7)*SF(4) + OP(4,7)*SF(6) - OP(2,7)*SPP(1) - OP(14,7)*SPP(9) + OP(15,7)*SPP(3) + OP(16,7)*SPP(6)); +nextP(7,10) = OP(7,10) + OP(2,10)*SF(5) - OP(3,10)*SF(6) + OP(4,10)*SF(4) + OP(1,10)*SPP(1) + OP(14,10)*SPP(5) - OP(15,10)*SPP(8) - OP(16,10)*SPP(2) + dt*(OP(7,7) + OP(2,7)*SF(5) - OP(3,7)*SF(6) + OP(4,7)*SF(4) + OP(1,7)*SPP(1) + OP(14,7)*SPP(5) - OP(15,7)*SPP(8) - OP(16,7)*SPP(2)); +nextP(8,10) = OP(8,10) + OP(5,10)*dt + dt*(OP(8,7) + OP(5,7)*dt); +nextP(9,10) = OP(9,10) + OP(6,10)*dt + dt*(OP(9,7) + OP(6,7)*dt); +nextP(10,10) = OP(10,10) + OP(7,10)*dt + dt*(OP(10,7) + OP(7,7)*dt); +nextP(1,11) = OP(1,11) + OP(2,11)*SF(10) + OP(3,11)*SF(12) + OP(4,11)*SF(11) + OP(11,11)*SF(15) + OP(12,11)*SF(16) + OP(13,11)*SPP(11); +nextP(2,11) = OP(2,11) + OP(1,11)*SF(9) + OP(3,11)*SF(8) + OP(4,11)*SF(12) - OP(13,11)*SF(16) + OP(12,11)*SPP(11) - (OP(11,11)*q0)/2; +nextP(3,11) = OP(3,11) + OP(1,11)*SF(7) + OP(2,11)*SF(11) + OP(4,11)*SF(9) + OP(13,11)*SF(15) - OP(11,11)*SPP(11) - (OP(12,11)*q0)/2; +nextP(4,11) = OP(4,11) + OP(1,11)*SF(8) + OP(2,11)*SF(7) + OP(3,11)*SF(10) + OP(11,11)*SF(16) - OP(12,11)*SF(15) - (OP(13,11)*q0)/2; +nextP(5,11) = OP(5,11) + OP(1,11)*SF(6) + OP(2,11)*SF(4) - OP(4,11)*SF(5) + OP(3,11)*SPP(1) + OP(14,11)*SPP(4) + OP(15,11)*SPP(7) - OP(16,11)*SPP(10); +nextP(6,11) = OP(6,11) + OP(1,11)*SF(5) + OP(3,11)*SF(4) + OP(4,11)*SF(6) - OP(2,11)*SPP(1) - OP(14,11)*SPP(9) + OP(15,11)*SPP(3) + OP(16,11)*SPP(6); +nextP(7,11) = OP(7,11) + OP(2,11)*SF(5) - OP(3,11)*SF(6) + OP(4,11)*SF(4) + OP(1,11)*SPP(1) + OP(14,11)*SPP(5) - OP(15,11)*SPP(8) - OP(16,11)*SPP(2); nextP(8,11) = OP(8,11) + OP(5,11)*dt; nextP(9,11) = OP(9,11) + OP(6,11)*dt; -nextP(10,11) = OP(10,11); +nextP(10,11) = OP(10,11) + OP(7,11)*dt; nextP(11,11) = OP(11,11); -nextP(1,12) = OP(1,12)*SPP(6) - OP(2,12)*SPP(5) + OP(3,12)*SPP(8) + OP(10,12)*SPP(23) + OP(13,12)*SPP(19); -nextP(2,12) = OP(2,12)*SPP(7) - OP(1,12)*SPP(3) - OP(3,12)*SPP(9) + OP(11,12)*SPP(23) + OP(14,12)*SPP(18); -nextP(3,12) = OP(1,12)*SPP(15) - OP(2,12)*SPP(4) + OP(3,12)*SPP(14) + OP(12,12)*SPP(23) + OP(15,12)*SPP(17); -nextP(4,12) = OP(4,12) + OP(1,12)*SPP(2) + OP(2,12)*SPP(20) + OP(3,12)*SPP(16) - OP(16,12)*SPP(22); -nextP(5,12) = OP(5,12) + OP(16,12)*SF(23) + OP(1,12)*SPP(21) + OP(2,12)*SPP(13) + OP(3,12)*SPP(12); -nextP(6,12) = OP(6,12) + OP(16,12)*SF(21) - OP(1,12)*SPP(10) + OP(2,12)*SPP(11) + OP(3,12)*SPP(1); -nextP(7,12) = OP(7,12) + OP(4,12)*dt; +nextP(1,12) = OP(1,12) + OP(2,12)*SF(10) + OP(3,12)*SF(12) + OP(4,12)*SF(11) + OP(11,12)*SF(15) + OP(12,12)*SF(16) + OP(13,12)*SPP(11); +nextP(2,12) = OP(2,12) + OP(1,12)*SF(9) + OP(3,12)*SF(8) + OP(4,12)*SF(12) - OP(13,12)*SF(16) + OP(12,12)*SPP(11) - (OP(11,12)*q0)/2; +nextP(3,12) = OP(3,12) + OP(1,12)*SF(7) + OP(2,12)*SF(11) + OP(4,12)*SF(9) + OP(13,12)*SF(15) - OP(11,12)*SPP(11) - (OP(12,12)*q0)/2; +nextP(4,12) = OP(4,12) + OP(1,12)*SF(8) + OP(2,12)*SF(7) + OP(3,12)*SF(10) + OP(11,12)*SF(16) - OP(12,12)*SF(15) - (OP(13,12)*q0)/2; +nextP(5,12) = OP(5,12) + OP(1,12)*SF(6) + OP(2,12)*SF(4) - OP(4,12)*SF(5) + OP(3,12)*SPP(1) + OP(14,12)*SPP(4) + OP(15,12)*SPP(7) - OP(16,12)*SPP(10); +nextP(6,12) = OP(6,12) + OP(1,12)*SF(5) + OP(3,12)*SF(4) + OP(4,12)*SF(6) - OP(2,12)*SPP(1) - OP(14,12)*SPP(9) + OP(15,12)*SPP(3) + OP(16,12)*SPP(6); +nextP(7,12) = OP(7,12) + OP(2,12)*SF(5) - OP(3,12)*SF(6) + OP(4,12)*SF(4) + OP(1,12)*SPP(1) + OP(14,12)*SPP(5) - OP(15,12)*SPP(8) - OP(16,12)*SPP(2); nextP(8,12) = OP(8,12) + OP(5,12)*dt; nextP(9,12) = OP(9,12) + OP(6,12)*dt; -nextP(10,12) = OP(10,12); +nextP(10,12) = OP(10,12) + OP(7,12)*dt; nextP(11,12) = OP(11,12); nextP(12,12) = OP(12,12); -nextP(1,13) = OP(1,13)*SPP(6) - OP(2,13)*SPP(5) + OP(3,13)*SPP(8) + OP(10,13)*SPP(23) + OP(13,13)*SPP(19); -nextP(2,13) = OP(2,13)*SPP(7) - OP(1,13)*SPP(3) - OP(3,13)*SPP(9) + OP(11,13)*SPP(23) + OP(14,13)*SPP(18); -nextP(3,13) = OP(1,13)*SPP(15) - OP(2,13)*SPP(4) + OP(3,13)*SPP(14) + OP(12,13)*SPP(23) + OP(15,13)*SPP(17); -nextP(4,13) = OP(4,13) + OP(1,13)*SPP(2) + OP(2,13)*SPP(20) + OP(3,13)*SPP(16) - OP(16,13)*SPP(22); -nextP(5,13) = OP(5,13) + OP(16,13)*SF(23) + OP(1,13)*SPP(21) + OP(2,13)*SPP(13) + OP(3,13)*SPP(12); -nextP(6,13) = OP(6,13) + OP(16,13)*SF(21) - OP(1,13)*SPP(10) + OP(2,13)*SPP(11) + OP(3,13)*SPP(1); -nextP(7,13) = OP(7,13) + OP(4,13)*dt; +nextP(1,13) = OP(1,13) + OP(2,13)*SF(10) + OP(3,13)*SF(12) + OP(4,13)*SF(11) + OP(11,13)*SF(15) + OP(12,13)*SF(16) + OP(13,13)*SPP(11); +nextP(2,13) = OP(2,13) + OP(1,13)*SF(9) + OP(3,13)*SF(8) + OP(4,13)*SF(12) - OP(13,13)*SF(16) + OP(12,13)*SPP(11) - (OP(11,13)*q0)/2; +nextP(3,13) = OP(3,13) + OP(1,13)*SF(7) + OP(2,13)*SF(11) + OP(4,13)*SF(9) + OP(13,13)*SF(15) - OP(11,13)*SPP(11) - (OP(12,13)*q0)/2; +nextP(4,13) = OP(4,13) + OP(1,13)*SF(8) + OP(2,13)*SF(7) + OP(3,13)*SF(10) + OP(11,13)*SF(16) - OP(12,13)*SF(15) - (OP(13,13)*q0)/2; +nextP(5,13) = OP(5,13) + OP(1,13)*SF(6) + OP(2,13)*SF(4) - OP(4,13)*SF(5) + OP(3,13)*SPP(1) + OP(14,13)*SPP(4) + OP(15,13)*SPP(7) - OP(16,13)*SPP(10); +nextP(6,13) = OP(6,13) + OP(1,13)*SF(5) + OP(3,13)*SF(4) + OP(4,13)*SF(6) - OP(2,13)*SPP(1) - OP(14,13)*SPP(9) + OP(15,13)*SPP(3) + OP(16,13)*SPP(6); +nextP(7,13) = OP(7,13) + OP(2,13)*SF(5) - OP(3,13)*SF(6) + OP(4,13)*SF(4) + OP(1,13)*SPP(1) + OP(14,13)*SPP(5) - OP(15,13)*SPP(8) - OP(16,13)*SPP(2); nextP(8,13) = OP(8,13) + OP(5,13)*dt; nextP(9,13) = OP(9,13) + OP(6,13)*dt; -nextP(10,13) = OP(10,13); +nextP(10,13) = OP(10,13) + OP(7,13)*dt; nextP(11,13) = OP(11,13); nextP(12,13) = OP(12,13); nextP(13,13) = OP(13,13); -nextP(1,14) = OP(1,14)*SPP(6) - OP(2,14)*SPP(5) + OP(3,14)*SPP(8) + OP(10,14)*SPP(23) + OP(13,14)*SPP(19); -nextP(2,14) = OP(2,14)*SPP(7) - OP(1,14)*SPP(3) - OP(3,14)*SPP(9) + OP(11,14)*SPP(23) + OP(14,14)*SPP(18); -nextP(3,14) = OP(1,14)*SPP(15) - OP(2,14)*SPP(4) + OP(3,14)*SPP(14) + OP(12,14)*SPP(23) + OP(15,14)*SPP(17); -nextP(4,14) = OP(4,14) + OP(1,14)*SPP(2) + OP(2,14)*SPP(20) + OP(3,14)*SPP(16) - OP(16,14)*SPP(22); -nextP(5,14) = OP(5,14) + OP(16,14)*SF(23) + OP(1,14)*SPP(21) + OP(2,14)*SPP(13) + OP(3,14)*SPP(12); -nextP(6,14) = OP(6,14) + OP(16,14)*SF(21) - OP(1,14)*SPP(10) + OP(2,14)*SPP(11) + OP(3,14)*SPP(1); -nextP(7,14) = OP(7,14) + OP(4,14)*dt; +nextP(1,14) = OP(1,14) + OP(2,14)*SF(10) + OP(3,14)*SF(12) + OP(4,14)*SF(11) + OP(11,14)*SF(15) + OP(12,14)*SF(16) + OP(13,14)*SPP(11); +nextP(2,14) = OP(2,14) + OP(1,14)*SF(9) + OP(3,14)*SF(8) + OP(4,14)*SF(12) - OP(13,14)*SF(16) + OP(12,14)*SPP(11) - (OP(11,14)*q0)/2; +nextP(3,14) = OP(3,14) + OP(1,14)*SF(7) + OP(2,14)*SF(11) + OP(4,14)*SF(9) + OP(13,14)*SF(15) - OP(11,14)*SPP(11) - (OP(12,14)*q0)/2; +nextP(4,14) = OP(4,14) + OP(1,14)*SF(8) + OP(2,14)*SF(7) + OP(3,14)*SF(10) + OP(11,14)*SF(16) - OP(12,14)*SF(15) - (OP(13,14)*q0)/2; +nextP(5,14) = OP(5,14) + OP(1,14)*SF(6) + OP(2,14)*SF(4) - OP(4,14)*SF(5) + OP(3,14)*SPP(1) + OP(14,14)*SPP(4) + OP(15,14)*SPP(7) - OP(16,14)*SPP(10); +nextP(6,14) = OP(6,14) + OP(1,14)*SF(5) + OP(3,14)*SF(4) + OP(4,14)*SF(6) - OP(2,14)*SPP(1) - OP(14,14)*SPP(9) + OP(15,14)*SPP(3) + OP(16,14)*SPP(6); +nextP(7,14) = OP(7,14) + OP(2,14)*SF(5) - OP(3,14)*SF(6) + OP(4,14)*SF(4) + OP(1,14)*SPP(1) + OP(14,14)*SPP(5) - OP(15,14)*SPP(8) - OP(16,14)*SPP(2); nextP(8,14) = OP(8,14) + OP(5,14)*dt; nextP(9,14) = OP(9,14) + OP(6,14)*dt; -nextP(10,14) = OP(10,14); +nextP(10,14) = OP(10,14) + OP(7,14)*dt; nextP(11,14) = OP(11,14); nextP(12,14) = OP(12,14); nextP(13,14) = OP(13,14); nextP(14,14) = OP(14,14); -nextP(1,15) = OP(1,15)*SPP(6) - OP(2,15)*SPP(5) + OP(3,15)*SPP(8) + OP(10,15)*SPP(23) + OP(13,15)*SPP(19); -nextP(2,15) = OP(2,15)*SPP(7) - OP(1,15)*SPP(3) - OP(3,15)*SPP(9) + OP(11,15)*SPP(23) + OP(14,15)*SPP(18); -nextP(3,15) = OP(1,15)*SPP(15) - OP(2,15)*SPP(4) + OP(3,15)*SPP(14) + OP(12,15)*SPP(23) + OP(15,15)*SPP(17); -nextP(4,15) = OP(4,15) + OP(1,15)*SPP(2) + OP(2,15)*SPP(20) + OP(3,15)*SPP(16) - OP(16,15)*SPP(22); -nextP(5,15) = OP(5,15) + OP(16,15)*SF(23) + OP(1,15)*SPP(21) + OP(2,15)*SPP(13) + OP(3,15)*SPP(12); -nextP(6,15) = OP(6,15) + OP(16,15)*SF(21) - OP(1,15)*SPP(10) + OP(2,15)*SPP(11) + OP(3,15)*SPP(1); -nextP(7,15) = OP(7,15) + OP(4,15)*dt; +nextP(1,15) = OP(1,15) + OP(2,15)*SF(10) + OP(3,15)*SF(12) + OP(4,15)*SF(11) + OP(11,15)*SF(15) + OP(12,15)*SF(16) + OP(13,15)*SPP(11); +nextP(2,15) = OP(2,15) + OP(1,15)*SF(9) + OP(3,15)*SF(8) + OP(4,15)*SF(12) - OP(13,15)*SF(16) + OP(12,15)*SPP(11) - (OP(11,15)*q0)/2; +nextP(3,15) = OP(3,15) + OP(1,15)*SF(7) + OP(2,15)*SF(11) + OP(4,15)*SF(9) + OP(13,15)*SF(15) - OP(11,15)*SPP(11) - (OP(12,15)*q0)/2; +nextP(4,15) = OP(4,15) + OP(1,15)*SF(8) + OP(2,15)*SF(7) + OP(3,15)*SF(10) + OP(11,15)*SF(16) - OP(12,15)*SF(15) - (OP(13,15)*q0)/2; +nextP(5,15) = OP(5,15) + OP(1,15)*SF(6) + OP(2,15)*SF(4) - OP(4,15)*SF(5) + OP(3,15)*SPP(1) + OP(14,15)*SPP(4) + OP(15,15)*SPP(7) - OP(16,15)*SPP(10); +nextP(6,15) = OP(6,15) + OP(1,15)*SF(5) + OP(3,15)*SF(4) + OP(4,15)*SF(6) - OP(2,15)*SPP(1) - OP(14,15)*SPP(9) + OP(15,15)*SPP(3) + OP(16,15)*SPP(6); +nextP(7,15) = OP(7,15) + OP(2,15)*SF(5) - OP(3,15)*SF(6) + OP(4,15)*SF(4) + OP(1,15)*SPP(1) + OP(14,15)*SPP(5) - OP(15,15)*SPP(8) - OP(16,15)*SPP(2); nextP(8,15) = OP(8,15) + OP(5,15)*dt; nextP(9,15) = OP(9,15) + OP(6,15)*dt; -nextP(10,15) = OP(10,15); +nextP(10,15) = OP(10,15) + OP(7,15)*dt; nextP(11,15) = OP(11,15); nextP(12,15) = OP(12,15); nextP(13,15) = OP(13,15); nextP(14,15) = OP(14,15); nextP(15,15) = OP(15,15); -nextP(1,16) = OP(1,16)*SPP(6) - OP(2,16)*SPP(5) + OP(3,16)*SPP(8) + OP(10,16)*SPP(23) + OP(13,16)*SPP(19); -nextP(2,16) = OP(2,16)*SPP(7) - OP(1,16)*SPP(3) - OP(3,16)*SPP(9) + OP(11,16)*SPP(23) + OP(14,16)*SPP(18); -nextP(3,16) = OP(1,16)*SPP(15) - OP(2,16)*SPP(4) + OP(3,16)*SPP(14) + OP(12,16)*SPP(23) + OP(15,16)*SPP(17); -nextP(4,16) = OP(4,16) + OP(1,16)*SPP(2) + OP(2,16)*SPP(20) + OP(3,16)*SPP(16) - OP(16,16)*SPP(22); -nextP(5,16) = OP(5,16) + OP(16,16)*SF(23) + OP(1,16)*SPP(21) + OP(2,16)*SPP(13) + OP(3,16)*SPP(12); -nextP(6,16) = OP(6,16) + OP(16,16)*SF(21) - OP(1,16)*SPP(10) + OP(2,16)*SPP(11) + OP(3,16)*SPP(1); -nextP(7,16) = OP(7,16) + OP(4,16)*dt; +nextP(1,16) = OP(1,16) + OP(2,16)*SF(10) + OP(3,16)*SF(12) + OP(4,16)*SF(11) + OP(11,16)*SF(15) + OP(12,16)*SF(16) + OP(13,16)*SPP(11); +nextP(2,16) = OP(2,16) + OP(1,16)*SF(9) + OP(3,16)*SF(8) + OP(4,16)*SF(12) - OP(13,16)*SF(16) + OP(12,16)*SPP(11) - (OP(11,16)*q0)/2; +nextP(3,16) = OP(3,16) + OP(1,16)*SF(7) + OP(2,16)*SF(11) + OP(4,16)*SF(9) + OP(13,16)*SF(15) - OP(11,16)*SPP(11) - (OP(12,16)*q0)/2; +nextP(4,16) = OP(4,16) + OP(1,16)*SF(8) + OP(2,16)*SF(7) + OP(3,16)*SF(10) + OP(11,16)*SF(16) - OP(12,16)*SF(15) - (OP(13,16)*q0)/2; +nextP(5,16) = OP(5,16) + OP(1,16)*SF(6) + OP(2,16)*SF(4) - OP(4,16)*SF(5) + OP(3,16)*SPP(1) + OP(14,16)*SPP(4) + OP(15,16)*SPP(7) - OP(16,16)*SPP(10); +nextP(6,16) = OP(6,16) + OP(1,16)*SF(5) + OP(3,16)*SF(4) + OP(4,16)*SF(6) - OP(2,16)*SPP(1) - OP(14,16)*SPP(9) + OP(15,16)*SPP(3) + OP(16,16)*SPP(6); +nextP(7,16) = OP(7,16) + OP(2,16)*SF(5) - OP(3,16)*SF(6) + OP(4,16)*SF(4) + OP(1,16)*SPP(1) + OP(14,16)*SPP(5) - OP(15,16)*SPP(8) - OP(16,16)*SPP(2); nextP(8,16) = OP(8,16) + OP(5,16)*dt; nextP(9,16) = OP(9,16) + OP(6,16)*dt; -nextP(10,16) = OP(10,16); +nextP(10,16) = OP(10,16) + OP(7,16)*dt; nextP(11,16) = OP(11,16); nextP(12,16) = OP(12,16); nextP(13,16) = OP(13,16); nextP(14,16) = OP(14,16); nextP(15,16) = OP(15,16); nextP(16,16) = OP(16,16); -nextP(1,17) = OP(1,17)*SPP(6) - OP(2,17)*SPP(5) + OP(3,17)*SPP(8) + OP(10,17)*SPP(23) + OP(13,17)*SPP(19); -nextP(2,17) = OP(2,17)*SPP(7) - OP(1,17)*SPP(3) - OP(3,17)*SPP(9) + OP(11,17)*SPP(23) + OP(14,17)*SPP(18); -nextP(3,17) = OP(1,17)*SPP(15) - OP(2,17)*SPP(4) + OP(3,17)*SPP(14) + OP(12,17)*SPP(23) + OP(15,17)*SPP(17); -nextP(4,17) = OP(4,17) + OP(1,17)*SPP(2) + OP(2,17)*SPP(20) + OP(3,17)*SPP(16) - OP(16,17)*SPP(22); -nextP(5,17) = OP(5,17) + OP(16,17)*SF(23) + OP(1,17)*SPP(21) + OP(2,17)*SPP(13) + OP(3,17)*SPP(12); -nextP(6,17) = OP(6,17) + OP(16,17)*SF(21) - OP(1,17)*SPP(10) + OP(2,17)*SPP(11) + OP(3,17)*SPP(1); -nextP(7,17) = OP(7,17) + OP(4,17)*dt; +nextP(1,17) = OP(1,17) + OP(2,17)*SF(10) + OP(3,17)*SF(12) + OP(4,17)*SF(11) + OP(11,17)*SF(15) + OP(12,17)*SF(16) + OP(13,17)*SPP(11); +nextP(2,17) = OP(2,17) + OP(1,17)*SF(9) + OP(3,17)*SF(8) + OP(4,17)*SF(12) - OP(13,17)*SF(16) + OP(12,17)*SPP(11) - (OP(11,17)*q0)/2; +nextP(3,17) = OP(3,17) + OP(1,17)*SF(7) + OP(2,17)*SF(11) + OP(4,17)*SF(9) + OP(13,17)*SF(15) - OP(11,17)*SPP(11) - (OP(12,17)*q0)/2; +nextP(4,17) = OP(4,17) + OP(1,17)*SF(8) + OP(2,17)*SF(7) + OP(3,17)*SF(10) + OP(11,17)*SF(16) - OP(12,17)*SF(15) - (OP(13,17)*q0)/2; +nextP(5,17) = OP(5,17) + OP(1,17)*SF(6) + OP(2,17)*SF(4) - OP(4,17)*SF(5) + OP(3,17)*SPP(1) + OP(14,17)*SPP(4) + OP(15,17)*SPP(7) - OP(16,17)*SPP(10); +nextP(6,17) = OP(6,17) + OP(1,17)*SF(5) + OP(3,17)*SF(4) + OP(4,17)*SF(6) - OP(2,17)*SPP(1) - OP(14,17)*SPP(9) + OP(15,17)*SPP(3) + OP(16,17)*SPP(6); +nextP(7,17) = OP(7,17) + OP(2,17)*SF(5) - OP(3,17)*SF(6) + OP(4,17)*SF(4) + OP(1,17)*SPP(1) + OP(14,17)*SPP(5) - OP(15,17)*SPP(8) - OP(16,17)*SPP(2); nextP(8,17) = OP(8,17) + OP(5,17)*dt; nextP(9,17) = OP(9,17) + OP(6,17)*dt; -nextP(10,17) = OP(10,17); +nextP(10,17) = OP(10,17) + OP(7,17)*dt; nextP(11,17) = OP(11,17); nextP(12,17) = OP(12,17); nextP(13,17) = OP(13,17); @@ -219,16 +207,16 @@ nextP(14,17) = OP(14,17); nextP(15,17) = OP(15,17); nextP(16,17) = OP(16,17); nextP(17,17) = OP(17,17); -nextP(1,18) = OP(1,18)*SPP(6) - OP(2,18)*SPP(5) + OP(3,18)*SPP(8) + OP(10,18)*SPP(23) + OP(13,18)*SPP(19); -nextP(2,18) = OP(2,18)*SPP(7) - OP(1,18)*SPP(3) - OP(3,18)*SPP(9) + OP(11,18)*SPP(23) + OP(14,18)*SPP(18); -nextP(3,18) = OP(1,18)*SPP(15) - OP(2,18)*SPP(4) + OP(3,18)*SPP(14) + OP(12,18)*SPP(23) + OP(15,18)*SPP(17); -nextP(4,18) = OP(4,18) + OP(1,18)*SPP(2) + OP(2,18)*SPP(20) + OP(3,18)*SPP(16) - OP(16,18)*SPP(22); -nextP(5,18) = OP(5,18) + OP(16,18)*SF(23) + OP(1,18)*SPP(21) + OP(2,18)*SPP(13) + OP(3,18)*SPP(12); -nextP(6,18) = OP(6,18) + OP(16,18)*SF(21) - OP(1,18)*SPP(10) + OP(2,18)*SPP(11) + OP(3,18)*SPP(1); -nextP(7,18) = OP(7,18) + OP(4,18)*dt; +nextP(1,18) = OP(1,18) + OP(2,18)*SF(10) + OP(3,18)*SF(12) + OP(4,18)*SF(11) + OP(11,18)*SF(15) + OP(12,18)*SF(16) + OP(13,18)*SPP(11); +nextP(2,18) = OP(2,18) + OP(1,18)*SF(9) + OP(3,18)*SF(8) + OP(4,18)*SF(12) - OP(13,18)*SF(16) + OP(12,18)*SPP(11) - (OP(11,18)*q0)/2; +nextP(3,18) = OP(3,18) + OP(1,18)*SF(7) + OP(2,18)*SF(11) + OP(4,18)*SF(9) + OP(13,18)*SF(15) - OP(11,18)*SPP(11) - (OP(12,18)*q0)/2; +nextP(4,18) = OP(4,18) + OP(1,18)*SF(8) + OP(2,18)*SF(7) + OP(3,18)*SF(10) + OP(11,18)*SF(16) - OP(12,18)*SF(15) - (OP(13,18)*q0)/2; +nextP(5,18) = OP(5,18) + OP(1,18)*SF(6) + OP(2,18)*SF(4) - OP(4,18)*SF(5) + OP(3,18)*SPP(1) + OP(14,18)*SPP(4) + OP(15,18)*SPP(7) - OP(16,18)*SPP(10); +nextP(6,18) = OP(6,18) + OP(1,18)*SF(5) + OP(3,18)*SF(4) + OP(4,18)*SF(6) - OP(2,18)*SPP(1) - OP(14,18)*SPP(9) + OP(15,18)*SPP(3) + OP(16,18)*SPP(6); +nextP(7,18) = OP(7,18) + OP(2,18)*SF(5) - OP(3,18)*SF(6) + OP(4,18)*SF(4) + OP(1,18)*SPP(1) + OP(14,18)*SPP(5) - OP(15,18)*SPP(8) - OP(16,18)*SPP(2); nextP(8,18) = OP(8,18) + OP(5,18)*dt; nextP(9,18) = OP(9,18) + OP(6,18)*dt; -nextP(10,18) = OP(10,18); +nextP(10,18) = OP(10,18) + OP(7,18)*dt; nextP(11,18) = OP(11,18); nextP(12,18) = OP(12,18); nextP(13,18) = OP(13,18); @@ -237,16 +225,16 @@ nextP(15,18) = OP(15,18); nextP(16,18) = OP(16,18); nextP(17,18) = OP(17,18); nextP(18,18) = OP(18,18); -nextP(1,19) = OP(1,19)*SPP(6) - OP(2,19)*SPP(5) + OP(3,19)*SPP(8) + OP(10,19)*SPP(23) + OP(13,19)*SPP(19); -nextP(2,19) = OP(2,19)*SPP(7) - OP(1,19)*SPP(3) - OP(3,19)*SPP(9) + OP(11,19)*SPP(23) + OP(14,19)*SPP(18); -nextP(3,19) = OP(1,19)*SPP(15) - OP(2,19)*SPP(4) + OP(3,19)*SPP(14) + OP(12,19)*SPP(23) + OP(15,19)*SPP(17); -nextP(4,19) = OP(4,19) + OP(1,19)*SPP(2) + OP(2,19)*SPP(20) + OP(3,19)*SPP(16) - OP(16,19)*SPP(22); -nextP(5,19) = OP(5,19) + OP(16,19)*SF(23) + OP(1,19)*SPP(21) + OP(2,19)*SPP(13) + OP(3,19)*SPP(12); -nextP(6,19) = OP(6,19) + OP(16,19)*SF(21) - OP(1,19)*SPP(10) + OP(2,19)*SPP(11) + OP(3,19)*SPP(1); -nextP(7,19) = OP(7,19) + OP(4,19)*dt; +nextP(1,19) = OP(1,19) + OP(2,19)*SF(10) + OP(3,19)*SF(12) + OP(4,19)*SF(11) + OP(11,19)*SF(15) + OP(12,19)*SF(16) + OP(13,19)*SPP(11); +nextP(2,19) = OP(2,19) + OP(1,19)*SF(9) + OP(3,19)*SF(8) + OP(4,19)*SF(12) - OP(13,19)*SF(16) + OP(12,19)*SPP(11) - (OP(11,19)*q0)/2; +nextP(3,19) = OP(3,19) + OP(1,19)*SF(7) + OP(2,19)*SF(11) + OP(4,19)*SF(9) + OP(13,19)*SF(15) - OP(11,19)*SPP(11) - (OP(12,19)*q0)/2; +nextP(4,19) = OP(4,19) + OP(1,19)*SF(8) + OP(2,19)*SF(7) + OP(3,19)*SF(10) + OP(11,19)*SF(16) - OP(12,19)*SF(15) - (OP(13,19)*q0)/2; +nextP(5,19) = OP(5,19) + OP(1,19)*SF(6) + OP(2,19)*SF(4) - OP(4,19)*SF(5) + OP(3,19)*SPP(1) + OP(14,19)*SPP(4) + OP(15,19)*SPP(7) - OP(16,19)*SPP(10); +nextP(6,19) = OP(6,19) + OP(1,19)*SF(5) + OP(3,19)*SF(4) + OP(4,19)*SF(6) - OP(2,19)*SPP(1) - OP(14,19)*SPP(9) + OP(15,19)*SPP(3) + OP(16,19)*SPP(6); +nextP(7,19) = OP(7,19) + OP(2,19)*SF(5) - OP(3,19)*SF(6) + OP(4,19)*SF(4) + OP(1,19)*SPP(1) + OP(14,19)*SPP(5) - OP(15,19)*SPP(8) - OP(16,19)*SPP(2); nextP(8,19) = OP(8,19) + OP(5,19)*dt; nextP(9,19) = OP(9,19) + OP(6,19)*dt; -nextP(10,19) = OP(10,19); +nextP(10,19) = OP(10,19) + OP(7,19)*dt; nextP(11,19) = OP(11,19); nextP(12,19) = OP(12,19); nextP(13,19) = OP(13,19); @@ -256,16 +244,16 @@ nextP(16,19) = OP(16,19); nextP(17,19) = OP(17,19); nextP(18,19) = OP(18,19); nextP(19,19) = OP(19,19); -nextP(1,20) = OP(1,20)*SPP(6) - OP(2,20)*SPP(5) + OP(3,20)*SPP(8) + OP(10,20)*SPP(23) + OP(13,20)*SPP(19); -nextP(2,20) = OP(2,20)*SPP(7) - OP(1,20)*SPP(3) - OP(3,20)*SPP(9) + OP(11,20)*SPP(23) + OP(14,20)*SPP(18); -nextP(3,20) = OP(1,20)*SPP(15) - OP(2,20)*SPP(4) + OP(3,20)*SPP(14) + OP(12,20)*SPP(23) + OP(15,20)*SPP(17); -nextP(4,20) = OP(4,20) + OP(1,20)*SPP(2) + OP(2,20)*SPP(20) + OP(3,20)*SPP(16) - OP(16,20)*SPP(22); -nextP(5,20) = OP(5,20) + OP(16,20)*SF(23) + OP(1,20)*SPP(21) + OP(2,20)*SPP(13) + OP(3,20)*SPP(12); -nextP(6,20) = OP(6,20) + OP(16,20)*SF(21) - OP(1,20)*SPP(10) + OP(2,20)*SPP(11) + OP(3,20)*SPP(1); -nextP(7,20) = OP(7,20) + OP(4,20)*dt; +nextP(1,20) = OP(1,20) + OP(2,20)*SF(10) + OP(3,20)*SF(12) + OP(4,20)*SF(11) + OP(11,20)*SF(15) + OP(12,20)*SF(16) + OP(13,20)*SPP(11); +nextP(2,20) = OP(2,20) + OP(1,20)*SF(9) + OP(3,20)*SF(8) + OP(4,20)*SF(12) - OP(13,20)*SF(16) + OP(12,20)*SPP(11) - (OP(11,20)*q0)/2; +nextP(3,20) = OP(3,20) + OP(1,20)*SF(7) + OP(2,20)*SF(11) + OP(4,20)*SF(9) + OP(13,20)*SF(15) - OP(11,20)*SPP(11) - (OP(12,20)*q0)/2; +nextP(4,20) = OP(4,20) + OP(1,20)*SF(8) + OP(2,20)*SF(7) + OP(3,20)*SF(10) + OP(11,20)*SF(16) - OP(12,20)*SF(15) - (OP(13,20)*q0)/2; +nextP(5,20) = OP(5,20) + OP(1,20)*SF(6) + OP(2,20)*SF(4) - OP(4,20)*SF(5) + OP(3,20)*SPP(1) + OP(14,20)*SPP(4) + OP(15,20)*SPP(7) - OP(16,20)*SPP(10); +nextP(6,20) = OP(6,20) + OP(1,20)*SF(5) + OP(3,20)*SF(4) + OP(4,20)*SF(6) - OP(2,20)*SPP(1) - OP(14,20)*SPP(9) + OP(15,20)*SPP(3) + OP(16,20)*SPP(6); +nextP(7,20) = OP(7,20) + OP(2,20)*SF(5) - OP(3,20)*SF(6) + OP(4,20)*SF(4) + OP(1,20)*SPP(1) + OP(14,20)*SPP(5) - OP(15,20)*SPP(8) - OP(16,20)*SPP(2); nextP(8,20) = OP(8,20) + OP(5,20)*dt; nextP(9,20) = OP(9,20) + OP(6,20)*dt; -nextP(10,20) = OP(10,20); +nextP(10,20) = OP(10,20) + OP(7,20)*dt; nextP(11,20) = OP(11,20); nextP(12,20) = OP(12,20); nextP(13,20) = OP(13,20); @@ -276,16 +264,16 @@ nextP(17,20) = OP(17,20); nextP(18,20) = OP(18,20); nextP(19,20) = OP(19,20); nextP(20,20) = OP(20,20); -nextP(1,21) = OP(1,21)*SPP(6) - OP(2,21)*SPP(5) + OP(3,21)*SPP(8) + OP(10,21)*SPP(23) + OP(13,21)*SPP(19); -nextP(2,21) = OP(2,21)*SPP(7) - OP(1,21)*SPP(3) - OP(3,21)*SPP(9) + OP(11,21)*SPP(23) + OP(14,21)*SPP(18); -nextP(3,21) = OP(1,21)*SPP(15) - OP(2,21)*SPP(4) + OP(3,21)*SPP(14) + OP(12,21)*SPP(23) + OP(15,21)*SPP(17); -nextP(4,21) = OP(4,21) + OP(1,21)*SPP(2) + OP(2,21)*SPP(20) + OP(3,21)*SPP(16) - OP(16,21)*SPP(22); -nextP(5,21) = OP(5,21) + OP(16,21)*SF(23) + OP(1,21)*SPP(21) + OP(2,21)*SPP(13) + OP(3,21)*SPP(12); -nextP(6,21) = OP(6,21) + OP(16,21)*SF(21) - OP(1,21)*SPP(10) + OP(2,21)*SPP(11) + OP(3,21)*SPP(1); -nextP(7,21) = OP(7,21) + OP(4,21)*dt; +nextP(1,21) = OP(1,21) + OP(2,21)*SF(10) + OP(3,21)*SF(12) + OP(4,21)*SF(11) + OP(11,21)*SF(15) + OP(12,21)*SF(16) + OP(13,21)*SPP(11); +nextP(2,21) = OP(2,21) + OP(1,21)*SF(9) + OP(3,21)*SF(8) + OP(4,21)*SF(12) - OP(13,21)*SF(16) + OP(12,21)*SPP(11) - (OP(11,21)*q0)/2; +nextP(3,21) = OP(3,21) + OP(1,21)*SF(7) + OP(2,21)*SF(11) + OP(4,21)*SF(9) + OP(13,21)*SF(15) - OP(11,21)*SPP(11) - (OP(12,21)*q0)/2; +nextP(4,21) = OP(4,21) + OP(1,21)*SF(8) + OP(2,21)*SF(7) + OP(3,21)*SF(10) + OP(11,21)*SF(16) - OP(12,21)*SF(15) - (OP(13,21)*q0)/2; +nextP(5,21) = OP(5,21) + OP(1,21)*SF(6) + OP(2,21)*SF(4) - OP(4,21)*SF(5) + OP(3,21)*SPP(1) + OP(14,21)*SPP(4) + OP(15,21)*SPP(7) - OP(16,21)*SPP(10); +nextP(6,21) = OP(6,21) + OP(1,21)*SF(5) + OP(3,21)*SF(4) + OP(4,21)*SF(6) - OP(2,21)*SPP(1) - OP(14,21)*SPP(9) + OP(15,21)*SPP(3) + OP(16,21)*SPP(6); +nextP(7,21) = OP(7,21) + OP(2,21)*SF(5) - OP(3,21)*SF(6) + OP(4,21)*SF(4) + OP(1,21)*SPP(1) + OP(14,21)*SPP(5) - OP(15,21)*SPP(8) - OP(16,21)*SPP(2); nextP(8,21) = OP(8,21) + OP(5,21)*dt; nextP(9,21) = OP(9,21) + OP(6,21)*dt; -nextP(10,21) = OP(10,21); +nextP(10,21) = OP(10,21) + OP(7,21)*dt; nextP(11,21) = OP(11,21); nextP(12,21) = OP(12,21); nextP(13,21) = OP(13,21); @@ -297,16 +285,16 @@ nextP(18,21) = OP(18,21); nextP(19,21) = OP(19,21); nextP(20,21) = OP(20,21); nextP(21,21) = OP(21,21); -nextP(1,22) = OP(1,22)*SPP(6) - OP(2,22)*SPP(5) + OP(3,22)*SPP(8) + OP(10,22)*SPP(23) + OP(13,22)*SPP(19); -nextP(2,22) = OP(2,22)*SPP(7) - OP(1,22)*SPP(3) - OP(3,22)*SPP(9) + OP(11,22)*SPP(23) + OP(14,22)*SPP(18); -nextP(3,22) = OP(1,22)*SPP(15) - OP(2,22)*SPP(4) + OP(3,22)*SPP(14) + OP(12,22)*SPP(23) + OP(15,22)*SPP(17); -nextP(4,22) = OP(4,22) + OP(1,22)*SPP(2) + OP(2,22)*SPP(20) + OP(3,22)*SPP(16) - OP(16,22)*SPP(22); -nextP(5,22) = OP(5,22) + OP(16,22)*SF(23) + OP(1,22)*SPP(21) + OP(2,22)*SPP(13) + OP(3,22)*SPP(12); -nextP(6,22) = OP(6,22) + OP(16,22)*SF(21) - OP(1,22)*SPP(10) + OP(2,22)*SPP(11) + OP(3,22)*SPP(1); -nextP(7,22) = OP(7,22) + OP(4,22)*dt; +nextP(1,22) = OP(1,22) + OP(2,22)*SF(10) + OP(3,22)*SF(12) + OP(4,22)*SF(11) + OP(11,22)*SF(15) + OP(12,22)*SF(16) + OP(13,22)*SPP(11); +nextP(2,22) = OP(2,22) + OP(1,22)*SF(9) + OP(3,22)*SF(8) + OP(4,22)*SF(12) - OP(13,22)*SF(16) + OP(12,22)*SPP(11) - (OP(11,22)*q0)/2; +nextP(3,22) = OP(3,22) + OP(1,22)*SF(7) + OP(2,22)*SF(11) + OP(4,22)*SF(9) + OP(13,22)*SF(15) - OP(11,22)*SPP(11) - (OP(12,22)*q0)/2; +nextP(4,22) = OP(4,22) + OP(1,22)*SF(8) + OP(2,22)*SF(7) + OP(3,22)*SF(10) + OP(11,22)*SF(16) - OP(12,22)*SF(15) - (OP(13,22)*q0)/2; +nextP(5,22) = OP(5,22) + OP(1,22)*SF(6) + OP(2,22)*SF(4) - OP(4,22)*SF(5) + OP(3,22)*SPP(1) + OP(14,22)*SPP(4) + OP(15,22)*SPP(7) - OP(16,22)*SPP(10); +nextP(6,22) = OP(6,22) + OP(1,22)*SF(5) + OP(3,22)*SF(4) + OP(4,22)*SF(6) - OP(2,22)*SPP(1) - OP(14,22)*SPP(9) + OP(15,22)*SPP(3) + OP(16,22)*SPP(6); +nextP(7,22) = OP(7,22) + OP(2,22)*SF(5) - OP(3,22)*SF(6) + OP(4,22)*SF(4) + OP(1,22)*SPP(1) + OP(14,22)*SPP(5) - OP(15,22)*SPP(8) - OP(16,22)*SPP(2); nextP(8,22) = OP(8,22) + OP(5,22)*dt; nextP(9,22) = OP(9,22) + OP(6,22)*dt; -nextP(10,22) = OP(10,22); +nextP(10,22) = OP(10,22) + OP(7,22)*dt; nextP(11,22) = OP(11,22); nextP(12,22) = OP(12,22); nextP(13,22) = OP(13,22); @@ -319,16 +307,16 @@ nextP(19,22) = OP(19,22); nextP(20,22) = OP(20,22); nextP(21,22) = OP(21,22); nextP(22,22) = OP(22,22); -nextP(1,23) = OP(1,23)*SPP(6) - OP(2,23)*SPP(5) + OP(3,23)*SPP(8) + OP(10,23)*SPP(23) + OP(13,23)*SPP(19); -nextP(2,23) = OP(2,23)*SPP(7) - OP(1,23)*SPP(3) - OP(3,23)*SPP(9) + OP(11,23)*SPP(23) + OP(14,23)*SPP(18); -nextP(3,23) = OP(1,23)*SPP(15) - OP(2,23)*SPP(4) + OP(3,23)*SPP(14) + OP(12,23)*SPP(23) + OP(15,23)*SPP(17); -nextP(4,23) = OP(4,23) + OP(1,23)*SPP(2) + OP(2,23)*SPP(20) + OP(3,23)*SPP(16) - OP(16,23)*SPP(22); -nextP(5,23) = OP(5,23) + OP(16,23)*SF(23) + OP(1,23)*SPP(21) + OP(2,23)*SPP(13) + OP(3,23)*SPP(12); -nextP(6,23) = OP(6,23) + OP(16,23)*SF(21) - OP(1,23)*SPP(10) + OP(2,23)*SPP(11) + OP(3,23)*SPP(1); -nextP(7,23) = OP(7,23) + OP(4,23)*dt; +nextP(1,23) = OP(1,23) + OP(2,23)*SF(10) + OP(3,23)*SF(12) + OP(4,23)*SF(11) + OP(11,23)*SF(15) + OP(12,23)*SF(16) + OP(13,23)*SPP(11); +nextP(2,23) = OP(2,23) + OP(1,23)*SF(9) + OP(3,23)*SF(8) + OP(4,23)*SF(12) - OP(13,23)*SF(16) + OP(12,23)*SPP(11) - (OP(11,23)*q0)/2; +nextP(3,23) = OP(3,23) + OP(1,23)*SF(7) + OP(2,23)*SF(11) + OP(4,23)*SF(9) + OP(13,23)*SF(15) - OP(11,23)*SPP(11) - (OP(12,23)*q0)/2; +nextP(4,23) = OP(4,23) + OP(1,23)*SF(8) + OP(2,23)*SF(7) + OP(3,23)*SF(10) + OP(11,23)*SF(16) - OP(12,23)*SF(15) - (OP(13,23)*q0)/2; +nextP(5,23) = OP(5,23) + OP(1,23)*SF(6) + OP(2,23)*SF(4) - OP(4,23)*SF(5) + OP(3,23)*SPP(1) + OP(14,23)*SPP(4) + OP(15,23)*SPP(7) - OP(16,23)*SPP(10); +nextP(6,23) = OP(6,23) + OP(1,23)*SF(5) + OP(3,23)*SF(4) + OP(4,23)*SF(6) - OP(2,23)*SPP(1) - OP(14,23)*SPP(9) + OP(15,23)*SPP(3) + OP(16,23)*SPP(6); +nextP(7,23) = OP(7,23) + OP(2,23)*SF(5) - OP(3,23)*SF(6) + OP(4,23)*SF(4) + OP(1,23)*SPP(1) + OP(14,23)*SPP(5) - OP(15,23)*SPP(8) - OP(16,23)*SPP(2); nextP(8,23) = OP(8,23) + OP(5,23)*dt; nextP(9,23) = OP(9,23) + OP(6,23)*dt; -nextP(10,23) = OP(10,23); +nextP(10,23) = OP(10,23) + OP(7,23)*dt; nextP(11,23) = OP(11,23); nextP(12,23) = OP(12,23); nextP(13,23) = OP(13,23); @@ -342,16 +330,16 @@ nextP(20,23) = OP(20,23); nextP(21,23) = OP(21,23); nextP(22,23) = OP(22,23); nextP(23,23) = OP(23,23); -nextP(1,24) = OP(1,24)*SPP(6) - OP(2,24)*SPP(5) + OP(3,24)*SPP(8) + OP(10,24)*SPP(23) + OP(13,24)*SPP(19); -nextP(2,24) = OP(2,24)*SPP(7) - OP(1,24)*SPP(3) - OP(3,24)*SPP(9) + OP(11,24)*SPP(23) + OP(14,24)*SPP(18); -nextP(3,24) = OP(1,24)*SPP(15) - OP(2,24)*SPP(4) + OP(3,24)*SPP(14) + OP(12,24)*SPP(23) + OP(15,24)*SPP(17); -nextP(4,24) = OP(4,24) + OP(1,24)*SPP(2) + OP(2,24)*SPP(20) + OP(3,24)*SPP(16) - OP(16,24)*SPP(22); -nextP(5,24) = OP(5,24) + OP(16,24)*SF(23) + OP(1,24)*SPP(21) + OP(2,24)*SPP(13) + OP(3,24)*SPP(12); -nextP(6,24) = OP(6,24) + OP(16,24)*SF(21) - OP(1,24)*SPP(10) + OP(2,24)*SPP(11) + OP(3,24)*SPP(1); -nextP(7,24) = OP(7,24) + OP(4,24)*dt; +nextP(1,24) = OP(1,24) + OP(2,24)*SF(10) + OP(3,24)*SF(12) + OP(4,24)*SF(11) + OP(11,24)*SF(15) + OP(12,24)*SF(16) + OP(13,24)*SPP(11); +nextP(2,24) = OP(2,24) + OP(1,24)*SF(9) + OP(3,24)*SF(8) + OP(4,24)*SF(12) - OP(13,24)*SF(16) + OP(12,24)*SPP(11) - (OP(11,24)*q0)/2; +nextP(3,24) = OP(3,24) + OP(1,24)*SF(7) + OP(2,24)*SF(11) + OP(4,24)*SF(9) + OP(13,24)*SF(15) - OP(11,24)*SPP(11) - (OP(12,24)*q0)/2; +nextP(4,24) = OP(4,24) + OP(1,24)*SF(8) + OP(2,24)*SF(7) + OP(3,24)*SF(10) + OP(11,24)*SF(16) - OP(12,24)*SF(15) - (OP(13,24)*q0)/2; +nextP(5,24) = OP(5,24) + OP(1,24)*SF(6) + OP(2,24)*SF(4) - OP(4,24)*SF(5) + OP(3,24)*SPP(1) + OP(14,24)*SPP(4) + OP(15,24)*SPP(7) - OP(16,24)*SPP(10); +nextP(6,24) = OP(6,24) + OP(1,24)*SF(5) + OP(3,24)*SF(4) + OP(4,24)*SF(6) - OP(2,24)*SPP(1) - OP(14,24)*SPP(9) + OP(15,24)*SPP(3) + OP(16,24)*SPP(6); +nextP(7,24) = OP(7,24) + OP(2,24)*SF(5) - OP(3,24)*SF(6) + OP(4,24)*SF(4) + OP(1,24)*SPP(1) + OP(14,24)*SPP(5) - OP(15,24)*SPP(8) - OP(16,24)*SPP(2); nextP(8,24) = OP(8,24) + OP(5,24)*dt; nextP(9,24) = OP(9,24) + OP(6,24)*dt; -nextP(10,24) = OP(10,24); +nextP(10,24) = OP(10,24) + OP(7,24)*dt; nextP(11,24) = OP(11,24); nextP(12,24) = OP(12,24); nextP(13,24) = OP(13,24); @@ -371,311 +359,328 @@ SH_TAS(1) = 1/((ve - vwe)^2 + (vn - vwn)^2 + vd^2)^(1/2); SH_TAS(2) = (SH_TAS(1)*(2*ve - 2*vwe))/2; SH_TAS(3) = (SH_TAS(1)*(2*vn - 2*vwn))/2; H_TAS = zeros(1,24); -H_TAS(1,4) = SH_TAS(3); -H_TAS(1,5) = SH_TAS(2); -H_TAS(1,6) = vd*SH_TAS(1); +H_TAS(1,5) = SH_TAS(3); +H_TAS(1,6) = SH_TAS(2); +H_TAS(1,7) = vd*SH_TAS(1); H_TAS(1,23) = -SH_TAS(3); H_TAS(1,24) = -SH_TAS(2); SK_TAS = zeros(2,1); -SK_TAS(1) = 1/(R_TAS + SH_TAS(3)*(OP(4,4)*SH_TAS(3) + OP(5,4)*SH_TAS(2) - OP(23,4)*SH_TAS(3) - OP(24,4)*SH_TAS(2) + OP(6,4)*vd*SH_TAS(1)) + SH_TAS(2)*(OP(4,5)*SH_TAS(3) + OP(5,5)*SH_TAS(2) - OP(23,5)*SH_TAS(3) - OP(24,5)*SH_TAS(2) + OP(6,5)*vd*SH_TAS(1)) - SH_TAS(3)*(OP(4,23)*SH_TAS(3) + OP(5,23)*SH_TAS(2) - OP(23,23)*SH_TAS(3) - OP(24,23)*SH_TAS(2) + OP(6,23)*vd*SH_TAS(1)) - SH_TAS(2)*(OP(4,24)*SH_TAS(3) + OP(5,24)*SH_TAS(2) - OP(23,24)*SH_TAS(3) - OP(24,24)*SH_TAS(2) + OP(6,24)*vd*SH_TAS(1)) + vd*SH_TAS(1)*(OP(4,6)*SH_TAS(3) + OP(5,6)*SH_TAS(2) - OP(23,6)*SH_TAS(3) - OP(24,6)*SH_TAS(2) + OP(6,6)*vd*SH_TAS(1))); +SK_TAS(1) = 1/(R_TAS + SH_TAS(3)*(OP(5,5)*SH_TAS(3) + OP(6,5)*SH_TAS(2) - OP(23,5)*SH_TAS(3) - OP(24,5)*SH_TAS(2) + OP(7,5)*vd*SH_TAS(1)) + SH_TAS(2)*(OP(5,6)*SH_TAS(3) + OP(6,6)*SH_TAS(2) - OP(23,6)*SH_TAS(3) - OP(24,6)*SH_TAS(2) + OP(7,6)*vd*SH_TAS(1)) - SH_TAS(3)*(OP(5,23)*SH_TAS(3) + OP(6,23)*SH_TAS(2) - OP(23,23)*SH_TAS(3) - OP(24,23)*SH_TAS(2) + OP(7,23)*vd*SH_TAS(1)) - SH_TAS(2)*(OP(5,24)*SH_TAS(3) + OP(6,24)*SH_TAS(2) - OP(23,24)*SH_TAS(3) - OP(24,24)*SH_TAS(2) + OP(7,24)*vd*SH_TAS(1)) + vd*SH_TAS(1)*(OP(5,7)*SH_TAS(3) + OP(6,7)*SH_TAS(2) - OP(23,7)*SH_TAS(3) - OP(24,7)*SH_TAS(2) + OP(7,7)*vd*SH_TAS(1))); SK_TAS(2) = SH_TAS(2); Kfusion = zeros(24,1); Kfusion = zeros(1,1); -Kfusion(1) = SK_TAS(1)*(OP(1,4)*SH_TAS(3) - OP(1,23)*SH_TAS(3) + OP(1,5)*SK_TAS(2) - OP(1,24)*SK_TAS(2) + OP(1,6)*vd*SH_TAS(1)); -Kfusion(2) = SK_TAS(1)*(OP(2,4)*SH_TAS(3) - OP(2,23)*SH_TAS(3) + OP(2,5)*SK_TAS(2) - OP(2,24)*SK_TAS(2) + OP(2,6)*vd*SH_TAS(1)); -Kfusion(3) = SK_TAS(1)*(OP(3,4)*SH_TAS(3) - OP(3,23)*SH_TAS(3) + OP(3,5)*SK_TAS(2) - OP(3,24)*SK_TAS(2) + OP(3,6)*vd*SH_TAS(1)); -Kfusion(4) = SK_TAS(1)*(OP(4,4)*SH_TAS(3) - OP(4,23)*SH_TAS(3) + OP(4,5)*SK_TAS(2) - OP(4,24)*SK_TAS(2) + OP(4,6)*vd*SH_TAS(1)); -Kfusion(5) = SK_TAS(1)*(OP(5,4)*SH_TAS(3) - OP(5,23)*SH_TAS(3) + OP(5,5)*SK_TAS(2) - OP(5,24)*SK_TAS(2) + OP(5,6)*vd*SH_TAS(1)); -Kfusion(6) = SK_TAS(1)*(OP(6,4)*SH_TAS(3) - OP(6,23)*SH_TAS(3) + OP(6,5)*SK_TAS(2) - OP(6,24)*SK_TAS(2) + OP(6,6)*vd*SH_TAS(1)); -Kfusion(7) = SK_TAS(1)*(OP(7,4)*SH_TAS(3) - OP(7,23)*SH_TAS(3) + OP(7,5)*SK_TAS(2) - OP(7,24)*SK_TAS(2) + OP(7,6)*vd*SH_TAS(1)); -Kfusion(8) = SK_TAS(1)*(OP(8,4)*SH_TAS(3) - OP(8,23)*SH_TAS(3) + OP(8,5)*SK_TAS(2) - OP(8,24)*SK_TAS(2) + OP(8,6)*vd*SH_TAS(1)); -Kfusion(9) = SK_TAS(1)*(OP(9,4)*SH_TAS(3) - OP(9,23)*SH_TAS(3) + OP(9,5)*SK_TAS(2) - OP(9,24)*SK_TAS(2) + OP(9,6)*vd*SH_TAS(1)); -Kfusion(10) = SK_TAS(1)*(OP(10,4)*SH_TAS(3) - OP(10,23)*SH_TAS(3) + OP(10,5)*SK_TAS(2) - OP(10,24)*SK_TAS(2) + OP(10,6)*vd*SH_TAS(1)); -Kfusion(11) = SK_TAS(1)*(OP(11,4)*SH_TAS(3) - OP(11,23)*SH_TAS(3) + OP(11,5)*SK_TAS(2) - OP(11,24)*SK_TAS(2) + OP(11,6)*vd*SH_TAS(1)); -Kfusion(12) = SK_TAS(1)*(OP(12,4)*SH_TAS(3) - OP(12,23)*SH_TAS(3) + OP(12,5)*SK_TAS(2) - OP(12,24)*SK_TAS(2) + OP(12,6)*vd*SH_TAS(1)); -Kfusion(13) = SK_TAS(1)*(OP(13,4)*SH_TAS(3) - OP(13,23)*SH_TAS(3) + OP(13,5)*SK_TAS(2) - OP(13,24)*SK_TAS(2) + OP(13,6)*vd*SH_TAS(1)); -Kfusion(14) = SK_TAS(1)*(OP(14,4)*SH_TAS(3) - OP(14,23)*SH_TAS(3) + OP(14,5)*SK_TAS(2) - OP(14,24)*SK_TAS(2) + OP(14,6)*vd*SH_TAS(1)); -Kfusion(15) = SK_TAS(1)*(OP(15,4)*SH_TAS(3) - OP(15,23)*SH_TAS(3) + OP(15,5)*SK_TAS(2) - OP(15,24)*SK_TAS(2) + OP(15,6)*vd*SH_TAS(1)); -Kfusion(16) = SK_TAS(1)*(OP(16,4)*SH_TAS(3) - OP(16,23)*SH_TAS(3) + OP(16,5)*SK_TAS(2) - OP(16,24)*SK_TAS(2) + OP(16,6)*vd*SH_TAS(1)); -Kfusion(17) = SK_TAS(1)*(OP(17,4)*SH_TAS(3) - OP(17,23)*SH_TAS(3) + OP(17,5)*SK_TAS(2) - OP(17,24)*SK_TAS(2) + OP(17,6)*vd*SH_TAS(1)); -Kfusion(18) = SK_TAS(1)*(OP(18,4)*SH_TAS(3) - OP(18,23)*SH_TAS(3) + OP(18,5)*SK_TAS(2) - OP(18,24)*SK_TAS(2) + OP(18,6)*vd*SH_TAS(1)); -Kfusion(19) = SK_TAS(1)*(OP(19,4)*SH_TAS(3) - OP(19,23)*SH_TAS(3) + OP(19,5)*SK_TAS(2) - OP(19,24)*SK_TAS(2) + OP(19,6)*vd*SH_TAS(1)); -Kfusion(20) = SK_TAS(1)*(OP(20,4)*SH_TAS(3) - OP(20,23)*SH_TAS(3) + OP(20,5)*SK_TAS(2) - OP(20,24)*SK_TAS(2) + OP(20,6)*vd*SH_TAS(1)); -Kfusion(21) = SK_TAS(1)*(OP(21,4)*SH_TAS(3) - OP(21,23)*SH_TAS(3) + OP(21,5)*SK_TAS(2) - OP(21,24)*SK_TAS(2) + OP(21,6)*vd*SH_TAS(1)); -Kfusion(22) = SK_TAS(1)*(OP(22,4)*SH_TAS(3) - OP(22,23)*SH_TAS(3) + OP(22,5)*SK_TAS(2) - OP(22,24)*SK_TAS(2) + OP(22,6)*vd*SH_TAS(1)); -Kfusion(23) = SK_TAS(1)*(OP(23,4)*SH_TAS(3) - OP(23,23)*SH_TAS(3) + OP(23,5)*SK_TAS(2) - OP(23,24)*SK_TAS(2) + OP(23,6)*vd*SH_TAS(1)); -Kfusion(24) = SK_TAS(1)*(OP(24,4)*SH_TAS(3) - OP(24,23)*SH_TAS(3) + OP(24,5)*SK_TAS(2) - OP(24,24)*SK_TAS(2) + OP(24,6)*vd*SH_TAS(1)); -SH_BETA = zeros(10,1); -SH_BETA(1) = (2*conj(q0)*conj(q3) + 2*conj(q1)*conj(q2))*(ve - vwe) - vd*(2*conj(q0)*conj(q2) - 2*conj(q1)*conj(q3)) + (vn - vwn)*(conj(q0)^2 + conj(q1)^2 - conj(q2)^2 - conj(q3)^2); -SH_BETA(2) = vd*(2*conj(q0)*conj(q1) + 2*conj(q2)*conj(q3)) - (2*conj(q0)*conj(q3) - 2*conj(q1)*conj(q2))*(vn - vwn) + (ve - vwe)*(conj(q0)^2 - conj(q1)^2 + conj(q2)^2 - conj(q3)^2); -SH_BETA(3) = (2*conj(q0)*conj(q2) + 2*conj(q1)*conj(q3))*(vn - vwn) - (2*conj(q0)*conj(q1) - 2*conj(q2)*conj(q3))*(ve - vwe) + vd*(conj(q0)^2 - conj(q1)^2 - conj(q2)^2 + conj(q3)^2); -SH_BETA(4) = (conj(q0)^2 - conj(q1)^2 + conj(q2)^2 - conj(q3)^2)/SH_BETA(1); +Kfusion(1) = SK_TAS(1)*(OP(1,5)*SH_TAS(3) - OP(1,23)*SH_TAS(3) + OP(1,6)*SK_TAS(2) - OP(1,24)*SK_TAS(2) + OP(1,7)*vd*SH_TAS(1)); +Kfusion(2) = SK_TAS(1)*(OP(2,5)*SH_TAS(3) - OP(2,23)*SH_TAS(3) + OP(2,6)*SK_TAS(2) - OP(2,24)*SK_TAS(2) + OP(2,7)*vd*SH_TAS(1)); +Kfusion(3) = SK_TAS(1)*(OP(3,5)*SH_TAS(3) - OP(3,23)*SH_TAS(3) + OP(3,6)*SK_TAS(2) - OP(3,24)*SK_TAS(2) + OP(3,7)*vd*SH_TAS(1)); +Kfusion(4) = SK_TAS(1)*(OP(4,5)*SH_TAS(3) - OP(4,23)*SH_TAS(3) + OP(4,6)*SK_TAS(2) - OP(4,24)*SK_TAS(2) + OP(4,7)*vd*SH_TAS(1)); +Kfusion(5) = SK_TAS(1)*(OP(5,5)*SH_TAS(3) - OP(5,23)*SH_TAS(3) + OP(5,6)*SK_TAS(2) - OP(5,24)*SK_TAS(2) + OP(5,7)*vd*SH_TAS(1)); +Kfusion(6) = SK_TAS(1)*(OP(6,5)*SH_TAS(3) - OP(6,23)*SH_TAS(3) + OP(6,6)*SK_TAS(2) - OP(6,24)*SK_TAS(2) + OP(6,7)*vd*SH_TAS(1)); +Kfusion(7) = SK_TAS(1)*(OP(7,5)*SH_TAS(3) - OP(7,23)*SH_TAS(3) + OP(7,6)*SK_TAS(2) - OP(7,24)*SK_TAS(2) + OP(7,7)*vd*SH_TAS(1)); +Kfusion(8) = SK_TAS(1)*(OP(8,5)*SH_TAS(3) - OP(8,23)*SH_TAS(3) + OP(8,6)*SK_TAS(2) - OP(8,24)*SK_TAS(2) + OP(8,7)*vd*SH_TAS(1)); +Kfusion(9) = SK_TAS(1)*(OP(9,5)*SH_TAS(3) - OP(9,23)*SH_TAS(3) + OP(9,6)*SK_TAS(2) - OP(9,24)*SK_TAS(2) + OP(9,7)*vd*SH_TAS(1)); +Kfusion(10) = SK_TAS(1)*(OP(10,5)*SH_TAS(3) - OP(10,23)*SH_TAS(3) + OP(10,6)*SK_TAS(2) - OP(10,24)*SK_TAS(2) + OP(10,7)*vd*SH_TAS(1)); +Kfusion(11) = SK_TAS(1)*(OP(11,5)*SH_TAS(3) - OP(11,23)*SH_TAS(3) + OP(11,6)*SK_TAS(2) - OP(11,24)*SK_TAS(2) + OP(11,7)*vd*SH_TAS(1)); +Kfusion(12) = SK_TAS(1)*(OP(12,5)*SH_TAS(3) - OP(12,23)*SH_TAS(3) + OP(12,6)*SK_TAS(2) - OP(12,24)*SK_TAS(2) + OP(12,7)*vd*SH_TAS(1)); +Kfusion(13) = SK_TAS(1)*(OP(13,5)*SH_TAS(3) - OP(13,23)*SH_TAS(3) + OP(13,6)*SK_TAS(2) - OP(13,24)*SK_TAS(2) + OP(13,7)*vd*SH_TAS(1)); +Kfusion(14) = SK_TAS(1)*(OP(14,5)*SH_TAS(3) - OP(14,23)*SH_TAS(3) + OP(14,6)*SK_TAS(2) - OP(14,24)*SK_TAS(2) + OP(14,7)*vd*SH_TAS(1)); +Kfusion(15) = SK_TAS(1)*(OP(15,5)*SH_TAS(3) - OP(15,23)*SH_TAS(3) + OP(15,6)*SK_TAS(2) - OP(15,24)*SK_TAS(2) + OP(15,7)*vd*SH_TAS(1)); +Kfusion(16) = SK_TAS(1)*(OP(16,5)*SH_TAS(3) - OP(16,23)*SH_TAS(3) + OP(16,6)*SK_TAS(2) - OP(16,24)*SK_TAS(2) + OP(16,7)*vd*SH_TAS(1)); +Kfusion(17) = SK_TAS(1)*(OP(17,5)*SH_TAS(3) - OP(17,23)*SH_TAS(3) + OP(17,6)*SK_TAS(2) - OP(17,24)*SK_TAS(2) + OP(17,7)*vd*SH_TAS(1)); +Kfusion(18) = SK_TAS(1)*(OP(18,5)*SH_TAS(3) - OP(18,23)*SH_TAS(3) + OP(18,6)*SK_TAS(2) - OP(18,24)*SK_TAS(2) + OP(18,7)*vd*SH_TAS(1)); +Kfusion(19) = SK_TAS(1)*(OP(19,5)*SH_TAS(3) - OP(19,23)*SH_TAS(3) + OP(19,6)*SK_TAS(2) - OP(19,24)*SK_TAS(2) + OP(19,7)*vd*SH_TAS(1)); +Kfusion(20) = SK_TAS(1)*(OP(20,5)*SH_TAS(3) - OP(20,23)*SH_TAS(3) + OP(20,6)*SK_TAS(2) - OP(20,24)*SK_TAS(2) + OP(20,7)*vd*SH_TAS(1)); +Kfusion(21) = SK_TAS(1)*(OP(21,5)*SH_TAS(3) - OP(21,23)*SH_TAS(3) + OP(21,6)*SK_TAS(2) - OP(21,24)*SK_TAS(2) + OP(21,7)*vd*SH_TAS(1)); +Kfusion(22) = SK_TAS(1)*(OP(22,5)*SH_TAS(3) - OP(22,23)*SH_TAS(3) + OP(22,6)*SK_TAS(2) - OP(22,24)*SK_TAS(2) + OP(22,7)*vd*SH_TAS(1)); +Kfusion(23) = SK_TAS(1)*(OP(23,5)*SH_TAS(3) - OP(23,23)*SH_TAS(3) + OP(23,6)*SK_TAS(2) - OP(23,24)*SK_TAS(2) + OP(23,7)*vd*SH_TAS(1)); +Kfusion(24) = SK_TAS(1)*(OP(24,5)*SH_TAS(3) - OP(24,23)*SH_TAS(3) + OP(24,6)*SK_TAS(2) - OP(24,24)*SK_TAS(2) + OP(24,7)*vd*SH_TAS(1)); +SH_BETA = zeros(13,1); +SH_BETA(1) = (vn - vwn)*(q0^2 + q1^2 - q2^2 - q3^2) - vd*(2*q0*q2 - 2*q1*q3) + (ve - vwe)*(2*q0*q3 + 2*q1*q2); +SH_BETA(2) = (ve - vwe)*(q0^2 - q1^2 + q2^2 - q3^2) + vd*(2*q0*q1 + 2*q2*q3) - (vn - vwn)*(2*q0*q3 - 2*q1*q2); +SH_BETA(3) = vn - vwn; +SH_BETA(4) = ve - vwe; SH_BETA(5) = 1/SH_BETA(1)^2; -SH_BETA(6) = conj(q0)^2 + conj(q1)^2 - conj(q2)^2 - conj(q3)^2; -SH_BETA(7) = 2*conj(q0)*conj(q3); -SH_BETA(8) = 1/SH_BETA(1); -SH_BETA(9) = SH_BETA(7) + 2*conj(q1)*conj(q2); -SH_BETA(10) = SH_BETA(7) - 2*conj(q1)*conj(q2); +SH_BETA(6) = 1/SH_BETA(1); +SH_BETA(7) = SH_BETA(6)*(q0^2 - q1^2 + q2^2 - q3^2); +SH_BETA(8) = q0^2 + q1^2 - q2^2 - q3^2; +SH_BETA(9) = 2*q0*SH_BETA(4) - 2*q3*SH_BETA(3) + 2*q1*vd; +SH_BETA(10) = 2*q0*SH_BETA(3) + 2*q3*SH_BETA(4) - 2*q2*vd; +SH_BETA(11) = 2*q2*SH_BETA(3) - 2*q1*SH_BETA(4) + 2*q0*vd; +SH_BETA(12) = 2*q1*SH_BETA(3) + 2*q2*SH_BETA(4) + 2*q3*vd; +SH_BETA(13) = 2*q0*q3; H_BETA = zeros(1,24); -H_BETA(1,1) = SH_BETA(3)*SH_BETA(8); -H_BETA(1,2) = SH_BETA(2)*SH_BETA(3)*SH_BETA(5); -H_BETA(1,3) = - SH_BETA(2)^2*SH_BETA(5) - 1; -H_BETA(1,4) = - SH_BETA(8)*SH_BETA(10) - SH_BETA(2)*SH_BETA(5)*SH_BETA(6); -H_BETA(1,5) = SH_BETA(4) - SH_BETA(2)*SH_BETA(5)*SH_BETA(9); -H_BETA(1,6) = SH_BETA(8)*(2*conj(q0)*conj(q1) + 2*conj(q2)*conj(q3)) + SH_BETA(2)*SH_BETA(5)*(2*conj(q0)*conj(q2) - 2*conj(q1)*conj(q3)); -H_BETA(1,23) = SH_BETA(8)*SH_BETA(10) + SH_BETA(2)*SH_BETA(5)*SH_BETA(6); -H_BETA(1,24) = SH_BETA(2)*SH_BETA(5)*SH_BETA(9) - SH_BETA(4); -SK_BETA = zeros(6,1); -SK_BETA(1) = 1/(R_BETA + (SH_BETA(8)*(2*conj(q0)*conj(q1) + 2*conj(q2)*conj(q3)) + SH_BETA(2)*SH_BETA(5)*(2*conj(q0)*conj(q2) - 2*conj(q1)*conj(q3)))*(OP(23,6)*(SH_BETA(8)*SH_BETA(10) + SH_BETA(2)*SH_BETA(5)*SH_BETA(6)) - OP(4,6)*(SH_BETA(8)*SH_BETA(10) + SH_BETA(2)*SH_BETA(5)*SH_BETA(6)) - OP(3,6)*(SH_BETA(2)^2*SH_BETA(5) + 1) + OP(6,6)*(SH_BETA(8)*(2*conj(q0)*conj(q1) + 2*conj(q2)*conj(q3)) + SH_BETA(2)*SH_BETA(5)*(2*conj(q0)*conj(q2) - 2*conj(q1)*conj(q3))) + OP(5,6)*(SH_BETA(4) - SH_BETA(2)*SH_BETA(5)*SH_BETA(9)) - OP(24,6)*(SH_BETA(4) - SH_BETA(2)*SH_BETA(5)*SH_BETA(9)) + OP(1,6)*SH_BETA(3)*SH_BETA(8) + OP(2,6)*SH_BETA(2)*SH_BETA(3)*SH_BETA(5)) + (SH_BETA(4) - SH_BETA(2)*SH_BETA(5)*SH_BETA(9))*(OP(23,5)*(SH_BETA(8)*SH_BETA(10) + SH_BETA(2)*SH_BETA(5)*SH_BETA(6)) - OP(4,5)*(SH_BETA(8)*SH_BETA(10) + SH_BETA(2)*SH_BETA(5)*SH_BETA(6)) - OP(3,5)*(SH_BETA(2)^2*SH_BETA(5) + 1) + OP(6,5)*(SH_BETA(8)*(2*conj(q0)*conj(q1) + 2*conj(q2)*conj(q3)) + SH_BETA(2)*SH_BETA(5)*(2*conj(q0)*conj(q2) - 2*conj(q1)*conj(q3))) + OP(5,5)*(SH_BETA(4) - SH_BETA(2)*SH_BETA(5)*SH_BETA(9)) - OP(24,5)*(SH_BETA(4) - SH_BETA(2)*SH_BETA(5)*SH_BETA(9)) + OP(1,5)*SH_BETA(3)*SH_BETA(8) + OP(2,5)*SH_BETA(2)*SH_BETA(3)*SH_BETA(5)) - (SH_BETA(4) - SH_BETA(2)*SH_BETA(5)*SH_BETA(9))*(OP(23,24)*(SH_BETA(8)*SH_BETA(10) + SH_BETA(2)*SH_BETA(5)*SH_BETA(6)) - OP(4,24)*(SH_BETA(8)*SH_BETA(10) + SH_BETA(2)*SH_BETA(5)*SH_BETA(6)) - OP(3,24)*(SH_BETA(2)^2*SH_BETA(5) + 1) + OP(6,24)*(SH_BETA(8)*(2*conj(q0)*conj(q1) + 2*conj(q2)*conj(q3)) + SH_BETA(2)*SH_BETA(5)*(2*conj(q0)*conj(q2) - 2*conj(q1)*conj(q3))) + OP(5,24)*(SH_BETA(4) - SH_BETA(2)*SH_BETA(5)*SH_BETA(9)) - OP(24,24)*(SH_BETA(4) - SH_BETA(2)*SH_BETA(5)*SH_BETA(9)) + OP(1,24)*SH_BETA(3)*SH_BETA(8) + OP(2,24)*SH_BETA(2)*SH_BETA(3)*SH_BETA(5)) - (SH_BETA(8)*SH_BETA(10) + SH_BETA(2)*SH_BETA(5)*SH_BETA(6))*(OP(23,4)*(SH_BETA(8)*SH_BETA(10) + SH_BETA(2)*SH_BETA(5)*SH_BETA(6)) - OP(4,4)*(SH_BETA(8)*SH_BETA(10) + SH_BETA(2)*SH_BETA(5)*SH_BETA(6)) - OP(3,4)*(SH_BETA(2)^2*SH_BETA(5) + 1) + OP(6,4)*(SH_BETA(8)*(2*conj(q0)*conj(q1) + 2*conj(q2)*conj(q3)) + SH_BETA(2)*SH_BETA(5)*(2*conj(q0)*conj(q2) - 2*conj(q1)*conj(q3))) + OP(5,4)*(SH_BETA(4) - SH_BETA(2)*SH_BETA(5)*SH_BETA(9)) - OP(24,4)*(SH_BETA(4) - SH_BETA(2)*SH_BETA(5)*SH_BETA(9)) + OP(1,4)*SH_BETA(3)*SH_BETA(8) + OP(2,4)*SH_BETA(2)*SH_BETA(3)*SH_BETA(5)) + (SH_BETA(8)*SH_BETA(10) + SH_BETA(2)*SH_BETA(5)*SH_BETA(6))*(OP(23,23)*(SH_BETA(8)*SH_BETA(10) + SH_BETA(2)*SH_BETA(5)*SH_BETA(6)) - OP(4,23)*(SH_BETA(8)*SH_BETA(10) + SH_BETA(2)*SH_BETA(5)*SH_BETA(6)) - OP(3,23)*(SH_BETA(2)^2*SH_BETA(5) + 1) + OP(6,23)*(SH_BETA(8)*(2*conj(q0)*conj(q1) + 2*conj(q2)*conj(q3)) + SH_BETA(2)*SH_BETA(5)*(2*conj(q0)*conj(q2) - 2*conj(q1)*conj(q3))) + OP(5,23)*(SH_BETA(4) - SH_BETA(2)*SH_BETA(5)*SH_BETA(9)) - OP(24,23)*(SH_BETA(4) - SH_BETA(2)*SH_BETA(5)*SH_BETA(9)) + OP(1,23)*SH_BETA(3)*SH_BETA(8) + OP(2,23)*SH_BETA(2)*SH_BETA(3)*SH_BETA(5)) - (SH_BETA(2)^2*SH_BETA(5) + 1)*(OP(23,3)*(SH_BETA(8)*SH_BETA(10) + SH_BETA(2)*SH_BETA(5)*SH_BETA(6)) - OP(4,3)*(SH_BETA(8)*SH_BETA(10) + SH_BETA(2)*SH_BETA(5)*SH_BETA(6)) - OP(3,3)*(SH_BETA(2)^2*SH_BETA(5) + 1) + OP(6,3)*(SH_BETA(8)*(2*conj(q0)*conj(q1) + 2*conj(q2)*conj(q3)) + SH_BETA(2)*SH_BETA(5)*(2*conj(q0)*conj(q2) - 2*conj(q1)*conj(q3))) + OP(5,3)*(SH_BETA(4) - SH_BETA(2)*SH_BETA(5)*SH_BETA(9)) - OP(24,3)*(SH_BETA(4) - SH_BETA(2)*SH_BETA(5)*SH_BETA(9)) + OP(1,3)*SH_BETA(3)*SH_BETA(8) + OP(2,3)*SH_BETA(2)*SH_BETA(3)*SH_BETA(5)) + SH_BETA(3)*SH_BETA(8)*(OP(23,1)*(SH_BETA(8)*SH_BETA(10) + SH_BETA(2)*SH_BETA(5)*SH_BETA(6)) - OP(4,1)*(SH_BETA(8)*SH_BETA(10) + SH_BETA(2)*SH_BETA(5)*SH_BETA(6)) - OP(3,1)*(SH_BETA(2)^2*SH_BETA(5) + 1) + OP(6,1)*(SH_BETA(8)*(2*conj(q0)*conj(q1) + 2*conj(q2)*conj(q3)) + SH_BETA(2)*SH_BETA(5)*(2*conj(q0)*conj(q2) - 2*conj(q1)*conj(q3))) + OP(5,1)*(SH_BETA(4) - SH_BETA(2)*SH_BETA(5)*SH_BETA(9)) - OP(24,1)*(SH_BETA(4) - SH_BETA(2)*SH_BETA(5)*SH_BETA(9)) + OP(1,1)*SH_BETA(3)*SH_BETA(8) + OP(2,1)*SH_BETA(2)*SH_BETA(3)*SH_BETA(5)) + SH_BETA(2)*SH_BETA(3)*SH_BETA(5)*(OP(23,2)*(SH_BETA(8)*SH_BETA(10) + SH_BETA(2)*SH_BETA(5)*SH_BETA(6)) - OP(4,2)*(SH_BETA(8)*SH_BETA(10) + SH_BETA(2)*SH_BETA(5)*SH_BETA(6)) - OP(3,2)*(SH_BETA(2)^2*SH_BETA(5) + 1) + OP(6,2)*(SH_BETA(8)*(2*conj(q0)*conj(q1) + 2*conj(q2)*conj(q3)) + SH_BETA(2)*SH_BETA(5)*(2*conj(q0)*conj(q2) - 2*conj(q1)*conj(q3))) + OP(5,2)*(SH_BETA(4) - SH_BETA(2)*SH_BETA(5)*SH_BETA(9)) - OP(24,2)*(SH_BETA(4) - SH_BETA(2)*SH_BETA(5)*SH_BETA(9)) + OP(1,2)*SH_BETA(3)*SH_BETA(8) + OP(2,2)*SH_BETA(2)*SH_BETA(3)*SH_BETA(5))); -SK_BETA(2) = SH_BETA(8)*(2*conj(q0)*conj(q1) + 2*conj(q2)*conj(q3)) + SH_BETA(2)*SH_BETA(5)*(2*conj(q0)*conj(q2) - 2*conj(q1)*conj(q3)); -SK_BETA(3) = SH_BETA(8)*SH_BETA(10) + SH_BETA(2)*SH_BETA(5)*SH_BETA(6); -SK_BETA(4) = SH_BETA(4) - SH_BETA(2)*SH_BETA(5)*SH_BETA(9); -SK_BETA(5) = SH_BETA(2)^2*SH_BETA(5) + 1; -SK_BETA(6) = SH_BETA(3); +H_BETA(1,1) = SH_BETA(6)*SH_BETA(9) - SH_BETA(2)*SH_BETA(5)*SH_BETA(10); +H_BETA(1,2) = SH_BETA(6)*SH_BETA(11) - SH_BETA(2)*SH_BETA(5)*SH_BETA(12); +H_BETA(1,3) = SH_BETA(6)*SH_BETA(12) + SH_BETA(2)*SH_BETA(5)*SH_BETA(11); +H_BETA(1,4) = - SH_BETA(6)*SH_BETA(10) - SH_BETA(2)*SH_BETA(5)*SH_BETA(9); +H_BETA(1,5) = - SH_BETA(6)*(SH_BETA(13) - 2*q1*q2) - SH_BETA(2)*SH_BETA(5)*SH_BETA(8); +H_BETA(1,6) = SH_BETA(7) - SH_BETA(2)*SH_BETA(5)*(SH_BETA(13) + 2*q1*q2); +H_BETA(1,7) = SH_BETA(6)*(2*q0*q1 + 2*q2*q3) + SH_BETA(2)*SH_BETA(5)*(2*q0*q2 - 2*q1*q3); +H_BETA(1,23) = SH_BETA(6)*(SH_BETA(13) - 2*q1*q2) + SH_BETA(2)*SH_BETA(5)*SH_BETA(8); +H_BETA(1,24) = SH_BETA(2)*SH_BETA(5)*(SH_BETA(13) + 2*q1*q2) - SH_BETA(7); +SK_BETA = zeros(8,1); +SK_BETA(1) = 1/(R_BETA - (SH_BETA(6)*(SH_BETA(13) - 2*q1*q2) + SH_BETA(2)*SH_BETA(5)*SH_BETA(8))*(OP(23,5)*(SH_BETA(6)*(SH_BETA(13) - 2*q1*q2) + SH_BETA(2)*SH_BETA(5)*SH_BETA(8)) - OP(5,5)*(SH_BETA(6)*(SH_BETA(13) - 2*q1*q2) + SH_BETA(2)*SH_BETA(5)*SH_BETA(8)) + OP(6,5)*(SH_BETA(7) - SH_BETA(2)*SH_BETA(5)*(SH_BETA(13) + 2*q1*q2)) - OP(24,5)*(SH_BETA(7) - SH_BETA(2)*SH_BETA(5)*(SH_BETA(13) + 2*q1*q2)) + OP(1,5)*(SH_BETA(6)*SH_BETA(9) - SH_BETA(2)*SH_BETA(5)*SH_BETA(10)) + OP(2,5)*(SH_BETA(6)*SH_BETA(11) - SH_BETA(2)*SH_BETA(5)*SH_BETA(12)) + OP(3,5)*(SH_BETA(6)*SH_BETA(12) + SH_BETA(2)*SH_BETA(5)*SH_BETA(11)) - OP(4,5)*(SH_BETA(6)*SH_BETA(10) + SH_BETA(2)*SH_BETA(5)*SH_BETA(9)) + OP(7,5)*(SH_BETA(6)*(2*q0*q1 + 2*q2*q3) + SH_BETA(2)*SH_BETA(5)*(2*q0*q2 - 2*q1*q3))) + (SH_BETA(6)*(SH_BETA(13) - 2*q1*q2) + SH_BETA(2)*SH_BETA(5)*SH_BETA(8))*(OP(23,23)*(SH_BETA(6)*(SH_BETA(13) - 2*q1*q2) + SH_BETA(2)*SH_BETA(5)*SH_BETA(8)) - OP(5,23)*(SH_BETA(6)*(SH_BETA(13) - 2*q1*q2) + SH_BETA(2)*SH_BETA(5)*SH_BETA(8)) + OP(6,23)*(SH_BETA(7) - SH_BETA(2)*SH_BETA(5)*(SH_BETA(13) + 2*q1*q2)) - OP(24,23)*(SH_BETA(7) - SH_BETA(2)*SH_BETA(5)*(SH_BETA(13) + 2*q1*q2)) + OP(1,23)*(SH_BETA(6)*SH_BETA(9) - SH_BETA(2)*SH_BETA(5)*SH_BETA(10)) + OP(2,23)*(SH_BETA(6)*SH_BETA(11) - SH_BETA(2)*SH_BETA(5)*SH_BETA(12)) + OP(3,23)*(SH_BETA(6)*SH_BETA(12) + SH_BETA(2)*SH_BETA(5)*SH_BETA(11)) - OP(4,23)*(SH_BETA(6)*SH_BETA(10) + SH_BETA(2)*SH_BETA(5)*SH_BETA(9)) + OP(7,23)*(SH_BETA(6)*(2*q0*q1 + 2*q2*q3) + SH_BETA(2)*SH_BETA(5)*(2*q0*q2 - 2*q1*q3))) + (SH_BETA(7) - SH_BETA(2)*SH_BETA(5)*(SH_BETA(13) + 2*q1*q2))*(OP(23,6)*(SH_BETA(6)*(SH_BETA(13) - 2*q1*q2) + SH_BETA(2)*SH_BETA(5)*SH_BETA(8)) - OP(5,6)*(SH_BETA(6)*(SH_BETA(13) - 2*q1*q2) + SH_BETA(2)*SH_BETA(5)*SH_BETA(8)) + OP(6,6)*(SH_BETA(7) - SH_BETA(2)*SH_BETA(5)*(SH_BETA(13) + 2*q1*q2)) - OP(24,6)*(SH_BETA(7) - SH_BETA(2)*SH_BETA(5)*(SH_BETA(13) + 2*q1*q2)) + OP(1,6)*(SH_BETA(6)*SH_BETA(9) - SH_BETA(2)*SH_BETA(5)*SH_BETA(10)) + OP(2,6)*(SH_BETA(6)*SH_BETA(11) - SH_BETA(2)*SH_BETA(5)*SH_BETA(12)) + OP(3,6)*(SH_BETA(6)*SH_BETA(12) + SH_BETA(2)*SH_BETA(5)*SH_BETA(11)) - OP(4,6)*(SH_BETA(6)*SH_BETA(10) + SH_BETA(2)*SH_BETA(5)*SH_BETA(9)) + OP(7,6)*(SH_BETA(6)*(2*q0*q1 + 2*q2*q3) + SH_BETA(2)*SH_BETA(5)*(2*q0*q2 - 2*q1*q3))) - (SH_BETA(7) - SH_BETA(2)*SH_BETA(5)*(SH_BETA(13) + 2*q1*q2))*(OP(23,24)*(SH_BETA(6)*(SH_BETA(13) - 2*q1*q2) + SH_BETA(2)*SH_BETA(5)*SH_BETA(8)) - OP(5,24)*(SH_BETA(6)*(SH_BETA(13) - 2*q1*q2) + SH_BETA(2)*SH_BETA(5)*SH_BETA(8)) + OP(6,24)*(SH_BETA(7) - SH_BETA(2)*SH_BETA(5)*(SH_BETA(13) + 2*q1*q2)) - OP(24,24)*(SH_BETA(7) - SH_BETA(2)*SH_BETA(5)*(SH_BETA(13) + 2*q1*q2)) + OP(1,24)*(SH_BETA(6)*SH_BETA(9) - SH_BETA(2)*SH_BETA(5)*SH_BETA(10)) + OP(2,24)*(SH_BETA(6)*SH_BETA(11) - SH_BETA(2)*SH_BETA(5)*SH_BETA(12)) + OP(3,24)*(SH_BETA(6)*SH_BETA(12) + SH_BETA(2)*SH_BETA(5)*SH_BETA(11)) - OP(4,24)*(SH_BETA(6)*SH_BETA(10) + SH_BETA(2)*SH_BETA(5)*SH_BETA(9)) + OP(7,24)*(SH_BETA(6)*(2*q0*q1 + 2*q2*q3) + SH_BETA(2)*SH_BETA(5)*(2*q0*q2 - 2*q1*q3))) + (SH_BETA(6)*SH_BETA(9) - SH_BETA(2)*SH_BETA(5)*SH_BETA(10))*(OP(23,1)*(SH_BETA(6)*(SH_BETA(13) - 2*q1*q2) + SH_BETA(2)*SH_BETA(5)*SH_BETA(8)) - OP(5,1)*(SH_BETA(6)*(SH_BETA(13) - 2*q1*q2) + SH_BETA(2)*SH_BETA(5)*SH_BETA(8)) + OP(6,1)*(SH_BETA(7) - SH_BETA(2)*SH_BETA(5)*(SH_BETA(13) + 2*q1*q2)) - OP(24,1)*(SH_BETA(7) - SH_BETA(2)*SH_BETA(5)*(SH_BETA(13) + 2*q1*q2)) + OP(1,1)*(SH_BETA(6)*SH_BETA(9) - SH_BETA(2)*SH_BETA(5)*SH_BETA(10)) + OP(2,1)*(SH_BETA(6)*SH_BETA(11) - SH_BETA(2)*SH_BETA(5)*SH_BETA(12)) + OP(3,1)*(SH_BETA(6)*SH_BETA(12) + SH_BETA(2)*SH_BETA(5)*SH_BETA(11)) - OP(4,1)*(SH_BETA(6)*SH_BETA(10) + SH_BETA(2)*SH_BETA(5)*SH_BETA(9)) + OP(7,1)*(SH_BETA(6)*(2*q0*q1 + 2*q2*q3) + SH_BETA(2)*SH_BETA(5)*(2*q0*q2 - 2*q1*q3))) + (SH_BETA(6)*SH_BETA(11) - SH_BETA(2)*SH_BETA(5)*SH_BETA(12))*(OP(23,2)*(SH_BETA(6)*(SH_BETA(13) - 2*q1*q2) + SH_BETA(2)*SH_BETA(5)*SH_BETA(8)) - OP(5,2)*(SH_BETA(6)*(SH_BETA(13) - 2*q1*q2) + SH_BETA(2)*SH_BETA(5)*SH_BETA(8)) + OP(6,2)*(SH_BETA(7) - SH_BETA(2)*SH_BETA(5)*(SH_BETA(13) + 2*q1*q2)) - OP(24,2)*(SH_BETA(7) - SH_BETA(2)*SH_BETA(5)*(SH_BETA(13) + 2*q1*q2)) + OP(1,2)*(SH_BETA(6)*SH_BETA(9) - SH_BETA(2)*SH_BETA(5)*SH_BETA(10)) + OP(2,2)*(SH_BETA(6)*SH_BETA(11) - SH_BETA(2)*SH_BETA(5)*SH_BETA(12)) + OP(3,2)*(SH_BETA(6)*SH_BETA(12) + SH_BETA(2)*SH_BETA(5)*SH_BETA(11)) - OP(4,2)*(SH_BETA(6)*SH_BETA(10) + SH_BETA(2)*SH_BETA(5)*SH_BETA(9)) + OP(7,2)*(SH_BETA(6)*(2*q0*q1 + 2*q2*q3) + SH_BETA(2)*SH_BETA(5)*(2*q0*q2 - 2*q1*q3))) + (SH_BETA(6)*SH_BETA(12) + SH_BETA(2)*SH_BETA(5)*SH_BETA(11))*(OP(23,3)*(SH_BETA(6)*(SH_BETA(13) - 2*q1*q2) + SH_BETA(2)*SH_BETA(5)*SH_BETA(8)) - OP(5,3)*(SH_BETA(6)*(SH_BETA(13) - 2*q1*q2) + SH_BETA(2)*SH_BETA(5)*SH_BETA(8)) + OP(6,3)*(SH_BETA(7) - SH_BETA(2)*SH_BETA(5)*(SH_BETA(13) + 2*q1*q2)) - OP(24,3)*(SH_BETA(7) - SH_BETA(2)*SH_BETA(5)*(SH_BETA(13) + 2*q1*q2)) + OP(1,3)*(SH_BETA(6)*SH_BETA(9) - SH_BETA(2)*SH_BETA(5)*SH_BETA(10)) + OP(2,3)*(SH_BETA(6)*SH_BETA(11) - SH_BETA(2)*SH_BETA(5)*SH_BETA(12)) + OP(3,3)*(SH_BETA(6)*SH_BETA(12) + SH_BETA(2)*SH_BETA(5)*SH_BETA(11)) - OP(4,3)*(SH_BETA(6)*SH_BETA(10) + SH_BETA(2)*SH_BETA(5)*SH_BETA(9)) + OP(7,3)*(SH_BETA(6)*(2*q0*q1 + 2*q2*q3) + SH_BETA(2)*SH_BETA(5)*(2*q0*q2 - 2*q1*q3))) - (SH_BETA(6)*SH_BETA(10) + SH_BETA(2)*SH_BETA(5)*SH_BETA(9))*(OP(23,4)*(SH_BETA(6)*(SH_BETA(13) - 2*q1*q2) + SH_BETA(2)*SH_BETA(5)*SH_BETA(8)) - OP(5,4)*(SH_BETA(6)*(SH_BETA(13) - 2*q1*q2) + SH_BETA(2)*SH_BETA(5)*SH_BETA(8)) + OP(6,4)*(SH_BETA(7) - SH_BETA(2)*SH_BETA(5)*(SH_BETA(13) + 2*q1*q2)) - OP(24,4)*(SH_BETA(7) - SH_BETA(2)*SH_BETA(5)*(SH_BETA(13) + 2*q1*q2)) + OP(1,4)*(SH_BETA(6)*SH_BETA(9) - SH_BETA(2)*SH_BETA(5)*SH_BETA(10)) + OP(2,4)*(SH_BETA(6)*SH_BETA(11) - SH_BETA(2)*SH_BETA(5)*SH_BETA(12)) + OP(3,4)*(SH_BETA(6)*SH_BETA(12) + SH_BETA(2)*SH_BETA(5)*SH_BETA(11)) - OP(4,4)*(SH_BETA(6)*SH_BETA(10) + SH_BETA(2)*SH_BETA(5)*SH_BETA(9)) + OP(7,4)*(SH_BETA(6)*(2*q0*q1 + 2*q2*q3) + SH_BETA(2)*SH_BETA(5)*(2*q0*q2 - 2*q1*q3))) + (SH_BETA(6)*(2*q0*q1 + 2*q2*q3) + SH_BETA(2)*SH_BETA(5)*(2*q0*q2 - 2*q1*q3))*(OP(23,7)*(SH_BETA(6)*(SH_BETA(13) - 2*q1*q2) + SH_BETA(2)*SH_BETA(5)*SH_BETA(8)) - OP(5,7)*(SH_BETA(6)*(SH_BETA(13) - 2*q1*q2) + SH_BETA(2)*SH_BETA(5)*SH_BETA(8)) + OP(6,7)*(SH_BETA(7) - SH_BETA(2)*SH_BETA(5)*(SH_BETA(13) + 2*q1*q2)) - OP(24,7)*(SH_BETA(7) - SH_BETA(2)*SH_BETA(5)*(SH_BETA(13) + 2*q1*q2)) + OP(1,7)*(SH_BETA(6)*SH_BETA(9) - SH_BETA(2)*SH_BETA(5)*SH_BETA(10)) + OP(2,7)*(SH_BETA(6)*SH_BETA(11) - SH_BETA(2)*SH_BETA(5)*SH_BETA(12)) + OP(3,7)*(SH_BETA(6)*SH_BETA(12) + SH_BETA(2)*SH_BETA(5)*SH_BETA(11)) - OP(4,7)*(SH_BETA(6)*SH_BETA(10) + SH_BETA(2)*SH_BETA(5)*SH_BETA(9)) + OP(7,7)*(SH_BETA(6)*(2*q0*q1 + 2*q2*q3) + SH_BETA(2)*SH_BETA(5)*(2*q0*q2 - 2*q1*q3)))); +SK_BETA(2) = SH_BETA(6)*(SH_BETA(13) - 2*q1*q2) + SH_BETA(2)*SH_BETA(5)*SH_BETA(8); +SK_BETA(3) = SH_BETA(7) - SH_BETA(2)*SH_BETA(5)*(SH_BETA(13) + 2*q1*q2); +SK_BETA(4) = SH_BETA(6)*(2*q0*q1 + 2*q2*q3) + SH_BETA(2)*SH_BETA(5)*(2*q0*q2 - 2*q1*q3); +SK_BETA(5) = SH_BETA(6)*SH_BETA(11) - SH_BETA(2)*SH_BETA(5)*SH_BETA(12); +SK_BETA(6) = SH_BETA(6)*SH_BETA(9) - SH_BETA(2)*SH_BETA(5)*SH_BETA(10); +SK_BETA(7) = SH_BETA(6)*SH_BETA(12) + SH_BETA(2)*SH_BETA(5)*SH_BETA(11); +SK_BETA(8) = SH_BETA(6)*SH_BETA(10) + SH_BETA(2)*SH_BETA(5)*SH_BETA(9); Kfusion = zeros(24,1); Kfusion = zeros(1,1); -Kfusion(1) = SK_BETA(1)*(OP(1,6)*SK_BETA(2) - OP(1,3)*SK_BETA(5) - OP(1,4)*SK_BETA(3) + OP(1,5)*SK_BETA(4) + OP(1,23)*SK_BETA(3) - OP(1,24)*SK_BETA(4) + OP(1,1)*SH_BETA(8)*SK_BETA(6) + OP(1,2)*SH_BETA(2)*SH_BETA(5)*SK_BETA(6)); -Kfusion(2) = SK_BETA(1)*(OP(2,6)*SK_BETA(2) - OP(2,3)*SK_BETA(5) - OP(2,4)*SK_BETA(3) + OP(2,5)*SK_BETA(4) + OP(2,23)*SK_BETA(3) - OP(2,24)*SK_BETA(4) + OP(2,1)*SH_BETA(8)*SK_BETA(6) + OP(2,2)*SH_BETA(2)*SH_BETA(5)*SK_BETA(6)); -Kfusion(3) = SK_BETA(1)*(OP(3,6)*SK_BETA(2) - OP(3,3)*SK_BETA(5) - OP(3,4)*SK_BETA(3) + OP(3,5)*SK_BETA(4) + OP(3,23)*SK_BETA(3) - OP(3,24)*SK_BETA(4) + OP(3,1)*SH_BETA(8)*SK_BETA(6) + OP(3,2)*SH_BETA(2)*SH_BETA(5)*SK_BETA(6)); -Kfusion(4) = SK_BETA(1)*(OP(4,6)*SK_BETA(2) - OP(4,3)*SK_BETA(5) - OP(4,4)*SK_BETA(3) + OP(4,5)*SK_BETA(4) + OP(4,23)*SK_BETA(3) - OP(4,24)*SK_BETA(4) + OP(4,1)*SH_BETA(8)*SK_BETA(6) + OP(4,2)*SH_BETA(2)*SH_BETA(5)*SK_BETA(6)); -Kfusion(5) = SK_BETA(1)*(OP(5,6)*SK_BETA(2) - OP(5,3)*SK_BETA(5) - OP(5,4)*SK_BETA(3) + OP(5,5)*SK_BETA(4) + OP(5,23)*SK_BETA(3) - OP(5,24)*SK_BETA(4) + OP(5,1)*SH_BETA(8)*SK_BETA(6) + OP(5,2)*SH_BETA(2)*SH_BETA(5)*SK_BETA(6)); -Kfusion(6) = SK_BETA(1)*(OP(6,6)*SK_BETA(2) - OP(6,3)*SK_BETA(5) - OP(6,4)*SK_BETA(3) + OP(6,5)*SK_BETA(4) + OP(6,23)*SK_BETA(3) - OP(6,24)*SK_BETA(4) + OP(6,1)*SH_BETA(8)*SK_BETA(6) + OP(6,2)*SH_BETA(2)*SH_BETA(5)*SK_BETA(6)); -Kfusion(7) = SK_BETA(1)*(OP(7,6)*SK_BETA(2) - OP(7,3)*SK_BETA(5) - OP(7,4)*SK_BETA(3) + OP(7,5)*SK_BETA(4) + OP(7,23)*SK_BETA(3) - OP(7,24)*SK_BETA(4) + OP(7,1)*SH_BETA(8)*SK_BETA(6) + OP(7,2)*SH_BETA(2)*SH_BETA(5)*SK_BETA(6)); -Kfusion(8) = SK_BETA(1)*(OP(8,6)*SK_BETA(2) - OP(8,3)*SK_BETA(5) - OP(8,4)*SK_BETA(3) + OP(8,5)*SK_BETA(4) + OP(8,23)*SK_BETA(3) - OP(8,24)*SK_BETA(4) + OP(8,1)*SH_BETA(8)*SK_BETA(6) + OP(8,2)*SH_BETA(2)*SH_BETA(5)*SK_BETA(6)); -Kfusion(9) = SK_BETA(1)*(OP(9,6)*SK_BETA(2) - OP(9,3)*SK_BETA(5) - OP(9,4)*SK_BETA(3) + OP(9,5)*SK_BETA(4) + OP(9,23)*SK_BETA(3) - OP(9,24)*SK_BETA(4) + OP(9,1)*SH_BETA(8)*SK_BETA(6) + OP(9,2)*SH_BETA(2)*SH_BETA(5)*SK_BETA(6)); -Kfusion(10) = SK_BETA(1)*(OP(10,6)*SK_BETA(2) - OP(10,3)*SK_BETA(5) - OP(10,4)*SK_BETA(3) + OP(10,5)*SK_BETA(4) + OP(10,23)*SK_BETA(3) - OP(10,24)*SK_BETA(4) + OP(10,1)*SH_BETA(8)*SK_BETA(6) + OP(10,2)*SH_BETA(2)*SH_BETA(5)*SK_BETA(6)); -Kfusion(11) = SK_BETA(1)*(OP(11,6)*SK_BETA(2) - OP(11,3)*SK_BETA(5) - OP(11,4)*SK_BETA(3) + OP(11,5)*SK_BETA(4) + OP(11,23)*SK_BETA(3) - OP(11,24)*SK_BETA(4) + OP(11,1)*SH_BETA(8)*SK_BETA(6) + OP(11,2)*SH_BETA(2)*SH_BETA(5)*SK_BETA(6)); -Kfusion(12) = SK_BETA(1)*(OP(12,6)*SK_BETA(2) - OP(12,3)*SK_BETA(5) - OP(12,4)*SK_BETA(3) + OP(12,5)*SK_BETA(4) + OP(12,23)*SK_BETA(3) - OP(12,24)*SK_BETA(4) + OP(12,1)*SH_BETA(8)*SK_BETA(6) + OP(12,2)*SH_BETA(2)*SH_BETA(5)*SK_BETA(6)); -Kfusion(13) = SK_BETA(1)*(OP(13,6)*SK_BETA(2) - OP(13,3)*SK_BETA(5) - OP(13,4)*SK_BETA(3) + OP(13,5)*SK_BETA(4) + OP(13,23)*SK_BETA(3) - OP(13,24)*SK_BETA(4) + OP(13,1)*SH_BETA(8)*SK_BETA(6) + OP(13,2)*SH_BETA(2)*SH_BETA(5)*SK_BETA(6)); -Kfusion(14) = SK_BETA(1)*(OP(14,6)*SK_BETA(2) - OP(14,3)*SK_BETA(5) - OP(14,4)*SK_BETA(3) + OP(14,5)*SK_BETA(4) + OP(14,23)*SK_BETA(3) - OP(14,24)*SK_BETA(4) + OP(14,1)*SH_BETA(8)*SK_BETA(6) + OP(14,2)*SH_BETA(2)*SH_BETA(5)*SK_BETA(6)); -Kfusion(15) = SK_BETA(1)*(OP(15,6)*SK_BETA(2) - OP(15,3)*SK_BETA(5) - OP(15,4)*SK_BETA(3) + OP(15,5)*SK_BETA(4) + OP(15,23)*SK_BETA(3) - OP(15,24)*SK_BETA(4) + OP(15,1)*SH_BETA(8)*SK_BETA(6) + OP(15,2)*SH_BETA(2)*SH_BETA(5)*SK_BETA(6)); -Kfusion(16) = SK_BETA(1)*(OP(16,6)*SK_BETA(2) - OP(16,3)*SK_BETA(5) - OP(16,4)*SK_BETA(3) + OP(16,5)*SK_BETA(4) + OP(16,23)*SK_BETA(3) - OP(16,24)*SK_BETA(4) + OP(16,1)*SH_BETA(8)*SK_BETA(6) + OP(16,2)*SH_BETA(2)*SH_BETA(5)*SK_BETA(6)); -Kfusion(17) = SK_BETA(1)*(OP(17,6)*SK_BETA(2) - OP(17,3)*SK_BETA(5) - OP(17,4)*SK_BETA(3) + OP(17,5)*SK_BETA(4) + OP(17,23)*SK_BETA(3) - OP(17,24)*SK_BETA(4) + OP(17,1)*SH_BETA(8)*SK_BETA(6) + OP(17,2)*SH_BETA(2)*SH_BETA(5)*SK_BETA(6)); -Kfusion(18) = SK_BETA(1)*(OP(18,6)*SK_BETA(2) - OP(18,3)*SK_BETA(5) - OP(18,4)*SK_BETA(3) + OP(18,5)*SK_BETA(4) + OP(18,23)*SK_BETA(3) - OP(18,24)*SK_BETA(4) + OP(18,1)*SH_BETA(8)*SK_BETA(6) + OP(18,2)*SH_BETA(2)*SH_BETA(5)*SK_BETA(6)); -Kfusion(19) = SK_BETA(1)*(OP(19,6)*SK_BETA(2) - OP(19,3)*SK_BETA(5) - OP(19,4)*SK_BETA(3) + OP(19,5)*SK_BETA(4) + OP(19,23)*SK_BETA(3) - OP(19,24)*SK_BETA(4) + OP(19,1)*SH_BETA(8)*SK_BETA(6) + OP(19,2)*SH_BETA(2)*SH_BETA(5)*SK_BETA(6)); -Kfusion(20) = SK_BETA(1)*(OP(20,6)*SK_BETA(2) - OP(20,3)*SK_BETA(5) - OP(20,4)*SK_BETA(3) + OP(20,5)*SK_BETA(4) + OP(20,23)*SK_BETA(3) - OP(20,24)*SK_BETA(4) + OP(20,1)*SH_BETA(8)*SK_BETA(6) + OP(20,2)*SH_BETA(2)*SH_BETA(5)*SK_BETA(6)); -Kfusion(21) = SK_BETA(1)*(OP(21,6)*SK_BETA(2) - OP(21,3)*SK_BETA(5) - OP(21,4)*SK_BETA(3) + OP(21,5)*SK_BETA(4) + OP(21,23)*SK_BETA(3) - OP(21,24)*SK_BETA(4) + OP(21,1)*SH_BETA(8)*SK_BETA(6) + OP(21,2)*SH_BETA(2)*SH_BETA(5)*SK_BETA(6)); -Kfusion(22) = SK_BETA(1)*(OP(22,6)*SK_BETA(2) - OP(22,3)*SK_BETA(5) - OP(22,4)*SK_BETA(3) + OP(22,5)*SK_BETA(4) + OP(22,23)*SK_BETA(3) - OP(22,24)*SK_BETA(4) + OP(22,1)*SH_BETA(8)*SK_BETA(6) + OP(22,2)*SH_BETA(2)*SH_BETA(5)*SK_BETA(6)); -Kfusion(23) = SK_BETA(1)*(OP(23,6)*SK_BETA(2) - OP(23,3)*SK_BETA(5) - OP(23,4)*SK_BETA(3) + OP(23,5)*SK_BETA(4) + OP(23,23)*SK_BETA(3) - OP(23,24)*SK_BETA(4) + OP(23,1)*SH_BETA(8)*SK_BETA(6) + OP(23,2)*SH_BETA(2)*SH_BETA(5)*SK_BETA(6)); -Kfusion(24) = SK_BETA(1)*(OP(24,6)*SK_BETA(2) - OP(24,3)*SK_BETA(5) - OP(24,4)*SK_BETA(3) + OP(24,5)*SK_BETA(4) + OP(24,23)*SK_BETA(3) - OP(24,24)*SK_BETA(4) + OP(24,1)*SH_BETA(8)*SK_BETA(6) + OP(24,2)*SH_BETA(2)*SH_BETA(5)*SK_BETA(6)); +Kfusion(1) = SK_BETA(1)*(OP(1,1)*SK_BETA(6) + OP(1,2)*SK_BETA(5) - OP(1,5)*SK_BETA(2) + OP(1,6)*SK_BETA(3) + OP(1,3)*SK_BETA(7) + OP(1,7)*SK_BETA(4) - OP(1,4)*SK_BETA(8) + OP(1,23)*SK_BETA(2) - OP(1,24)*SK_BETA(3)); +Kfusion(2) = SK_BETA(1)*(OP(2,1)*SK_BETA(6) + OP(2,2)*SK_BETA(5) - OP(2,5)*SK_BETA(2) + OP(2,6)*SK_BETA(3) + OP(2,3)*SK_BETA(7) + OP(2,7)*SK_BETA(4) - OP(2,4)*SK_BETA(8) + OP(2,23)*SK_BETA(2) - OP(2,24)*SK_BETA(3)); +Kfusion(3) = SK_BETA(1)*(OP(3,1)*SK_BETA(6) + OP(3,2)*SK_BETA(5) - OP(3,5)*SK_BETA(2) + OP(3,6)*SK_BETA(3) + OP(3,3)*SK_BETA(7) + OP(3,7)*SK_BETA(4) - OP(3,4)*SK_BETA(8) + OP(3,23)*SK_BETA(2) - OP(3,24)*SK_BETA(3)); +Kfusion(4) = SK_BETA(1)*(OP(4,1)*SK_BETA(6) + OP(4,2)*SK_BETA(5) - OP(4,5)*SK_BETA(2) + OP(4,6)*SK_BETA(3) + OP(4,3)*SK_BETA(7) + OP(4,7)*SK_BETA(4) - OP(4,4)*SK_BETA(8) + OP(4,23)*SK_BETA(2) - OP(4,24)*SK_BETA(3)); +Kfusion(5) = SK_BETA(1)*(OP(5,1)*SK_BETA(6) + OP(5,2)*SK_BETA(5) - OP(5,5)*SK_BETA(2) + OP(5,6)*SK_BETA(3) + OP(5,3)*SK_BETA(7) + OP(5,7)*SK_BETA(4) - OP(5,4)*SK_BETA(8) + OP(5,23)*SK_BETA(2) - OP(5,24)*SK_BETA(3)); +Kfusion(6) = SK_BETA(1)*(OP(6,1)*SK_BETA(6) + OP(6,2)*SK_BETA(5) - OP(6,5)*SK_BETA(2) + OP(6,6)*SK_BETA(3) + OP(6,3)*SK_BETA(7) + OP(6,7)*SK_BETA(4) - OP(6,4)*SK_BETA(8) + OP(6,23)*SK_BETA(2) - OP(6,24)*SK_BETA(3)); +Kfusion(7) = SK_BETA(1)*(OP(7,1)*SK_BETA(6) + OP(7,2)*SK_BETA(5) - OP(7,5)*SK_BETA(2) + OP(7,6)*SK_BETA(3) + OP(7,3)*SK_BETA(7) + OP(7,7)*SK_BETA(4) - OP(7,4)*SK_BETA(8) + OP(7,23)*SK_BETA(2) - OP(7,24)*SK_BETA(3)); +Kfusion(8) = SK_BETA(1)*(OP(8,1)*SK_BETA(6) + OP(8,2)*SK_BETA(5) - OP(8,5)*SK_BETA(2) + OP(8,6)*SK_BETA(3) + OP(8,3)*SK_BETA(7) + OP(8,7)*SK_BETA(4) - OP(8,4)*SK_BETA(8) + OP(8,23)*SK_BETA(2) - OP(8,24)*SK_BETA(3)); +Kfusion(9) = SK_BETA(1)*(OP(9,1)*SK_BETA(6) + OP(9,2)*SK_BETA(5) - OP(9,5)*SK_BETA(2) + OP(9,6)*SK_BETA(3) + OP(9,3)*SK_BETA(7) + OP(9,7)*SK_BETA(4) - OP(9,4)*SK_BETA(8) + OP(9,23)*SK_BETA(2) - OP(9,24)*SK_BETA(3)); +Kfusion(10) = SK_BETA(1)*(OP(10,1)*SK_BETA(6) + OP(10,2)*SK_BETA(5) - OP(10,5)*SK_BETA(2) + OP(10,6)*SK_BETA(3) + OP(10,3)*SK_BETA(7) + OP(10,7)*SK_BETA(4) - OP(10,4)*SK_BETA(8) + OP(10,23)*SK_BETA(2) - OP(10,24)*SK_BETA(3)); +Kfusion(11) = SK_BETA(1)*(OP(11,1)*SK_BETA(6) + OP(11,2)*SK_BETA(5) - OP(11,5)*SK_BETA(2) + OP(11,6)*SK_BETA(3) + OP(11,3)*SK_BETA(7) + OP(11,7)*SK_BETA(4) - OP(11,4)*SK_BETA(8) + OP(11,23)*SK_BETA(2) - OP(11,24)*SK_BETA(3)); +Kfusion(12) = SK_BETA(1)*(OP(12,1)*SK_BETA(6) + OP(12,2)*SK_BETA(5) - OP(12,5)*SK_BETA(2) + OP(12,6)*SK_BETA(3) + OP(12,3)*SK_BETA(7) + OP(12,7)*SK_BETA(4) - OP(12,4)*SK_BETA(8) + OP(12,23)*SK_BETA(2) - OP(12,24)*SK_BETA(3)); +Kfusion(13) = SK_BETA(1)*(OP(13,1)*SK_BETA(6) + OP(13,2)*SK_BETA(5) - OP(13,5)*SK_BETA(2) + OP(13,6)*SK_BETA(3) + OP(13,3)*SK_BETA(7) + OP(13,7)*SK_BETA(4) - OP(13,4)*SK_BETA(8) + OP(13,23)*SK_BETA(2) - OP(13,24)*SK_BETA(3)); +Kfusion(14) = SK_BETA(1)*(OP(14,1)*SK_BETA(6) + OP(14,2)*SK_BETA(5) - OP(14,5)*SK_BETA(2) + OP(14,6)*SK_BETA(3) + OP(14,3)*SK_BETA(7) + OP(14,7)*SK_BETA(4) - OP(14,4)*SK_BETA(8) + OP(14,23)*SK_BETA(2) - OP(14,24)*SK_BETA(3)); +Kfusion(15) = SK_BETA(1)*(OP(15,1)*SK_BETA(6) + OP(15,2)*SK_BETA(5) - OP(15,5)*SK_BETA(2) + OP(15,6)*SK_BETA(3) + OP(15,3)*SK_BETA(7) + OP(15,7)*SK_BETA(4) - OP(15,4)*SK_BETA(8) + OP(15,23)*SK_BETA(2) - OP(15,24)*SK_BETA(3)); +Kfusion(16) = SK_BETA(1)*(OP(16,1)*SK_BETA(6) + OP(16,2)*SK_BETA(5) - OP(16,5)*SK_BETA(2) + OP(16,6)*SK_BETA(3) + OP(16,3)*SK_BETA(7) + OP(16,7)*SK_BETA(4) - OP(16,4)*SK_BETA(8) + OP(16,23)*SK_BETA(2) - OP(16,24)*SK_BETA(3)); +Kfusion(17) = SK_BETA(1)*(OP(17,1)*SK_BETA(6) + OP(17,2)*SK_BETA(5) - OP(17,5)*SK_BETA(2) + OP(17,6)*SK_BETA(3) + OP(17,3)*SK_BETA(7) + OP(17,7)*SK_BETA(4) - OP(17,4)*SK_BETA(8) + OP(17,23)*SK_BETA(2) - OP(17,24)*SK_BETA(3)); +Kfusion(18) = SK_BETA(1)*(OP(18,1)*SK_BETA(6) + OP(18,2)*SK_BETA(5) - OP(18,5)*SK_BETA(2) + OP(18,6)*SK_BETA(3) + OP(18,3)*SK_BETA(7) + OP(18,7)*SK_BETA(4) - OP(18,4)*SK_BETA(8) + OP(18,23)*SK_BETA(2) - OP(18,24)*SK_BETA(3)); +Kfusion(19) = SK_BETA(1)*(OP(19,1)*SK_BETA(6) + OP(19,2)*SK_BETA(5) - OP(19,5)*SK_BETA(2) + OP(19,6)*SK_BETA(3) + OP(19,3)*SK_BETA(7) + OP(19,7)*SK_BETA(4) - OP(19,4)*SK_BETA(8) + OP(19,23)*SK_BETA(2) - OP(19,24)*SK_BETA(3)); +Kfusion(20) = SK_BETA(1)*(OP(20,1)*SK_BETA(6) + OP(20,2)*SK_BETA(5) - OP(20,5)*SK_BETA(2) + OP(20,6)*SK_BETA(3) + OP(20,3)*SK_BETA(7) + OP(20,7)*SK_BETA(4) - OP(20,4)*SK_BETA(8) + OP(20,23)*SK_BETA(2) - OP(20,24)*SK_BETA(3)); +Kfusion(21) = SK_BETA(1)*(OP(21,1)*SK_BETA(6) + OP(21,2)*SK_BETA(5) - OP(21,5)*SK_BETA(2) + OP(21,6)*SK_BETA(3) + OP(21,3)*SK_BETA(7) + OP(21,7)*SK_BETA(4) - OP(21,4)*SK_BETA(8) + OP(21,23)*SK_BETA(2) - OP(21,24)*SK_BETA(3)); +Kfusion(22) = SK_BETA(1)*(OP(22,1)*SK_BETA(6) + OP(22,2)*SK_BETA(5) - OP(22,5)*SK_BETA(2) + OP(22,6)*SK_BETA(3) + OP(22,3)*SK_BETA(7) + OP(22,7)*SK_BETA(4) - OP(22,4)*SK_BETA(8) + OP(22,23)*SK_BETA(2) - OP(22,24)*SK_BETA(3)); +Kfusion(23) = SK_BETA(1)*(OP(23,1)*SK_BETA(6) + OP(23,2)*SK_BETA(5) - OP(23,5)*SK_BETA(2) + OP(23,6)*SK_BETA(3) + OP(23,3)*SK_BETA(7) + OP(23,7)*SK_BETA(4) - OP(23,4)*SK_BETA(8) + OP(23,23)*SK_BETA(2) - OP(23,24)*SK_BETA(3)); +Kfusion(24) = SK_BETA(1)*(OP(24,1)*SK_BETA(6) + OP(24,2)*SK_BETA(5) - OP(24,5)*SK_BETA(2) + OP(24,6)*SK_BETA(3) + OP(24,3)*SK_BETA(7) + OP(24,7)*SK_BETA(4) - OP(24,4)*SK_BETA(8) + OP(24,23)*SK_BETA(2) - OP(24,24)*SK_BETA(3)); SH_MAG = zeros(9,1); -SH_MAG(1) = q0^2 - q1^2 + q2^2 - q3^2; -SH_MAG(2) = q0^2 + q1^2 - q2^2 - q3^2; -SH_MAG(3) = q0^2 - q1^2 - q2^2 + q3^2; -SH_MAG(4) = 2*q0*q1 + 2*q2*q3; -SH_MAG(5) = 2*q0*q3 + 2*q1*q2; -SH_MAG(6) = 2*q0*q2 + 2*q1*q3; -SH_MAG(7) = magE*(2*q0*q1 - 2*q2*q3); -SH_MAG(8) = 2*q1*q3 - 2*q0*q2; -SH_MAG(9) = 2*q0*q3; +SH_MAG(1) = 2*magD*q3 + 2*magE*q2 + 2*magN*q1; +SH_MAG(2) = 2*magD*q0 - 2*magE*q1 + 2*magN*q2; +SH_MAG(3) = 2*magD*q1 + 2*magE*q0 - 2*magN*q3; +SH_MAG(4) = q3^2; +SH_MAG(5) = q2^2; +SH_MAG(6) = q1^2; +SH_MAG(7) = q0^2; +SH_MAG(8) = 2*magN*q0; +SH_MAG(9) = 2*magE*q3; H_MAG = zeros(1,24); -H_MAG(2) = SH_MAG(7) - magD*SH_MAG(3) - magN*SH_MAG(6); -H_MAG(3) = magE*SH_MAG(1) + magD*SH_MAG(4) - magN*(SH_MAG(9) - 2*q1*q2); -H_MAG(17) = SH_MAG(2); -H_MAG(18) = SH_MAG(5); -H_MAG(19) = SH_MAG(8); +H_MAG(1) = SH_MAG(8) + SH_MAG(9) - 2*magD*q2; +H_MAG(2) = SH_MAG(1); +H_MAG(3) = -SH_MAG(2); +H_MAG(4) = SH_MAG(3); +H_MAG(17) = SH_MAG(6) - SH_MAG(5) - SH_MAG(4) + SH_MAG(7); +H_MAG(18) = 2*q0*q3 + 2*q1*q2; +H_MAG(19) = 2*q1*q3 - 2*q0*q2; H_MAG(20) = 1; -SK_MX = zeros(4,1); -SK_MX(1) = 1/(OP(20,20) + R_MAG - OP(2,20)*(magD*SH_MAG(3) - SH_MAG(7) + magN*SH_MAG(6)) + OP(17,20)*SH_MAG(2) + OP(18,20)*SH_MAG(5) + OP(19,20)*SH_MAG(8) + OP(3,20)*(magE*SH_MAG(1) + magD*SH_MAG(4) - magN*(SH_MAG(9) - 2*q1*q2)) - (magD*SH_MAG(3) - SH_MAG(7) + magN*SH_MAG(6))*(OP(20,2) - OP(2,2)*(magD*SH_MAG(3) - SH_MAG(7) + magN*SH_MAG(6)) + OP(17,2)*SH_MAG(2) + OP(18,2)*SH_MAG(5) + OP(19,2)*SH_MAG(8) + OP(3,2)*(magE*SH_MAG(1) + magD*SH_MAG(4) - magN*(SH_MAG(9) - 2*q1*q2))) + SH_MAG(2)*(OP(20,17) - OP(2,17)*(magD*SH_MAG(3) - SH_MAG(7) + magN*SH_MAG(6)) + OP(17,17)*SH_MAG(2) + OP(18,17)*SH_MAG(5) + OP(19,17)*SH_MAG(8) + OP(3,17)*(magE*SH_MAG(1) + magD*SH_MAG(4) - magN*(SH_MAG(9) - 2*q1*q2))) + SH_MAG(5)*(OP(20,18) - OP(2,18)*(magD*SH_MAG(3) - SH_MAG(7) + magN*SH_MAG(6)) + OP(17,18)*SH_MAG(2) + OP(18,18)*SH_MAG(5) + OP(19,18)*SH_MAG(8) + OP(3,18)*(magE*SH_MAG(1) + magD*SH_MAG(4) - magN*(SH_MAG(9) - 2*q1*q2))) + SH_MAG(8)*(OP(20,19) - OP(2,19)*(magD*SH_MAG(3) - SH_MAG(7) + magN*SH_MAG(6)) + OP(17,19)*SH_MAG(2) + OP(18,19)*SH_MAG(5) + OP(19,19)*SH_MAG(8) + OP(3,19)*(magE*SH_MAG(1) + magD*SH_MAG(4) - magN*(SH_MAG(9) - 2*q1*q2))) + (magE*SH_MAG(1) + magD*SH_MAG(4) - magN*(SH_MAG(9) - 2*q1*q2))*(OP(20,3) - OP(2,3)*(magD*SH_MAG(3) - SH_MAG(7) + magN*SH_MAG(6)) + OP(17,3)*SH_MAG(2) + OP(18,3)*SH_MAG(5) + OP(19,3)*SH_MAG(8) + OP(3,3)*(magE*SH_MAG(1) + magD*SH_MAG(4) - magN*(SH_MAG(9) - 2*q1*q2)))); -SK_MX(2) = magE*SH_MAG(1) + magD*SH_MAG(4) - magN*(SH_MAG(9) - 2*q1*q2); -SK_MX(3) = magD*SH_MAG(3) - SH_MAG(7) + magN*SH_MAG(6); -SK_MX(4) = SH_MAG(8); +SK_MX = zeros(5,1); +SK_MX(1) = 1/(OP(20,20) + R_MAG + OP(2,20)*SH_MAG(1) - OP(3,20)*SH_MAG(2) + OP(4,20)*SH_MAG(3) - OP(17,20)*(SH_MAG(4) + SH_MAG(5) - SH_MAG(6) - SH_MAG(7)) + (2*q0*q3 + 2*q1*q2)*(OP(20,18) + OP(2,18)*SH_MAG(1) - OP(3,18)*SH_MAG(2) + OP(4,18)*SH_MAG(3) - OP(17,18)*(SH_MAG(4) + SH_MAG(5) - SH_MAG(6) - SH_MAG(7)) + OP(18,18)*(2*q0*q3 + 2*q1*q2) - OP(19,18)*(2*q0*q2 - 2*q1*q3) + OP(1,18)*(SH_MAG(8) + SH_MAG(9) - 2*magD*q2)) - (2*q0*q2 - 2*q1*q3)*(OP(20,19) + OP(2,19)*SH_MAG(1) - OP(3,19)*SH_MAG(2) + OP(4,19)*SH_MAG(3) - OP(17,19)*(SH_MAG(4) + SH_MAG(5) - SH_MAG(6) - SH_MAG(7)) + OP(18,19)*(2*q0*q3 + 2*q1*q2) - OP(19,19)*(2*q0*q2 - 2*q1*q3) + OP(1,19)*(SH_MAG(8) + SH_MAG(9) - 2*magD*q2)) + (SH_MAG(8) + SH_MAG(9) - 2*magD*q2)*(OP(20,1) + OP(2,1)*SH_MAG(1) - OP(3,1)*SH_MAG(2) + OP(4,1)*SH_MAG(3) - OP(17,1)*(SH_MAG(4) + SH_MAG(5) - SH_MAG(6) - SH_MAG(7)) + OP(18,1)*(2*q0*q3 + 2*q1*q2) - OP(19,1)*(2*q0*q2 - 2*q1*q3) + OP(1,1)*(SH_MAG(8) + SH_MAG(9) - 2*magD*q2)) + OP(18,20)*(2*q0*q3 + 2*q1*q2) - OP(19,20)*(2*q0*q2 - 2*q1*q3) + SH_MAG(1)*(OP(20,2) + OP(2,2)*SH_MAG(1) - OP(3,2)*SH_MAG(2) + OP(4,2)*SH_MAG(3) - OP(17,2)*(SH_MAG(4) + SH_MAG(5) - SH_MAG(6) - SH_MAG(7)) + OP(18,2)*(2*q0*q3 + 2*q1*q2) - OP(19,2)*(2*q0*q2 - 2*q1*q3) + OP(1,2)*(SH_MAG(8) + SH_MAG(9) - 2*magD*q2)) - SH_MAG(2)*(OP(20,3) + OP(2,3)*SH_MAG(1) - OP(3,3)*SH_MAG(2) + OP(4,3)*SH_MAG(3) - OP(17,3)*(SH_MAG(4) + SH_MAG(5) - SH_MAG(6) - SH_MAG(7)) + OP(18,3)*(2*q0*q3 + 2*q1*q2) - OP(19,3)*(2*q0*q2 - 2*q1*q3) + OP(1,3)*(SH_MAG(8) + SH_MAG(9) - 2*magD*q2)) + SH_MAG(3)*(OP(20,4) + OP(2,4)*SH_MAG(1) - OP(3,4)*SH_MAG(2) + OP(4,4)*SH_MAG(3) - OP(17,4)*(SH_MAG(4) + SH_MAG(5) - SH_MAG(6) - SH_MAG(7)) + OP(18,4)*(2*q0*q3 + 2*q1*q2) - OP(19,4)*(2*q0*q2 - 2*q1*q3) + OP(1,4)*(SH_MAG(8) + SH_MAG(9) - 2*magD*q2)) - (SH_MAG(4) + SH_MAG(5) - SH_MAG(6) - SH_MAG(7))*(OP(20,17) + OP(2,17)*SH_MAG(1) - OP(3,17)*SH_MAG(2) + OP(4,17)*SH_MAG(3) - OP(17,17)*(SH_MAG(4) + SH_MAG(5) - SH_MAG(6) - SH_MAG(7)) + OP(18,17)*(2*q0*q3 + 2*q1*q2) - OP(19,17)*(2*q0*q2 - 2*q1*q3) + OP(1,17)*(SH_MAG(8) + SH_MAG(9) - 2*magD*q2)) + OP(1,20)*(SH_MAG(8) + SH_MAG(9) - 2*magD*q2)); +SK_MX(2) = SH_MAG(4) + SH_MAG(5) - SH_MAG(6) - SH_MAG(7); +SK_MX(3) = SH_MAG(8) + SH_MAG(9) - 2*magD*q2; +SK_MX(4) = 2*q0*q2 - 2*q1*q3; +SK_MX(5) = 2*q0*q3 + 2*q1*q2; Kfusion = zeros(24,1); Kfusion = zeros(1,1); -Kfusion(1) = SK_MX(1)*(OP(1,20) + OP(1,17)*SH_MAG(2) + OP(1,18)*SH_MAG(5) - OP(1,2)*SK_MX(3) + OP(1,3)*SK_MX(2) + OP(1,19)*SK_MX(4)); -Kfusion(2) = SK_MX(1)*(OP(2,20) + OP(2,17)*SH_MAG(2) + OP(2,18)*SH_MAG(5) - OP(2,2)*SK_MX(3) + OP(2,3)*SK_MX(2) + OP(2,19)*SK_MX(4)); -Kfusion(3) = SK_MX(1)*(OP(3,20) + OP(3,17)*SH_MAG(2) + OP(3,18)*SH_MAG(5) - OP(3,2)*SK_MX(3) + OP(3,3)*SK_MX(2) + OP(3,19)*SK_MX(4)); -Kfusion(4) = SK_MX(1)*(OP(4,20) + OP(4,17)*SH_MAG(2) + OP(4,18)*SH_MAG(5) - OP(4,2)*SK_MX(3) + OP(4,3)*SK_MX(2) + OP(4,19)*SK_MX(4)); -Kfusion(5) = SK_MX(1)*(OP(5,20) + OP(5,17)*SH_MAG(2) + OP(5,18)*SH_MAG(5) - OP(5,2)*SK_MX(3) + OP(5,3)*SK_MX(2) + OP(5,19)*SK_MX(4)); -Kfusion(6) = SK_MX(1)*(OP(6,20) + OP(6,17)*SH_MAG(2) + OP(6,18)*SH_MAG(5) - OP(6,2)*SK_MX(3) + OP(6,3)*SK_MX(2) + OP(6,19)*SK_MX(4)); -Kfusion(7) = SK_MX(1)*(OP(7,20) + OP(7,17)*SH_MAG(2) + OP(7,18)*SH_MAG(5) - OP(7,2)*SK_MX(3) + OP(7,3)*SK_MX(2) + OP(7,19)*SK_MX(4)); -Kfusion(8) = SK_MX(1)*(OP(8,20) + OP(8,17)*SH_MAG(2) + OP(8,18)*SH_MAG(5) - OP(8,2)*SK_MX(3) + OP(8,3)*SK_MX(2) + OP(8,19)*SK_MX(4)); -Kfusion(9) = SK_MX(1)*(OP(9,20) + OP(9,17)*SH_MAG(2) + OP(9,18)*SH_MAG(5) - OP(9,2)*SK_MX(3) + OP(9,3)*SK_MX(2) + OP(9,19)*SK_MX(4)); -Kfusion(10) = SK_MX(1)*(OP(10,20) + OP(10,17)*SH_MAG(2) + OP(10,18)*SH_MAG(5) - OP(10,2)*SK_MX(3) + OP(10,3)*SK_MX(2) + OP(10,19)*SK_MX(4)); -Kfusion(11) = SK_MX(1)*(OP(11,20) + OP(11,17)*SH_MAG(2) + OP(11,18)*SH_MAG(5) - OP(11,2)*SK_MX(3) + OP(11,3)*SK_MX(2) + OP(11,19)*SK_MX(4)); -Kfusion(12) = SK_MX(1)*(OP(12,20) + OP(12,17)*SH_MAG(2) + OP(12,18)*SH_MAG(5) - OP(12,2)*SK_MX(3) + OP(12,3)*SK_MX(2) + OP(12,19)*SK_MX(4)); -Kfusion(13) = SK_MX(1)*(OP(13,20) + OP(13,17)*SH_MAG(2) + OP(13,18)*SH_MAG(5) - OP(13,2)*SK_MX(3) + OP(13,3)*SK_MX(2) + OP(13,19)*SK_MX(4)); -Kfusion(14) = SK_MX(1)*(OP(14,20) + OP(14,17)*SH_MAG(2) + OP(14,18)*SH_MAG(5) - OP(14,2)*SK_MX(3) + OP(14,3)*SK_MX(2) + OP(14,19)*SK_MX(4)); -Kfusion(15) = SK_MX(1)*(OP(15,20) + OP(15,17)*SH_MAG(2) + OP(15,18)*SH_MAG(5) - OP(15,2)*SK_MX(3) + OP(15,3)*SK_MX(2) + OP(15,19)*SK_MX(4)); -Kfusion(16) = SK_MX(1)*(OP(16,20) + OP(16,17)*SH_MAG(2) + OP(16,18)*SH_MAG(5) - OP(16,2)*SK_MX(3) + OP(16,3)*SK_MX(2) + OP(16,19)*SK_MX(4)); -Kfusion(17) = SK_MX(1)*(OP(17,20) + OP(17,17)*SH_MAG(2) + OP(17,18)*SH_MAG(5) - OP(17,2)*SK_MX(3) + OP(17,3)*SK_MX(2) + OP(17,19)*SK_MX(4)); -Kfusion(18) = SK_MX(1)*(OP(18,20) + OP(18,17)*SH_MAG(2) + OP(18,18)*SH_MAG(5) - OP(18,2)*SK_MX(3) + OP(18,3)*SK_MX(2) + OP(18,19)*SK_MX(4)); -Kfusion(19) = SK_MX(1)*(OP(19,20) + OP(19,17)*SH_MAG(2) + OP(19,18)*SH_MAG(5) - OP(19,2)*SK_MX(3) + OP(19,3)*SK_MX(2) + OP(19,19)*SK_MX(4)); -Kfusion(20) = SK_MX(1)*(OP(20,20) + OP(20,17)*SH_MAG(2) + OP(20,18)*SH_MAG(5) - OP(20,2)*SK_MX(3) + OP(20,3)*SK_MX(2) + OP(20,19)*SK_MX(4)); -Kfusion(21) = SK_MX(1)*(OP(21,20) + OP(21,17)*SH_MAG(2) + OP(21,18)*SH_MAG(5) - OP(21,2)*SK_MX(3) + OP(21,3)*SK_MX(2) + OP(21,19)*SK_MX(4)); -Kfusion(22) = SK_MX(1)*(OP(22,20) + OP(22,17)*SH_MAG(2) + OP(22,18)*SH_MAG(5) - OP(22,2)*SK_MX(3) + OP(22,3)*SK_MX(2) + OP(22,19)*SK_MX(4)); -Kfusion(23) = SK_MX(1)*(OP(23,20) + OP(23,17)*SH_MAG(2) + OP(23,18)*SH_MAG(5) - OP(23,2)*SK_MX(3) + OP(23,3)*SK_MX(2) + OP(23,19)*SK_MX(4)); -Kfusion(24) = SK_MX(1)*(OP(24,20) + OP(24,17)*SH_MAG(2) + OP(24,18)*SH_MAG(5) - OP(24,2)*SK_MX(3) + OP(24,3)*SK_MX(2) + OP(24,19)*SK_MX(4)); +Kfusion(1) = SK_MX(1)*(OP(1,20) + OP(1,2)*SH_MAG(1) - OP(1,3)*SH_MAG(2) + OP(1,4)*SH_MAG(3) + OP(1,1)*SK_MX(3) - OP(1,17)*SK_MX(2) + OP(1,18)*SK_MX(5) - OP(1,19)*SK_MX(4)); +Kfusion(2) = SK_MX(1)*(OP(2,20) + OP(2,2)*SH_MAG(1) - OP(2,3)*SH_MAG(2) + OP(2,4)*SH_MAG(3) + OP(2,1)*SK_MX(3) - OP(2,17)*SK_MX(2) + OP(2,18)*SK_MX(5) - OP(2,19)*SK_MX(4)); +Kfusion(3) = SK_MX(1)*(OP(3,20) + OP(3,2)*SH_MAG(1) - OP(3,3)*SH_MAG(2) + OP(3,4)*SH_MAG(3) + OP(3,1)*SK_MX(3) - OP(3,17)*SK_MX(2) + OP(3,18)*SK_MX(5) - OP(3,19)*SK_MX(4)); +Kfusion(4) = SK_MX(1)*(OP(4,20) + OP(4,2)*SH_MAG(1) - OP(4,3)*SH_MAG(2) + OP(4,4)*SH_MAG(3) + OP(4,1)*SK_MX(3) - OP(4,17)*SK_MX(2) + OP(4,18)*SK_MX(5) - OP(4,19)*SK_MX(4)); +Kfusion(5) = SK_MX(1)*(OP(5,20) + OP(5,2)*SH_MAG(1) - OP(5,3)*SH_MAG(2) + OP(5,4)*SH_MAG(3) + OP(5,1)*SK_MX(3) - OP(5,17)*SK_MX(2) + OP(5,18)*SK_MX(5) - OP(5,19)*SK_MX(4)); +Kfusion(6) = SK_MX(1)*(OP(6,20) + OP(6,2)*SH_MAG(1) - OP(6,3)*SH_MAG(2) + OP(6,4)*SH_MAG(3) + OP(6,1)*SK_MX(3) - OP(6,17)*SK_MX(2) + OP(6,18)*SK_MX(5) - OP(6,19)*SK_MX(4)); +Kfusion(7) = SK_MX(1)*(OP(7,20) + OP(7,2)*SH_MAG(1) - OP(7,3)*SH_MAG(2) + OP(7,4)*SH_MAG(3) + OP(7,1)*SK_MX(3) - OP(7,17)*SK_MX(2) + OP(7,18)*SK_MX(5) - OP(7,19)*SK_MX(4)); +Kfusion(8) = SK_MX(1)*(OP(8,20) + OP(8,2)*SH_MAG(1) - OP(8,3)*SH_MAG(2) + OP(8,4)*SH_MAG(3) + OP(8,1)*SK_MX(3) - OP(8,17)*SK_MX(2) + OP(8,18)*SK_MX(5) - OP(8,19)*SK_MX(4)); +Kfusion(9) = SK_MX(1)*(OP(9,20) + OP(9,2)*SH_MAG(1) - OP(9,3)*SH_MAG(2) + OP(9,4)*SH_MAG(3) + OP(9,1)*SK_MX(3) - OP(9,17)*SK_MX(2) + OP(9,18)*SK_MX(5) - OP(9,19)*SK_MX(4)); +Kfusion(10) = SK_MX(1)*(OP(10,20) + OP(10,2)*SH_MAG(1) - OP(10,3)*SH_MAG(2) + OP(10,4)*SH_MAG(3) + OP(10,1)*SK_MX(3) - OP(10,17)*SK_MX(2) + OP(10,18)*SK_MX(5) - OP(10,19)*SK_MX(4)); +Kfusion(11) = SK_MX(1)*(OP(11,20) + OP(11,2)*SH_MAG(1) - OP(11,3)*SH_MAG(2) + OP(11,4)*SH_MAG(3) + OP(11,1)*SK_MX(3) - OP(11,17)*SK_MX(2) + OP(11,18)*SK_MX(5) - OP(11,19)*SK_MX(4)); +Kfusion(12) = SK_MX(1)*(OP(12,20) + OP(12,2)*SH_MAG(1) - OP(12,3)*SH_MAG(2) + OP(12,4)*SH_MAG(3) + OP(12,1)*SK_MX(3) - OP(12,17)*SK_MX(2) + OP(12,18)*SK_MX(5) - OP(12,19)*SK_MX(4)); +Kfusion(13) = SK_MX(1)*(OP(13,20) + OP(13,2)*SH_MAG(1) - OP(13,3)*SH_MAG(2) + OP(13,4)*SH_MAG(3) + OP(13,1)*SK_MX(3) - OP(13,17)*SK_MX(2) + OP(13,18)*SK_MX(5) - OP(13,19)*SK_MX(4)); +Kfusion(14) = SK_MX(1)*(OP(14,20) + OP(14,2)*SH_MAG(1) - OP(14,3)*SH_MAG(2) + OP(14,4)*SH_MAG(3) + OP(14,1)*SK_MX(3) - OP(14,17)*SK_MX(2) + OP(14,18)*SK_MX(5) - OP(14,19)*SK_MX(4)); +Kfusion(15) = SK_MX(1)*(OP(15,20) + OP(15,2)*SH_MAG(1) - OP(15,3)*SH_MAG(2) + OP(15,4)*SH_MAG(3) + OP(15,1)*SK_MX(3) - OP(15,17)*SK_MX(2) + OP(15,18)*SK_MX(5) - OP(15,19)*SK_MX(4)); +Kfusion(16) = SK_MX(1)*(OP(16,20) + OP(16,2)*SH_MAG(1) - OP(16,3)*SH_MAG(2) + OP(16,4)*SH_MAG(3) + OP(16,1)*SK_MX(3) - OP(16,17)*SK_MX(2) + OP(16,18)*SK_MX(5) - OP(16,19)*SK_MX(4)); +Kfusion(17) = SK_MX(1)*(OP(17,20) + OP(17,2)*SH_MAG(1) - OP(17,3)*SH_MAG(2) + OP(17,4)*SH_MAG(3) + OP(17,1)*SK_MX(3) - OP(17,17)*SK_MX(2) + OP(17,18)*SK_MX(5) - OP(17,19)*SK_MX(4)); +Kfusion(18) = SK_MX(1)*(OP(18,20) + OP(18,2)*SH_MAG(1) - OP(18,3)*SH_MAG(2) + OP(18,4)*SH_MAG(3) + OP(18,1)*SK_MX(3) - OP(18,17)*SK_MX(2) + OP(18,18)*SK_MX(5) - OP(18,19)*SK_MX(4)); +Kfusion(19) = SK_MX(1)*(OP(19,20) + OP(19,2)*SH_MAG(1) - OP(19,3)*SH_MAG(2) + OP(19,4)*SH_MAG(3) + OP(19,1)*SK_MX(3) - OP(19,17)*SK_MX(2) + OP(19,18)*SK_MX(5) - OP(19,19)*SK_MX(4)); +Kfusion(20) = SK_MX(1)*(OP(20,20) + OP(20,2)*SH_MAG(1) - OP(20,3)*SH_MAG(2) + OP(20,4)*SH_MAG(3) + OP(20,1)*SK_MX(3) - OP(20,17)*SK_MX(2) + OP(20,18)*SK_MX(5) - OP(20,19)*SK_MX(4)); +Kfusion(21) = SK_MX(1)*(OP(21,20) + OP(21,2)*SH_MAG(1) - OP(21,3)*SH_MAG(2) + OP(21,4)*SH_MAG(3) + OP(21,1)*SK_MX(3) - OP(21,17)*SK_MX(2) + OP(21,18)*SK_MX(5) - OP(21,19)*SK_MX(4)); +Kfusion(22) = SK_MX(1)*(OP(22,20) + OP(22,2)*SH_MAG(1) - OP(22,3)*SH_MAG(2) + OP(22,4)*SH_MAG(3) + OP(22,1)*SK_MX(3) - OP(22,17)*SK_MX(2) + OP(22,18)*SK_MX(5) - OP(22,19)*SK_MX(4)); +Kfusion(23) = SK_MX(1)*(OP(23,20) + OP(23,2)*SH_MAG(1) - OP(23,3)*SH_MAG(2) + OP(23,4)*SH_MAG(3) + OP(23,1)*SK_MX(3) - OP(23,17)*SK_MX(2) + OP(23,18)*SK_MX(5) - OP(23,19)*SK_MX(4)); +Kfusion(24) = SK_MX(1)*(OP(24,20) + OP(24,2)*SH_MAG(1) - OP(24,3)*SH_MAG(2) + OP(24,4)*SH_MAG(3) + OP(24,1)*SK_MX(3) - OP(24,17)*SK_MX(2) + OP(24,18)*SK_MX(5) - OP(24,19)*SK_MX(4)); H_MAG = zeros(1,24); -H_MAG(1) = magD*SH_MAG(3) - SH_MAG(7) + magN*SH_MAG(6); -H_MAG(3) = - magE*SH_MAG(5) - magD*SH_MAG(8) - magN*SH_MAG(2); -H_MAG(17) = 2*q1*q2 - SH_MAG(9); -H_MAG(18) = SH_MAG(1); -H_MAG(19) = SH_MAG(4); +H_MAG(1) = SH_MAG(3); +H_MAG(2) = SH_MAG(2); +H_MAG(3) = SH_MAG(1); +H_MAG(4) = 2*magD*q2 - SH_MAG(9) - SH_MAG(8); +H_MAG(17) = 2*q1*q2 - 2*q0*q3; +H_MAG(18) = SH_MAG(5) - SH_MAG(4) - SH_MAG(6) + SH_MAG(7); +H_MAG(19) = 2*q0*q1 + 2*q2*q3; H_MAG(21) = 1; -SK_MY = zeros(4,1); -SK_MY(1) = 1/(OP(21,21) + R_MAG + OP(1,21)*(magD*SH_MAG(3) - SH_MAG(7) + magN*SH_MAG(6)) + OP(18,21)*SH_MAG(1) + OP(19,21)*SH_MAG(4) - (SH_MAG(9) - 2*q1*q2)*(OP(21,17) + OP(1,17)*(magD*SH_MAG(3) - SH_MAG(7) + magN*SH_MAG(6)) + OP(18,17)*SH_MAG(1) + OP(19,17)*SH_MAG(4) - OP(3,17)*(magE*SH_MAG(5) + magD*SH_MAG(8) + magN*SH_MAG(2)) - OP(17,17)*(SH_MAG(9) - 2*q1*q2)) - OP(3,21)*(magE*SH_MAG(5) + magD*SH_MAG(8) + magN*SH_MAG(2)) + (magD*SH_MAG(3) - SH_MAG(7) + magN*SH_MAG(6))*(OP(21,1) + OP(1,1)*(magD*SH_MAG(3) - SH_MAG(7) + magN*SH_MAG(6)) + OP(18,1)*SH_MAG(1) + OP(19,1)*SH_MAG(4) - OP(3,1)*(magE*SH_MAG(5) + magD*SH_MAG(8) + magN*SH_MAG(2)) - OP(17,1)*(SH_MAG(9) - 2*q1*q2)) + SH_MAG(1)*(OP(21,18) + OP(1,18)*(magD*SH_MAG(3) - SH_MAG(7) + magN*SH_MAG(6)) + OP(18,18)*SH_MAG(1) + OP(19,18)*SH_MAG(4) - OP(3,18)*(magE*SH_MAG(5) + magD*SH_MAG(8) + magN*SH_MAG(2)) - OP(17,18)*(SH_MAG(9) - 2*q1*q2)) + SH_MAG(4)*(OP(21,19) + OP(1,19)*(magD*SH_MAG(3) - SH_MAG(7) + magN*SH_MAG(6)) + OP(18,19)*SH_MAG(1) + OP(19,19)*SH_MAG(4) - OP(3,19)*(magE*SH_MAG(5) + magD*SH_MAG(8) + magN*SH_MAG(2)) - OP(17,19)*(SH_MAG(9) - 2*q1*q2)) - OP(17,21)*(SH_MAG(9) - 2*q1*q2) - (magE*SH_MAG(5) + magD*SH_MAG(8) + magN*SH_MAG(2))*(OP(21,3) + OP(1,3)*(magD*SH_MAG(3) - SH_MAG(7) + magN*SH_MAG(6)) + OP(18,3)*SH_MAG(1) + OP(19,3)*SH_MAG(4) - OP(3,3)*(magE*SH_MAG(5) + magD*SH_MAG(8) + magN*SH_MAG(2)) - OP(17,3)*(SH_MAG(9) - 2*q1*q2))); -SK_MY(2) = magE*SH_MAG(5) + magD*SH_MAG(8) + magN*SH_MAG(2); -SK_MY(3) = magD*SH_MAG(3) - SH_MAG(7) + magN*SH_MAG(6); -SK_MY(4) = SH_MAG(9) - 2*q1*q2; +SK_MY = zeros(5,1); +SK_MY(1) = 1/(OP(21,21) + R_MAG + OP(1,21)*SH_MAG(3) + OP(2,21)*SH_MAG(2) + OP(3,21)*SH_MAG(1) - OP(18,21)*(SH_MAG(4) - SH_MAG(5) + SH_MAG(6) - SH_MAG(7)) - (2*q0*q3 - 2*q1*q2)*(OP(21,17) + OP(1,17)*SH_MAG(3) + OP(2,17)*SH_MAG(2) + OP(3,17)*SH_MAG(1) - OP(18,17)*(SH_MAG(4) - SH_MAG(5) + SH_MAG(6) - SH_MAG(7)) - OP(17,17)*(2*q0*q3 - 2*q1*q2) + OP(19,17)*(2*q0*q1 + 2*q2*q3) - OP(4,17)*(SH_MAG(8) + SH_MAG(9) - 2*magD*q2)) + (2*q0*q1 + 2*q2*q3)*(OP(21,19) + OP(1,19)*SH_MAG(3) + OP(2,19)*SH_MAG(2) + OP(3,19)*SH_MAG(1) - OP(18,19)*(SH_MAG(4) - SH_MAG(5) + SH_MAG(6) - SH_MAG(7)) - OP(17,19)*(2*q0*q3 - 2*q1*q2) + OP(19,19)*(2*q0*q1 + 2*q2*q3) - OP(4,19)*(SH_MAG(8) + SH_MAG(9) - 2*magD*q2)) - (SH_MAG(8) + SH_MAG(9) - 2*magD*q2)*(OP(21,4) + OP(1,4)*SH_MAG(3) + OP(2,4)*SH_MAG(2) + OP(3,4)*SH_MAG(1) - OP(18,4)*(SH_MAG(4) - SH_MAG(5) + SH_MAG(6) - SH_MAG(7)) - OP(17,4)*(2*q0*q3 - 2*q1*q2) + OP(19,4)*(2*q0*q1 + 2*q2*q3) - OP(4,4)*(SH_MAG(8) + SH_MAG(9) - 2*magD*q2)) - OP(17,21)*(2*q0*q3 - 2*q1*q2) + OP(19,21)*(2*q0*q1 + 2*q2*q3) + SH_MAG(3)*(OP(21,1) + OP(1,1)*SH_MAG(3) + OP(2,1)*SH_MAG(2) + OP(3,1)*SH_MAG(1) - OP(18,1)*(SH_MAG(4) - SH_MAG(5) + SH_MAG(6) - SH_MAG(7)) - OP(17,1)*(2*q0*q3 - 2*q1*q2) + OP(19,1)*(2*q0*q1 + 2*q2*q3) - OP(4,1)*(SH_MAG(8) + SH_MAG(9) - 2*magD*q2)) + SH_MAG(2)*(OP(21,2) + OP(1,2)*SH_MAG(3) + OP(2,2)*SH_MAG(2) + OP(3,2)*SH_MAG(1) - OP(18,2)*(SH_MAG(4) - SH_MAG(5) + SH_MAG(6) - SH_MAG(7)) - OP(17,2)*(2*q0*q3 - 2*q1*q2) + OP(19,2)*(2*q0*q1 + 2*q2*q3) - OP(4,2)*(SH_MAG(8) + SH_MAG(9) - 2*magD*q2)) + SH_MAG(1)*(OP(21,3) + OP(1,3)*SH_MAG(3) + OP(2,3)*SH_MAG(2) + OP(3,3)*SH_MAG(1) - OP(18,3)*(SH_MAG(4) - SH_MAG(5) + SH_MAG(6) - SH_MAG(7)) - OP(17,3)*(2*q0*q3 - 2*q1*q2) + OP(19,3)*(2*q0*q1 + 2*q2*q3) - OP(4,3)*(SH_MAG(8) + SH_MAG(9) - 2*magD*q2)) - (SH_MAG(4) - SH_MAG(5) + SH_MAG(6) - SH_MAG(7))*(OP(21,18) + OP(1,18)*SH_MAG(3) + OP(2,18)*SH_MAG(2) + OP(3,18)*SH_MAG(1) - OP(18,18)*(SH_MAG(4) - SH_MAG(5) + SH_MAG(6) - SH_MAG(7)) - OP(17,18)*(2*q0*q3 - 2*q1*q2) + OP(19,18)*(2*q0*q1 + 2*q2*q3) - OP(4,18)*(SH_MAG(8) + SH_MAG(9) - 2*magD*q2)) - OP(4,21)*(SH_MAG(8) + SH_MAG(9) - 2*magD*q2)); +SK_MY(2) = SH_MAG(4) - SH_MAG(5) + SH_MAG(6) - SH_MAG(7); +SK_MY(3) = SH_MAG(8) + SH_MAG(9) - 2*magD*q2; +SK_MY(4) = 2*q0*q3 - 2*q1*q2; +SK_MY(5) = 2*q0*q1 + 2*q2*q3; Kfusion = zeros(24,1); Kfusion = zeros(1,1); -Kfusion(1) = SK_MY(1)*(OP(1,21) + OP(1,18)*SH_MAG(1) + OP(1,19)*SH_MAG(4) + OP(1,1)*SK_MY(3) - OP(1,3)*SK_MY(2) - OP(1,17)*SK_MY(4)); -Kfusion(2) = SK_MY(1)*(OP(2,21) + OP(2,18)*SH_MAG(1) + OP(2,19)*SH_MAG(4) + OP(2,1)*SK_MY(3) - OP(2,3)*SK_MY(2) - OP(2,17)*SK_MY(4)); -Kfusion(3) = SK_MY(1)*(OP(3,21) + OP(3,18)*SH_MAG(1) + OP(3,19)*SH_MAG(4) + OP(3,1)*SK_MY(3) - OP(3,3)*SK_MY(2) - OP(3,17)*SK_MY(4)); -Kfusion(4) = SK_MY(1)*(OP(4,21) + OP(4,18)*SH_MAG(1) + OP(4,19)*SH_MAG(4) + OP(4,1)*SK_MY(3) - OP(4,3)*SK_MY(2) - OP(4,17)*SK_MY(4)); -Kfusion(5) = SK_MY(1)*(OP(5,21) + OP(5,18)*SH_MAG(1) + OP(5,19)*SH_MAG(4) + OP(5,1)*SK_MY(3) - OP(5,3)*SK_MY(2) - OP(5,17)*SK_MY(4)); -Kfusion(6) = SK_MY(1)*(OP(6,21) + OP(6,18)*SH_MAG(1) + OP(6,19)*SH_MAG(4) + OP(6,1)*SK_MY(3) - OP(6,3)*SK_MY(2) - OP(6,17)*SK_MY(4)); -Kfusion(7) = SK_MY(1)*(OP(7,21) + OP(7,18)*SH_MAG(1) + OP(7,19)*SH_MAG(4) + OP(7,1)*SK_MY(3) - OP(7,3)*SK_MY(2) - OP(7,17)*SK_MY(4)); -Kfusion(8) = SK_MY(1)*(OP(8,21) + OP(8,18)*SH_MAG(1) + OP(8,19)*SH_MAG(4) + OP(8,1)*SK_MY(3) - OP(8,3)*SK_MY(2) - OP(8,17)*SK_MY(4)); -Kfusion(9) = SK_MY(1)*(OP(9,21) + OP(9,18)*SH_MAG(1) + OP(9,19)*SH_MAG(4) + OP(9,1)*SK_MY(3) - OP(9,3)*SK_MY(2) - OP(9,17)*SK_MY(4)); -Kfusion(10) = SK_MY(1)*(OP(10,21) + OP(10,18)*SH_MAG(1) + OP(10,19)*SH_MAG(4) + OP(10,1)*SK_MY(3) - OP(10,3)*SK_MY(2) - OP(10,17)*SK_MY(4)); -Kfusion(11) = SK_MY(1)*(OP(11,21) + OP(11,18)*SH_MAG(1) + OP(11,19)*SH_MAG(4) + OP(11,1)*SK_MY(3) - OP(11,3)*SK_MY(2) - OP(11,17)*SK_MY(4)); -Kfusion(12) = SK_MY(1)*(OP(12,21) + OP(12,18)*SH_MAG(1) + OP(12,19)*SH_MAG(4) + OP(12,1)*SK_MY(3) - OP(12,3)*SK_MY(2) - OP(12,17)*SK_MY(4)); -Kfusion(13) = SK_MY(1)*(OP(13,21) + OP(13,18)*SH_MAG(1) + OP(13,19)*SH_MAG(4) + OP(13,1)*SK_MY(3) - OP(13,3)*SK_MY(2) - OP(13,17)*SK_MY(4)); -Kfusion(14) = SK_MY(1)*(OP(14,21) + OP(14,18)*SH_MAG(1) + OP(14,19)*SH_MAG(4) + OP(14,1)*SK_MY(3) - OP(14,3)*SK_MY(2) - OP(14,17)*SK_MY(4)); -Kfusion(15) = SK_MY(1)*(OP(15,21) + OP(15,18)*SH_MAG(1) + OP(15,19)*SH_MAG(4) + OP(15,1)*SK_MY(3) - OP(15,3)*SK_MY(2) - OP(15,17)*SK_MY(4)); -Kfusion(16) = SK_MY(1)*(OP(16,21) + OP(16,18)*SH_MAG(1) + OP(16,19)*SH_MAG(4) + OP(16,1)*SK_MY(3) - OP(16,3)*SK_MY(2) - OP(16,17)*SK_MY(4)); -Kfusion(17) = SK_MY(1)*(OP(17,21) + OP(17,18)*SH_MAG(1) + OP(17,19)*SH_MAG(4) + OP(17,1)*SK_MY(3) - OP(17,3)*SK_MY(2) - OP(17,17)*SK_MY(4)); -Kfusion(18) = SK_MY(1)*(OP(18,21) + OP(18,18)*SH_MAG(1) + OP(18,19)*SH_MAG(4) + OP(18,1)*SK_MY(3) - OP(18,3)*SK_MY(2) - OP(18,17)*SK_MY(4)); -Kfusion(19) = SK_MY(1)*(OP(19,21) + OP(19,18)*SH_MAG(1) + OP(19,19)*SH_MAG(4) + OP(19,1)*SK_MY(3) - OP(19,3)*SK_MY(2) - OP(19,17)*SK_MY(4)); -Kfusion(20) = SK_MY(1)*(OP(20,21) + OP(20,18)*SH_MAG(1) + OP(20,19)*SH_MAG(4) + OP(20,1)*SK_MY(3) - OP(20,3)*SK_MY(2) - OP(20,17)*SK_MY(4)); -Kfusion(21) = SK_MY(1)*(OP(21,21) + OP(21,18)*SH_MAG(1) + OP(21,19)*SH_MAG(4) + OP(21,1)*SK_MY(3) - OP(21,3)*SK_MY(2) - OP(21,17)*SK_MY(4)); -Kfusion(22) = SK_MY(1)*(OP(22,21) + OP(22,18)*SH_MAG(1) + OP(22,19)*SH_MAG(4) + OP(22,1)*SK_MY(3) - OP(22,3)*SK_MY(2) - OP(22,17)*SK_MY(4)); -Kfusion(23) = SK_MY(1)*(OP(23,21) + OP(23,18)*SH_MAG(1) + OP(23,19)*SH_MAG(4) + OP(23,1)*SK_MY(3) - OP(23,3)*SK_MY(2) - OP(23,17)*SK_MY(4)); -Kfusion(24) = SK_MY(1)*(OP(24,21) + OP(24,18)*SH_MAG(1) + OP(24,19)*SH_MAG(4) + OP(24,1)*SK_MY(3) - OP(24,3)*SK_MY(2) - OP(24,17)*SK_MY(4)); +Kfusion(1) = SK_MY(1)*(OP(1,21) + OP(1,1)*SH_MAG(3) + OP(1,2)*SH_MAG(2) + OP(1,3)*SH_MAG(1) - OP(1,4)*SK_MY(3) - OP(1,18)*SK_MY(2) - OP(1,17)*SK_MY(4) + OP(1,19)*SK_MY(5)); +Kfusion(2) = SK_MY(1)*(OP(2,21) + OP(2,1)*SH_MAG(3) + OP(2,2)*SH_MAG(2) + OP(2,3)*SH_MAG(1) - OP(2,4)*SK_MY(3) - OP(2,18)*SK_MY(2) - OP(2,17)*SK_MY(4) + OP(2,19)*SK_MY(5)); +Kfusion(3) = SK_MY(1)*(OP(3,21) + OP(3,1)*SH_MAG(3) + OP(3,2)*SH_MAG(2) + OP(3,3)*SH_MAG(1) - OP(3,4)*SK_MY(3) - OP(3,18)*SK_MY(2) - OP(3,17)*SK_MY(4) + OP(3,19)*SK_MY(5)); +Kfusion(4) = SK_MY(1)*(OP(4,21) + OP(4,1)*SH_MAG(3) + OP(4,2)*SH_MAG(2) + OP(4,3)*SH_MAG(1) - OP(4,4)*SK_MY(3) - OP(4,18)*SK_MY(2) - OP(4,17)*SK_MY(4) + OP(4,19)*SK_MY(5)); +Kfusion(5) = SK_MY(1)*(OP(5,21) + OP(5,1)*SH_MAG(3) + OP(5,2)*SH_MAG(2) + OP(5,3)*SH_MAG(1) - OP(5,4)*SK_MY(3) - OP(5,18)*SK_MY(2) - OP(5,17)*SK_MY(4) + OP(5,19)*SK_MY(5)); +Kfusion(6) = SK_MY(1)*(OP(6,21) + OP(6,1)*SH_MAG(3) + OP(6,2)*SH_MAG(2) + OP(6,3)*SH_MAG(1) - OP(6,4)*SK_MY(3) - OP(6,18)*SK_MY(2) - OP(6,17)*SK_MY(4) + OP(6,19)*SK_MY(5)); +Kfusion(7) = SK_MY(1)*(OP(7,21) + OP(7,1)*SH_MAG(3) + OP(7,2)*SH_MAG(2) + OP(7,3)*SH_MAG(1) - OP(7,4)*SK_MY(3) - OP(7,18)*SK_MY(2) - OP(7,17)*SK_MY(4) + OP(7,19)*SK_MY(5)); +Kfusion(8) = SK_MY(1)*(OP(8,21) + OP(8,1)*SH_MAG(3) + OP(8,2)*SH_MAG(2) + OP(8,3)*SH_MAG(1) - OP(8,4)*SK_MY(3) - OP(8,18)*SK_MY(2) - OP(8,17)*SK_MY(4) + OP(8,19)*SK_MY(5)); +Kfusion(9) = SK_MY(1)*(OP(9,21) + OP(9,1)*SH_MAG(3) + OP(9,2)*SH_MAG(2) + OP(9,3)*SH_MAG(1) - OP(9,4)*SK_MY(3) - OP(9,18)*SK_MY(2) - OP(9,17)*SK_MY(4) + OP(9,19)*SK_MY(5)); +Kfusion(10) = SK_MY(1)*(OP(10,21) + OP(10,1)*SH_MAG(3) + OP(10,2)*SH_MAG(2) + OP(10,3)*SH_MAG(1) - OP(10,4)*SK_MY(3) - OP(10,18)*SK_MY(2) - OP(10,17)*SK_MY(4) + OP(10,19)*SK_MY(5)); +Kfusion(11) = SK_MY(1)*(OP(11,21) + OP(11,1)*SH_MAG(3) + OP(11,2)*SH_MAG(2) + OP(11,3)*SH_MAG(1) - OP(11,4)*SK_MY(3) - OP(11,18)*SK_MY(2) - OP(11,17)*SK_MY(4) + OP(11,19)*SK_MY(5)); +Kfusion(12) = SK_MY(1)*(OP(12,21) + OP(12,1)*SH_MAG(3) + OP(12,2)*SH_MAG(2) + OP(12,3)*SH_MAG(1) - OP(12,4)*SK_MY(3) - OP(12,18)*SK_MY(2) - OP(12,17)*SK_MY(4) + OP(12,19)*SK_MY(5)); +Kfusion(13) = SK_MY(1)*(OP(13,21) + OP(13,1)*SH_MAG(3) + OP(13,2)*SH_MAG(2) + OP(13,3)*SH_MAG(1) - OP(13,4)*SK_MY(3) - OP(13,18)*SK_MY(2) - OP(13,17)*SK_MY(4) + OP(13,19)*SK_MY(5)); +Kfusion(14) = SK_MY(1)*(OP(14,21) + OP(14,1)*SH_MAG(3) + OP(14,2)*SH_MAG(2) + OP(14,3)*SH_MAG(1) - OP(14,4)*SK_MY(3) - OP(14,18)*SK_MY(2) - OP(14,17)*SK_MY(4) + OP(14,19)*SK_MY(5)); +Kfusion(15) = SK_MY(1)*(OP(15,21) + OP(15,1)*SH_MAG(3) + OP(15,2)*SH_MAG(2) + OP(15,3)*SH_MAG(1) - OP(15,4)*SK_MY(3) - OP(15,18)*SK_MY(2) - OP(15,17)*SK_MY(4) + OP(15,19)*SK_MY(5)); +Kfusion(16) = SK_MY(1)*(OP(16,21) + OP(16,1)*SH_MAG(3) + OP(16,2)*SH_MAG(2) + OP(16,3)*SH_MAG(1) - OP(16,4)*SK_MY(3) - OP(16,18)*SK_MY(2) - OP(16,17)*SK_MY(4) + OP(16,19)*SK_MY(5)); +Kfusion(17) = SK_MY(1)*(OP(17,21) + OP(17,1)*SH_MAG(3) + OP(17,2)*SH_MAG(2) + OP(17,3)*SH_MAG(1) - OP(17,4)*SK_MY(3) - OP(17,18)*SK_MY(2) - OP(17,17)*SK_MY(4) + OP(17,19)*SK_MY(5)); +Kfusion(18) = SK_MY(1)*(OP(18,21) + OP(18,1)*SH_MAG(3) + OP(18,2)*SH_MAG(2) + OP(18,3)*SH_MAG(1) - OP(18,4)*SK_MY(3) - OP(18,18)*SK_MY(2) - OP(18,17)*SK_MY(4) + OP(18,19)*SK_MY(5)); +Kfusion(19) = SK_MY(1)*(OP(19,21) + OP(19,1)*SH_MAG(3) + OP(19,2)*SH_MAG(2) + OP(19,3)*SH_MAG(1) - OP(19,4)*SK_MY(3) - OP(19,18)*SK_MY(2) - OP(19,17)*SK_MY(4) + OP(19,19)*SK_MY(5)); +Kfusion(20) = SK_MY(1)*(OP(20,21) + OP(20,1)*SH_MAG(3) + OP(20,2)*SH_MAG(2) + OP(20,3)*SH_MAG(1) - OP(20,4)*SK_MY(3) - OP(20,18)*SK_MY(2) - OP(20,17)*SK_MY(4) + OP(20,19)*SK_MY(5)); +Kfusion(21) = SK_MY(1)*(OP(21,21) + OP(21,1)*SH_MAG(3) + OP(21,2)*SH_MAG(2) + OP(21,3)*SH_MAG(1) - OP(21,4)*SK_MY(3) - OP(21,18)*SK_MY(2) - OP(21,17)*SK_MY(4) + OP(21,19)*SK_MY(5)); +Kfusion(22) = SK_MY(1)*(OP(22,21) + OP(22,1)*SH_MAG(3) + OP(22,2)*SH_MAG(2) + OP(22,3)*SH_MAG(1) - OP(22,4)*SK_MY(3) - OP(22,18)*SK_MY(2) - OP(22,17)*SK_MY(4) + OP(22,19)*SK_MY(5)); +Kfusion(23) = SK_MY(1)*(OP(23,21) + OP(23,1)*SH_MAG(3) + OP(23,2)*SH_MAG(2) + OP(23,3)*SH_MAG(1) - OP(23,4)*SK_MY(3) - OP(23,18)*SK_MY(2) - OP(23,17)*SK_MY(4) + OP(23,19)*SK_MY(5)); +Kfusion(24) = SK_MY(1)*(OP(24,21) + OP(24,1)*SH_MAG(3) + OP(24,2)*SH_MAG(2) + OP(24,3)*SH_MAG(1) - OP(24,4)*SK_MY(3) - OP(24,18)*SK_MY(2) - OP(24,17)*SK_MY(4) + OP(24,19)*SK_MY(5)); H_MAG = zeros(1,24); -H_MAG(1) = magN*(SH_MAG(9) - 2*q1*q2) - magD*SH_MAG(4) - magE*SH_MAG(1); -H_MAG(2) = magE*SH_MAG(5) + magD*SH_MAG(8) + magN*SH_MAG(2); -H_MAG(17) = SH_MAG(6); +H_MAG(1) = SH_MAG(2); +H_MAG(2) = -SH_MAG(3); +H_MAG(3) = SH_MAG(8) + SH_MAG(9) - 2*magD*q2; +H_MAG(4) = SH_MAG(1); +H_MAG(17) = 2*q0*q2 + 2*q1*q3; H_MAG(18) = 2*q2*q3 - 2*q0*q1; -H_MAG(19) = SH_MAG(3); +H_MAG(19) = SH_MAG(4) - SH_MAG(5) - SH_MAG(6) + SH_MAG(7); H_MAG(22) = 1; -SK_MZ = zeros(4,1); -SK_MZ(1) = 1/(OP(22,22) + R_MAG + OP(17,22)*SH_MAG(6) + OP(19,22)*SH_MAG(3) - (2*q0*q1 - 2*q2*q3)*(OP(22,18) + OP(17,18)*SH_MAG(6) + OP(19,18)*SH_MAG(3) - OP(1,18)*(magE*SH_MAG(1) + magD*SH_MAG(4) - magN*(SH_MAG(9) - 2*q1*q2)) + OP(2,18)*(magE*SH_MAG(5) + magD*SH_MAG(8) + magN*SH_MAG(2)) - OP(18,18)*(2*q0*q1 - 2*q2*q3)) - OP(1,22)*(magE*SH_MAG(1) + magD*SH_MAG(4) - magN*(SH_MAG(9) - 2*q1*q2)) + OP(2,22)*(magE*SH_MAG(5) + magD*SH_MAG(8) + magN*SH_MAG(2)) + SH_MAG(6)*(OP(22,17) + OP(17,17)*SH_MAG(6) + OP(19,17)*SH_MAG(3) - OP(1,17)*(magE*SH_MAG(1) + magD*SH_MAG(4) - magN*(SH_MAG(9) - 2*q1*q2)) + OP(2,17)*(magE*SH_MAG(5) + magD*SH_MAG(8) + magN*SH_MAG(2)) - OP(18,17)*(2*q0*q1 - 2*q2*q3)) + SH_MAG(3)*(OP(22,19) + OP(17,19)*SH_MAG(6) + OP(19,19)*SH_MAG(3) - OP(1,19)*(magE*SH_MAG(1) + magD*SH_MAG(4) - magN*(SH_MAG(9) - 2*q1*q2)) + OP(2,19)*(magE*SH_MAG(5) + magD*SH_MAG(8) + magN*SH_MAG(2)) - OP(18,19)*(2*q0*q1 - 2*q2*q3)) - (magE*SH_MAG(1) + magD*SH_MAG(4) - magN*(SH_MAG(9) - 2*q1*q2))*(OP(22,1) + OP(17,1)*SH_MAG(6) + OP(19,1)*SH_MAG(3) - OP(1,1)*(magE*SH_MAG(1) + magD*SH_MAG(4) - magN*(SH_MAG(9) - 2*q1*q2)) + OP(2,1)*(magE*SH_MAG(5) + magD*SH_MAG(8) + magN*SH_MAG(2)) - OP(18,1)*(2*q0*q1 - 2*q2*q3)) - OP(18,22)*(2*q0*q1 - 2*q2*q3) + (magE*SH_MAG(5) + magD*SH_MAG(8) + magN*SH_MAG(2))*(OP(22,2) + OP(17,2)*SH_MAG(6) + OP(19,2)*SH_MAG(3) - OP(1,2)*(magE*SH_MAG(1) + magD*SH_MAG(4) - magN*(SH_MAG(9) - 2*q1*q2)) + OP(2,2)*(magE*SH_MAG(5) + magD*SH_MAG(8) + magN*SH_MAG(2)) - OP(18,2)*(2*q0*q1 - 2*q2*q3))); -SK_MZ(2) = magE*SH_MAG(1) + magD*SH_MAG(4) - magN*(SH_MAG(9) - 2*q1*q2); -SK_MZ(3) = magE*SH_MAG(5) + magD*SH_MAG(8) + magN*SH_MAG(2); +SK_MZ = zeros(5,1); +SK_MZ(1) = 1/(OP(22,22) + R_MAG + OP(1,22)*SH_MAG(2) - OP(2,22)*SH_MAG(3) + OP(4,22)*SH_MAG(1) + OP(19,22)*(SH_MAG(4) - SH_MAG(5) - SH_MAG(6) + SH_MAG(7)) + (2*q0*q2 + 2*q1*q3)*(OP(22,17) + OP(1,17)*SH_MAG(2) - OP(2,17)*SH_MAG(3) + OP(4,17)*SH_MAG(1) + OP(19,17)*(SH_MAG(4) - SH_MAG(5) - SH_MAG(6) + SH_MAG(7)) + OP(17,17)*(2*q0*q2 + 2*q1*q3) - OP(18,17)*(2*q0*q1 - 2*q2*q3) + OP(3,17)*(SH_MAG(8) + SH_MAG(9) - 2*magD*q2)) - (2*q0*q1 - 2*q2*q3)*(OP(22,18) + OP(1,18)*SH_MAG(2) - OP(2,18)*SH_MAG(3) + OP(4,18)*SH_MAG(1) + OP(19,18)*(SH_MAG(4) - SH_MAG(5) - SH_MAG(6) + SH_MAG(7)) + OP(17,18)*(2*q0*q2 + 2*q1*q3) - OP(18,18)*(2*q0*q1 - 2*q2*q3) + OP(3,18)*(SH_MAG(8) + SH_MAG(9) - 2*magD*q2)) + (SH_MAG(8) + SH_MAG(9) - 2*magD*q2)*(OP(22,3) + OP(1,3)*SH_MAG(2) - OP(2,3)*SH_MAG(3) + OP(4,3)*SH_MAG(1) + OP(19,3)*(SH_MAG(4) - SH_MAG(5) - SH_MAG(6) + SH_MAG(7)) + OP(17,3)*(2*q0*q2 + 2*q1*q3) - OP(18,3)*(2*q0*q1 - 2*q2*q3) + OP(3,3)*(SH_MAG(8) + SH_MAG(9) - 2*magD*q2)) + OP(17,22)*(2*q0*q2 + 2*q1*q3) - OP(18,22)*(2*q0*q1 - 2*q2*q3) + SH_MAG(2)*(OP(22,1) + OP(1,1)*SH_MAG(2) - OP(2,1)*SH_MAG(3) + OP(4,1)*SH_MAG(1) + OP(19,1)*(SH_MAG(4) - SH_MAG(5) - SH_MAG(6) + SH_MAG(7)) + OP(17,1)*(2*q0*q2 + 2*q1*q3) - OP(18,1)*(2*q0*q1 - 2*q2*q3) + OP(3,1)*(SH_MAG(8) + SH_MAG(9) - 2*magD*q2)) - SH_MAG(3)*(OP(22,2) + OP(1,2)*SH_MAG(2) - OP(2,2)*SH_MAG(3) + OP(4,2)*SH_MAG(1) + OP(19,2)*(SH_MAG(4) - SH_MAG(5) - SH_MAG(6) + SH_MAG(7)) + OP(17,2)*(2*q0*q2 + 2*q1*q3) - OP(18,2)*(2*q0*q1 - 2*q2*q3) + OP(3,2)*(SH_MAG(8) + SH_MAG(9) - 2*magD*q2)) + SH_MAG(1)*(OP(22,4) + OP(1,4)*SH_MAG(2) - OP(2,4)*SH_MAG(3) + OP(4,4)*SH_MAG(1) + OP(19,4)*(SH_MAG(4) - SH_MAG(5) - SH_MAG(6) + SH_MAG(7)) + OP(17,4)*(2*q0*q2 + 2*q1*q3) - OP(18,4)*(2*q0*q1 - 2*q2*q3) + OP(3,4)*(SH_MAG(8) + SH_MAG(9) - 2*magD*q2)) + (SH_MAG(4) - SH_MAG(5) - SH_MAG(6) + SH_MAG(7))*(OP(22,19) + OP(1,19)*SH_MAG(2) - OP(2,19)*SH_MAG(3) + OP(4,19)*SH_MAG(1) + OP(19,19)*(SH_MAG(4) - SH_MAG(5) - SH_MAG(6) + SH_MAG(7)) + OP(17,19)*(2*q0*q2 + 2*q1*q3) - OP(18,19)*(2*q0*q1 - 2*q2*q3) + OP(3,19)*(SH_MAG(8) + SH_MAG(9) - 2*magD*q2)) + OP(3,22)*(SH_MAG(8) + SH_MAG(9) - 2*magD*q2)); +SK_MZ(2) = SH_MAG(4) - SH_MAG(5) - SH_MAG(6) + SH_MAG(7); +SK_MZ(3) = SH_MAG(8) + SH_MAG(9) - 2*magD*q2; SK_MZ(4) = 2*q0*q1 - 2*q2*q3; +SK_MZ(5) = 2*q0*q2 + 2*q1*q3; Kfusion = zeros(24,1); Kfusion = zeros(1,1); -Kfusion(1) = SK_MZ(1)*(OP(1,22) + OP(1,19)*SH_MAG(3) + OP(1,17)*SH_MAG(6) - OP(1,1)*SK_MZ(2) + OP(1,2)*SK_MZ(3) - OP(1,18)*SK_MZ(4)); -Kfusion(2) = SK_MZ(1)*(OP(2,22) + OP(2,19)*SH_MAG(3) + OP(2,17)*SH_MAG(6) - OP(2,1)*SK_MZ(2) + OP(2,2)*SK_MZ(3) - OP(2,18)*SK_MZ(4)); -Kfusion(3) = SK_MZ(1)*(OP(3,22) + OP(3,19)*SH_MAG(3) + OP(3,17)*SH_MAG(6) - OP(3,1)*SK_MZ(2) + OP(3,2)*SK_MZ(3) - OP(3,18)*SK_MZ(4)); -Kfusion(4) = SK_MZ(1)*(OP(4,22) + OP(4,19)*SH_MAG(3) + OP(4,17)*SH_MAG(6) - OP(4,1)*SK_MZ(2) + OP(4,2)*SK_MZ(3) - OP(4,18)*SK_MZ(4)); -Kfusion(5) = SK_MZ(1)*(OP(5,22) + OP(5,19)*SH_MAG(3) + OP(5,17)*SH_MAG(6) - OP(5,1)*SK_MZ(2) + OP(5,2)*SK_MZ(3) - OP(5,18)*SK_MZ(4)); -Kfusion(6) = SK_MZ(1)*(OP(6,22) + OP(6,19)*SH_MAG(3) + OP(6,17)*SH_MAG(6) - OP(6,1)*SK_MZ(2) + OP(6,2)*SK_MZ(3) - OP(6,18)*SK_MZ(4)); -Kfusion(7) = SK_MZ(1)*(OP(7,22) + OP(7,19)*SH_MAG(3) + OP(7,17)*SH_MAG(6) - OP(7,1)*SK_MZ(2) + OP(7,2)*SK_MZ(3) - OP(7,18)*SK_MZ(4)); -Kfusion(8) = SK_MZ(1)*(OP(8,22) + OP(8,19)*SH_MAG(3) + OP(8,17)*SH_MAG(6) - OP(8,1)*SK_MZ(2) + OP(8,2)*SK_MZ(3) - OP(8,18)*SK_MZ(4)); -Kfusion(9) = SK_MZ(1)*(OP(9,22) + OP(9,19)*SH_MAG(3) + OP(9,17)*SH_MAG(6) - OP(9,1)*SK_MZ(2) + OP(9,2)*SK_MZ(3) - OP(9,18)*SK_MZ(4)); -Kfusion(10) = SK_MZ(1)*(OP(10,22) + OP(10,19)*SH_MAG(3) + OP(10,17)*SH_MAG(6) - OP(10,1)*SK_MZ(2) + OP(10,2)*SK_MZ(3) - OP(10,18)*SK_MZ(4)); -Kfusion(11) = SK_MZ(1)*(OP(11,22) + OP(11,19)*SH_MAG(3) + OP(11,17)*SH_MAG(6) - OP(11,1)*SK_MZ(2) + OP(11,2)*SK_MZ(3) - OP(11,18)*SK_MZ(4)); -Kfusion(12) = SK_MZ(1)*(OP(12,22) + OP(12,19)*SH_MAG(3) + OP(12,17)*SH_MAG(6) - OP(12,1)*SK_MZ(2) + OP(12,2)*SK_MZ(3) - OP(12,18)*SK_MZ(4)); -Kfusion(13) = SK_MZ(1)*(OP(13,22) + OP(13,19)*SH_MAG(3) + OP(13,17)*SH_MAG(6) - OP(13,1)*SK_MZ(2) + OP(13,2)*SK_MZ(3) - OP(13,18)*SK_MZ(4)); -Kfusion(14) = SK_MZ(1)*(OP(14,22) + OP(14,19)*SH_MAG(3) + OP(14,17)*SH_MAG(6) - OP(14,1)*SK_MZ(2) + OP(14,2)*SK_MZ(3) - OP(14,18)*SK_MZ(4)); -Kfusion(15) = SK_MZ(1)*(OP(15,22) + OP(15,19)*SH_MAG(3) + OP(15,17)*SH_MAG(6) - OP(15,1)*SK_MZ(2) + OP(15,2)*SK_MZ(3) - OP(15,18)*SK_MZ(4)); -Kfusion(16) = SK_MZ(1)*(OP(16,22) + OP(16,19)*SH_MAG(3) + OP(16,17)*SH_MAG(6) - OP(16,1)*SK_MZ(2) + OP(16,2)*SK_MZ(3) - OP(16,18)*SK_MZ(4)); -Kfusion(17) = SK_MZ(1)*(OP(17,22) + OP(17,19)*SH_MAG(3) + OP(17,17)*SH_MAG(6) - OP(17,1)*SK_MZ(2) + OP(17,2)*SK_MZ(3) - OP(17,18)*SK_MZ(4)); -Kfusion(18) = SK_MZ(1)*(OP(18,22) + OP(18,19)*SH_MAG(3) + OP(18,17)*SH_MAG(6) - OP(18,1)*SK_MZ(2) + OP(18,2)*SK_MZ(3) - OP(18,18)*SK_MZ(4)); -Kfusion(19) = SK_MZ(1)*(OP(19,22) + OP(19,19)*SH_MAG(3) + OP(19,17)*SH_MAG(6) - OP(19,1)*SK_MZ(2) + OP(19,2)*SK_MZ(3) - OP(19,18)*SK_MZ(4)); -Kfusion(20) = SK_MZ(1)*(OP(20,22) + OP(20,19)*SH_MAG(3) + OP(20,17)*SH_MAG(6) - OP(20,1)*SK_MZ(2) + OP(20,2)*SK_MZ(3) - OP(20,18)*SK_MZ(4)); -Kfusion(21) = SK_MZ(1)*(OP(21,22) + OP(21,19)*SH_MAG(3) + OP(21,17)*SH_MAG(6) - OP(21,1)*SK_MZ(2) + OP(21,2)*SK_MZ(3) - OP(21,18)*SK_MZ(4)); -Kfusion(22) = SK_MZ(1)*(OP(22,22) + OP(22,19)*SH_MAG(3) + OP(22,17)*SH_MAG(6) - OP(22,1)*SK_MZ(2) + OP(22,2)*SK_MZ(3) - OP(22,18)*SK_MZ(4)); -Kfusion(23) = SK_MZ(1)*(OP(23,22) + OP(23,19)*SH_MAG(3) + OP(23,17)*SH_MAG(6) - OP(23,1)*SK_MZ(2) + OP(23,2)*SK_MZ(3) - OP(23,18)*SK_MZ(4)); -Kfusion(24) = SK_MZ(1)*(OP(24,22) + OP(24,19)*SH_MAG(3) + OP(24,17)*SH_MAG(6) - OP(24,1)*SK_MZ(2) + OP(24,2)*SK_MZ(3) - OP(24,18)*SK_MZ(4)); -SH_ACCX = zeros(7,1); +Kfusion(1) = SK_MZ(1)*(OP(1,22) + OP(1,1)*SH_MAG(2) - OP(1,2)*SH_MAG(3) + OP(1,4)*SH_MAG(1) + OP(1,3)*SK_MZ(3) + OP(1,19)*SK_MZ(2) + OP(1,17)*SK_MZ(5) - OP(1,18)*SK_MZ(4)); +Kfusion(2) = SK_MZ(1)*(OP(2,22) + OP(2,1)*SH_MAG(2) - OP(2,2)*SH_MAG(3) + OP(2,4)*SH_MAG(1) + OP(2,3)*SK_MZ(3) + OP(2,19)*SK_MZ(2) + OP(2,17)*SK_MZ(5) - OP(2,18)*SK_MZ(4)); +Kfusion(3) = SK_MZ(1)*(OP(3,22) + OP(3,1)*SH_MAG(2) - OP(3,2)*SH_MAG(3) + OP(3,4)*SH_MAG(1) + OP(3,3)*SK_MZ(3) + OP(3,19)*SK_MZ(2) + OP(3,17)*SK_MZ(5) - OP(3,18)*SK_MZ(4)); +Kfusion(4) = SK_MZ(1)*(OP(4,22) + OP(4,1)*SH_MAG(2) - OP(4,2)*SH_MAG(3) + OP(4,4)*SH_MAG(1) + OP(4,3)*SK_MZ(3) + OP(4,19)*SK_MZ(2) + OP(4,17)*SK_MZ(5) - OP(4,18)*SK_MZ(4)); +Kfusion(5) = SK_MZ(1)*(OP(5,22) + OP(5,1)*SH_MAG(2) - OP(5,2)*SH_MAG(3) + OP(5,4)*SH_MAG(1) + OP(5,3)*SK_MZ(3) + OP(5,19)*SK_MZ(2) + OP(5,17)*SK_MZ(5) - OP(5,18)*SK_MZ(4)); +Kfusion(6) = SK_MZ(1)*(OP(6,22) + OP(6,1)*SH_MAG(2) - OP(6,2)*SH_MAG(3) + OP(6,4)*SH_MAG(1) + OP(6,3)*SK_MZ(3) + OP(6,19)*SK_MZ(2) + OP(6,17)*SK_MZ(5) - OP(6,18)*SK_MZ(4)); +Kfusion(7) = SK_MZ(1)*(OP(7,22) + OP(7,1)*SH_MAG(2) - OP(7,2)*SH_MAG(3) + OP(7,4)*SH_MAG(1) + OP(7,3)*SK_MZ(3) + OP(7,19)*SK_MZ(2) + OP(7,17)*SK_MZ(5) - OP(7,18)*SK_MZ(4)); +Kfusion(8) = SK_MZ(1)*(OP(8,22) + OP(8,1)*SH_MAG(2) - OP(8,2)*SH_MAG(3) + OP(8,4)*SH_MAG(1) + OP(8,3)*SK_MZ(3) + OP(8,19)*SK_MZ(2) + OP(8,17)*SK_MZ(5) - OP(8,18)*SK_MZ(4)); +Kfusion(9) = SK_MZ(1)*(OP(9,22) + OP(9,1)*SH_MAG(2) - OP(9,2)*SH_MAG(3) + OP(9,4)*SH_MAG(1) + OP(9,3)*SK_MZ(3) + OP(9,19)*SK_MZ(2) + OP(9,17)*SK_MZ(5) - OP(9,18)*SK_MZ(4)); +Kfusion(10) = SK_MZ(1)*(OP(10,22) + OP(10,1)*SH_MAG(2) - OP(10,2)*SH_MAG(3) + OP(10,4)*SH_MAG(1) + OP(10,3)*SK_MZ(3) + OP(10,19)*SK_MZ(2) + OP(10,17)*SK_MZ(5) - OP(10,18)*SK_MZ(4)); +Kfusion(11) = SK_MZ(1)*(OP(11,22) + OP(11,1)*SH_MAG(2) - OP(11,2)*SH_MAG(3) + OP(11,4)*SH_MAG(1) + OP(11,3)*SK_MZ(3) + OP(11,19)*SK_MZ(2) + OP(11,17)*SK_MZ(5) - OP(11,18)*SK_MZ(4)); +Kfusion(12) = SK_MZ(1)*(OP(12,22) + OP(12,1)*SH_MAG(2) - OP(12,2)*SH_MAG(3) + OP(12,4)*SH_MAG(1) + OP(12,3)*SK_MZ(3) + OP(12,19)*SK_MZ(2) + OP(12,17)*SK_MZ(5) - OP(12,18)*SK_MZ(4)); +Kfusion(13) = SK_MZ(1)*(OP(13,22) + OP(13,1)*SH_MAG(2) - OP(13,2)*SH_MAG(3) + OP(13,4)*SH_MAG(1) + OP(13,3)*SK_MZ(3) + OP(13,19)*SK_MZ(2) + OP(13,17)*SK_MZ(5) - OP(13,18)*SK_MZ(4)); +Kfusion(14) = SK_MZ(1)*(OP(14,22) + OP(14,1)*SH_MAG(2) - OP(14,2)*SH_MAG(3) + OP(14,4)*SH_MAG(1) + OP(14,3)*SK_MZ(3) + OP(14,19)*SK_MZ(2) + OP(14,17)*SK_MZ(5) - OP(14,18)*SK_MZ(4)); +Kfusion(15) = SK_MZ(1)*(OP(15,22) + OP(15,1)*SH_MAG(2) - OP(15,2)*SH_MAG(3) + OP(15,4)*SH_MAG(1) + OP(15,3)*SK_MZ(3) + OP(15,19)*SK_MZ(2) + OP(15,17)*SK_MZ(5) - OP(15,18)*SK_MZ(4)); +Kfusion(16) = SK_MZ(1)*(OP(16,22) + OP(16,1)*SH_MAG(2) - OP(16,2)*SH_MAG(3) + OP(16,4)*SH_MAG(1) + OP(16,3)*SK_MZ(3) + OP(16,19)*SK_MZ(2) + OP(16,17)*SK_MZ(5) - OP(16,18)*SK_MZ(4)); +Kfusion(17) = SK_MZ(1)*(OP(17,22) + OP(17,1)*SH_MAG(2) - OP(17,2)*SH_MAG(3) + OP(17,4)*SH_MAG(1) + OP(17,3)*SK_MZ(3) + OP(17,19)*SK_MZ(2) + OP(17,17)*SK_MZ(5) - OP(17,18)*SK_MZ(4)); +Kfusion(18) = SK_MZ(1)*(OP(18,22) + OP(18,1)*SH_MAG(2) - OP(18,2)*SH_MAG(3) + OP(18,4)*SH_MAG(1) + OP(18,3)*SK_MZ(3) + OP(18,19)*SK_MZ(2) + OP(18,17)*SK_MZ(5) - OP(18,18)*SK_MZ(4)); +Kfusion(19) = SK_MZ(1)*(OP(19,22) + OP(19,1)*SH_MAG(2) - OP(19,2)*SH_MAG(3) + OP(19,4)*SH_MAG(1) + OP(19,3)*SK_MZ(3) + OP(19,19)*SK_MZ(2) + OP(19,17)*SK_MZ(5) - OP(19,18)*SK_MZ(4)); +Kfusion(20) = SK_MZ(1)*(OP(20,22) + OP(20,1)*SH_MAG(2) - OP(20,2)*SH_MAG(3) + OP(20,4)*SH_MAG(1) + OP(20,3)*SK_MZ(3) + OP(20,19)*SK_MZ(2) + OP(20,17)*SK_MZ(5) - OP(20,18)*SK_MZ(4)); +Kfusion(21) = SK_MZ(1)*(OP(21,22) + OP(21,1)*SH_MAG(2) - OP(21,2)*SH_MAG(3) + OP(21,4)*SH_MAG(1) + OP(21,3)*SK_MZ(3) + OP(21,19)*SK_MZ(2) + OP(21,17)*SK_MZ(5) - OP(21,18)*SK_MZ(4)); +Kfusion(22) = SK_MZ(1)*(OP(22,22) + OP(22,1)*SH_MAG(2) - OP(22,2)*SH_MAG(3) + OP(22,4)*SH_MAG(1) + OP(22,3)*SK_MZ(3) + OP(22,19)*SK_MZ(2) + OP(22,17)*SK_MZ(5) - OP(22,18)*SK_MZ(4)); +Kfusion(23) = SK_MZ(1)*(OP(23,22) + OP(23,1)*SH_MAG(2) - OP(23,2)*SH_MAG(3) + OP(23,4)*SH_MAG(1) + OP(23,3)*SK_MZ(3) + OP(23,19)*SK_MZ(2) + OP(23,17)*SK_MZ(5) - OP(23,18)*SK_MZ(4)); +Kfusion(24) = SK_MZ(1)*(OP(24,22) + OP(24,1)*SH_MAG(2) - OP(24,2)*SH_MAG(3) + OP(24,4)*SH_MAG(1) + OP(24,3)*SK_MZ(3) + OP(24,19)*SK_MZ(2) + OP(24,17)*SK_MZ(5) - OP(24,18)*SK_MZ(4)); +SH_ACCX = zeros(4,1); SH_ACCX(1) = q0^2 + q1^2 - q2^2 - q3^2; -SH_ACCX(2) = 2*q0*q3 + 2*q1*q2; -SH_ACCX(3) = vn - vwn; -SH_ACCX(4) = ve - vwe; -SH_ACCX(5) = q3^2; -SH_ACCX(6) = 2*q0*q2; -SH_ACCX(7) = 2*q0*q1; +SH_ACCX(2) = vn - vwn; +SH_ACCX(3) = ve - vwe; +SH_ACCX(4) = 2*q0*q3 + 2*q1*q2; H_ACCX = zeros(1,24); -H_ACCX(1,2) = Kaccx*(SH_ACCX(3)*(SH_ACCX(6) + 2*q1*q3) - SH_ACCX(4)*(SH_ACCX(7) - 2*q2*q3) + vd*(SH_ACCX(5) + q0^2 - q1^2 - q2^2)); -H_ACCX(1,3) = Kaccx*(SH_ACCX(3)*(2*q0*q3 - 2*q1*q2) + SH_ACCX(4)*(SH_ACCX(5) - q0^2 + q1^2 - q2^2) - vd*(SH_ACCX(7) + 2*q2*q3)); -H_ACCX(1,4) = -Kaccx*SH_ACCX(1); -H_ACCX(1,5) = -Kaccx*SH_ACCX(2); -H_ACCX(1,6) = Kaccx*(SH_ACCX(6) - 2*q1*q3); +H_ACCX(1,1) = -Kaccx*(2*q0*SH_ACCX(2) + 2*q3*SH_ACCX(3) - 2*q2*vd); +H_ACCX(1,2) = -Kaccx*(2*q1*SH_ACCX(2) + 2*q2*SH_ACCX(3) + 2*q3*vd); +H_ACCX(1,3) = Kaccx*(2*q2*SH_ACCX(2) - 2*q1*SH_ACCX(3) + 2*q0*vd); +H_ACCX(1,4) = -Kaccx*(2*q0*SH_ACCX(3) - 2*q3*SH_ACCX(2) + 2*q1*vd); +H_ACCX(1,5) = -Kaccx*SH_ACCX(1); +H_ACCX(1,6) = -Kaccx*SH_ACCX(4); +H_ACCX(1,7) = Kaccx*(2*q0*q2 - 2*q1*q3); H_ACCX(1,23) = Kaccx*SH_ACCX(1); -H_ACCX(1,24) = Kaccx*SH_ACCX(2); -SK_ACCX = zeros(5,1); -SK_ACCX(1) = 1/(R_ACC - Kaccx*SH_ACCX(1)*(Kaccx*OP(23,4)*SH_ACCX(1) - Kaccx*OP(5,4)*SH_ACCX(2) - Kaccx*OP(4,4)*SH_ACCX(1) + Kaccx*OP(24,4)*SH_ACCX(2) + Kaccx*OP(3,4)*(SH_ACCX(3)*(2*q0*q3 - 2*q1*q2) + SH_ACCX(4)*(SH_ACCX(5) - q0^2 + q1^2 - q2^2) - vd*(SH_ACCX(7) + 2*q2*q3)) + Kaccx*OP(2,4)*(SH_ACCX(3)*(SH_ACCX(6) + 2*q1*q3) - SH_ACCX(4)*(SH_ACCX(7) - 2*q2*q3) + vd*(SH_ACCX(5) + q0^2 - q1^2 - q2^2)) + Kaccx*OP(6,4)*(SH_ACCX(6) - 2*q1*q3)) - Kaccx*SH_ACCX(2)*(Kaccx*OP(23,5)*SH_ACCX(1) - Kaccx*OP(5,5)*SH_ACCX(2) - Kaccx*OP(4,5)*SH_ACCX(1) + Kaccx*OP(24,5)*SH_ACCX(2) + Kaccx*OP(3,5)*(SH_ACCX(3)*(2*q0*q3 - 2*q1*q2) + SH_ACCX(4)*(SH_ACCX(5) - q0^2 + q1^2 - q2^2) - vd*(SH_ACCX(7) + 2*q2*q3)) + Kaccx*OP(2,5)*(SH_ACCX(3)*(SH_ACCX(6) + 2*q1*q3) - SH_ACCX(4)*(SH_ACCX(7) - 2*q2*q3) + vd*(SH_ACCX(5) + q0^2 - q1^2 - q2^2)) + Kaccx*OP(6,5)*(SH_ACCX(6) - 2*q1*q3)) + Kaccx*SH_ACCX(1)*(Kaccx*OP(23,23)*SH_ACCX(1) - Kaccx*OP(5,23)*SH_ACCX(2) - Kaccx*OP(4,23)*SH_ACCX(1) + Kaccx*OP(24,23)*SH_ACCX(2) + Kaccx*OP(3,23)*(SH_ACCX(3)*(2*q0*q3 - 2*q1*q2) + SH_ACCX(4)*(SH_ACCX(5) - q0^2 + q1^2 - q2^2) - vd*(SH_ACCX(7) + 2*q2*q3)) + Kaccx*OP(2,23)*(SH_ACCX(3)*(SH_ACCX(6) + 2*q1*q3) - SH_ACCX(4)*(SH_ACCX(7) - 2*q2*q3) + vd*(SH_ACCX(5) + q0^2 - q1^2 - q2^2)) + Kaccx*OP(6,23)*(SH_ACCX(6) - 2*q1*q3)) + Kaccx*SH_ACCX(2)*(Kaccx*OP(23,24)*SH_ACCX(1) - Kaccx*OP(5,24)*SH_ACCX(2) - Kaccx*OP(4,24)*SH_ACCX(1) + Kaccx*OP(24,24)*SH_ACCX(2) + Kaccx*OP(3,24)*(SH_ACCX(3)*(2*q0*q3 - 2*q1*q2) + SH_ACCX(4)*(SH_ACCX(5) - q0^2 + q1^2 - q2^2) - vd*(SH_ACCX(7) + 2*q2*q3)) + Kaccx*OP(2,24)*(SH_ACCX(3)*(SH_ACCX(6) + 2*q1*q3) - SH_ACCX(4)*(SH_ACCX(7) - 2*q2*q3) + vd*(SH_ACCX(5) + q0^2 - q1^2 - q2^2)) + Kaccx*OP(6,24)*(SH_ACCX(6) - 2*q1*q3)) + Kaccx*(SH_ACCX(3)*(2*q0*q3 - 2*q1*q2) + SH_ACCX(4)*(SH_ACCX(5) - q0^2 + q1^2 - q2^2) - vd*(SH_ACCX(7) + 2*q2*q3))*(Kaccx*OP(23,3)*SH_ACCX(1) - Kaccx*OP(5,3)*SH_ACCX(2) - Kaccx*OP(4,3)*SH_ACCX(1) + Kaccx*OP(24,3)*SH_ACCX(2) + Kaccx*OP(3,3)*(SH_ACCX(3)*(2*q0*q3 - 2*q1*q2) + SH_ACCX(4)*(SH_ACCX(5) - q0^2 + q1^2 - q2^2) - vd*(SH_ACCX(7) + 2*q2*q3)) + Kaccx*OP(2,3)*(SH_ACCX(3)*(SH_ACCX(6) + 2*q1*q3) - SH_ACCX(4)*(SH_ACCX(7) - 2*q2*q3) + vd*(SH_ACCX(5) + q0^2 - q1^2 - q2^2)) + Kaccx*OP(6,3)*(SH_ACCX(6) - 2*q1*q3)) + Kaccx*(SH_ACCX(3)*(SH_ACCX(6) + 2*q1*q3) - SH_ACCX(4)*(SH_ACCX(7) - 2*q2*q3) + vd*(SH_ACCX(5) + q0^2 - q1^2 - q2^2))*(Kaccx*OP(23,2)*SH_ACCX(1) - Kaccx*OP(5,2)*SH_ACCX(2) - Kaccx*OP(4,2)*SH_ACCX(1) + Kaccx*OP(24,2)*SH_ACCX(2) + Kaccx*OP(3,2)*(SH_ACCX(3)*(2*q0*q3 - 2*q1*q2) + SH_ACCX(4)*(SH_ACCX(5) - q0^2 + q1^2 - q2^2) - vd*(SH_ACCX(7) + 2*q2*q3)) + Kaccx*OP(2,2)*(SH_ACCX(3)*(SH_ACCX(6) + 2*q1*q3) - SH_ACCX(4)*(SH_ACCX(7) - 2*q2*q3) + vd*(SH_ACCX(5) + q0^2 - q1^2 - q2^2)) + Kaccx*OP(6,2)*(SH_ACCX(6) - 2*q1*q3)) + Kaccx*(SH_ACCX(6) - 2*q1*q3)*(Kaccx*OP(23,6)*SH_ACCX(1) - Kaccx*OP(5,6)*SH_ACCX(2) - Kaccx*OP(4,6)*SH_ACCX(1) + Kaccx*OP(24,6)*SH_ACCX(2) + Kaccx*OP(3,6)*(SH_ACCX(3)*(2*q0*q3 - 2*q1*q2) + SH_ACCX(4)*(SH_ACCX(5) - q0^2 + q1^2 - q2^2) - vd*(SH_ACCX(7) + 2*q2*q3)) + Kaccx*OP(2,6)*(SH_ACCX(3)*(SH_ACCX(6) + 2*q1*q3) - SH_ACCX(4)*(SH_ACCX(7) - 2*q2*q3) + vd*(SH_ACCX(5) + q0^2 - q1^2 - q2^2)) + Kaccx*OP(6,6)*(SH_ACCX(6) - 2*q1*q3))); -SK_ACCX(2) = SH_ACCX(3)*(2*q0*q3 - 2*q1*q2) + SH_ACCX(4)*(SH_ACCX(5) - q0^2 + q1^2 - q2^2) - vd*(SH_ACCX(7) + 2*q2*q3); -SK_ACCX(3) = SH_ACCX(3)*(SH_ACCX(6) + 2*q1*q3) - SH_ACCX(4)*(SH_ACCX(7) - 2*q2*q3) + vd*(SH_ACCX(5) + q0^2 - q1^2 - q2^2); -SK_ACCX(4) = SH_ACCX(6) - 2*q1*q3; -SK_ACCX(5) = SH_ACCX(2); +H_ACCX(1,24) = Kaccx*SH_ACCX(4); +SK_ACCX = zeros(7,1); +SK_ACCX(1) = 1/(R_ACC + Kaccx*SH_ACCX(1)*(Kaccx*OP(5,5)*SH_ACCX(1) + Kaccx*OP(6,5)*SH_ACCX(4) - Kaccx*OP(23,5)*SH_ACCX(1) - Kaccx*OP(24,5)*SH_ACCX(4) - Kaccx*OP(7,5)*(2*q0*q2 - 2*q1*q3) + Kaccx*OP(1,5)*(2*q0*SH_ACCX(2) + 2*q3*SH_ACCX(3) - 2*q2*vd) + Kaccx*OP(2,5)*(2*q1*SH_ACCX(2) + 2*q2*SH_ACCX(3) + 2*q3*vd) - Kaccx*OP(3,5)*(2*q2*SH_ACCX(2) - 2*q1*SH_ACCX(3) + 2*q0*vd) + Kaccx*OP(4,5)*(2*q0*SH_ACCX(3) - 2*q3*SH_ACCX(2) + 2*q1*vd)) + Kaccx*SH_ACCX(4)*(Kaccx*OP(5,6)*SH_ACCX(1) + Kaccx*OP(6,6)*SH_ACCX(4) - Kaccx*OP(23,6)*SH_ACCX(1) - Kaccx*OP(24,6)*SH_ACCX(4) - Kaccx*OP(7,6)*(2*q0*q2 - 2*q1*q3) + Kaccx*OP(1,6)*(2*q0*SH_ACCX(2) + 2*q3*SH_ACCX(3) - 2*q2*vd) + Kaccx*OP(2,6)*(2*q1*SH_ACCX(2) + 2*q2*SH_ACCX(3) + 2*q3*vd) - Kaccx*OP(3,6)*(2*q2*SH_ACCX(2) - 2*q1*SH_ACCX(3) + 2*q0*vd) + Kaccx*OP(4,6)*(2*q0*SH_ACCX(3) - 2*q3*SH_ACCX(2) + 2*q1*vd)) - Kaccx*SH_ACCX(1)*(Kaccx*OP(5,23)*SH_ACCX(1) + Kaccx*OP(6,23)*SH_ACCX(4) - Kaccx*OP(23,23)*SH_ACCX(1) - Kaccx*OP(24,23)*SH_ACCX(4) - Kaccx*OP(7,23)*(2*q0*q2 - 2*q1*q3) + Kaccx*OP(1,23)*(2*q0*SH_ACCX(2) + 2*q3*SH_ACCX(3) - 2*q2*vd) + Kaccx*OP(2,23)*(2*q1*SH_ACCX(2) + 2*q2*SH_ACCX(3) + 2*q3*vd) - Kaccx*OP(3,23)*(2*q2*SH_ACCX(2) - 2*q1*SH_ACCX(3) + 2*q0*vd) + Kaccx*OP(4,23)*(2*q0*SH_ACCX(3) - 2*q3*SH_ACCX(2) + 2*q1*vd)) - Kaccx*SH_ACCX(4)*(Kaccx*OP(5,24)*SH_ACCX(1) + Kaccx*OP(6,24)*SH_ACCX(4) - Kaccx*OP(23,24)*SH_ACCX(1) - Kaccx*OP(24,24)*SH_ACCX(4) - Kaccx*OP(7,24)*(2*q0*q2 - 2*q1*q3) + Kaccx*OP(1,24)*(2*q0*SH_ACCX(2) + 2*q3*SH_ACCX(3) - 2*q2*vd) + Kaccx*OP(2,24)*(2*q1*SH_ACCX(2) + 2*q2*SH_ACCX(3) + 2*q3*vd) - Kaccx*OP(3,24)*(2*q2*SH_ACCX(2) - 2*q1*SH_ACCX(3) + 2*q0*vd) + Kaccx*OP(4,24)*(2*q0*SH_ACCX(3) - 2*q3*SH_ACCX(2) + 2*q1*vd)) - Kaccx*(2*q0*q2 - 2*q1*q3)*(Kaccx*OP(5,7)*SH_ACCX(1) + Kaccx*OP(6,7)*SH_ACCX(4) - Kaccx*OP(23,7)*SH_ACCX(1) - Kaccx*OP(24,7)*SH_ACCX(4) - Kaccx*OP(7,7)*(2*q0*q2 - 2*q1*q3) + Kaccx*OP(1,7)*(2*q0*SH_ACCX(2) + 2*q3*SH_ACCX(3) - 2*q2*vd) + Kaccx*OP(2,7)*(2*q1*SH_ACCX(2) + 2*q2*SH_ACCX(3) + 2*q3*vd) - Kaccx*OP(3,7)*(2*q2*SH_ACCX(2) - 2*q1*SH_ACCX(3) + 2*q0*vd) + Kaccx*OP(4,7)*(2*q0*SH_ACCX(3) - 2*q3*SH_ACCX(2) + 2*q1*vd)) + Kaccx*(2*q0*SH_ACCX(2) + 2*q3*SH_ACCX(3) - 2*q2*vd)*(Kaccx*OP(5,1)*SH_ACCX(1) + Kaccx*OP(6,1)*SH_ACCX(4) - Kaccx*OP(23,1)*SH_ACCX(1) - Kaccx*OP(24,1)*SH_ACCX(4) - Kaccx*OP(7,1)*(2*q0*q2 - 2*q1*q3) + Kaccx*OP(1,1)*(2*q0*SH_ACCX(2) + 2*q3*SH_ACCX(3) - 2*q2*vd) + Kaccx*OP(2,1)*(2*q1*SH_ACCX(2) + 2*q2*SH_ACCX(3) + 2*q3*vd) - Kaccx*OP(3,1)*(2*q2*SH_ACCX(2) - 2*q1*SH_ACCX(3) + 2*q0*vd) + Kaccx*OP(4,1)*(2*q0*SH_ACCX(3) - 2*q3*SH_ACCX(2) + 2*q1*vd)) + Kaccx*(2*q1*SH_ACCX(2) + 2*q2*SH_ACCX(3) + 2*q3*vd)*(Kaccx*OP(5,2)*SH_ACCX(1) + Kaccx*OP(6,2)*SH_ACCX(4) - Kaccx*OP(23,2)*SH_ACCX(1) - Kaccx*OP(24,2)*SH_ACCX(4) - Kaccx*OP(7,2)*(2*q0*q2 - 2*q1*q3) + Kaccx*OP(1,2)*(2*q0*SH_ACCX(2) + 2*q3*SH_ACCX(3) - 2*q2*vd) + Kaccx*OP(2,2)*(2*q1*SH_ACCX(2) + 2*q2*SH_ACCX(3) + 2*q3*vd) - Kaccx*OP(3,2)*(2*q2*SH_ACCX(2) - 2*q1*SH_ACCX(3) + 2*q0*vd) + Kaccx*OP(4,2)*(2*q0*SH_ACCX(3) - 2*q3*SH_ACCX(2) + 2*q1*vd)) - Kaccx*(2*q2*SH_ACCX(2) - 2*q1*SH_ACCX(3) + 2*q0*vd)*(Kaccx*OP(5,3)*SH_ACCX(1) + Kaccx*OP(6,3)*SH_ACCX(4) - Kaccx*OP(23,3)*SH_ACCX(1) - Kaccx*OP(24,3)*SH_ACCX(4) - Kaccx*OP(7,3)*(2*q0*q2 - 2*q1*q3) + Kaccx*OP(1,3)*(2*q0*SH_ACCX(2) + 2*q3*SH_ACCX(3) - 2*q2*vd) + Kaccx*OP(2,3)*(2*q1*SH_ACCX(2) + 2*q2*SH_ACCX(3) + 2*q3*vd) - Kaccx*OP(3,3)*(2*q2*SH_ACCX(2) - 2*q1*SH_ACCX(3) + 2*q0*vd) + Kaccx*OP(4,3)*(2*q0*SH_ACCX(3) - 2*q3*SH_ACCX(2) + 2*q1*vd)) + Kaccx*(2*q0*SH_ACCX(3) - 2*q3*SH_ACCX(2) + 2*q1*vd)*(Kaccx*OP(5,4)*SH_ACCX(1) + Kaccx*OP(6,4)*SH_ACCX(4) - Kaccx*OP(23,4)*SH_ACCX(1) - Kaccx*OP(24,4)*SH_ACCX(4) - Kaccx*OP(7,4)*(2*q0*q2 - 2*q1*q3) + Kaccx*OP(1,4)*(2*q0*SH_ACCX(2) + 2*q3*SH_ACCX(3) - 2*q2*vd) + Kaccx*OP(2,4)*(2*q1*SH_ACCX(2) + 2*q2*SH_ACCX(3) + 2*q3*vd) - Kaccx*OP(3,4)*(2*q2*SH_ACCX(2) - 2*q1*SH_ACCX(3) + 2*q0*vd) + Kaccx*OP(4,4)*(2*q0*SH_ACCX(3) - 2*q3*SH_ACCX(2) + 2*q1*vd))); +SK_ACCX(2) = 2*q0*SH_ACCX(3) - 2*q3*SH_ACCX(2) + 2*q1*vd; +SK_ACCX(3) = 2*q2*SH_ACCX(2) - 2*q1*SH_ACCX(3) + 2*q0*vd; +SK_ACCX(4) = 2*q0*SH_ACCX(2) + 2*q3*SH_ACCX(3) - 2*q2*vd; +SK_ACCX(5) = 2*q1*SH_ACCX(2) + 2*q2*SH_ACCX(3) + 2*q3*vd; +SK_ACCX(6) = 2*q0*q2 - 2*q1*q3; +SK_ACCX(7) = SH_ACCX(4); Kfusion = zeros(24,1); Kfusion = zeros(1,1); -Kfusion(1) = SK_ACCX(1)*(Kaccx*OP(1,23)*SH_ACCX(1) - Kaccx*OP(1,4)*SH_ACCX(1) + Kaccx*OP(1,2)*SK_ACCX(3) + Kaccx*OP(1,3)*SK_ACCX(2) - Kaccx*OP(1,5)*SK_ACCX(5) + Kaccx*OP(1,6)*SK_ACCX(4) + Kaccx*OP(1,24)*SK_ACCX(5)); -Kfusion(2) = SK_ACCX(1)*(Kaccx*OP(2,23)*SH_ACCX(1) - Kaccx*OP(2,4)*SH_ACCX(1) + Kaccx*OP(2,2)*SK_ACCX(3) + Kaccx*OP(2,3)*SK_ACCX(2) - Kaccx*OP(2,5)*SK_ACCX(5) + Kaccx*OP(2,6)*SK_ACCX(4) + Kaccx*OP(2,24)*SK_ACCX(5)); -Kfusion(3) = SK_ACCX(1)*(Kaccx*OP(3,23)*SH_ACCX(1) - Kaccx*OP(3,4)*SH_ACCX(1) + Kaccx*OP(3,2)*SK_ACCX(3) + Kaccx*OP(3,3)*SK_ACCX(2) - Kaccx*OP(3,5)*SK_ACCX(5) + Kaccx*OP(3,6)*SK_ACCX(4) + Kaccx*OP(3,24)*SK_ACCX(5)); -Kfusion(4) = SK_ACCX(1)*(Kaccx*OP(4,23)*SH_ACCX(1) - Kaccx*OP(4,4)*SH_ACCX(1) + Kaccx*OP(4,2)*SK_ACCX(3) + Kaccx*OP(4,3)*SK_ACCX(2) - Kaccx*OP(4,5)*SK_ACCX(5) + Kaccx*OP(4,6)*SK_ACCX(4) + Kaccx*OP(4,24)*SK_ACCX(5)); -Kfusion(5) = SK_ACCX(1)*(Kaccx*OP(5,23)*SH_ACCX(1) - Kaccx*OP(5,4)*SH_ACCX(1) + Kaccx*OP(5,2)*SK_ACCX(3) + Kaccx*OP(5,3)*SK_ACCX(2) - Kaccx*OP(5,5)*SK_ACCX(5) + Kaccx*OP(5,6)*SK_ACCX(4) + Kaccx*OP(5,24)*SK_ACCX(5)); -Kfusion(6) = SK_ACCX(1)*(Kaccx*OP(6,23)*SH_ACCX(1) - Kaccx*OP(6,4)*SH_ACCX(1) + Kaccx*OP(6,2)*SK_ACCX(3) + Kaccx*OP(6,3)*SK_ACCX(2) - Kaccx*OP(6,5)*SK_ACCX(5) + Kaccx*OP(6,6)*SK_ACCX(4) + Kaccx*OP(6,24)*SK_ACCX(5)); -Kfusion(7) = SK_ACCX(1)*(Kaccx*OP(7,23)*SH_ACCX(1) - Kaccx*OP(7,4)*SH_ACCX(1) + Kaccx*OP(7,2)*SK_ACCX(3) + Kaccx*OP(7,3)*SK_ACCX(2) - Kaccx*OP(7,5)*SK_ACCX(5) + Kaccx*OP(7,6)*SK_ACCX(4) + Kaccx*OP(7,24)*SK_ACCX(5)); -Kfusion(8) = SK_ACCX(1)*(Kaccx*OP(8,23)*SH_ACCX(1) - Kaccx*OP(8,4)*SH_ACCX(1) + Kaccx*OP(8,2)*SK_ACCX(3) + Kaccx*OP(8,3)*SK_ACCX(2) - Kaccx*OP(8,5)*SK_ACCX(5) + Kaccx*OP(8,6)*SK_ACCX(4) + Kaccx*OP(8,24)*SK_ACCX(5)); -Kfusion(9) = SK_ACCX(1)*(Kaccx*OP(9,23)*SH_ACCX(1) - Kaccx*OP(9,4)*SH_ACCX(1) + Kaccx*OP(9,2)*SK_ACCX(3) + Kaccx*OP(9,3)*SK_ACCX(2) - Kaccx*OP(9,5)*SK_ACCX(5) + Kaccx*OP(9,6)*SK_ACCX(4) + Kaccx*OP(9,24)*SK_ACCX(5)); -Kfusion(10) = SK_ACCX(1)*(Kaccx*OP(10,23)*SH_ACCX(1) - Kaccx*OP(10,4)*SH_ACCX(1) + Kaccx*OP(10,2)*SK_ACCX(3) + Kaccx*OP(10,3)*SK_ACCX(2) - Kaccx*OP(10,5)*SK_ACCX(5) + Kaccx*OP(10,6)*SK_ACCX(4) + Kaccx*OP(10,24)*SK_ACCX(5)); -Kfusion(11) = SK_ACCX(1)*(Kaccx*OP(11,23)*SH_ACCX(1) - Kaccx*OP(11,4)*SH_ACCX(1) + Kaccx*OP(11,2)*SK_ACCX(3) + Kaccx*OP(11,3)*SK_ACCX(2) - Kaccx*OP(11,5)*SK_ACCX(5) + Kaccx*OP(11,6)*SK_ACCX(4) + Kaccx*OP(11,24)*SK_ACCX(5)); -Kfusion(12) = SK_ACCX(1)*(Kaccx*OP(12,23)*SH_ACCX(1) - Kaccx*OP(12,4)*SH_ACCX(1) + Kaccx*OP(12,2)*SK_ACCX(3) + Kaccx*OP(12,3)*SK_ACCX(2) - Kaccx*OP(12,5)*SK_ACCX(5) + Kaccx*OP(12,6)*SK_ACCX(4) + Kaccx*OP(12,24)*SK_ACCX(5)); -Kfusion(13) = SK_ACCX(1)*(Kaccx*OP(13,23)*SH_ACCX(1) - Kaccx*OP(13,4)*SH_ACCX(1) + Kaccx*OP(13,2)*SK_ACCX(3) + Kaccx*OP(13,3)*SK_ACCX(2) - Kaccx*OP(13,5)*SK_ACCX(5) + Kaccx*OP(13,6)*SK_ACCX(4) + Kaccx*OP(13,24)*SK_ACCX(5)); -Kfusion(14) = SK_ACCX(1)*(Kaccx*OP(14,23)*SH_ACCX(1) - Kaccx*OP(14,4)*SH_ACCX(1) + Kaccx*OP(14,2)*SK_ACCX(3) + Kaccx*OP(14,3)*SK_ACCX(2) - Kaccx*OP(14,5)*SK_ACCX(5) + Kaccx*OP(14,6)*SK_ACCX(4) + Kaccx*OP(14,24)*SK_ACCX(5)); -Kfusion(15) = SK_ACCX(1)*(Kaccx*OP(15,23)*SH_ACCX(1) - Kaccx*OP(15,4)*SH_ACCX(1) + Kaccx*OP(15,2)*SK_ACCX(3) + Kaccx*OP(15,3)*SK_ACCX(2) - Kaccx*OP(15,5)*SK_ACCX(5) + Kaccx*OP(15,6)*SK_ACCX(4) + Kaccx*OP(15,24)*SK_ACCX(5)); -Kfusion(16) = SK_ACCX(1)*(Kaccx*OP(16,23)*SH_ACCX(1) - Kaccx*OP(16,4)*SH_ACCX(1) + Kaccx*OP(16,2)*SK_ACCX(3) + Kaccx*OP(16,3)*SK_ACCX(2) - Kaccx*OP(16,5)*SK_ACCX(5) + Kaccx*OP(16,6)*SK_ACCX(4) + Kaccx*OP(16,24)*SK_ACCX(5)); -Kfusion(17) = SK_ACCX(1)*(Kaccx*OP(17,23)*SH_ACCX(1) - Kaccx*OP(17,4)*SH_ACCX(1) + Kaccx*OP(17,2)*SK_ACCX(3) + Kaccx*OP(17,3)*SK_ACCX(2) - Kaccx*OP(17,5)*SK_ACCX(5) + Kaccx*OP(17,6)*SK_ACCX(4) + Kaccx*OP(17,24)*SK_ACCX(5)); -Kfusion(18) = SK_ACCX(1)*(Kaccx*OP(18,23)*SH_ACCX(1) - Kaccx*OP(18,4)*SH_ACCX(1) + Kaccx*OP(18,2)*SK_ACCX(3) + Kaccx*OP(18,3)*SK_ACCX(2) - Kaccx*OP(18,5)*SK_ACCX(5) + Kaccx*OP(18,6)*SK_ACCX(4) + Kaccx*OP(18,24)*SK_ACCX(5)); -Kfusion(19) = SK_ACCX(1)*(Kaccx*OP(19,23)*SH_ACCX(1) - Kaccx*OP(19,4)*SH_ACCX(1) + Kaccx*OP(19,2)*SK_ACCX(3) + Kaccx*OP(19,3)*SK_ACCX(2) - Kaccx*OP(19,5)*SK_ACCX(5) + Kaccx*OP(19,6)*SK_ACCX(4) + Kaccx*OP(19,24)*SK_ACCX(5)); -Kfusion(20) = SK_ACCX(1)*(Kaccx*OP(20,23)*SH_ACCX(1) - Kaccx*OP(20,4)*SH_ACCX(1) + Kaccx*OP(20,2)*SK_ACCX(3) + Kaccx*OP(20,3)*SK_ACCX(2) - Kaccx*OP(20,5)*SK_ACCX(5) + Kaccx*OP(20,6)*SK_ACCX(4) + Kaccx*OP(20,24)*SK_ACCX(5)); -Kfusion(21) = SK_ACCX(1)*(Kaccx*OP(21,23)*SH_ACCX(1) - Kaccx*OP(21,4)*SH_ACCX(1) + Kaccx*OP(21,2)*SK_ACCX(3) + Kaccx*OP(21,3)*SK_ACCX(2) - Kaccx*OP(21,5)*SK_ACCX(5) + Kaccx*OP(21,6)*SK_ACCX(4) + Kaccx*OP(21,24)*SK_ACCX(5)); -Kfusion(22) = SK_ACCX(1)*(Kaccx*OP(22,23)*SH_ACCX(1) - Kaccx*OP(22,4)*SH_ACCX(1) + Kaccx*OP(22,2)*SK_ACCX(3) + Kaccx*OP(22,3)*SK_ACCX(2) - Kaccx*OP(22,5)*SK_ACCX(5) + Kaccx*OP(22,6)*SK_ACCX(4) + Kaccx*OP(22,24)*SK_ACCX(5)); -Kfusion(23) = SK_ACCX(1)*(Kaccx*OP(23,23)*SH_ACCX(1) - Kaccx*OP(23,4)*SH_ACCX(1) + Kaccx*OP(23,2)*SK_ACCX(3) + Kaccx*OP(23,3)*SK_ACCX(2) - Kaccx*OP(23,5)*SK_ACCX(5) + Kaccx*OP(23,6)*SK_ACCX(4) + Kaccx*OP(23,24)*SK_ACCX(5)); -Kfusion(24) = SK_ACCX(1)*(Kaccx*OP(24,23)*SH_ACCX(1) - Kaccx*OP(24,4)*SH_ACCX(1) + Kaccx*OP(24,2)*SK_ACCX(3) + Kaccx*OP(24,3)*SK_ACCX(2) - Kaccx*OP(24,5)*SK_ACCX(5) + Kaccx*OP(24,6)*SK_ACCX(4) + Kaccx*OP(24,24)*SK_ACCX(5)); -SH_ACCY = zeros(6,1); +Kfusion(1) = -SK_ACCX(1)*(Kaccx*OP(1,5)*SH_ACCX(1) - Kaccx*OP(1,23)*SH_ACCX(1) + Kaccx*OP(1,1)*SK_ACCX(4) - Kaccx*OP(1,3)*SK_ACCX(3) + Kaccx*OP(1,4)*SK_ACCX(2) + Kaccx*OP(1,2)*SK_ACCX(5) + Kaccx*OP(1,6)*SK_ACCX(7) - Kaccx*OP(1,7)*SK_ACCX(6) - Kaccx*OP(1,24)*SK_ACCX(7)); +Kfusion(2) = -SK_ACCX(1)*(Kaccx*OP(2,5)*SH_ACCX(1) - Kaccx*OP(2,23)*SH_ACCX(1) + Kaccx*OP(2,1)*SK_ACCX(4) - Kaccx*OP(2,3)*SK_ACCX(3) + Kaccx*OP(2,4)*SK_ACCX(2) + Kaccx*OP(2,2)*SK_ACCX(5) + Kaccx*OP(2,6)*SK_ACCX(7) - Kaccx*OP(2,7)*SK_ACCX(6) - Kaccx*OP(2,24)*SK_ACCX(7)); +Kfusion(3) = -SK_ACCX(1)*(Kaccx*OP(3,5)*SH_ACCX(1) - Kaccx*OP(3,23)*SH_ACCX(1) + Kaccx*OP(3,1)*SK_ACCX(4) - Kaccx*OP(3,3)*SK_ACCX(3) + Kaccx*OP(3,4)*SK_ACCX(2) + Kaccx*OP(3,2)*SK_ACCX(5) + Kaccx*OP(3,6)*SK_ACCX(7) - Kaccx*OP(3,7)*SK_ACCX(6) - Kaccx*OP(3,24)*SK_ACCX(7)); +Kfusion(4) = -SK_ACCX(1)*(Kaccx*OP(4,5)*SH_ACCX(1) - Kaccx*OP(4,23)*SH_ACCX(1) + Kaccx*OP(4,1)*SK_ACCX(4) - Kaccx*OP(4,3)*SK_ACCX(3) + Kaccx*OP(4,4)*SK_ACCX(2) + Kaccx*OP(4,2)*SK_ACCX(5) + Kaccx*OP(4,6)*SK_ACCX(7) - Kaccx*OP(4,7)*SK_ACCX(6) - Kaccx*OP(4,24)*SK_ACCX(7)); +Kfusion(5) = -SK_ACCX(1)*(Kaccx*OP(5,5)*SH_ACCX(1) - Kaccx*OP(5,23)*SH_ACCX(1) + Kaccx*OP(5,1)*SK_ACCX(4) - Kaccx*OP(5,3)*SK_ACCX(3) + Kaccx*OP(5,4)*SK_ACCX(2) + Kaccx*OP(5,2)*SK_ACCX(5) + Kaccx*OP(5,6)*SK_ACCX(7) - Kaccx*OP(5,7)*SK_ACCX(6) - Kaccx*OP(5,24)*SK_ACCX(7)); +Kfusion(6) = -SK_ACCX(1)*(Kaccx*OP(6,5)*SH_ACCX(1) - Kaccx*OP(6,23)*SH_ACCX(1) + Kaccx*OP(6,1)*SK_ACCX(4) - Kaccx*OP(6,3)*SK_ACCX(3) + Kaccx*OP(6,4)*SK_ACCX(2) + Kaccx*OP(6,2)*SK_ACCX(5) + Kaccx*OP(6,6)*SK_ACCX(7) - Kaccx*OP(6,7)*SK_ACCX(6) - Kaccx*OP(6,24)*SK_ACCX(7)); +Kfusion(7) = -SK_ACCX(1)*(Kaccx*OP(7,5)*SH_ACCX(1) - Kaccx*OP(7,23)*SH_ACCX(1) + Kaccx*OP(7,1)*SK_ACCX(4) - Kaccx*OP(7,3)*SK_ACCX(3) + Kaccx*OP(7,4)*SK_ACCX(2) + Kaccx*OP(7,2)*SK_ACCX(5) + Kaccx*OP(7,6)*SK_ACCX(7) - Kaccx*OP(7,7)*SK_ACCX(6) - Kaccx*OP(7,24)*SK_ACCX(7)); +Kfusion(8) = -SK_ACCX(1)*(Kaccx*OP(8,5)*SH_ACCX(1) - Kaccx*OP(8,23)*SH_ACCX(1) + Kaccx*OP(8,1)*SK_ACCX(4) - Kaccx*OP(8,3)*SK_ACCX(3) + Kaccx*OP(8,4)*SK_ACCX(2) + Kaccx*OP(8,2)*SK_ACCX(5) + Kaccx*OP(8,6)*SK_ACCX(7) - Kaccx*OP(8,7)*SK_ACCX(6) - Kaccx*OP(8,24)*SK_ACCX(7)); +Kfusion(9) = -SK_ACCX(1)*(Kaccx*OP(9,5)*SH_ACCX(1) - Kaccx*OP(9,23)*SH_ACCX(1) + Kaccx*OP(9,1)*SK_ACCX(4) - Kaccx*OP(9,3)*SK_ACCX(3) + Kaccx*OP(9,4)*SK_ACCX(2) + Kaccx*OP(9,2)*SK_ACCX(5) + Kaccx*OP(9,6)*SK_ACCX(7) - Kaccx*OP(9,7)*SK_ACCX(6) - Kaccx*OP(9,24)*SK_ACCX(7)); +Kfusion(10) = -SK_ACCX(1)*(Kaccx*OP(10,5)*SH_ACCX(1) - Kaccx*OP(10,23)*SH_ACCX(1) + Kaccx*OP(10,1)*SK_ACCX(4) - Kaccx*OP(10,3)*SK_ACCX(3) + Kaccx*OP(10,4)*SK_ACCX(2) + Kaccx*OP(10,2)*SK_ACCX(5) + Kaccx*OP(10,6)*SK_ACCX(7) - Kaccx*OP(10,7)*SK_ACCX(6) - Kaccx*OP(10,24)*SK_ACCX(7)); +Kfusion(11) = -SK_ACCX(1)*(Kaccx*OP(11,5)*SH_ACCX(1) - Kaccx*OP(11,23)*SH_ACCX(1) + Kaccx*OP(11,1)*SK_ACCX(4) - Kaccx*OP(11,3)*SK_ACCX(3) + Kaccx*OP(11,4)*SK_ACCX(2) + Kaccx*OP(11,2)*SK_ACCX(5) + Kaccx*OP(11,6)*SK_ACCX(7) - Kaccx*OP(11,7)*SK_ACCX(6) - Kaccx*OP(11,24)*SK_ACCX(7)); +Kfusion(12) = -SK_ACCX(1)*(Kaccx*OP(12,5)*SH_ACCX(1) - Kaccx*OP(12,23)*SH_ACCX(1) + Kaccx*OP(12,1)*SK_ACCX(4) - Kaccx*OP(12,3)*SK_ACCX(3) + Kaccx*OP(12,4)*SK_ACCX(2) + Kaccx*OP(12,2)*SK_ACCX(5) + Kaccx*OP(12,6)*SK_ACCX(7) - Kaccx*OP(12,7)*SK_ACCX(6) - Kaccx*OP(12,24)*SK_ACCX(7)); +Kfusion(13) = -SK_ACCX(1)*(Kaccx*OP(13,5)*SH_ACCX(1) - Kaccx*OP(13,23)*SH_ACCX(1) + Kaccx*OP(13,1)*SK_ACCX(4) - Kaccx*OP(13,3)*SK_ACCX(3) + Kaccx*OP(13,4)*SK_ACCX(2) + Kaccx*OP(13,2)*SK_ACCX(5) + Kaccx*OP(13,6)*SK_ACCX(7) - Kaccx*OP(13,7)*SK_ACCX(6) - Kaccx*OP(13,24)*SK_ACCX(7)); +Kfusion(14) = -SK_ACCX(1)*(Kaccx*OP(14,5)*SH_ACCX(1) - Kaccx*OP(14,23)*SH_ACCX(1) + Kaccx*OP(14,1)*SK_ACCX(4) - Kaccx*OP(14,3)*SK_ACCX(3) + Kaccx*OP(14,4)*SK_ACCX(2) + Kaccx*OP(14,2)*SK_ACCX(5) + Kaccx*OP(14,6)*SK_ACCX(7) - Kaccx*OP(14,7)*SK_ACCX(6) - Kaccx*OP(14,24)*SK_ACCX(7)); +Kfusion(15) = -SK_ACCX(1)*(Kaccx*OP(15,5)*SH_ACCX(1) - Kaccx*OP(15,23)*SH_ACCX(1) + Kaccx*OP(15,1)*SK_ACCX(4) - Kaccx*OP(15,3)*SK_ACCX(3) + Kaccx*OP(15,4)*SK_ACCX(2) + Kaccx*OP(15,2)*SK_ACCX(5) + Kaccx*OP(15,6)*SK_ACCX(7) - Kaccx*OP(15,7)*SK_ACCX(6) - Kaccx*OP(15,24)*SK_ACCX(7)); +Kfusion(16) = -SK_ACCX(1)*(Kaccx*OP(16,5)*SH_ACCX(1) - Kaccx*OP(16,23)*SH_ACCX(1) + Kaccx*OP(16,1)*SK_ACCX(4) - Kaccx*OP(16,3)*SK_ACCX(3) + Kaccx*OP(16,4)*SK_ACCX(2) + Kaccx*OP(16,2)*SK_ACCX(5) + Kaccx*OP(16,6)*SK_ACCX(7) - Kaccx*OP(16,7)*SK_ACCX(6) - Kaccx*OP(16,24)*SK_ACCX(7)); +Kfusion(17) = -SK_ACCX(1)*(Kaccx*OP(17,5)*SH_ACCX(1) - Kaccx*OP(17,23)*SH_ACCX(1) + Kaccx*OP(17,1)*SK_ACCX(4) - Kaccx*OP(17,3)*SK_ACCX(3) + Kaccx*OP(17,4)*SK_ACCX(2) + Kaccx*OP(17,2)*SK_ACCX(5) + Kaccx*OP(17,6)*SK_ACCX(7) - Kaccx*OP(17,7)*SK_ACCX(6) - Kaccx*OP(17,24)*SK_ACCX(7)); +Kfusion(18) = -SK_ACCX(1)*(Kaccx*OP(18,5)*SH_ACCX(1) - Kaccx*OP(18,23)*SH_ACCX(1) + Kaccx*OP(18,1)*SK_ACCX(4) - Kaccx*OP(18,3)*SK_ACCX(3) + Kaccx*OP(18,4)*SK_ACCX(2) + Kaccx*OP(18,2)*SK_ACCX(5) + Kaccx*OP(18,6)*SK_ACCX(7) - Kaccx*OP(18,7)*SK_ACCX(6) - Kaccx*OP(18,24)*SK_ACCX(7)); +Kfusion(19) = -SK_ACCX(1)*(Kaccx*OP(19,5)*SH_ACCX(1) - Kaccx*OP(19,23)*SH_ACCX(1) + Kaccx*OP(19,1)*SK_ACCX(4) - Kaccx*OP(19,3)*SK_ACCX(3) + Kaccx*OP(19,4)*SK_ACCX(2) + Kaccx*OP(19,2)*SK_ACCX(5) + Kaccx*OP(19,6)*SK_ACCX(7) - Kaccx*OP(19,7)*SK_ACCX(6) - Kaccx*OP(19,24)*SK_ACCX(7)); +Kfusion(20) = -SK_ACCX(1)*(Kaccx*OP(20,5)*SH_ACCX(1) - Kaccx*OP(20,23)*SH_ACCX(1) + Kaccx*OP(20,1)*SK_ACCX(4) - Kaccx*OP(20,3)*SK_ACCX(3) + Kaccx*OP(20,4)*SK_ACCX(2) + Kaccx*OP(20,2)*SK_ACCX(5) + Kaccx*OP(20,6)*SK_ACCX(7) - Kaccx*OP(20,7)*SK_ACCX(6) - Kaccx*OP(20,24)*SK_ACCX(7)); +Kfusion(21) = -SK_ACCX(1)*(Kaccx*OP(21,5)*SH_ACCX(1) - Kaccx*OP(21,23)*SH_ACCX(1) + Kaccx*OP(21,1)*SK_ACCX(4) - Kaccx*OP(21,3)*SK_ACCX(3) + Kaccx*OP(21,4)*SK_ACCX(2) + Kaccx*OP(21,2)*SK_ACCX(5) + Kaccx*OP(21,6)*SK_ACCX(7) - Kaccx*OP(21,7)*SK_ACCX(6) - Kaccx*OP(21,24)*SK_ACCX(7)); +Kfusion(22) = -SK_ACCX(1)*(Kaccx*OP(22,5)*SH_ACCX(1) - Kaccx*OP(22,23)*SH_ACCX(1) + Kaccx*OP(22,1)*SK_ACCX(4) - Kaccx*OP(22,3)*SK_ACCX(3) + Kaccx*OP(22,4)*SK_ACCX(2) + Kaccx*OP(22,2)*SK_ACCX(5) + Kaccx*OP(22,6)*SK_ACCX(7) - Kaccx*OP(22,7)*SK_ACCX(6) - Kaccx*OP(22,24)*SK_ACCX(7)); +Kfusion(23) = -SK_ACCX(1)*(Kaccx*OP(23,5)*SH_ACCX(1) - Kaccx*OP(23,23)*SH_ACCX(1) + Kaccx*OP(23,1)*SK_ACCX(4) - Kaccx*OP(23,3)*SK_ACCX(3) + Kaccx*OP(23,4)*SK_ACCX(2) + Kaccx*OP(23,2)*SK_ACCX(5) + Kaccx*OP(23,6)*SK_ACCX(7) - Kaccx*OP(23,7)*SK_ACCX(6) - Kaccx*OP(23,24)*SK_ACCX(7)); +Kfusion(24) = -SK_ACCX(1)*(Kaccx*OP(24,5)*SH_ACCX(1) - Kaccx*OP(24,23)*SH_ACCX(1) + Kaccx*OP(24,1)*SK_ACCX(4) - Kaccx*OP(24,3)*SK_ACCX(3) + Kaccx*OP(24,4)*SK_ACCX(2) + Kaccx*OP(24,2)*SK_ACCX(5) + Kaccx*OP(24,6)*SK_ACCX(7) - Kaccx*OP(24,7)*SK_ACCX(6) - Kaccx*OP(24,24)*SK_ACCX(7)); +SH_ACCY = zeros(3,1); SH_ACCY(1) = q0^2 - q1^2 + q2^2 - q3^2; -SH_ACCY(2) = ve - vwe; -SH_ACCY(3) = vn - vwn; -SH_ACCY(4) = q1^2; -SH_ACCY(5) = 2*q0*q1; -SH_ACCY(6) = 2*q0*q3; +SH_ACCY(2) = vn - vwn; +SH_ACCY(3) = ve - vwe; H_ACCY = zeros(1,24); -H_ACCY(1,1) = Kaccy*(SH_ACCY(2)*(SH_ACCY(5) - 2*q2*q3) - SH_ACCY(3)*(2*q0*q2 + 2*q1*q3) + vd*(SH_ACCY(4) - q0^2 + q2^2 - q3^2)); -H_ACCY(1,3) = Kaccy*(SH_ACCY(3)*(SH_ACCY(4) + q0^2 - q2^2 - q3^2) + SH_ACCY(2)*(SH_ACCY(6) + 2*q1*q2) - 2*vd*(q0*q2 - q1*q3)); -H_ACCY(1,4) = Kaccy*(SH_ACCY(6) - 2*q1*q2); -H_ACCY(1,5) = -Kaccy*SH_ACCY(1); -H_ACCY(1,6) = -Kaccy*(SH_ACCY(5) + 2*q2*q3); +H_ACCY(1,1) = -Kaccy*(2*q0*SH_ACCY(3) - 2*q3*SH_ACCY(2) + 2*q1*vd); +H_ACCY(1,2) = -Kaccy*(2*q2*SH_ACCY(2) - 2*q1*SH_ACCY(3) + 2*q0*vd); +H_ACCY(1,3) = -Kaccy*(2*q1*SH_ACCY(2) + 2*q2*SH_ACCY(3) + 2*q3*vd); +H_ACCY(1,4) = Kaccy*(2*q0*SH_ACCY(2) + 2*q3*SH_ACCY(3) - 2*q2*vd); +H_ACCY(1,5) = Kaccy*(2*q0*q3 - 2*q1*q2); +H_ACCY(1,6) = -Kaccy*SH_ACCY(1); +H_ACCY(1,7) = -Kaccy*(2*q0*q1 + 2*q2*q3); H_ACCY(1,23) = -2*Kaccy*(q0*q3 - q1*q2); H_ACCY(1,24) = Kaccy*SH_ACCY(1); -SK_ACCY = zeros(7,1); -SK_ACCY(1) = 1/(R_ACC - Kaccy*SH_ACCY(1)*(Kaccy*OP(24,5)*SH_ACCY(1) - Kaccy*OP(5,5)*SH_ACCY(1) + Kaccy*OP(1,5)*(SH_ACCY(2)*(SH_ACCY(5) - 2*q2*q3) - SH_ACCY(3)*(2*q0*q2 + 2*q1*q3) + vd*(SH_ACCY(4) - q0^2 + q2^2 - q3^2)) + Kaccy*OP(3,5)*(SH_ACCY(3)*(SH_ACCY(4) + q0^2 - q2^2 - q3^2) + SH_ACCY(2)*(SH_ACCY(6) + 2*q1*q2) - 2*vd*(q0*q2 - q1*q3)) - 2*Kaccy*OP(23,5)*(q0*q3 - q1*q2) + Kaccy*OP(4,5)*(SH_ACCY(6) - 2*q1*q2) - Kaccy*OP(6,5)*(SH_ACCY(5) + 2*q2*q3)) + Kaccy*SH_ACCY(1)*(Kaccy*OP(24,24)*SH_ACCY(1) - Kaccy*OP(5,24)*SH_ACCY(1) + Kaccy*OP(1,24)*(SH_ACCY(2)*(SH_ACCY(5) - 2*q2*q3) - SH_ACCY(3)*(2*q0*q2 + 2*q1*q3) + vd*(SH_ACCY(4) - q0^2 + q2^2 - q3^2)) + Kaccy*OP(3,24)*(SH_ACCY(3)*(SH_ACCY(4) + q0^2 - q2^2 - q3^2) + SH_ACCY(2)*(SH_ACCY(6) + 2*q1*q2) - 2*vd*(q0*q2 - q1*q3)) - 2*Kaccy*OP(23,24)*(q0*q3 - q1*q2) + Kaccy*OP(4,24)*(SH_ACCY(6) - 2*q1*q2) - Kaccy*OP(6,24)*(SH_ACCY(5) + 2*q2*q3)) + Kaccy*(SH_ACCY(2)*(SH_ACCY(5) - 2*q2*q3) - SH_ACCY(3)*(2*q0*q2 + 2*q1*q3) + vd*(SH_ACCY(4) - q0^2 + q2^2 - q3^2))*(Kaccy*OP(24,1)*SH_ACCY(1) - Kaccy*OP(5,1)*SH_ACCY(1) + Kaccy*OP(1,1)*(SH_ACCY(2)*(SH_ACCY(5) - 2*q2*q3) - SH_ACCY(3)*(2*q0*q2 + 2*q1*q3) + vd*(SH_ACCY(4) - q0^2 + q2^2 - q3^2)) + Kaccy*OP(3,1)*(SH_ACCY(3)*(SH_ACCY(4) + q0^2 - q2^2 - q3^2) + SH_ACCY(2)*(SH_ACCY(6) + 2*q1*q2) - 2*vd*(q0*q2 - q1*q3)) - 2*Kaccy*OP(23,1)*(q0*q3 - q1*q2) + Kaccy*OP(4,1)*(SH_ACCY(6) - 2*q1*q2) - Kaccy*OP(6,1)*(SH_ACCY(5) + 2*q2*q3)) + Kaccy*(SH_ACCY(3)*(SH_ACCY(4) + q0^2 - q2^2 - q3^2) + SH_ACCY(2)*(SH_ACCY(6) + 2*q1*q2) - 2*vd*(q0*q2 - q1*q3))*(Kaccy*OP(24,3)*SH_ACCY(1) - Kaccy*OP(5,3)*SH_ACCY(1) + Kaccy*OP(1,3)*(SH_ACCY(2)*(SH_ACCY(5) - 2*q2*q3) - SH_ACCY(3)*(2*q0*q2 + 2*q1*q3) + vd*(SH_ACCY(4) - q0^2 + q2^2 - q3^2)) + Kaccy*OP(3,3)*(SH_ACCY(3)*(SH_ACCY(4) + q0^2 - q2^2 - q3^2) + SH_ACCY(2)*(SH_ACCY(6) + 2*q1*q2) - 2*vd*(q0*q2 - q1*q3)) - 2*Kaccy*OP(23,3)*(q0*q3 - q1*q2) + Kaccy*OP(4,3)*(SH_ACCY(6) - 2*q1*q2) - Kaccy*OP(6,3)*(SH_ACCY(5) + 2*q2*q3)) - 2*Kaccy*(q0*q3 - q1*q2)*(Kaccy*OP(24,23)*SH_ACCY(1) - Kaccy*OP(5,23)*SH_ACCY(1) + Kaccy*OP(1,23)*(SH_ACCY(2)*(SH_ACCY(5) - 2*q2*q3) - SH_ACCY(3)*(2*q0*q2 + 2*q1*q3) + vd*(SH_ACCY(4) - q0^2 + q2^2 - q3^2)) + Kaccy*OP(3,23)*(SH_ACCY(3)*(SH_ACCY(4) + q0^2 - q2^2 - q3^2) + SH_ACCY(2)*(SH_ACCY(6) + 2*q1*q2) - 2*vd*(q0*q2 - q1*q3)) - 2*Kaccy*OP(23,23)*(q0*q3 - q1*q2) + Kaccy*OP(4,23)*(SH_ACCY(6) - 2*q1*q2) - Kaccy*OP(6,23)*(SH_ACCY(5) + 2*q2*q3)) + Kaccy*(SH_ACCY(6) - 2*q1*q2)*(Kaccy*OP(24,4)*SH_ACCY(1) - Kaccy*OP(5,4)*SH_ACCY(1) + Kaccy*OP(1,4)*(SH_ACCY(2)*(SH_ACCY(5) - 2*q2*q3) - SH_ACCY(3)*(2*q0*q2 + 2*q1*q3) + vd*(SH_ACCY(4) - q0^2 + q2^2 - q3^2)) + Kaccy*OP(3,4)*(SH_ACCY(3)*(SH_ACCY(4) + q0^2 - q2^2 - q3^2) + SH_ACCY(2)*(SH_ACCY(6) + 2*q1*q2) - 2*vd*(q0*q2 - q1*q3)) - 2*Kaccy*OP(23,4)*(q0*q3 - q1*q2) + Kaccy*OP(4,4)*(SH_ACCY(6) - 2*q1*q2) - Kaccy*OP(6,4)*(SH_ACCY(5) + 2*q2*q3)) - Kaccy*(SH_ACCY(5) + 2*q2*q3)*(Kaccy*OP(24,6)*SH_ACCY(1) - Kaccy*OP(5,6)*SH_ACCY(1) + Kaccy*OP(1,6)*(SH_ACCY(2)*(SH_ACCY(5) - 2*q2*q3) - SH_ACCY(3)*(2*q0*q2 + 2*q1*q3) + vd*(SH_ACCY(4) - q0^2 + q2^2 - q3^2)) + Kaccy*OP(3,6)*(SH_ACCY(3)*(SH_ACCY(4) + q0^2 - q2^2 - q3^2) + SH_ACCY(2)*(SH_ACCY(6) + 2*q1*q2) - 2*vd*(q0*q2 - q1*q3)) - 2*Kaccy*OP(23,6)*(q0*q3 - q1*q2) + Kaccy*OP(4,6)*(SH_ACCY(6) - 2*q1*q2) - Kaccy*OP(6,6)*(SH_ACCY(5) + 2*q2*q3))); -SK_ACCY(2) = SH_ACCY(3)*(SH_ACCY(4) + q0^2 - q2^2 - q3^2) + SH_ACCY(2)*(SH_ACCY(6) + 2*q1*q2) - 2*vd*(q0*q2 - q1*q3); -SK_ACCY(3) = SH_ACCY(2)*(SH_ACCY(5) - 2*q2*q3) - SH_ACCY(3)*(2*q0*q2 + 2*q1*q3) + vd*(SH_ACCY(4) - q0^2 + q2^2 - q3^2); -SK_ACCY(4) = q0*q3 - q1*q2; -SK_ACCY(5) = SH_ACCY(6) - 2*q1*q2; -SK_ACCY(6) = SH_ACCY(5) + 2*q2*q3; -SK_ACCY(7) = SH_ACCY(1); +SK_ACCY = zeros(9,1); +SK_ACCY(1) = 1/(R_ACC + Kaccy*SH_ACCY(1)*(Kaccy*OP(6,6)*SH_ACCY(1) - Kaccy*OP(24,6)*SH_ACCY(1) - Kaccy*OP(5,6)*(2*q0*q3 - 2*q1*q2) + Kaccy*OP(7,6)*(2*q0*q1 + 2*q2*q3) + 2*Kaccy*OP(23,6)*(q0*q3 - q1*q2) + Kaccy*OP(1,6)*(2*q0*SH_ACCY(3) - 2*q3*SH_ACCY(2) + 2*q1*vd) + Kaccy*OP(2,6)*(2*q2*SH_ACCY(2) - 2*q1*SH_ACCY(3) + 2*q0*vd) + Kaccy*OP(3,6)*(2*q1*SH_ACCY(2) + 2*q2*SH_ACCY(3) + 2*q3*vd) - Kaccy*OP(4,6)*(2*q0*SH_ACCY(2) + 2*q3*SH_ACCY(3) - 2*q2*vd)) - Kaccy*SH_ACCY(1)*(Kaccy*OP(6,24)*SH_ACCY(1) - Kaccy*OP(24,24)*SH_ACCY(1) - Kaccy*OP(5,24)*(2*q0*q3 - 2*q1*q2) + Kaccy*OP(7,24)*(2*q0*q1 + 2*q2*q3) + 2*Kaccy*OP(23,24)*(q0*q3 - q1*q2) + Kaccy*OP(1,24)*(2*q0*SH_ACCY(3) - 2*q3*SH_ACCY(2) + 2*q1*vd) + Kaccy*OP(2,24)*(2*q2*SH_ACCY(2) - 2*q1*SH_ACCY(3) + 2*q0*vd) + Kaccy*OP(3,24)*(2*q1*SH_ACCY(2) + 2*q2*SH_ACCY(3) + 2*q3*vd) - Kaccy*OP(4,24)*(2*q0*SH_ACCY(2) + 2*q3*SH_ACCY(3) - 2*q2*vd)) - Kaccy*(2*q0*q3 - 2*q1*q2)*(Kaccy*OP(6,5)*SH_ACCY(1) - Kaccy*OP(24,5)*SH_ACCY(1) - Kaccy*OP(5,5)*(2*q0*q3 - 2*q1*q2) + Kaccy*OP(7,5)*(2*q0*q1 + 2*q2*q3) + 2*Kaccy*OP(23,5)*(q0*q3 - q1*q2) + Kaccy*OP(1,5)*(2*q0*SH_ACCY(3) - 2*q3*SH_ACCY(2) + 2*q1*vd) + Kaccy*OP(2,5)*(2*q2*SH_ACCY(2) - 2*q1*SH_ACCY(3) + 2*q0*vd) + Kaccy*OP(3,5)*(2*q1*SH_ACCY(2) + 2*q2*SH_ACCY(3) + 2*q3*vd) - Kaccy*OP(4,5)*(2*q0*SH_ACCY(2) + 2*q3*SH_ACCY(3) - 2*q2*vd)) + Kaccy*(2*q0*q1 + 2*q2*q3)*(Kaccy*OP(6,7)*SH_ACCY(1) - Kaccy*OP(24,7)*SH_ACCY(1) - Kaccy*OP(5,7)*(2*q0*q3 - 2*q1*q2) + Kaccy*OP(7,7)*(2*q0*q1 + 2*q2*q3) + 2*Kaccy*OP(23,7)*(q0*q3 - q1*q2) + Kaccy*OP(1,7)*(2*q0*SH_ACCY(3) - 2*q3*SH_ACCY(2) + 2*q1*vd) + Kaccy*OP(2,7)*(2*q2*SH_ACCY(2) - 2*q1*SH_ACCY(3) + 2*q0*vd) + Kaccy*OP(3,7)*(2*q1*SH_ACCY(2) + 2*q2*SH_ACCY(3) + 2*q3*vd) - Kaccy*OP(4,7)*(2*q0*SH_ACCY(2) + 2*q3*SH_ACCY(3) - 2*q2*vd)) + 2*Kaccy*(q0*q3 - q1*q2)*(Kaccy*OP(6,23)*SH_ACCY(1) - Kaccy*OP(24,23)*SH_ACCY(1) - Kaccy*OP(5,23)*(2*q0*q3 - 2*q1*q2) + Kaccy*OP(7,23)*(2*q0*q1 + 2*q2*q3) + 2*Kaccy*OP(23,23)*(q0*q3 - q1*q2) + Kaccy*OP(1,23)*(2*q0*SH_ACCY(3) - 2*q3*SH_ACCY(2) + 2*q1*vd) + Kaccy*OP(2,23)*(2*q2*SH_ACCY(2) - 2*q1*SH_ACCY(3) + 2*q0*vd) + Kaccy*OP(3,23)*(2*q1*SH_ACCY(2) + 2*q2*SH_ACCY(3) + 2*q3*vd) - Kaccy*OP(4,23)*(2*q0*SH_ACCY(2) + 2*q3*SH_ACCY(3) - 2*q2*vd)) + Kaccy*(2*q0*SH_ACCY(3) - 2*q3*SH_ACCY(2) + 2*q1*vd)*(Kaccy*OP(6,1)*SH_ACCY(1) - Kaccy*OP(24,1)*SH_ACCY(1) - Kaccy*OP(5,1)*(2*q0*q3 - 2*q1*q2) + Kaccy*OP(7,1)*(2*q0*q1 + 2*q2*q3) + 2*Kaccy*OP(23,1)*(q0*q3 - q1*q2) + Kaccy*OP(1,1)*(2*q0*SH_ACCY(3) - 2*q3*SH_ACCY(2) + 2*q1*vd) + Kaccy*OP(2,1)*(2*q2*SH_ACCY(2) - 2*q1*SH_ACCY(3) + 2*q0*vd) + Kaccy*OP(3,1)*(2*q1*SH_ACCY(2) + 2*q2*SH_ACCY(3) + 2*q3*vd) - Kaccy*OP(4,1)*(2*q0*SH_ACCY(2) + 2*q3*SH_ACCY(3) - 2*q2*vd)) + Kaccy*(2*q2*SH_ACCY(2) - 2*q1*SH_ACCY(3) + 2*q0*vd)*(Kaccy*OP(6,2)*SH_ACCY(1) - Kaccy*OP(24,2)*SH_ACCY(1) - Kaccy*OP(5,2)*(2*q0*q3 - 2*q1*q2) + Kaccy*OP(7,2)*(2*q0*q1 + 2*q2*q3) + 2*Kaccy*OP(23,2)*(q0*q3 - q1*q2) + Kaccy*OP(1,2)*(2*q0*SH_ACCY(3) - 2*q3*SH_ACCY(2) + 2*q1*vd) + Kaccy*OP(2,2)*(2*q2*SH_ACCY(2) - 2*q1*SH_ACCY(3) + 2*q0*vd) + Kaccy*OP(3,2)*(2*q1*SH_ACCY(2) + 2*q2*SH_ACCY(3) + 2*q3*vd) - Kaccy*OP(4,2)*(2*q0*SH_ACCY(2) + 2*q3*SH_ACCY(3) - 2*q2*vd)) + Kaccy*(2*q1*SH_ACCY(2) + 2*q2*SH_ACCY(3) + 2*q3*vd)*(Kaccy*OP(6,3)*SH_ACCY(1) - Kaccy*OP(24,3)*SH_ACCY(1) - Kaccy*OP(5,3)*(2*q0*q3 - 2*q1*q2) + Kaccy*OP(7,3)*(2*q0*q1 + 2*q2*q3) + 2*Kaccy*OP(23,3)*(q0*q3 - q1*q2) + Kaccy*OP(1,3)*(2*q0*SH_ACCY(3) - 2*q3*SH_ACCY(2) + 2*q1*vd) + Kaccy*OP(2,3)*(2*q2*SH_ACCY(2) - 2*q1*SH_ACCY(3) + 2*q0*vd) + Kaccy*OP(3,3)*(2*q1*SH_ACCY(2) + 2*q2*SH_ACCY(3) + 2*q3*vd) - Kaccy*OP(4,3)*(2*q0*SH_ACCY(2) + 2*q3*SH_ACCY(3) - 2*q2*vd)) - Kaccy*(2*q0*SH_ACCY(2) + 2*q3*SH_ACCY(3) - 2*q2*vd)*(Kaccy*OP(6,4)*SH_ACCY(1) - Kaccy*OP(24,4)*SH_ACCY(1) - Kaccy*OP(5,4)*(2*q0*q3 - 2*q1*q2) + Kaccy*OP(7,4)*(2*q0*q1 + 2*q2*q3) + 2*Kaccy*OP(23,4)*(q0*q3 - q1*q2) + Kaccy*OP(1,4)*(2*q0*SH_ACCY(3) - 2*q3*SH_ACCY(2) + 2*q1*vd) + Kaccy*OP(2,4)*(2*q2*SH_ACCY(2) - 2*q1*SH_ACCY(3) + 2*q0*vd) + Kaccy*OP(3,4)*(2*q1*SH_ACCY(2) + 2*q2*SH_ACCY(3) + 2*q3*vd) - Kaccy*OP(4,4)*(2*q0*SH_ACCY(2) + 2*q3*SH_ACCY(3) - 2*q2*vd))); +SK_ACCY(2) = 2*q0*SH_ACCY(2) + 2*q3*SH_ACCY(3) - 2*q2*vd; +SK_ACCY(3) = 2*q2*SH_ACCY(2) - 2*q1*SH_ACCY(3) + 2*q0*vd; +SK_ACCY(4) = 2*q0*SH_ACCY(3) - 2*q3*SH_ACCY(2) + 2*q1*vd; +SK_ACCY(5) = 2*q1*SH_ACCY(2) + 2*q2*SH_ACCY(3) + 2*q3*vd; +SK_ACCY(6) = 2*q0*q3 - 2*q1*q2; +SK_ACCY(7) = q0*q3 - q1*q2; +SK_ACCY(8) = 2*q0*q1 + 2*q2*q3; +SK_ACCY(9) = SH_ACCY(1); Kfusion = zeros(24,1); Kfusion = zeros(1,1); -Kfusion(1) = SK_ACCY(1)*(Kaccy*OP(1,1)*SK_ACCY(3) + Kaccy*OP(1,3)*SK_ACCY(2) + Kaccy*OP(1,4)*SK_ACCY(5) - Kaccy*OP(1,5)*SK_ACCY(7) - Kaccy*OP(1,6)*SK_ACCY(6) - 2*Kaccy*OP(1,23)*SK_ACCY(4) + Kaccy*OP(1,24)*SK_ACCY(7)); -Kfusion(2) = SK_ACCY(1)*(Kaccy*OP(2,1)*SK_ACCY(3) + Kaccy*OP(2,3)*SK_ACCY(2) + Kaccy*OP(2,4)*SK_ACCY(5) - Kaccy*OP(2,5)*SK_ACCY(7) - Kaccy*OP(2,6)*SK_ACCY(6) - 2*Kaccy*OP(2,23)*SK_ACCY(4) + Kaccy*OP(2,24)*SK_ACCY(7)); -Kfusion(3) = SK_ACCY(1)*(Kaccy*OP(3,1)*SK_ACCY(3) + Kaccy*OP(3,3)*SK_ACCY(2) + Kaccy*OP(3,4)*SK_ACCY(5) - Kaccy*OP(3,5)*SK_ACCY(7) - Kaccy*OP(3,6)*SK_ACCY(6) - 2*Kaccy*OP(3,23)*SK_ACCY(4) + Kaccy*OP(3,24)*SK_ACCY(7)); -Kfusion(4) = SK_ACCY(1)*(Kaccy*OP(4,1)*SK_ACCY(3) + Kaccy*OP(4,3)*SK_ACCY(2) + Kaccy*OP(4,4)*SK_ACCY(5) - Kaccy*OP(4,5)*SK_ACCY(7) - Kaccy*OP(4,6)*SK_ACCY(6) - 2*Kaccy*OP(4,23)*SK_ACCY(4) + Kaccy*OP(4,24)*SK_ACCY(7)); -Kfusion(5) = SK_ACCY(1)*(Kaccy*OP(5,1)*SK_ACCY(3) + Kaccy*OP(5,3)*SK_ACCY(2) + Kaccy*OP(5,4)*SK_ACCY(5) - Kaccy*OP(5,5)*SK_ACCY(7) - Kaccy*OP(5,6)*SK_ACCY(6) - 2*Kaccy*OP(5,23)*SK_ACCY(4) + Kaccy*OP(5,24)*SK_ACCY(7)); -Kfusion(6) = SK_ACCY(1)*(Kaccy*OP(6,1)*SK_ACCY(3) + Kaccy*OP(6,3)*SK_ACCY(2) + Kaccy*OP(6,4)*SK_ACCY(5) - Kaccy*OP(6,5)*SK_ACCY(7) - Kaccy*OP(6,6)*SK_ACCY(6) - 2*Kaccy*OP(6,23)*SK_ACCY(4) + Kaccy*OP(6,24)*SK_ACCY(7)); -Kfusion(7) = SK_ACCY(1)*(Kaccy*OP(7,1)*SK_ACCY(3) + Kaccy*OP(7,3)*SK_ACCY(2) + Kaccy*OP(7,4)*SK_ACCY(5) - Kaccy*OP(7,5)*SK_ACCY(7) - Kaccy*OP(7,6)*SK_ACCY(6) - 2*Kaccy*OP(7,23)*SK_ACCY(4) + Kaccy*OP(7,24)*SK_ACCY(7)); -Kfusion(8) = SK_ACCY(1)*(Kaccy*OP(8,1)*SK_ACCY(3) + Kaccy*OP(8,3)*SK_ACCY(2) + Kaccy*OP(8,4)*SK_ACCY(5) - Kaccy*OP(8,5)*SK_ACCY(7) - Kaccy*OP(8,6)*SK_ACCY(6) - 2*Kaccy*OP(8,23)*SK_ACCY(4) + Kaccy*OP(8,24)*SK_ACCY(7)); -Kfusion(9) = SK_ACCY(1)*(Kaccy*OP(9,1)*SK_ACCY(3) + Kaccy*OP(9,3)*SK_ACCY(2) + Kaccy*OP(9,4)*SK_ACCY(5) - Kaccy*OP(9,5)*SK_ACCY(7) - Kaccy*OP(9,6)*SK_ACCY(6) - 2*Kaccy*OP(9,23)*SK_ACCY(4) + Kaccy*OP(9,24)*SK_ACCY(7)); -Kfusion(10) = SK_ACCY(1)*(Kaccy*OP(10,1)*SK_ACCY(3) + Kaccy*OP(10,3)*SK_ACCY(2) + Kaccy*OP(10,4)*SK_ACCY(5) - Kaccy*OP(10,5)*SK_ACCY(7) - Kaccy*OP(10,6)*SK_ACCY(6) - 2*Kaccy*OP(10,23)*SK_ACCY(4) + Kaccy*OP(10,24)*SK_ACCY(7)); -Kfusion(11) = SK_ACCY(1)*(Kaccy*OP(11,1)*SK_ACCY(3) + Kaccy*OP(11,3)*SK_ACCY(2) + Kaccy*OP(11,4)*SK_ACCY(5) - Kaccy*OP(11,5)*SK_ACCY(7) - Kaccy*OP(11,6)*SK_ACCY(6) - 2*Kaccy*OP(11,23)*SK_ACCY(4) + Kaccy*OP(11,24)*SK_ACCY(7)); -Kfusion(12) = SK_ACCY(1)*(Kaccy*OP(12,1)*SK_ACCY(3) + Kaccy*OP(12,3)*SK_ACCY(2) + Kaccy*OP(12,4)*SK_ACCY(5) - Kaccy*OP(12,5)*SK_ACCY(7) - Kaccy*OP(12,6)*SK_ACCY(6) - 2*Kaccy*OP(12,23)*SK_ACCY(4) + Kaccy*OP(12,24)*SK_ACCY(7)); -Kfusion(13) = SK_ACCY(1)*(Kaccy*OP(13,1)*SK_ACCY(3) + Kaccy*OP(13,3)*SK_ACCY(2) + Kaccy*OP(13,4)*SK_ACCY(5) - Kaccy*OP(13,5)*SK_ACCY(7) - Kaccy*OP(13,6)*SK_ACCY(6) - 2*Kaccy*OP(13,23)*SK_ACCY(4) + Kaccy*OP(13,24)*SK_ACCY(7)); -Kfusion(14) = SK_ACCY(1)*(Kaccy*OP(14,1)*SK_ACCY(3) + Kaccy*OP(14,3)*SK_ACCY(2) + Kaccy*OP(14,4)*SK_ACCY(5) - Kaccy*OP(14,5)*SK_ACCY(7) - Kaccy*OP(14,6)*SK_ACCY(6) - 2*Kaccy*OP(14,23)*SK_ACCY(4) + Kaccy*OP(14,24)*SK_ACCY(7)); -Kfusion(15) = SK_ACCY(1)*(Kaccy*OP(15,1)*SK_ACCY(3) + Kaccy*OP(15,3)*SK_ACCY(2) + Kaccy*OP(15,4)*SK_ACCY(5) - Kaccy*OP(15,5)*SK_ACCY(7) - Kaccy*OP(15,6)*SK_ACCY(6) - 2*Kaccy*OP(15,23)*SK_ACCY(4) + Kaccy*OP(15,24)*SK_ACCY(7)); -Kfusion(16) = SK_ACCY(1)*(Kaccy*OP(16,1)*SK_ACCY(3) + Kaccy*OP(16,3)*SK_ACCY(2) + Kaccy*OP(16,4)*SK_ACCY(5) - Kaccy*OP(16,5)*SK_ACCY(7) - Kaccy*OP(16,6)*SK_ACCY(6) - 2*Kaccy*OP(16,23)*SK_ACCY(4) + Kaccy*OP(16,24)*SK_ACCY(7)); -Kfusion(17) = SK_ACCY(1)*(Kaccy*OP(17,1)*SK_ACCY(3) + Kaccy*OP(17,3)*SK_ACCY(2) + Kaccy*OP(17,4)*SK_ACCY(5) - Kaccy*OP(17,5)*SK_ACCY(7) - Kaccy*OP(17,6)*SK_ACCY(6) - 2*Kaccy*OP(17,23)*SK_ACCY(4) + Kaccy*OP(17,24)*SK_ACCY(7)); -Kfusion(18) = SK_ACCY(1)*(Kaccy*OP(18,1)*SK_ACCY(3) + Kaccy*OP(18,3)*SK_ACCY(2) + Kaccy*OP(18,4)*SK_ACCY(5) - Kaccy*OP(18,5)*SK_ACCY(7) - Kaccy*OP(18,6)*SK_ACCY(6) - 2*Kaccy*OP(18,23)*SK_ACCY(4) + Kaccy*OP(18,24)*SK_ACCY(7)); -Kfusion(19) = SK_ACCY(1)*(Kaccy*OP(19,1)*SK_ACCY(3) + Kaccy*OP(19,3)*SK_ACCY(2) + Kaccy*OP(19,4)*SK_ACCY(5) - Kaccy*OP(19,5)*SK_ACCY(7) - Kaccy*OP(19,6)*SK_ACCY(6) - 2*Kaccy*OP(19,23)*SK_ACCY(4) + Kaccy*OP(19,24)*SK_ACCY(7)); -Kfusion(20) = SK_ACCY(1)*(Kaccy*OP(20,1)*SK_ACCY(3) + Kaccy*OP(20,3)*SK_ACCY(2) + Kaccy*OP(20,4)*SK_ACCY(5) - Kaccy*OP(20,5)*SK_ACCY(7) - Kaccy*OP(20,6)*SK_ACCY(6) - 2*Kaccy*OP(20,23)*SK_ACCY(4) + Kaccy*OP(20,24)*SK_ACCY(7)); -Kfusion(21) = SK_ACCY(1)*(Kaccy*OP(21,1)*SK_ACCY(3) + Kaccy*OP(21,3)*SK_ACCY(2) + Kaccy*OP(21,4)*SK_ACCY(5) - Kaccy*OP(21,5)*SK_ACCY(7) - Kaccy*OP(21,6)*SK_ACCY(6) - 2*Kaccy*OP(21,23)*SK_ACCY(4) + Kaccy*OP(21,24)*SK_ACCY(7)); -Kfusion(22) = SK_ACCY(1)*(Kaccy*OP(22,1)*SK_ACCY(3) + Kaccy*OP(22,3)*SK_ACCY(2) + Kaccy*OP(22,4)*SK_ACCY(5) - Kaccy*OP(22,5)*SK_ACCY(7) - Kaccy*OP(22,6)*SK_ACCY(6) - 2*Kaccy*OP(22,23)*SK_ACCY(4) + Kaccy*OP(22,24)*SK_ACCY(7)); -Kfusion(23) = SK_ACCY(1)*(Kaccy*OP(23,1)*SK_ACCY(3) + Kaccy*OP(23,3)*SK_ACCY(2) + Kaccy*OP(23,4)*SK_ACCY(5) - Kaccy*OP(23,5)*SK_ACCY(7) - Kaccy*OP(23,6)*SK_ACCY(6) - 2*Kaccy*OP(23,23)*SK_ACCY(4) + Kaccy*OP(23,24)*SK_ACCY(7)); -Kfusion(24) = SK_ACCY(1)*(Kaccy*OP(24,1)*SK_ACCY(3) + Kaccy*OP(24,3)*SK_ACCY(2) + Kaccy*OP(24,4)*SK_ACCY(5) - Kaccy*OP(24,5)*SK_ACCY(7) - Kaccy*OP(24,6)*SK_ACCY(6) - 2*Kaccy*OP(24,23)*SK_ACCY(4) + Kaccy*OP(24,24)*SK_ACCY(7)); +Kfusion(1) = -SK_ACCY(1)*(Kaccy*OP(1,1)*SK_ACCY(4) + Kaccy*OP(1,2)*SK_ACCY(3) - Kaccy*OP(1,4)*SK_ACCY(2) + Kaccy*OP(1,3)*SK_ACCY(5) - Kaccy*OP(1,5)*SK_ACCY(6) + Kaccy*OP(1,6)*SK_ACCY(9) + Kaccy*OP(1,7)*SK_ACCY(8) + 2*Kaccy*OP(1,23)*SK_ACCY(7) - Kaccy*OP(1,24)*SK_ACCY(9)); +Kfusion(2) = -SK_ACCY(1)*(Kaccy*OP(2,1)*SK_ACCY(4) + Kaccy*OP(2,2)*SK_ACCY(3) - Kaccy*OP(2,4)*SK_ACCY(2) + Kaccy*OP(2,3)*SK_ACCY(5) - Kaccy*OP(2,5)*SK_ACCY(6) + Kaccy*OP(2,6)*SK_ACCY(9) + Kaccy*OP(2,7)*SK_ACCY(8) + 2*Kaccy*OP(2,23)*SK_ACCY(7) - Kaccy*OP(2,24)*SK_ACCY(9)); +Kfusion(3) = -SK_ACCY(1)*(Kaccy*OP(3,1)*SK_ACCY(4) + Kaccy*OP(3,2)*SK_ACCY(3) - Kaccy*OP(3,4)*SK_ACCY(2) + Kaccy*OP(3,3)*SK_ACCY(5) - Kaccy*OP(3,5)*SK_ACCY(6) + Kaccy*OP(3,6)*SK_ACCY(9) + Kaccy*OP(3,7)*SK_ACCY(8) + 2*Kaccy*OP(3,23)*SK_ACCY(7) - Kaccy*OP(3,24)*SK_ACCY(9)); +Kfusion(4) = -SK_ACCY(1)*(Kaccy*OP(4,1)*SK_ACCY(4) + Kaccy*OP(4,2)*SK_ACCY(3) - Kaccy*OP(4,4)*SK_ACCY(2) + Kaccy*OP(4,3)*SK_ACCY(5) - Kaccy*OP(4,5)*SK_ACCY(6) + Kaccy*OP(4,6)*SK_ACCY(9) + Kaccy*OP(4,7)*SK_ACCY(8) + 2*Kaccy*OP(4,23)*SK_ACCY(7) - Kaccy*OP(4,24)*SK_ACCY(9)); +Kfusion(5) = -SK_ACCY(1)*(Kaccy*OP(5,1)*SK_ACCY(4) + Kaccy*OP(5,2)*SK_ACCY(3) - Kaccy*OP(5,4)*SK_ACCY(2) + Kaccy*OP(5,3)*SK_ACCY(5) - Kaccy*OP(5,5)*SK_ACCY(6) + Kaccy*OP(5,6)*SK_ACCY(9) + Kaccy*OP(5,7)*SK_ACCY(8) + 2*Kaccy*OP(5,23)*SK_ACCY(7) - Kaccy*OP(5,24)*SK_ACCY(9)); +Kfusion(6) = -SK_ACCY(1)*(Kaccy*OP(6,1)*SK_ACCY(4) + Kaccy*OP(6,2)*SK_ACCY(3) - Kaccy*OP(6,4)*SK_ACCY(2) + Kaccy*OP(6,3)*SK_ACCY(5) - Kaccy*OP(6,5)*SK_ACCY(6) + Kaccy*OP(6,6)*SK_ACCY(9) + Kaccy*OP(6,7)*SK_ACCY(8) + 2*Kaccy*OP(6,23)*SK_ACCY(7) - Kaccy*OP(6,24)*SK_ACCY(9)); +Kfusion(7) = -SK_ACCY(1)*(Kaccy*OP(7,1)*SK_ACCY(4) + Kaccy*OP(7,2)*SK_ACCY(3) - Kaccy*OP(7,4)*SK_ACCY(2) + Kaccy*OP(7,3)*SK_ACCY(5) - Kaccy*OP(7,5)*SK_ACCY(6) + Kaccy*OP(7,6)*SK_ACCY(9) + Kaccy*OP(7,7)*SK_ACCY(8) + 2*Kaccy*OP(7,23)*SK_ACCY(7) - Kaccy*OP(7,24)*SK_ACCY(9)); +Kfusion(8) = -SK_ACCY(1)*(Kaccy*OP(8,1)*SK_ACCY(4) + Kaccy*OP(8,2)*SK_ACCY(3) - Kaccy*OP(8,4)*SK_ACCY(2) + Kaccy*OP(8,3)*SK_ACCY(5) - Kaccy*OP(8,5)*SK_ACCY(6) + Kaccy*OP(8,6)*SK_ACCY(9) + Kaccy*OP(8,7)*SK_ACCY(8) + 2*Kaccy*OP(8,23)*SK_ACCY(7) - Kaccy*OP(8,24)*SK_ACCY(9)); +Kfusion(9) = -SK_ACCY(1)*(Kaccy*OP(9,1)*SK_ACCY(4) + Kaccy*OP(9,2)*SK_ACCY(3) - Kaccy*OP(9,4)*SK_ACCY(2) + Kaccy*OP(9,3)*SK_ACCY(5) - Kaccy*OP(9,5)*SK_ACCY(6) + Kaccy*OP(9,6)*SK_ACCY(9) + Kaccy*OP(9,7)*SK_ACCY(8) + 2*Kaccy*OP(9,23)*SK_ACCY(7) - Kaccy*OP(9,24)*SK_ACCY(9)); +Kfusion(10) = -SK_ACCY(1)*(Kaccy*OP(10,1)*SK_ACCY(4) + Kaccy*OP(10,2)*SK_ACCY(3) - Kaccy*OP(10,4)*SK_ACCY(2) + Kaccy*OP(10,3)*SK_ACCY(5) - Kaccy*OP(10,5)*SK_ACCY(6) + Kaccy*OP(10,6)*SK_ACCY(9) + Kaccy*OP(10,7)*SK_ACCY(8) + 2*Kaccy*OP(10,23)*SK_ACCY(7) - Kaccy*OP(10,24)*SK_ACCY(9)); +Kfusion(11) = -SK_ACCY(1)*(Kaccy*OP(11,1)*SK_ACCY(4) + Kaccy*OP(11,2)*SK_ACCY(3) - Kaccy*OP(11,4)*SK_ACCY(2) + Kaccy*OP(11,3)*SK_ACCY(5) - Kaccy*OP(11,5)*SK_ACCY(6) + Kaccy*OP(11,6)*SK_ACCY(9) + Kaccy*OP(11,7)*SK_ACCY(8) + 2*Kaccy*OP(11,23)*SK_ACCY(7) - Kaccy*OP(11,24)*SK_ACCY(9)); +Kfusion(12) = -SK_ACCY(1)*(Kaccy*OP(12,1)*SK_ACCY(4) + Kaccy*OP(12,2)*SK_ACCY(3) - Kaccy*OP(12,4)*SK_ACCY(2) + Kaccy*OP(12,3)*SK_ACCY(5) - Kaccy*OP(12,5)*SK_ACCY(6) + Kaccy*OP(12,6)*SK_ACCY(9) + Kaccy*OP(12,7)*SK_ACCY(8) + 2*Kaccy*OP(12,23)*SK_ACCY(7) - Kaccy*OP(12,24)*SK_ACCY(9)); +Kfusion(13) = -SK_ACCY(1)*(Kaccy*OP(13,1)*SK_ACCY(4) + Kaccy*OP(13,2)*SK_ACCY(3) - Kaccy*OP(13,4)*SK_ACCY(2) + Kaccy*OP(13,3)*SK_ACCY(5) - Kaccy*OP(13,5)*SK_ACCY(6) + Kaccy*OP(13,6)*SK_ACCY(9) + Kaccy*OP(13,7)*SK_ACCY(8) + 2*Kaccy*OP(13,23)*SK_ACCY(7) - Kaccy*OP(13,24)*SK_ACCY(9)); +Kfusion(14) = -SK_ACCY(1)*(Kaccy*OP(14,1)*SK_ACCY(4) + Kaccy*OP(14,2)*SK_ACCY(3) - Kaccy*OP(14,4)*SK_ACCY(2) + Kaccy*OP(14,3)*SK_ACCY(5) - Kaccy*OP(14,5)*SK_ACCY(6) + Kaccy*OP(14,6)*SK_ACCY(9) + Kaccy*OP(14,7)*SK_ACCY(8) + 2*Kaccy*OP(14,23)*SK_ACCY(7) - Kaccy*OP(14,24)*SK_ACCY(9)); +Kfusion(15) = -SK_ACCY(1)*(Kaccy*OP(15,1)*SK_ACCY(4) + Kaccy*OP(15,2)*SK_ACCY(3) - Kaccy*OP(15,4)*SK_ACCY(2) + Kaccy*OP(15,3)*SK_ACCY(5) - Kaccy*OP(15,5)*SK_ACCY(6) + Kaccy*OP(15,6)*SK_ACCY(9) + Kaccy*OP(15,7)*SK_ACCY(8) + 2*Kaccy*OP(15,23)*SK_ACCY(7) - Kaccy*OP(15,24)*SK_ACCY(9)); +Kfusion(16) = -SK_ACCY(1)*(Kaccy*OP(16,1)*SK_ACCY(4) + Kaccy*OP(16,2)*SK_ACCY(3) - Kaccy*OP(16,4)*SK_ACCY(2) + Kaccy*OP(16,3)*SK_ACCY(5) - Kaccy*OP(16,5)*SK_ACCY(6) + Kaccy*OP(16,6)*SK_ACCY(9) + Kaccy*OP(16,7)*SK_ACCY(8) + 2*Kaccy*OP(16,23)*SK_ACCY(7) - Kaccy*OP(16,24)*SK_ACCY(9)); +Kfusion(17) = -SK_ACCY(1)*(Kaccy*OP(17,1)*SK_ACCY(4) + Kaccy*OP(17,2)*SK_ACCY(3) - Kaccy*OP(17,4)*SK_ACCY(2) + Kaccy*OP(17,3)*SK_ACCY(5) - Kaccy*OP(17,5)*SK_ACCY(6) + Kaccy*OP(17,6)*SK_ACCY(9) + Kaccy*OP(17,7)*SK_ACCY(8) + 2*Kaccy*OP(17,23)*SK_ACCY(7) - Kaccy*OP(17,24)*SK_ACCY(9)); +Kfusion(18) = -SK_ACCY(1)*(Kaccy*OP(18,1)*SK_ACCY(4) + Kaccy*OP(18,2)*SK_ACCY(3) - Kaccy*OP(18,4)*SK_ACCY(2) + Kaccy*OP(18,3)*SK_ACCY(5) - Kaccy*OP(18,5)*SK_ACCY(6) + Kaccy*OP(18,6)*SK_ACCY(9) + Kaccy*OP(18,7)*SK_ACCY(8) + 2*Kaccy*OP(18,23)*SK_ACCY(7) - Kaccy*OP(18,24)*SK_ACCY(9)); +Kfusion(19) = -SK_ACCY(1)*(Kaccy*OP(19,1)*SK_ACCY(4) + Kaccy*OP(19,2)*SK_ACCY(3) - Kaccy*OP(19,4)*SK_ACCY(2) + Kaccy*OP(19,3)*SK_ACCY(5) - Kaccy*OP(19,5)*SK_ACCY(6) + Kaccy*OP(19,6)*SK_ACCY(9) + Kaccy*OP(19,7)*SK_ACCY(8) + 2*Kaccy*OP(19,23)*SK_ACCY(7) - Kaccy*OP(19,24)*SK_ACCY(9)); +Kfusion(20) = -SK_ACCY(1)*(Kaccy*OP(20,1)*SK_ACCY(4) + Kaccy*OP(20,2)*SK_ACCY(3) - Kaccy*OP(20,4)*SK_ACCY(2) + Kaccy*OP(20,3)*SK_ACCY(5) - Kaccy*OP(20,5)*SK_ACCY(6) + Kaccy*OP(20,6)*SK_ACCY(9) + Kaccy*OP(20,7)*SK_ACCY(8) + 2*Kaccy*OP(20,23)*SK_ACCY(7) - Kaccy*OP(20,24)*SK_ACCY(9)); +Kfusion(21) = -SK_ACCY(1)*(Kaccy*OP(21,1)*SK_ACCY(4) + Kaccy*OP(21,2)*SK_ACCY(3) - Kaccy*OP(21,4)*SK_ACCY(2) + Kaccy*OP(21,3)*SK_ACCY(5) - Kaccy*OP(21,5)*SK_ACCY(6) + Kaccy*OP(21,6)*SK_ACCY(9) + Kaccy*OP(21,7)*SK_ACCY(8) + 2*Kaccy*OP(21,23)*SK_ACCY(7) - Kaccy*OP(21,24)*SK_ACCY(9)); +Kfusion(22) = -SK_ACCY(1)*(Kaccy*OP(22,1)*SK_ACCY(4) + Kaccy*OP(22,2)*SK_ACCY(3) - Kaccy*OP(22,4)*SK_ACCY(2) + Kaccy*OP(22,3)*SK_ACCY(5) - Kaccy*OP(22,5)*SK_ACCY(6) + Kaccy*OP(22,6)*SK_ACCY(9) + Kaccy*OP(22,7)*SK_ACCY(8) + 2*Kaccy*OP(22,23)*SK_ACCY(7) - Kaccy*OP(22,24)*SK_ACCY(9)); +Kfusion(23) = -SK_ACCY(1)*(Kaccy*OP(23,1)*SK_ACCY(4) + Kaccy*OP(23,2)*SK_ACCY(3) - Kaccy*OP(23,4)*SK_ACCY(2) + Kaccy*OP(23,3)*SK_ACCY(5) - Kaccy*OP(23,5)*SK_ACCY(6) + Kaccy*OP(23,6)*SK_ACCY(9) + Kaccy*OP(23,7)*SK_ACCY(8) + 2*Kaccy*OP(23,23)*SK_ACCY(7) - Kaccy*OP(23,24)*SK_ACCY(9)); +Kfusion(24) = -SK_ACCY(1)*(Kaccy*OP(24,1)*SK_ACCY(4) + Kaccy*OP(24,2)*SK_ACCY(3) - Kaccy*OP(24,4)*SK_ACCY(2) + Kaccy*OP(24,3)*SK_ACCY(5) - Kaccy*OP(24,5)*SK_ACCY(6) + Kaccy*OP(24,6)*SK_ACCY(9) + Kaccy*OP(24,7)*SK_ACCY(8) + 2*Kaccy*OP(24,23)*SK_ACCY(7) - Kaccy*OP(24,24)*SK_ACCY(9)); diff --git a/matlab/scripts/Inertial Nav EKF/Magnetometer.mat b/matlab/scripts/Inertial Nav EKF/Magnetometer.mat index a4525f229589e6159b2e6c1e504c7a8bc3566425..c302dd2ae05bdb092c29447191a3b9b759b5d237 100644 GIT binary patch delta 18875 zcmV(&K;gf;kpY~T0gyKoO<{Q;ATb~@G&(akIxsmPGB7bVkx?U&Utr~-fdNB{tM zoUC`r4(!Nr?d^6;wroi7`vtG`zy;??fEQ$Oo{KZNF*p{<;yf0)^5=NzPx0q?`PlBO z*R2b+R!$(0b%L3!AQ>5P&L6&f`SQo&%a`BY^FQ47yDvYD-+aa2-S*%4PxFuC`>*)R zce4H?{=;oy{`3Ct|H}S9+fRS~AO7dscVE}&57YVceg63u_xV3x*MIl_=O6xO?T`5P zw+VGy1amTu#r$vo_I3Y%Wk2u#`Tu^x|MX29Kd%4d_rLz!|NY%xuK)h4@B6R6q1&vl z_Q%`*pWpp-{m*0hvYg$QzdpYI75^{CcYg(c_gDOXj^|td-+i@j{Xc(vwQv2u`D)+# zfBV(G_5b}>`_}&tU+vf8{_bzs_ut^Z`v(8;4gSqH__yESzyI>TH~#R8dHlzp^X7-I z{$J+%pZ@XZ=l$oe_|AqQZT|G9avnNoo$LPf$A2l5%NHSdM|m4E=5@5H<*`~0Coq!` z_7f{NH8i|Oxoe^tp=E!BZ(uKUJ92?H4yMTjo#XUjKQTER8CiD({>rvP0$*&UNb?SH z6Yt5BT6t=A>V4QCS6Lf-x+(85SO6LA_pmQX3XN1-c~q||2C$UYY)?CY%OXYI0i$^- zTbjCnl$Aw6IcPR2{K}!P3)NkDYz!0@%SA=iw5dzkvd+eEO}HuwIUeflyF; zPwmi!rcpy8-*f9!eKW&PGHK;ijYrxd?FeuR^>BYU4(d;^9%%JY3VVOSB>ArNtLOn(rmO|ou2U`?2KgXP4XWdFR8m2wuq67)I zXlayBJHMC-AK9>=;1gwtsBDlZV*?7APKD8P`gpooK&5-7KzGe;K`>UFp?LNaDZXDF z_)v6JZ5w}ap9Z_y`L`GHP;Itmx#~dkx*YU5JzKzd@{-$ZbA$C*Jd-n`ZV!&`cA$i@ z7db7l?rcrIhVz~$!D|Um+?!Rr2(|HWFWQ)}`L(fN4+(o998?XgXG->?Jik_^uOGzA zJ%+48wcSHeOL@7Dw;LqSrQBo^-DR8jFl#ZLNVtEa@h(O{Hd?XNp?&ga|7eV4D+1Dg zJXdYbUB{wwK+a_@Oz3TelE!)?J|+;7B?4OIEbGWZE^A`MA^<#$K*WG85_R?;m9)Lu za$0PYP5^h4VOa^a+UO#JsE`LW3J6fsDL|-pDI;pkHN?D+s#_KzD%Qq!K)zyxN?GAL zi2#4s&b!lLYl|0d>Y0S(9dKrI^joim`@fqCmXypo>oo1UWDgnZdRD#de)4u&nEq=DS^tCen$zRlT`QPzb8J}^*-rZPUT23;>!Ga;NJH_fi9{H#1s z1mK+uPIO6AheEd0EL#-%dlTYf0})JUQdB@wbOvr217Z20SNLTQDxd;Y<`iXH5nU~O)P&M(|4h- z#<+qSlq6j~g9j62gxCS=h$Q{|N->|hq|YO~lb0ecj&yyU!At?*x6H428t^lC^_&aqErJP@yeN|ITazZB{0h1_tARC(ujEQ_Zz&y{W`< zV9`04xGA1mM?rHIJw$)D46j(ve1n2NIYp?wWBLgm6f+~xTB$J>>3Tv|;xl7il4xZh zGvCcy!X6opOYQJh^RVxpg>Fz6RTg121Is2+&Bl#oYYHG^oxAe7qsCYQyJ#gvUR#+T z28DrbeqC9Le{y}T#Oqn?SS-uYg45%RI9*|5T99!cdVUds=(A!~vzRzmD^Qtj35#PY*XOz;wsd6fp+ zUCOrM-MpT1Z!?r!Y1M%(kpM7Y_B1tlO(}-uW%-e`PFH`nh!g=}7o#7fBfNke@f~fc z8EgxkT=D0-Hs7+jBOz5;S89Uqxp%BfTY%C%T{C^2G4`OhN{C_;jjXNT`D>TMwVFW~ zY}NUug*&o3TCa@U3vIToAhW*rgqs)BFmiL*)1@0laz2HPYr?yk-(bUs4`Hr=3T!^R zgA#Y~5R`vy2BqS$re1MZnus0^%Nl?nW9>s?F{}}J@>t2sL6V8m90;k*-o97OpX%{vn^c z_D0^VSj&{u86lf_87Tsfs-?JWE4`b04XeLw9jsU*dOwwRRE25YtzfthZ!PC-b^xmD z^hSSI z)Upgo%M8aS(EhY+da@(li&&_5J&@B`GN(hWwMQggKD4F-DwuET-Pn-kl!Z9trZ<%~ zgiS~DOdWEZ0vuq{>UQKsaDZqBLR57|_`gL~*@btnhd$>^gs9 zj#-&F@sZHOS*#)Sy_OZAkBc*5e$>DU0lFs}$Km)?p=%`E<&0qU5Rs`u*FWAtQea(0G)u)^&mcWM9tPMq+E~Ek8@6zSi=c#fW>( zFay*tI{HXC-Pt;!O6rE~HfHR|r5axTu8<%3W>B3neh72I6v6y3{_csOuo#`c z?z|MNRf7uSTJ6C}yB^(Fm=p?op7~-mP}6GWdKvB4j50w>5LbSe9tjt!E2e)_tOYVP z&?tY&QuGtnAymXZP;jJF4$`dHpPoBD#4d3Uy6LvihZ3dncMBvxLm*inO|%?o$RFTh zhY$+SR?9DEf}D8LZ&P-XHj22;MLPL_nvCI<_UK`kakq`o>z^lJEPT2X3C+)<%+WB{ zJ1azI1jHZAB|C)Mo7i-z$E5DAPsKsu{J2ROiS#SQ2q21noS zH9r$}1l;|S4h#%p20b{J+(asc+=$U@OF#4KS)*KG-L#U~hmK~*7I@eMYLo-{(vIXc zp<6!*D+#|Ib7BhndwO1Xci(*BLzd46&Pr5Hv^^g{+A*I)EL4ARnunl_!Z5tQdQA*n z79~RKGf!A?vzY1X3ZC>XTux_Ol1ioE*ph)~fL7uoj3*;jfO)hgl${u)J%;kqeF$pY zGw_9ZO_ee%nRfJUza9d7fe2J1*2%)c(H&iyX0yx^I(YY7~DBrEJ+J4Ir?8pG^5doB6V{Z)W$}vlc z?wrA-ZQwY6T4|B_Z(+@(gJ236QGnB1(>*|$Hw+pecC1L5het$VYg0P65H@zD{`7pS zAD9i+CfBc295KNC>OP>p5%a?Wif2i6p+rse<3Tf!TMmC>>Q_et8jw~jHgUKWr4LaK z+Q`c?_wGUzSOM#U>Hs@LlKc&SvUxp6-iys;exMn^0x3AA%`bV_fBgP$^RW5%f62ps z#J|SFdi`#|eB>V-bnS7!*mxxHO;m~>Ud9zgYw5M@uxe=6cF~v7G&);~UbH4#-FQIh*^ zybS@v2~PI1fWtPX5Ha@qx$Q#`0+l^Rtkt*LoYYPGar)m;!%IxY%D9gc0JHhC7^>+Fe148N0>y zK0{WJ<`3tjS|QPm45cIasoP ztv`P^jiUv+%yw9V413ItQapRd=S>4o$-bP4s?@N>&{*+3i=-e>l^~1*_aWTN-V7q< zwWc%=l(YrVZ6@WeZ9){0@aDwlnATbDVSb=B@{=TU0orkrp`jkT$FOP+N8bc36 z!_shEdd8b=++TS!{upeiO|M%3&8-5g7sz8$7Thx51>LqJq@F)(XtAXIs=a8l9O8d6 z_JzEw5NrFIiV>KGzlEa=@MFE+W35=|ohd`QG4V3hBUr)_-;&S}Q4Z*!u|x$(%~B9- zHT1w(9dpuUh$=1tUIG={EE0Wxv}u3DSKy8F_5P@c1xVbh{!G0`CJ*ch+Ar*m#hddf z!tyLk7!2G4tLGV_UpX-YBPlCD)2|qXD?9vLKuq{FMG8;b!qIguLl) zyP~`!2kQMi$zj`ky2ZQMYmzG`8e`qm6BoUW;=1ib2<^h>rAALB&dGMmH2Pz1ab>`8 z0r*tw?)(UD9NmM_-LFXDL(k-+S%7?z#0{Q^MpeOZmv`(#QCIN6QIO3+0IvE&E2vl zz;kvf!0JRqxg>i0h_^1WtT2_{tCgs~Ez1gL%hcU=6n{x0& zFYdy5bKvZ)6A4^xr`CR)$KMBZ_%WfcAc4T^`}~ zX~p89;`qv17&Y}lc&mlGd9D&LG+i&IRPOn)C;8d}j#1QTG^A^FDbcBvy9HLMn15}Yc zv0UqIJ;-F_ky6a^2cjabThJeqHIB%Vx3&vR-!|c!Ixb{T+j*G zk~Sg6q<}f*k~M$IE1K#uwTxu}$5?O3b*bK0)IAt37y7<``nlD**^XuplGjLf?8zBd zTs1YpXqoP=Ddd5N+y0)7w%>cgz8d^o_5-R`xdDg%_6qTYPH@uAv?Qf`m@n7OtOyIL zt`^Em+eGG>5w6KEC-M3~?}fa(TlUezitjB>#nV@5XKjB)`?ol~CBXI2X|P!F9?DmW z%oQjcL%jlZIDnzRafQRb*5vw;ujwBfcftLPFbv+h7y+-T?{O^zRqplLE3T&rRS%Dx z{eJ)e0RR7#c}WiI$d=tVU>gPsWq1uWvJnIJT>&)^MX?h*u_tG2#lG*CQ==N!YP*>>0o$;E10h0`Ziweb+;e#@mB}OZGJLoan92OcN`vUBw+)rw$em{(pA1vO z+|GD~7KO;cMg~gB;DTCeA&r@)XRU$s6Pxsja--|gPSk>F@95Nz0~v68b^dqz7+@Pq z`0ch=vyC4?;X`Hz+kCAEr46D0Fk~6sU}6|rVora?w1^|O*YRK`+Qj#SUa+Bx^QYr| zDcpL(EBf-h@0hN}uDdZ9r=_4Ue`hcSd*(;_AZbi^I38uV0+kvlq-JiSs@aMPX;;T_ z*S>dUoCJT78YlKCxiJ7y2yiG5oT0w?(V{an);9LhVg{Or4&-LlMr3{*t5<~SVZIp6 zgv5Ur8j|e=g?&f*6C}cj4=!`7D<6C^b%WeKCyfab79?}NHN}95PW1{3yp=}ipaYd@ z)S~OTn-3e=`O)y|pussM?a3wQ8HYt95I=!loT62nlJ-kr4*e{lPp|d_?`3n!Q!bkD z2CMF8REUc2pm%`BobKp_J=}KvY-+M3`-y)b-)7pDAa0xwzBOZoCns!WpD>d1*V8NQ z*61f}Q9D-WFZL5HddIqB#tW}JHLWRL`$>Oqn#&;k z*s5A7s``~%!NPd8L^((S89{4t=wKk<-E_sMX31&xmAx*j` zzx?Gt-|zqB#((@d{g?mrYy5v7Zv5*%{CxlM`ftC+^V#-s_0RvDPkn1GQ`vq0`#)v! z<$5!+VXu$Vp&!gn-^Po7PVn-6e@4Oghu*L>{rxWa0qx5=N;Qe$S%k=T(xdfti#;Ze z6KfRNCnK?s@-cUDb3P#a6$r zqw)MIg}Ni2q7U29NqXR$Rr$rgEC`-VkchP*jsmBt75Ol|7grz+f~{)@B(WAcGP=)1 zhFP_0RkU>0x(_Daqpl)jBi)<{20Dt61&<(%Jk{Crk`MLTR?FxPs10`YjTX2R7uk=U zjgaO^J^dlxX{H&mPYQqVOYq#PnK^+L7OG8g+ zO~O(elQWAX4U=|X^MkC1oC{wS-lu|9?i9)b53Mg>6%EZ=;TL}gqsQ4)9_x1Bv&>4* z9lQrk@(JUg>VZ3yxGis3n1Oc?Jdr1Z^|f$-~&mJEy6xdp+LAJ<19d-n%YsE{ac_ zv>m}<6PCf+GCwn$iq&7Sr6&CwS4f9o@7{ft?|cGACvDv{e=vup{0do5{8}|6d#$X! zZ{^n+C-{FuO0W)`U^;Q1GSa8&0##vzj+Lh(E%Z+XkbI&Vq(zF2b6-?LR2)9b(AE-S zLdfwkq2lfx?`ZLZ&vjB+wxfayJ2*&Fg1T#UiUlIRpeyl=8zl4V(dT>#BK7zst$opa zw{Bd-F-?)F)=wnTB0TWBXq@=u=pkiVn85E9-*bOS3RRx*84mZMJtLl@L|R1@Bsq4i zL(dpOA)=Yf3&yTPyN$0j1N;dSA8b<&t!pDTjx}FU`>v7z%gJV8UJ^1ZUWYS|bnCR? zu)$zJrb40gi>FvkFdJBF4>C(N?4*XArI4<7uf_OO3%hO-$kS$)^-ziLogFIKN@t%{ zQR08FcInJ}J+`SEo)^feC=dNdkN70A^~v$|<_3Lcc~l-a-lW8u;c1HnA6L1;zBQQZ z18@Ks8<>bpGZ_$GZe3_a|YL`gvksKC6v-I70Z}Fh2 zdw<9L!_tYfRZ{@NNo7@~ABWvDggE9vk`*QSM&qn}psRWFPwX2lM;47SPqQes@kG%A zgI<~-N}J#!jd$Zw*Fvg7>hIqP#+6zCl<=W*FAg9?6tYjYNNE^2=!l*8K$ZKnl3Raq zak^$GKGm&KeUvJWxz@S|MB{?oY(MsN&=DVxdqs4RJOy6Uq&4dBAe{4Ir`IgnjTekZPd~N%w~U;#ltXIHB5YHqxF?fmVDIh^BSK zJ(~? z3CB3vcX4lk!LU#MT;Oe8clV<8wt_a*Adcyy5hTQbswF6d);Q!l>*|X`k6TGRm6o6r zfrhlI@PPPA>33?kT|=I&sM~+*$M1T9$2RQ|@5EV%Aot0W?9_=3^=)P^$o0O;U6?yTAj>7`P|*W9@rX0{d>Rq;y2jbYAlzLHNE$yz4izYz<2o3U@j;zV zA(u3@en~o?+S6bcsArzM5!$p1-83;p=jmrfABM8P=wyuGKoL42dRBihNlzubgQPPg z=d~laYy<5&bM`da`Bos{T!@y(xWR%M`e+QvEn$zq4~UsC^jzF`f5~8I-c1heZz(CG ztn+NY?bE`~TGbB3E=BU_>hK1~5jfR?k3-~ms~KTIQYUj~8Vu;c$Kw_#%&~bzA2Nze zQH%^FbEng=$o5oASC)SO)98xjQ!=uhva)z00X)T^3Ov%g9rHZMIp}xtg5I>a(Oq(< zK-y#??FS2ev_2;1cb@jv$s}DDRqAH5z8W6Z`Z>=MJj1M8h)#JbxY=9+{g_%64bx*y z6Z+0awp!*yJ6a64&j!XlU|;1YskQ;DR?MMx`5of&f*7=AH9&uCiEA6KyPzk|a&`24 zD73F#E&UFg>=`Ha3RCi=ZT!VtM-_T7QN6T&^j(Y&5zG*k)PyHkd z#`eZqS)iIQqFR55lkN!uv}%%M!Fc+C5=LCX_7AK&Ks|Z&|fLJrm zbc>!Zmm)>74%XuPH~RkH{_+2=@27wKTYdjy{D0E-or-@N#4B)j4!*Xqo6RdwWMN0+ zmj%wJ=fC3&s{5jEmS$GxLDyPSw1#KtDOlPy4Yx4pfhC=8jZgk{N+SD`6I~Rm$F>{T zi+k7J1|GxX@%+?sqq=U|GQLZA(>g78!Ahff4x5!BC^vVhiJa(3Yj;K1(s`wrb-QBJ z{obEZVZMKiV_s|xFbyQjTQxQN9Jpe3_m8;x6np~UP#HjUB-vOin0~%`=V^8=h!#aESq&(QB!4hMIvAYO!(zPS)$}v5o-W6i&1!E*z3B5$Y+t6(P z1^xR)A+@kOtM-EahQm zx5Wg=%doY}bcMw)B&F_zd4Z5@xe^t#&#dAA1NR8G+CrEUa<&g9G&Mp~Z&P+YIM!@S zlIO@RFiv=$Uy-H8v*VvHCvDg)w~k0VR$D5Pc-X})lDbGu9UD&SH@+K+T3?NYaoB=Z zstSMCTA|%~yQ(aYk-#ROxd#@biUOm7I357s*c*{Y98iyT)oHJ$-gM{evx(Up>)SJ< zFNG%N3_6P-z+B#IxckPuVXl`bK59f;i5=u{9}XN2aAxjkru10fyORE{PomxiF#S3- zFck$AY*%X=XJjs!To3*c2PpdyT@R~rF4%wAC26gcu}JQmVAViM>#_PS_i7RUeG}Sc z^4Y4{UDsmDZeql?+wdTBiV-hnqlWoDuS6ntt zfV11++_~mWkMEk@dZiTaBKx2!kN)UwyU_U>?AF{5JsifyM8WwJIBD(+epg%&g{6Nf zgVzkPwFjq{f^6~~{0SdH*ir|jiA6He<@=IFj8*Gy2O{71yE9;n+>-a%uKB%XIt!Zhk-JaaG~Cs`9aEFa zi#TZL?fJMR4=L8nRgx22!}lf=U{rr#U2xM(Hx6_}eb#r=aMwilW;fXJJfEK{k|RdQ z8?Xv(qNu5$CtB#Us__*qE>h=%y5xLbXS;K*8PgC=NkG}-y55)tB@~au03u^;`xp;$ z)J?uL9J9n762cTLv-;e_+s!m{R5LPQD**w`VwUCsS$fOHy)|=-@{)h)@ai=@ zRob#6_rg>|=5c`Ho{Y=*NmE+(Vi=>Zff8qlnOooT$l@MvHV*ry4!c`oJ;jRJC6*CA zw`|`VP!Jt~*vPs z!vX!f%lQGuj6)&#r9Dp!RcL?Qjo)T=k@@sy&VeYKeBhwCn|QF3r-NP#VKcgZ$>^Dk zls~EJG-(-KLL1K=VP!HHQEL%Xoqpj=WZaV5@p8tzOoq3FHTrP$6k^BmBBNb$vUeK| zhvCNboT9ul(0*nAZu&UrjF6IgmoIva06c~IYFsc8V1yn(y(*b^iV=S#5!`iO4P{hh z5S^mHRb?=C*V!OkW0`qENb+WDJN=$nBVGP=m>}h;lDe-^w5~gJI<41ochTop02^bq zT>S3p7v2iJlah|<%=6c zcGWDWu}$YEUTQQ_l0)k=`}$~=OPC1U?lp#x-Pq9VytCFJOt(udd^{~Sr)=|$5u|qZ zzMUe--Bkc@^VWZxWdUs=rR_O;J3fXDUV63;3wTY|Mn2ZuQV^4&vvFGKhV4|FhfVp~ z!Rp~6?8`xhSVYRiBfXaoTA%cg5#wApES4wTOUf_JCB15_iG)umZ^lBVzf>o4AZk*R zB*tus%I|%5(ai)Q+Wryu;#wI&h-v*hl=;RygN_29N=JW&JuOZWdyl?@OlOUaVmlj1 zCHOE_ydm~z8;#tI3tWN^Fl~cD1s%I!LsS}VWM23&#CZxKnuqdC4%P=y>8oj`gU5E# zBOt8Va~8^yu3*wu5n*A%yF@_1r#(P6~&TR=eNa9f3#p|Jk2K1TC1vXrH#s%43 zs%!>+g#~}#^zW9c=xaQH@1h4oO@uq$*X8|sH|R6jzeoGD$vEV}y5Uf(NV7r4AH+pG z{(|rAcG#pSJL^UXjRDEclV19}<9vJ_^>t3E9#80-&84RP#~vE&{WEpP(bXUS_UKh)#N-R(NuTlq_EU zn9zetI)MJem6<)N9SZdNRNHA~<*DbMaU2Wyfj= z5tKiBGAseXpG3nAA^GLKpdXyV)95n(j+{WqiMm-oWyIpavnpFA1*)fwsC zz}8UsyC)NJ#m3SkGhKNsT>YX!<+5s9W-^o`GSM$jCj4}rGIRSjovX9#mqJ5Q(%XC5 zthpHA{coO3&eLBXUmA16Cu!?i?}NkMhkX12T%C_S2&;O(MCBvRE4cXr_kH?>6$F3x z?cVR(T{Io)-CV&p9yd?FL%sP5@7w*uGx2Y})|;;%p59+^^Ob(lo3G*K3pGRM=Ie9w z^gEK9FZ}+2;^vFH`C2YFRBGiCCBN03RaKXps{`X=BhixMTwu?O9n_1x=O0Ma8NK5y zcbr(sC3TT&;Uip?#D?blm?c{M180Ayq%3wq*pNLry6=Duxy%zGkvxO$Labc6^5=f- zfBirFn1BB}Kjz>6Km3^bEqg=cxP>EaTgYm?Q%_@W)sdxJLk(B3W4O(&R^tasF-wdt z3-Z3@fDC`sr(}`ID!y3go34^5)@VmRUhm?Wyk1K;y|BF6u5b?Ter0q!v6z1^6v{Ru zrNm1^OY?DBYROHw0uib5a13@MzF#>f{V()lVX-jx~>K6iU zuxDhE`y$f8z!!YZPCVYcEen4tMLI0zBJBNHU5Y2JoRIZ&#%Czz|8D>Q0RR7ddC3a= zK9}7WNJ60LkZ0&sf)^g-v7r~`@;sNz^Uh;=p692@I!~2HiT_`Bpnr?Ra1bh4NY=eN z_Z*62ogRB_{x{Cls3mnet3!?U@XR`|RAM?!PR4_@Z*g`eiW}1WfZl)0d8X5ywtk4tFS#-l4V_$a+B4J z#G_rdtfBTSaZzWVZF!of=dWQBV8Y3{QTlW2=A0@^V_dcxNiddtm#0}mKY^e{>+mgZ zYw1%;VyRC3ayQ@iP;h^c-CzR_n_7e1-Q*r@cN8vt&!#0WGs#@<7OsgKlA+?8B0df_ z`uTE+p!iYL>U;fI(0O2s9KNxRQCl2DPVs+%(B`h zQ_Tm&jQz1QN|5-kRj02IF~RzK_xT*pbYL8_=%m9JA7g1zLPSeEoJG6>6=jKk9vb#`IITGpj|OGeWU=* zk_SiPHuph7wf^Bwr_Nz6-$nxLc; zf%6vVEc|SVMM_)f&{jtzA)zEtu~;-kjMJGD0rFW#SSo*H*mgJ+!|FrB?i`a7+Mk28 zTq}In=s;uVCd;_)tfWbPGMVsamJEVCR-|U_R(toA10$=;KLROY@?HDFCn~JzX6UHD zs^J&y@l_b#Sk1%Xwv7={n%atH>4hYf7C{LajpWTGJKL-#U`{tp4wON@>v_vPzT*qrhKT7pvf84$Ju&$%RT>k<-JxdxYH6+$<6+oYvY z9L3)L+yJM-=3KF;^Or^)ZIF^JP?FwnypI}8;Shg5^J)n!5zpc~WmHfXgqcGPbc^Wk zg`U8kaeMfE9Te4Zf3Gu@OIE{&-(0oO8-bSo1Z`HytvXXd{oXxmGY$g2j7@RsZ4S^j zp6NO>3b7QJ7#`0t`w)A3p=adml6poxyEszR-<}SVsJ|RYqV7G67VA)Bv4sC2Ea`NN`>x)ya9O?iBmVKA*Y`e)bv289sUsMZ-VX`+ zytplD79>jQKljfAS#c26F80z)+?2@c1Kf2{Uv{ddPyLDyF;9K0=lg}P1i1iTH5KUd z&|h@TC-tazXnB7j-A=0V@Tg=br7ZOc)nb2`B{24WFO=0@vA!8d8aGh#SEeV@zzK7I z#3<>Pf3h+-aZY z908@i3u@k3Jh9@0g>93l!9g9lM@nkEmXH)&=s6OU{2>lQk~1N@VFowx7rPKlcmID( zY$JAxk>XcCvdhBI(CuDcZ$VbvV`=EYp6O-*Sk&04Qx9&g?*gT7$~9_G$Pw`hU?ckw zXGGPQ#{5!ZI>@zWWPk#6|1}9}R`0!83J!QDvt8BhOHsQrMq}?LkA2}c#2x7twEN8Z zldvQr@`dKon!pSAo*BLAXdBbl6*+$mUT)riQujinyO;#l9wZ?S@@%Eyb((Lw;b5%A z59wy^k9C6KTegku|N z_Q~{g2CV{SVxv%e^9=WF33yabESrUq*tOxit7Ij>7*wgf%LyA~URKF`QyG6mFfBb2 z2bUCpTP@Hh$kHAF*{@Duv5ZA=%2UwXNoafGt^9Jx8RE(vT!ov6*4^L>m}C8{kIQ3f zNW@-doX10}@yoT;Nsjs)%WQC(11|QRsP!P5hj9!!b5O1mtVqn=~Mej3}m) zqP$>kzX_U-{OTs~CV20L3($XfU~;l9x@$B?*hXhP9FaA%VLgql zN8-5fRJrf1qiJ9H^@x9c()(83WzMxwiit{bT5pZvUDu+Peb`5jDBY|j#nlBW(G0NG zhAL5;MoZkP+2WSgenF=XQK2Z$8s?ckl`5&|{bN+mAt;@75xS6`y>!t;D?R7Y{&f`k z5*DNIyer<%n3oU)*+b1mG9#+4aGb^SZ~bm+i&<;6X|12EW>tT9zrkMvR)as!nArb) ztOJNN!3A}wex?+{{H;e2mkXQ|Ms{4 z{Ivh&!GHYMpa1rs{;mHX9`yhCukByYfBU!oa&<#e|MNc=^U!_Qx$1xa{hxB>_Ie$A zmiTxFhur(;rjCC^RvIx-hW+Jf?bQJbS5@(cE!U-IL)ub&^?QpFn)PePWhfR>YZ;Lq z-w{`p@+|Luae_!=fso*zU46~KYP8QwRut9d6X9$b5TRbuP2f?ExiDR4=Tl%>Nha9# zX}=cV(e;pVk7TDAm{}wL?tJ*U;OD!9Vz?)MkVnA7c}jmQJbtoKL%<7`$D*fdh_7M$ zCkPBoLP}$Bb1406Ti8h9dHgyQOnvV`R~~Nfn=n zC>A>7cyu72(#9fvZS=d;-wUJ3&Cd6+uX=aw^l+vrqDrpbG?wjCW`k< zDm=`(35S2B>_^o^mU_Vr0~Z#DIQo@34A!8M!p*BmIlsp;)iRDn(0N{QY4p;&1mKHqr9ZPhoUKZeg_Hx8NNoyPM)D`2 zIwM8=Vll_9=(L;IJ(iRJPru5jLz2ibWW>k`-)?_}mS20jq)Ax3ykb`@SYfZsD_U8Q z8OI(o`Cjx%x+oIG7ulM|Q~X4&c0bzBYVB`A=lp$Z*t9waQ-tsYsf9Gn#)(_p6P&BK zvDg(UOe;AIPg6Roox|Y)xrvgoz-FYw%4qBdC+Ludm9=M|E)#+qb3RF+jC|pmB~99I z4oiQXCtJw@|ACA66j}AfdPQ#SP)zec*Hf&lXBR;oSlFDHEh`>yRjg-aP41>;~zo%jugokUvX?j z7maX2=t~UjB+AF5G0ICX+lQnqC^7{@HPd zznu#OXPc6W0r-y}^$6!TY{r(usgi$uS46(4v|<7B4Nx_&aSf#}q7gC#qcQe03Tc0l zI9D~+`?J#6=a$h%V@i!_O{HIp(DZ#2eo6v$Bj2$hQ7?7{1K&j(Ik2v*}`j;8JD`jnsTL~niEmibBMM)$}TFxY>yL5iKn zXFX|6!nBa;^@j`C9)!``j~POMO$$`DSW_@yr^g#S#4-d8FwmlNMxJ7c@8`S6*|)aA z++lZ7Gb-LV=*v3DZ!z;v27MUD4~^j7Ob)(cbh)pJr?(hF=E&SE28Tk*ZS~^bUx>eN z+h-GD7UBH7DB;Y(E^5bvHK2dWz!T^0E7@S->R+@e8X>N;%7V5T|FElVrKTDzrXhBJO#+l ziGE2`11671#ype*Teg3=XG(~g3h{9WqXJ`59Mtm~rr;VibhLy?ZLTE7#HH5Oz)%_U z5Q4MEM`dQD-!$m{TCbM?{M^sj_Mlznxr47{|Ll#_!NcBo`n<5nO&nK%T)nC;^V|!f zZ)n0yJQSmugMJ6FlA1bycRuFCb!rga7Jfm;KR7kaa z2irN`OKQ5-4L7-JB+-`dE;JB%?!oULDQmbh&R?!X5&lENdLZuBEfDHyeeux8h|Jmj zIc_k*Sx`&q?UPKpLH7pBM2_zbm=`C3 zwXZ1^Qbsbi2b0R?12{7fgrPqS-)S>_PdKEK!^EJJAHaXlallf_W-6)HA6?z!NY+pQ z$3(0x3wxzLMeOaSt*S8f;yjVlh!kn(?j%-L82^UDvHVPrw!9R`sRO8*{-AZm zwMP|7p{;9++zG&y`w$pLpS{Eg448l!I2VBr+hvCtf)D!3>LNZcVpA#<`v&MM8+Odl z)2;cyvNrP4B@(4`m)IM$2gN3rzo^?tcNdV#^V=_4YH|1;?FXsH&^XtJGmb6SW3s`dm-bvyzqF5&AE@%qc(d4KZGS1 z?^A!l%Jk*Ty&SkZp6YUEhxa`#C9WOuYa#z_jnNK%=t!*YClzqRh|b_cvxM>arXFIw z{_h$V81uxBD09NFO$5hE0svwJwu6kwwxaD^g)q0cP|QB`gC zMb+FH$SUn`_(40Dv(rY8KJi6=55z7BUf6%1h)yv{U%`Mp=Mbt;Vu_q^1W~s6UH6Hx31rssHXa9tkoNwwIu_?RYO97n;V)h)Bf3@2S zbAuOu^;Uja%dc72M1%zkmf69No@ijSFvjl^1p5I?Od5V)|MGXQ_Lool-~aIc_i6v@ zAO7@dfA#-gKFwdy9q=Ew$3DQxOp6!ZGqS4cXA*;8`E`i;@jO@iuB>1nWNeeFG+k?p zu0xdN*h*m--nyp9lP{6w*~|pm?*$(^Xt?r!B5eA_^0KTAbtMLSO-BpRp(Qi0(NDLB zn-hkR9-%@kAXHpU*5ABk4KUOqDW0^1>Ebdd1qjrCR`f zq(%gUkI{Qpj%zY&S+*Fx`;_3#=xfrkqJ8qnK+<9+uE~pT(aT_o25$(&P$Y_k9X=L+ z1?S7~!m%U1WydH_Fe8Vo_>!w=GMI24)|z~NA&$-uvgVAT4&|#SB?$`F4al@XP@_`2 zXrKT|AEk1qAp2|8Eo4#)WQ_MKa@5&bgeSq_?qn_*R~ZrIO9A@S5VU`pNrDmt4n@j4 z)T=g>`UouUGLXl)2MyHNNWs?H#~jpu9>O}C@lB3(!u1y6`JwQ6z_=u^B|<$VfwlIZ}d^g+n~@>($H0Zx`_0_ zY?9;=iO5^OK;J5kMzZhB-<@{oBf?SYTdlPhJY}p=8NYh|o*1xeyQWrOmzf`bxr@{F z$0J+TFl{IX)fWP~Yv$|}BEL_CX4Kk-;9cpI{8vYmxYeS`N}{hTXv7f>imv>kd$}D_ zO@D8{B^BrTVY+Qkv^X&iO2UbMbCW5&qa4g#OP_&@hr|-rrK9L}=if3eRH5g!GEVLaEn130K6|BE;l>Wub+M;hD2- zH27tpb$$r0;G;2a*-x$*ZX3lnyrIy5d?>!SRoWhDJC>8!L3n8GF^J&2B}`7t&KWK| zF!fykqU?b674d{o5O%q?(Gz8ZhR$YT%Gy9htMC1SU$YHG)TUn^oZCdx+abr+w3T}Y}tN%ae|6aI4=l!^|f z3to$hCp1q)PE9zFJ##07oF|{{s*cI=NX5F@hN>4$#dqV;?pf*)POV(jeCy{h|ndvlkOc7 zCq}tb(9^rU#~F)#M0>>BV%DuNY76Y!?5ur{x<;IJ6ybfqCsWqG@So}ahob$O_i>`$ zGw*D`XI!Cw3mpo^>brMDv>PIz&J`qM6nqeR#)*_j$?rsgBoITZvA<%!iZp>ZaK;>F z9X*;EToPD(TEe+&KM2RurFRC)o+!>?J;)C|jOgTc%;1~=@?XajEM!F)kJC7&7JmwT0~C{i{#QmIv? zs#B*On~g6HvF9Qwrwmm*fNpH3#G(yJ*-giUD3ASZwQx01*217|RCAC$E*r7yS#^6u zdY0~g2G2<7WG)4KPCPpq`!;+SR~OuaPAx55?j#Mhz$Jq96-{$=acF9tirp}Ss>2Ml z)u}=AY@W9yoEZ@9?Dn=NvI^$_!;tl-Ws$Ni_Fx0kzPYXyU+y5cxrND67ldkiHCQ+h z`(9WDh9&~sAH|`97A;qat6qdwnAi)c#mPW_iPy32kWS1Tvx0qbBAYpcZZKy4?F_(n zXaN-6O#}pm#^NhOY1QncuB_Qe^+^?VLx94&Gg0b3utgi(29|gQz4?e}GP`Rq8PAko zc$~wc>w3SDzT5=V-IKG1KLw6DFv5n9O=aAaFyZ{iW7<-RZnNFEXUsD*Mbo??hH&kF z=OD^`SLf=f%_D({jQEW(swQ9|W9cnrv5>is$8rRk9bo z08~c+^5C>1T=Gs#rqZwlrppB@bG?)S+$mimJ6byXq(OVRa^{X_#&d!hiCB2`6)1DM zA(l*bB%9-nY^sEilzILj8-$hN6A7n(O&Kx+v7=Q>4@>aCWSHvam@^u=umm*cWZ4Oa zt~Baqng=?}ySu?|s;6i^#W8S>6(bOmk?No@`#5nMwy`ZxC%QUqKsdz_Mj3h?8z%Sl zkku;65iV{;s5iLwr`4co@nB$!Z5}>5Muo}7%wCWmEVi1}y+@9;5!a>A&Lu2=WV3FO z&j{hbI11e!!%im8s?xIvE6a5>qs3~YJG1eemuLe2$s}jdu(f90>E2x>LyIF^LzI$G` z=3@;ak1FQJnedZT;4a;X!dnV|@-@zPT|pf)&88r?1k%zD&QTU>-ow`_%jv7Vh8*Oa zU_gg7whUb`2*BcY$eMxAwzkMsE-(?u6G}2(x4-`O@_l}J;*TeOeB!4kzWgP>e0%3# z-?b0@%`bfNfBlF5!}s@|AO83J@1OEN|4SZy@_&8jFJJcNM_&Dp{?C0AZ~foi`P*x5 OZTDl(+x!WmO|kx+t4Ia_ delta 18003 zcmV($K;yrhm;t+y0gyKoL2z;)ATuB`GCDLiIyE&QGB7bVkx?U&Utr~-eRMF0SJ zoUC}q670y8-RqtvXE+)$q+gg76{i1U%##Y;s4D){b}u2 z{GV^($|m!sXc)5TkAM8OANtk)U;giB{GYzFU*@y@^4G_Ye?$N4@xx!iKl~N_pY8cx{}12fd;Nb;-{gD!Z@$U* z`rm$&@Ad!qO}^Lv(>M8BcK`5qIE?d1}b_kru(PI z86`j)&sX9#uSR@9aqWM>1CQ0&I1-7Uf!@q7TkL`HWEf-je9-SFTkd@wbHD>k9-8>3 zbKqeZZ`UZL`aN}sxq`W^0s%m;{TW${PgZT7)2gR+;@b*1P1YKk+g95+xEz{=Cwus3 zOQ1NKn5h1m<|hg)U;cxWEvm*&7nl8IIg>=IbBumRfW+mKCTEYML?RK@ zfp;PrqW*Gwo$)q^Oo*+3hO1M3fmVNtO9Db3x;)L7Ll!X63~u#ySY#LqMN;x)N$Dozqs?qyZTu z_OXq`g@E;nasKSfDPx_g&_Q@u5ZkCej7tQfCQQ-QwUHb%J8Ec$oP_%Y()=f`Hm_vx z-dCB|n41}^YrW5fj`8owRQ1E;l;r#=T z6;+dC;7@O&b3?rj02v{aXltu%&&THp%)R=w@(5l|XqGchPagJsv5N7|VVwyYBUR_J zK6uQAn+T6zdlYFq3~?gdQ;S5sQ%ZRpv_y_x3RF$U;o_#Q5lWuv;CB;7DN5L9K{HNT zS9;gyh46ohb#y-bQi6D2IPO|Q;oWtl9ru{*3O%RTAorH40!IA;V1YMIEr2^eo?tKm zK3$FRVwO&ocxbjwRTiPIr6XuZCg9v>Ve~oR9h?~HT3j`9rL%DCJV0Y9DJ;_TDH#7^ zh@Qp72p$odC0+X13yHztZBGjgyQX*vsPpN&S44m4my=1IC1>sWg0Z*WlD2fIV;EBO z8F9vF`Vm-VrT|{ zNTN)_S>l7*S`Q%&H(Tdu>oZk%VFlA0*~3p8Esg`UPw|Qlph<#HF@WY_5*Y6QAFc`UHOSooOilCv9$`{_ZI=w^4PEo*1ZD?8jRQk|Ip01el86zh_Od64#NI-w` z;^5L6U90rx0bgJ^Q6~1WFB)DPX160biqBzDDbV` z*8MyZia4xLbs4f)s(E}Li5XtfE)jpGcbIWoKrA!bIb%Ag8LJ@92iS<_T&G3W)w#*Jv<9gJ)*D^-$qrGHV~QYDwbnhr2|O2u#%AR^0@=k4 zZAu2=Da=p`n#1%E>x`P8s4GcK6qEaU*fI|a0M4k3`%Zt_b1!EX z@d@kDnso8yszTLZz(1QX%Z#8U0l^L|IIEu-OT zxTYa>*c|R8_0+Y6PPa0aw=6#FI>O>pw<0?i;Shw)XdkRK2%Ix>2d=_rk0^_aF+=H| z*L${b5^Pq~{nBNCW^;=Pc6EOQFFBbjl9YlM$Ybx7h6vLmxBQ_kJ>&sa!$NshWD<;H zkx^pKbn0n9?($Q|Ly^)fht5)g8c-L!(@7bq>%eZ%npS?eV{_Icf|`ig?vDG}7FtF# z8B^pvI0AE%^%{oor%L*g53di1LAY_sZN-7+&OB{So3yyuDvpu;Gv9w@cuis`;-Val z!iW@KAQgg-XSo~AijZXV#E?o~sJOSuJV17GB>4pzl4^}b;%qyp(%)5NoD_7H4YkKS zP52e)BP7U?OA*@WWqw9Bz#DvXZ@-dUeh=zA=tb+gHH`^%=s>u zDB{*Iz{``1atnN2VlRK2ei_+*CrQ_mz%XF;d`xNYeIhCQt>SHh`VMh2sGc%|{xabT zcu}lwT%h-1Hy`rrjFDV}6u>&0nyAMx3^_)q%J}@;7#g-Enyer_c!EP!05y#r!n1&i zmKowIY{&P3$(heK!rJT4%5NTlpI3Nw=gXH+^_>HQ&qZ))Abx)k{dL8~5=4JXr`e)Xkw33)?r}3nu_z|eb@K23`rm%xoB#2+@Z_U|57x3YU%!dQqpt0`DDX+Q!90qo;6i_Es|X|01Szn{C=zZ-(Fg*_ z=a-4Ha%ye%p~4h&jl>wR?gVV={fx()gp5xGcQOOXwQA*UYVc@tc&^(f$5wnLxK-ur z;h`zsDm#saXgm|xjL_&~#5w?{RbWr58OSZXmdGbTs@Rh|O^&ka?X+WKVVwMVG-yhh zh#MuEV4#1WB$?aNKf$NYI99y#l5nj2<*UtHa9A&cFVDANAtY5b&0j3pS{Pu()O@sA zx3&e5yvDF>F%_tUB{+IYBBbpQt$hBF?6JEPGk2tN^wY~F`7oSykSpeevdLKOK{@R^ z#sKDUDK93iN1yrhSg{hhyDSeFZ#rbrNWQ8O$+dssl^<8ZZCg>_v8stXr#JZS!>>fQ zS8-f@EK(o%+nL3iXMWZ*fpUr!0w@3#Q%4G}5CiRk6-0o@IzjhcpjRMcPuCgwCw3R( zHNgkG5$Pu1cGVg{C(CULA|~8-9Kbn%3=&ulgGi4Bjn5D=2Fc??sdV={fs#D`9PE*Z z`Xhg213FC7N819@<+w*2>vzc+IsAHw0u9^j zzHc#|9x(RM-p&XEsa&&*kdFV?TGNaAy%LT~KolrP;L1XeB5CZl- z#S|T+)gJGDV8i9XElv|)C^zKMw5-8l`uspufY^4LolZh+Nav`JcTUnd8L@KKD>aG{ zF7tMDczWTJyGsc-~`TClbbK|>*yl>^~OmYOJis$D~gQ0&z z7&*u}9<`%M3kMmOS}R1)%RCvisb`b-lhHj<=z|O=p#|E|sycsCwO$`GtZ5>_-6!2RQ#ZAX*n(M?GN-%X|JWup(bAx?ZoNuZz@jJ)HEwsQVOJN$ne@mqj) zv6}HB2h;}I-Ut?c^~i-B0o_$g4d9nE6@(5AJzAkO6{z*4>p^i6coo=yH4<&6np6yz zCW7Q4Ov4tkMH*mv4ruE$A7amOSJW~2#BT=zQzFrQvGr`2wEUnDj^1DU1oH;4EA~?` zbR~yrc~t$2-0^V2s}DQq-I#xQ@py@IbdiP6Gcandd#;Q{g%laeS~Caa-gflo%HGT{ z^HPxn&{^nMEAyTMf|K>E#+XJewBQAs>aJXFpeZ_1pCh|l%9)%jES_m@Ncx!K!+CrT z8DwUs==B=_G`hc^I9LnXCTYt%4IYF5*n)O6*)I;?-- zo=b?2bJbDM2;UGq(d2)o@r#WyvvMwJL#5l-%i zS;AC9Ngyfk0AF|=ptYoa20kbY!DCyWymuWAK|D=d%LD_ky8?^oF16>$mHao^p3yuU z>MO=;+a%DoQHXyv6?w|<=qw|2MG3_X0^%d-0KLJ^QJb4&8!~O^+E@U@;bkIoB)>&4 zx;Z(7fnG~r>E;1N39!ksIm^RFYr&N9=f&i!^2gGqZ9W7h+-d@NqiC8Y>%=dYH zPe#Y{;4@o646J;AD3 z1r+bH^yPnIzU;&}Gx@}fz#2bz`pg&+&D(Xr+I)GYo4?rL9?q>W zp(lrw<#VT6Q7v3F*&LU1{mVINv<*7KJN%T+CK@JbqVZjV#u%ghM17FwW(UYc)TmGh z;E%HcxJbUxq`~RO6&XGLQN0iUiS-hi7nTMy;|+gTOEx8duIgLbBt9|)u{N(7ndG`q zd?*dJHtS8s{+Oh`Pfe?d4N8~PT1ZR8#KI72)pIXt94g;c$-pqw6NP3oF+E{4Gm85R zOonT07q|Od9o>Xa3#ZCxt;}3Z@({Slq&m=U)smzgMhS=a_>9zbV*$&g`^^O7Hho+i ztMq^OnIIze+dM|g$efQNl}@%0X|p=%wW2zbM;9Qtdp@l>n)4Etl@}be&KExEU_TZ1 zjKJ8atjO4YkaAV*4kFxbxgX&+;7DM4tVNB8g10Rk@0~KAgi=U|X;wo5aYWq+8m%u@ zh@TUeLBe<<)M#U#99!l#&dWBT<)2ZzEfIgpY(gFpG`As6udI?Is*6a~-R5guSPtpq zj%T8twROk2F7qkpIPUfYB+c1YC^REcZETr5TK25TD(*N?PY3NitKadX(^Ii)`go-u z^zc;N{_c16_G2m;q)Fvvo8@Js9{@(v*i!XYts(MLQ+49qmM^&CRD{!sD&XB*9yxzH za+z&n>RxC0TJ#Pj2tH_zGS5Q`KbGcQ?@j3@4Rs2%(EChG218$(q@aOP7!Evia!E(<5Y2K!kv4!d7uJL! ztINwuhWf`7!i*|Uk+P(>Zkc{${j9z7qPfoma+Jh%|+)&f(w8|zI0gEV2q5HOhg5wdp_SGHJ5A} zZVm<-FNyB43BkH4&CA3gK;ck5QSzDXl^61Om(Z&P2&Yn{6kzQlE6v0loNR0rsH2U35L_#`j}EyX z48;ayA~T9D23oeKah14ZUD|dI?)L%{;MSGq29XuAv>N*LV}K%O6Ew3<8&GE+y4R)Z zs)}cn3Hz@W#MiK!M?WLz3GRQ-ql+$hr;y@M4>XM9hb9@+zz)yFy52A((-q|IBBveT zo=^is65ANkg)*R;njFu<34H?;y7WMv!j!0lviKxyJWfrV zBEmUVU(1RPGvnz+Q|7N&jsSI}tcUkBX^d_`qw%hG>>M5h`W8I#Zm zyh-H|I4WD7h*kp%&_=u+SY=Zix8e8wVCD7HMQSx5frP?uiu1+ z7SWW&LhCo*MNUz0xiEzh2i)bBqL7vWhD)H|`0|j(#8TPe1sNHpE_inrzS1MfMwk8qnr4F4ty(#T%*(U zK$d7PF}?|bPsFDdO+~AAKEv_uxuQ8lWI-Fdf_PA$Htnwd_C9|GWKyb&mzy?O*2qx# zOgG5U*Kl^Z6;_~}Ao{hRXaKoSMD6$FbM}ht0u(}B4$@^-4bSPYUdlW9Mc@F}>5Gs* zHZ>xnqyR3NH`x(qDF|Gm3-S|pv+_btpx1JpzL=C7w6Fu9Baz~&Zc3te^C)m;$+R>A zk&p@I^sXFYl^uV%sHY9OlRHHoTDbI4u~1!3i`5 z)Pcc6#|jgQQ|*pn2yicf6q^``dJc6p$aT>iiRN)%z+tX~1QfQ%(hxWi?F`;-&oP}* zxm$I4Q;Mza;$Y69D)S?leqGT*87|(C*hJ5s_}aI1UKM`=%laUpltEM)RPjY@bFPpB z11a`WoR9pwH#1?fdN0zNGE}$@>l=c)y~OM2pvvH{x?BBg@@t*79$kcH)Psd)%V(BKjZ?zw$yQs|wo<~n3Q z^vVTm{w{F)E5+LAKgS`P%O2eyQcTntTx!iI4m5vZgX1z6s73U2SMrV|QR610V(17u zl9J6|zf+Lp>8&N6<9y=w|eu{Gr2Si@&ZoUmf2^v}YSpap9r=vv) zZ9J}TeznE4fm9C#Y>(a)xR3du6WynDm~4@*#|MP{-1z!z(5a@AHTx9)kZ-g z+bbNg@qBWRulGsCt{12ISul^$`jv%ve&_e~*VcV)>9@n<^%juT_uan{8_i;B*i4XA zZLMq7&`G>z^G7oUVC(Lwle_=XI+9j3-~WmSX~HWD9_5XlBb zk!%xnSj|U>5S3j!m)9AX)^54LRkBxinjoGYH${q~u>A8k^% z8@LhnmqWvOVpZtxk8Jd^pXki~cJzNE^Zx%E7lpb0Xy1Sd<`?rXZ@jk4Yx|XidKNX| zx0Z6_HoU!H9L`lxc`lOx^^_s71rYHNSj zn~}x%_u*HJdH$}sucomuVbQsiin{{=DhL`dxoZ;zQoJh1!+rkCzx>mG`|E$N|NPfq zfBnyY`0KC#_}2gFz5e}Qf0zI8ulN7%z5d5P{9XSk|K(rr*SjCn=AZw$T*ltrmU{U8 z*MBOM=Nqisfqv|0Ky1{@4N08YZxVFEn6sKj+D@yvwcFN-QEMs9ii$K($ur|<0`f^f zA8B6iELZ0r{;WT{#J{T|#3X;RW-mopK&br&8DxwSueHU|A-O z9~m9*rz!`o-+s!{Nx|>ERuRn`Xs0`1S2RE*$z|hyJerw^pVNNwb?eZ07%JfRrH!Qk z+CoFagxu)+L=ARFrl@QlBxzPupJ{Dr_6!;i3~diwZnfUKOIX&&qSSwI(}C=3L2qbSYn5_aD|IC2k3}%MsYfVfl-r)-2 zNyS2>kZRF0EnT}_2j1v+u(aG_S7rhhuXmPdD1%$9rEhO4mK#wXBJnopnEZ$i9>* z6<+8NUZ=xbzs?A*(49#6RBG44OWctC{-{ezc1NPskc9#>YnClj7!J^%btNQ>gmoAa zB^n`2A*rW~qsLQ;7RsrULqAP#97O;~%Bs9W9|0Dgh z9;u_(t1@hgk?PL2Q(Rn2_B0inS<|3|;YV^8EQO1s8_$9zR>bP9*1{9ELO-&w6zhu& z<@&_$9Ox%I(hF*n?uig<+l)*5ebO@GAQ`UY@tU}oSF88v)YYPBrfTQV8or-a%8CL+ z@WQe&HhzMUa6Er65F<{4ZWfQh3K(<%kJ|1LcO6^U>0`J72WhuuOLP%A!gue=qLuE< z@M8(1K@m9F=@fq=((#EPKo)#y{9yhjb7?H;MNP2g6<<1+M8jp-O&Y})8W%>i@C-6P zcxSO%pvLMZ92R~5J*zBLUYTce!{tIwTYa*&mP# z&>+hem*%u_&c|yxNM26ugb~r?1FP%fK{9El$C-av0DydYxy>)^x57tpNNq~p2oirw zvfCMrz%hFT2OJs9@2MJJU{3+b8ihs4e}ja)3&>QYS3_h4ItL%YrQUViKopcv5eVR( zOu+T)7LxN7QxnHVTz3gl8)9?%t|XysHjN`t+MkwhW$ST~2UBXkPiER1UOq?hyU4sf z>!W{OciIK)?h9H5UTuALfq|(xGpO%UUt7KL%N;WJUW$XnvSKsSFpS%i4dj|f_mfi# zF@>#*Kg$pPOU^Mc@u#(nVcMa@?A=29y*j zWC+FHSC_aF)L>C+@_|1XNZ-)Vl7N$WcxI#aEGYSH*i-zx;GaNaXkg-HtmWz>VFJ=o z)+v;**L`3btNW%DIrO%b;vx6Y{egcpB{Rh!0l_{O)3Zv*K>y78iTL87T8$uyf%1%b zzSs~6ttw2h?Z)FYpLR5jRGdk*if<2jZy3OzYZR^)ntS&Is7C2b$pgYO;sE!pt5^4^ zTB&YQgkqsJJd~>fWatS@2a{6sU3_1lwCchF)skgOT`(Bb z5{rniPmkxqvDdsi`pDnD10=aq`K9wnDoN+1hlD#qAfPp0xg4*+l;a_)RV!?!O-^I6 z879LaIye?DT)t&r`uJ&7wMe-~)T0Z2erXy9^}}tqHup+tb*@6?V@K87=(d1ZJHJGh zuGj2#1rqiN^guBT zBWeKIWtv6)x`8U=r8nPLwuQ$K*?@?hr; zK{jr4CUtRgE+P5sY@yrp{!QI`s*m4lbSZoLR3Yo6h|kiEyoQ4d_Bov5mK;R)F2wx#0p@=TFJPzeKo6aOxHv5Yw_t+6)b($bwu6`8~6H;ZxN+7p!=A0B^H*hc97tnO3oy$wu8LAn+%7;T`( z3YadXz#6t$66<{M*z#N3{9VoDQ5%SvVMlU?$}7T)9T71ocAaqs_i!kHZe8&#T-;sz z!uc+_1=<4Xhb+}-Vh@!3(%kRS(AEqrR|r^Dv;>X(y}ZL_lT;q!S$0&1N|vIsd5ctf zr*waH8$zCX-A+k_5;Ok)6Y&(LX zet}?-#vNU2r;kDmA;CD>EWM$n1~wSL;Wu+HB^dinSpwMr)Q=NFlql+i=|?Kt)!W^y zDALb;J``|d&_zHb4`@BUPBR<=o+Nh@5H^1vqW0ef-7S3$NaErTec22^K(rYvB=JoB z=3r?glGkuGkqfP1wYeGaqGiL^y`0KOPl7N4H z8uZt~pz`I%A}UIsNW9~&Xc7<}JVsn&QIN@MFY?Wg@tCMlD9;yAdkmA7(4Jl;pv=FJ zs>hbhCLxyQIYFt;mgf4tOWnZ*TGMf!m@Wxu%%@!hi4USN_+Xe)YM^k@vm`cHh6X$+ zC3Im*uCt(>BwlBcSiNQ`T=if;pAjnJ!&7wdZjI4!8~m#9)I(cy#Rj;js|fefC<{7%9yLQCp2t&^zDJ z2B#He)Gpu&JhZu#neH3us(OFbbdOibgQAvlkcX1({5|N~09ZF_mCQ-9D z-JNSboq=x(I5z-_|M1xn=@D=NQaM<#!oxayQXAz-+yvpRdCN~K*g1bC`(a0Eis3c3 zYw=SEVDgLp(ahz;H9v@;aiE%@skZ=29U$QM1;3{M{h|jEz2W!^wzszeafOb-llzwm z)mMKwd$FQ?zk~9=@}=<#tO!(0V22k>>FE^vEtiH~A&IT7!iHs>#qgO&H;y^3i)(9S zrq?T+Pp!ZLWF>DMI&y#bY$mjKl5a*x*z9yh(F# zvsfY{iAzrcoHwE~M33{8=-i1H7+8D_-d`!MXtps#$DQM3j~o2)>~yJzbD#z)oGL0} z$=jp}itkWw%v;>4)W&Gc|S6X;jlr{aIdWq=*Zl3_4%-1eIHCJ{CWP*d9$SSGORY+ z?|kH~#DW@JhR)%YGrTeu_w73qC_l!b@6{Y?jquD-kJ2+% zzxVl>r3e|r$a8!;p%B=kcRb+?E1Sn5|H=gHHGIb@X)+u<``bjDISvPsdL#ZubZR6u zTt@lV42h_m32SA~nnc9oprhI+!i=fx$S(-y-JgGN84e>R4U=6WgV%<$#_J2%$Jr3O z@y1g`Uu^b2*w}vq_WoA=^K#n%%_;J7+I-UO<<$4S?RYM_Qw8sC^4iibU`f;0GNQ`P z`i=N#KE>;Q+s67ODt^9p3>vG9`S^C+kLRO1?`Xz4;?Zoh_a}OBh1}Oox`>Ze@tyCk zJ}G~qFb1!mBHKqiLz=9PM0`W}qKa9-L9Y&hPQDLb<&Ns1hl3zbcyf=9|MGw4DgQsu z=f(EV`MiU*8w7a{RoUv{LgU1ZaZy0OI@wf3b(Im3w;f7chnU3?-)UkygY8IzSM%BS zJg^KcvwVGyZ7Ki^m@%dz(_ASA7+)A{B?v)Xl(k%dyC0Rc8!&`e7h zHn?j1`wd+%Wa+{WtrY`Ij3=~uaXSm3{3=WG@f%w!Lv4 z)=1&w2NL)+b#IWbE87pGT*$X$)R%ud8=S3An588QbE*d>&L@4uSC=x)lpl5p=O!XX zuO>hfa?%B;@TgR5=bg)WT$CQdD1Rep&Z_pw%Y~KefYYgEuWA$bUV+nK#Qs!)Tz@5o zk_SOjb3uOuU|#x~_g9eojnh;b-davssZOu7hkhK8+2(Ij5;wmD;1s;15A237mvEjFz&`7oDNHIe@Z1aSYrfKtSk1aS^ zZc0BDg>}G?21w6mOXC{)A$Vm}jl7ZCTuY?XrP#fJ~3TvXZ8oUv7*ly?+d@A^y8@W^ErCTbz> zLVo>9Q=~&7*qVL_ttDP7xl{-#12jMc1+(MBKS%R{B$h1l#X?Lhjn#kloELL;bkZE2 zSPdpavKg!6BnOzP2SC6oxH3_%M#_{Nx0*0frC>?e_<5J@W(WE3X3^8XeH(o7QGw3S zeisY4jzc~=>Ti}61a?y*qeT2K00030|E-uu&h*N4hOY$Ka1acyK_eR+Fed{Vkj>O= z=1k5Qn>ptdcqv|wS7d+wy7$78;V?0QLZQxAp}$k-RJ~96bCPe_8BYY#BS(x&feA0+ z2~>LU!h;FQX%vy<4=qqotX-$k9f*HjY)0>Amsk)Oq5ax)I^5ilw}RQcU=DN}r@Ve> zqTdl2&(?Y0pbu3c+Z|Yjk;5@fsB46LHBY`)Yc|4UXP|4BIsAW1SqWrWBHiYYVI|*C z(OI(U>Q@0)!M$U)hWQm!ZaI!(=t2d#;wv!jzkl`+Qjw z4Iz{;Y*!@n&vQw*HFcU~Uh{l9%$&^L5`e0yK$gYP_ekT$hK%M>pFh7e5nrQTXnaW( zF>;9Kjg?eQ_=tb40$n-A6y8=&eg%P-LC)mgQiyAcv2IJbCk$=U7XeB+#w=jwtdhbb zmQ53mv>-M226Ffu0z#UMlibx6xqE}Kti%W)m=xl6a>J<{91 zg{qb=a&RU#lZG$I1JMZuzv-mGQRMAu%%C z3kNH5F6<%JE`9G#-mubLytoW#5ay2YdmQxP)z8Pa75H_M-;%6ekZA87VmTr*?rhc< zR4Rb2@kYrWQPcAiA86+2M>yghP*}e0C@i3HtC!T21Hy9_z;zt%y#Qp3{mP8F?y4$m zQNeL1JxG7GjU*MyEdt5C*&*QzbsLcRyg&PFj2-H;v#vFOl(N+8R=y53#T;KyB(i!U8;R>61afsW9c(|uJ%Gb2Sb!79|}0R2HHLP(4|@P1>ys#_YG%KYlReY9F2mAT2k}W=+P8g_sw5Ra-WC zf$e`jcJEjnk(AG@sm*TmwK`RHa@2W{eMh{HxuqnU^Kg;_G>K%x<*iHY0-~lLxcHR{ z#I8D}kMyjPv_SvTkIKz_?8-afU_j{8mto0p7XJAXoxV-ZM5#okusO?RR zl%(O4h#=msm~(7F6#c=wq0prf*Mk=M0RA7Kyy=4w(hHL^uJt*Ynt2E)7oL~(i-!K9GMS(JZv z&=vhVrXxB@VR1qP*RSa*Z57_Yl3NXW$QsEz!ns2CZ#$sz*a;(wG5lIZ)VWW~eavp$ zI9;^vqFvOnvm~{z1s*v>z7$g5lZm>z`hInS@)@XAf{c&|pcAhGFeWMc>%gICFg&w_KgDA%9qA3J|Or#+HLKfq3!J%_gN@zp|yBC zla28TUf#tTRc@}DOUb|sZA6&!cZE1z^+1JXM(WVF3s>i7jNL2UTwy2W!PiK?uL3Y_ z+G9DuFH$?!ynKlk#0wImvnM<<`>TeptK7xFS6C73ilOHujXXU=bc$JH`xJlKlnKa; z7Sz1gEiixl;~)O{r$2rF@RWc1{ZBvr^;7@NQ-1fe`KQ17rTv?y%)kG+{_*|eFYV>( zhNS+Ne<|jnv)8%mzyI`yT)w@ILJX8M-9tf02qC~v#@c>6T6;f_QH0_nQ$bO&!SS35 zTlw~;a?~PHNe=$F9Ou*eN9%v;FM%*$9A8>0sw^CMFi=ysHz}N^tiPD@9R=YPgw)y@ zMlApc5{XqE8Q7i|eUF1{3mmH1ed8h7i<%71k202JaH)t`6%Bnh1Kz(FXnQUu(id zXEr8$@6@d9JS<{}7lnGE|P#2PwR0zHT=_hLL~5KwDZGm&-U6 zqG(-z$k!fm>(=rR@LiEcqw6k81c<_OT!1H6BDpoApxW%7Hjt_rh$(Nv;M*iS^bz}> zK%eaCOP2DCjNnVs*g!Mx+_X>^G;mg;<)Q*Wjbyuz7|CzMN!B$VQE&IuD!Mx0`H%P> zei=#*e6Ayp=$-ta@?L)?a?_revRi?G@?^7*T7jNR)>kGn%z1Suxqb9m$qs?$z#R|( zt-V1ixJIk(uA-JXP}5y#6g2uLI^{^GC?Y1!^wV7py7u~w0;d_Axc+Q-dmeXBUF}8r z66K;SWOA8kC{&QnW0Q`gSLb3=xQKyG#@u3rv$l$PM6vPFM%aHd-U~^9wkYaa0s>IN zAG;=P^gYg|vHF-{$7h96p#xchbP}MdUQ>Q6$n* z?OXG~v=a%#J9%=}RA!DPmQ z;%{3o5ea(b7k(-Hbt-j!mhgZ$`5jF9`JG899t|-B_+oz;AFsii%k9`Ez&6ao(Ar-+ z93JL15_MAUsuXR}Ti3sfVUmiWi6>OWLI0I z^ljs4U_nO}q$DPc_$F{$(S%hyci16%8ff*m+x<2yF6xPS!=Jz-jMUY*(l9^WYt8BN zQFL&Dh8%w`Wb;vpxM{CXMt}imVsT+Z1Tj}-n#|ESiz@7H zdjNODApm`v!_WzIU4D%vN#`wNH)!8ET^X}0tC`s9>j6mEWl&4Ko^cvosr z-;o57QYQ2sle#5dJ%@8OcNY2elf$0|$WS+f$kcxkr7e2JYD^tTS%e!ht*?+4@i1Lz zD*=qHC0iWn^P0R1gu}LN0(kMcB$!8TY1>5QE`+RG_sH~K( z;pl$}@*o56M_rpMw--KKeGsh_0?V+PuX!{$N9G%<%FsggHClmN-fQ z;WhAe^$MohTgG|fgt#F0O>hm$v&(Mfsz5dEWe+$LME7<}MvsCN3J3=BI87``%^v+b zCR7T3s4tK&TBW`+F{bCsN1Q^*t$FZ$q_%(d_j}2%Es5xw(Bw#nZ&-r2;H z^#!q==eeHT&cIra3|l~x{LL|K17Ckacj8W9fOnM~uX{lV?F6e4o4NvdeNYPjK2W1W zo`;5dyfjAuLWsTSS&a_2j6I=tpUPaORdw*2? z65XO;D74)7fmwt)Zfq6u$)JDRniCT-_(U6kWx=*FQ5-dz#~IDdXodkGxoDatXj!o} z)ZLy2+2IRlGbuNkV<6wX*>tJj_Rx3KaBU z9@(NIipcz_%<>&AZ!TJxnP=;$VGjNNhEjBJ-On}SRUt)~wbOpJEoP9YR=Nr>-5ZYY?smUgHwa;+O%{7EF|hhfnWR7XdS=X^6|?2GhA%#J$x9a{V|GAAI{g7$UDaOiPi$D~+w0q>k<= zW?naBe@zkfIBkEMnMAW$B(D3%KiT6S;+s{2n8+6M7}@0%6+cDd$3O71r`GD5wf*=N z_P*LQ;0w$P(WJ$1E}Y8l{F7gQ`00u|?e(nJK2hj8Q8OI3YL#7B2a2A^&wBPZs2Egf z7)a@UE^~B;OUT7f=!h(r^~@oj-;j%ryZcc;*QQ;Y)djdBB*3Q*V-x-j+uEYQt zlAMO8%SNsLuQQmZW#6+D)N8T~(kFo2O?t9-eR%kw< z=ef#r+Dp+`0v7QRCpz=JMI1Bm1Y`vDn!m<$LWufzQDlg3X*t z)pVuY1xVN~QM%UZwVW5rqM6br2g|y3z;HUz2Mm7-dwMeI5x**Nb+&&PupzyvYk1{M zEfzyoJYFER*Gcwz)xnla^{>~_fbzZzB@1}LK@Gj* zg5XoWJjQjE2Y1$k}aFA`_{k`K@J$VZadx+K*$%aA8B2piRj8 z0~~+#9o#9)lX|Uue4XNyl@%nY3cR@kBeKlDQzrVDN}x%Qa6%ysT~ViA@G45G=0f0A zP_E8RLv>0LS(J>hBz^8dss+XoH|R$4;Jepd?fb3w^)){H>`pD@|U^a{(LzWNyO4=;6zuXV06)s+6MOMY&N@0jJ^RTLBO zGP^rVRTGweMayfaFv`DFeguJ|`sMIaD-weFlCn4*S# z7cwCgu0s2?XtZ1q)7$9NJW)RzB$*z#Rj*us<)(FR06w)-mzw00^s$*&3l?O@%5IO@ zk}&(6`jvvNJ~sPHD_=B4J<_h!D3I{hyJ>gfJir$sKMYC;YWiRcBAzGm>e>;3?_Ggv z|KVf8KsKCBCfbK1ZTa>`mO0if?me<}DQPQ&utxnh`DscZ1csZ}@(p(f_P;)Y zde%9W$7L`k(S+_ANh|9jJ7Mq5&aCs**AF{dBzJ(OidEXqVwZ7~>!wR%-6=Ul;6WH6 zPu5xh1{4oOUVo0Qhud&ouMih zm!z|f==#kEJ&J=0jTyp<92!-5adqgABCWFfy^U(wvKL^^0gx*-SE%#_?2CVYdpHML zu?!3sI~T@KbTbTnBU-K>hGHzrD;9qrfwE&&j6I&%0R2%O@J=v(yxHqKSgAM_hf>w$1MpS!tQWzrBs`mn%R^xY~E44{x z0bjhqGb=vG{($ZD-EXaXPSXp=C#I8E+=f3jhH}A>55!kG5mdQEsqc{lnzM-XUYmYy zx$kO=WEWh4q`No(yqFX$Y z1#<8qrZ-h|h7_8q)J{?ys45aW?av0DewFnGW575!cTU9a1@86ZRb5m2%7 zDT#829i~A&6LFF(0FZkT789Ow66{r_^uggH%eEsib?Qq2xiL^k0N&!>Wm5rCtVh2T zlm?ZpBnY9CyEiJo5#-8ce4r7t!>3o@JbBMcLANSsS(0C3jBktp);|)MdN78Gs}$ZVS9&0g{74YsA&&pAD|w! zpdx?2Brzj@QTBZ!A*y$e2zsqHSeZrJ&}?r;`t{=E*MjWAYZ z6-9OWYgs9}1lSU`g<#wrAN?}wa}S8;h&tB3y&lb478FZk9pRh*<^BGr|J1|3`7e6- zx4+nawg2c({aOFt{x|yhr@xrzcmMC>|Mkzt|LuP(Gd}pU{=faD{nKyW>aXLa|6~0> aU+>5IfAvfIN3Fhe``3AXeE$Jk&ifEFYyzJE diff --git a/matlab/scripts/Inertial Nav EKF/Sideslip.mat b/matlab/scripts/Inertial Nav EKF/Sideslip.mat index c0abe0b417cf0cf322dead6954e660c9050c6581..f6d8de8d86e8169e8e561aa1aa6b91afeb9d7bbe 100644 GIT binary patch delta 9448 zcmV>yXu%&Kp1AUZ=cy$g(&>3lr_*-&1$m0}JkMWnKaJ=6C0Bd_K3%7% z>Q+}nNL$Vwj19^f5-mc{Ndi$?_-R+_5A5Mzx~B?{^|Spum64h%^${o)BoWT zv8XeDjQTzs|NY;;&;Jkf=lMUs???S_|70EC#^+yu{kxg3e?0z&?|naf|BZb6?(gy+ zm;B?`AMgLvrZ3aceEIY3hhORcW&8SP^sj%W|EKl*Y5!k+mp|?Qf6aIKwda2Q3-ZIC z=zsOU_>Q02?|yOp*T4UH-+x-mFYV<&|L*7Y{Ns21+RZL5fB$mH9sRd|)58}vP

PeGI0(!~<9jo?rb|e#ScnzG z^P#+y3@`!oWP-b4FR_I*ML^1_OyDc#Y{xM`AKA;fx0$9!dhRe+z@IkeF+5+V)azz7 z8_^p+Hx)`_eQ;~v za}|65G5dqKuIPhNb7>;V1#AlO{CqN}d{_*$MjI8{O{Op@(=>tjIMQR}RIC6`!0k{G zU_c^{M{02uGa;b}L`!?H<8(idDbgIfSE=L1Y}w6ym=xGzqaYez2(~4YPW4Ravn5uc zPg~^4yzYb4e@`hXW})$UiK#HxGwu7^eGQjujdi72vfI^SL>KCe2jldR9r#=5*7H^p=?H-AOfFd7_pCOhX6!0Fihc9d6}5blNFQ zCbg0FK-Ty&g-mVLY&$#RgS{O)=Y%Elc86y?;)4{FWP<9+m+K%1@^~_G8;+lPw>FwC zPN*-Ge;A7Bazt`S;h-~vWomY6^=V>pjI!?-4T!o=`~wHU2%*5Xs7xh&fk|IhQnV~p zt@16V@W$>kR9o(X1|s>%0Z*HfXNlW$i^qbp>16|Rm{68hzhLFzXv{zdA%n?CjlIXy z+Yp@N7&=xHJSwDEOpe)q3OTjD>Ba!`SUqTje@%OAINgDvZbpo?8$*P|V(y6lksP$f zABeL0rq^4V2J=uDkhQsujyyckrLCC*!`;H8sBM5U0%5(^d4nDke^zynP!xEKQiu+4 zAt~;5r^dH{QBBXHbNdc9{2{+koF0Q@muw!JlbjvAwHBIZ9l;S2)&GLfTNQvMyIJ0)8ZVq z>+nodsN-hqWl;m9PNp{sY3(FZX zs5oq&&F2U{cHU3%;)B@>v}~70IqMW0e_sZwl5eebV|An+y#=prv7U>A!c4vBUZ%^8 zVWQ)Ea1SmE%b?|i<>W12fn;yxeMK@k0+`zlfrCUlkFNDv5}R~8A#3NWnU?SEEI6o< zMkno$O3O@_gPuce%#*bjegItj?PkPXb6`}PZ$LpRIHeBVch*)cv1-kWvn(Jne}T3> zg<-L3p*kaN7uOOtlY!k7fHEGyApw8crEFdPFww!DbD12_Vp*)CE~xV)>}8BVX5u>i zJBm&m$#`?XspO?kK$pX;cZXGls)avdm!qaOM_?}N^@J2yne^C>bYUtK8LwD z({c%V;_1P+n!dw4uVw30kZ{#Xf6HJ`O8OQXZNMe6Z;yQhCTQ)_=;2`&=zT{Lh3Tmm zE!?G5nhq+(q2u9}H`ooTK!e!>uItz*=d=c`Y~}5fI^4j``0b>JgK6B;KTrWCjwPIjA-UF=JUKT;+kxHYFdBh5~aX^O*dbTvDHvMPzm`SUX|ef41MpxGeffgM<2^ zQApb=f^FE$n;R4HT(iX4ZFIpW6t1t}#x&QxmBHi7{ad75;!qFuEGA|avXGdJ)&N}+ zm0YEp%Yl*LGbXH^%)rhM2U&b#-b^|ZGKfQUbm1Zu@=FGK(PWl(%2vX7hZw}E&UHfM z@IAZ3&>-QJb9dPUf7sme8H<~-qN|v>hb|X)Bf;))$m@IV2b53Aqpe30!!i8S7=9Dm z9|Mf75>~6|J~n!>RW-ngYNe;7c+?8Kg1NZ|^pk;M|6IFmRiyrS_vfiH0UP@*Ul&;%I_XOJCEcqCpmTOSHn|G|D-hau+X(e+ap-l)3ry8vD?5eEbDo{B(-)c3wTNpS0w(IB|l^%wj~_t1)E>vPI!D z&BcBGJl=2ylQvYp8|e)rNE!lZJuJpnLCWy?ek`V#Bsj$< zvMgCE!*=j(xaJv{!;6hO?)<(u}yyyu5Z$Tn1o_Bg% zRm*T;f4d{dPW0~KI*T3%$xo-z@kA{sy52lmJnPpumCg~HN>2s%E3R}UIX#)hjM#Lp z?7K>HF*9O#7}uYIvQ>uB4$l*;0#dGZG7eliZ_hF^nK&KYK{A!NlI3k`A)kZDaw6tI zt#6$vxg>YUo@VS|99V}RC7HYcVz+$*Z7?#ff8LOWokp~_d{%)Me;N8Kx_=;)=7nBs zc{$xvOL}Ezp%aS|%QL@sRfVaTdmqlxXYQr_z@_ZdLAg+oNyFPsBg46nT<9^Y^~qN2 zQ6@1Huf3`s44VNx4~Do=qvH%oZX!6-DTOISueC`MvpEi+3vTPrbFL6W9x;k@1$aNW ze|;n9VS~6;HbI)AUU##x2o_k9V7OG1++U`kApgs+7gjPZ*D@Viv8V0$a|z z0G5BE5$BQ{UJy=%S&^7tiHj3U3cRRxe*)ylBvfZDD1ip^VnA*f6#8~&B4QB_1j9sE ztnqxf1tYc~xR9qgY>e#DpdL}8y>^u3W12>c7+LjwF>exQ^zg1MVAC>ZExmKXkEeFV z&P6BLhv%WOIMK}@du+r#KX2gmAtUK*QXZ}k7o+l_Ik@rWJzS0z?8lQz2EeBje=)Ap zaUgbEPomFkCF@(<7NAa=PhFZ*fL8pyK5OC+s7BFa! zy^z*g*$$R8KC3cARuS_%WS2v)cZJU09GK9zy({B;FyAz)5IJ&3lNS*^0U1H;_IcPE z<-D?Y>AqQeVPPdvtu13iNKDgye-yIGWLwFlm!-b!qJ3l)^+ZQJKFZ?2-_vaEed6AW z0j^@XVHt0$S-}t1@dfX=#6gFjgb)+6az4~-Mbb5zTF6e}#kn&v&4sIW^62%!+lmzm z)GTwzING7Yv0hUN)w_DkPw%?M5fuBJ=xvWP{yA>)VX8KsRXKWvO!ZCne<$){2A!joFy%Hu-7)z>7(U!=7d0Wj_(l=%Rh2 ziRrXm;fh^(KR2Hw8=UA-f9S;SD>Eww0%dt@ zeToHAH&{JLZYE)Ulx3lruQPx;5@H7H`67prhmjNT#GV)y4?TdHuowJ|tI@Pl#quW6 z0xbCK%>2IL8}CAkMDEMQi)m#UP?$ds{HoJe`k}FhE^u?e_;J+$*l{mj^tc)y+NXwG z=fk11eZ!y0khyple`o{5VoI94#CsE(z_Bz6`$o=s!!Qnw=-S@ z`K^GA;zmh)%)VB+xv#itGZMr!OquuHf!nevpZbZ4f8gbOa7rnj1=Owg;IeclX$rUG zn3;Z{T}!M^Q!CJmh3Af1)m4cagAF1EEYpBDyqao#7REATYzbQj+e+r4#^U&{k#8@H zh}+_ncA@nfa@+yGLV<#iWxKO;MO{UKJ%9LE?O%NvXuV4srOZvXa69{ug_{xXmLzkm2+9{r~O8jrRHWRt?%+fUqG!ILOI>sMq*h4oensVVZhX9(%Xv;|?G&0a&y5fFac+S- zAH>aOc$2&l$%KL%r^xD!_~;RJg!DoU^}eJye><8Itx^RYvmWgYa7ucY88l&7`{ClV z*$2mhjGhBwf!Lnhk`5lT6E~P(r8#=MmDrP@o`GsuWucSYp~D|ei`$k4Ts zqTs@t5}MbL4UsW91>I;GV0H9`CGg7R7L-F2o2LX(L~?CxSBA`0oyL(t_?>Q=P^s>0EfWX`hP+UTswyZ^SF?!H zhrwPIvuYXP(W$>|;rOkt@DO@o58pv_+p~8FxePB-f0K8H z^XFO=k;5}%y_YP7Bp9+}h;ZeRFvx+5I?k#SSI)r?r>Ssf%k~%@A46InBl6@!XV?5u z1Y%PIP2YWna*JdqPd!+-namKF2{|f|OBgzWS}&`mIAfw?6`XX`QLiRqBr6jG&8}Xq zP!*xffP{Tv#tnU&*1(LQapH0ce*?^5LY$LRa@42Fl#z)V}&fyan!^Ebza$q4VpeAe}RdD8usDA zPPla>v;1Rj?UC*<$m2K4EX55%Nz4els=g3c><(x(Ny>bUO(u!V*^+v2ADgt7M+&Y` z8u5gVa_7e^&mLPl24jP@ZB-*{Z4;^!(VSL)I5ZyEwXUtvyMbyHCD9fFn%tjvxLc5A zPh%E#*E4?Eq$Rp$@h(w8e_6x@Mkf~UuAOW35%B}^9g9>--F8>a^z$me0g*E9p+|Ho z5pnr`AvL{T{_-?p<{A5|HLcKY>GQ&xd9M^WG4BS;IzhMcZfq=JUa`h%ZpoQ`vV-p* zU@95KU*bNjV$7p9^F%dM9w40|`iAjwFQ)P4Hr5)^LCk`56J&<$f4)GrDH#y0k6s{U z;?<9J2q0*4(T-Y5CWb$j1Eckmtlr%`H$gBR{+`?+|6PV)g*Eb->#hd|7miyckMm4e z?5W#2dYzwJlF-387@L+x%mH5o8qw_p1+&=wf)QH3iYM08Q~6j)f1&aef0UeS#Vpw(p5nk~RE@Pn z<_TvnBm<+@tS{Kd_3RZ9IbRn$D$xM-&KQC7r3P%`!L6;xaGTxL@_Dv^m1nil(@;bh zn6rKLGUZ`BbP+&3m?8K=XyG%XnSsSeW{q;=e_k%m%El}4P85G&W#nQ=(Ay_5=_pRY zy@Zc!Wzlqbe8wGoEgCqH|%j7CeNU_JeH$z8um4Hc|MuZ!(&DqIB zg1kYEyU!)I>@}J~B}j2MXtGJjv%29m(q;~5SQYu&k+rhXb`Ly{?ry}10#z4RzOdH{ zM%FbUbVJ~)RyDdU!BQgA2Ef-uAZzRhXK_t`%6g?*YT~D4PzivvX`r5U-t0csS@3g& zA}q5obj|Wjy5TOd_vf}RKG9Zzilh@tU;YCj9yi(igPNJ($mV2Y!ZT! z7#eLxe_=pYW!%06riX3FBPNUtTb)@v2392)8vhFb0RR83m&vZIN_K`%m8vXTDp`Jp z8rfn%-&yj29y0041TtrIL6`JBPvFP!(2r^M-RG+AwMz2DNTHATwPLLxVi66)*~(V& zq$1Iu)a6UCl1v3!GGXvn_z{dTb`}!u{dtHJe`26+bR<#oO!oFYgDSY|RuqQ!@ia{Z zo^K*#gP?rl>*U`V7W4rQO;ear>Fsqk+WkzSnm)%4@6<-dp4dBBgHc2#x7mC+vPW8d z6$>UHs7$Xx7LI8g*#L%Tx?gayAz$T4rKmo2p*?5CgYNMJPg8oS#sx(n6!+RN?)&t% ze?zadgQ)CIvp$NAKHBysT2{)(88W((D5w>xhT21#V#6gy)~jG?n|9R9#sQUr0DHet zwAjO*jx7ea(t#k>16mtcuQ#^7r!f2I>Z7usNkzvDjxmc56OE}B1e1ar3XdLb`%_D^ z*Z?7!@|KxI-qb)P(Jtxt@RRzFBURffYP8lg3UA&_1EBD<2aJk2D6JU&ecYwqT} z?faacZN#@0B4+OnJ9!nu1Z(bBUII1tDUC*Ca<|4ZM>}5N;FSjtdD`Ka$8I@qe^ST+ z*mre_Hznac&T>XhT~JGSG(k!J1}ZzZ4NQ~rh;hh_SNpv1M8cP-5i{Jl6=(& zx6^j`!8;L=gPcuj4VDwF>g%YJJw ziog0%dfj#m@uxj!kf-7N&i+(>`Z;P1)CT|6moIz6{ff!|&fc(pjccWs2FFX-qcshM zo`OC;(ML%}G7XDJRc`X%NgLCD5eP5IJ=D~HYGoAH(F;-&MK{vyB0UHbJO z)Qa^@Q}ZgZFMlc370YUbf4`OPMN%C{Qk5rZ`+Chie&t5|P40cZHG`aT^qa*hNRE8E z2A4>Qkw_0-<&DkdLQ@h|Q`-2$4T^I&<_bpJgM<({c)}Fij$p;rYJ`u9d=A`y{Po{{ z{PO(sRsQQQKYskf#eclYpT6ZEfBsqj!&R!keDmx1m!I|NXu7!ifA@a}W7l}|Sho4U z{x!Rue!!qBE;-K@bMP|&4@X{P&^3WmLTs%u&9hvFUTPn1>6-STyAB)r?-{(6HlD`} zof~Axx4d<^O)K>NAQDG~c#O!C>=A)YkR(adG+*2*9p7o=h?R6Y6>{)L6Kyk=X7GN+ zGmLF$0m%!sbF=kEe?l@cv9>3NxT!vY(-%5p?=dW9ESKBsHm}f0rxQ~2=d!3wq^_*L znJk&b;xh`E**~^+dZg>owTpdQQ*0L2k|4==B;qzCaJxXn<}qb(25DHTPOdxX`bbZF zLQ`CY1b7}wMwfY~xI-hE2&cL$MpqH~X~FB=MP+v(E2t{De~MY`rYC%BBGFH?=?yV9 zRT)yA$*ecH-(V)(pn31Q;VoVpS&veb$KVgJ5kiInKH)+Mj0G}R#N*2BF;l5x`lc>56`0U2+L7?aC9#8JEMzHG?q36>Q z(k|sSAO`{Af8Ic}+w&~@=8?u^IPN!~64=BtzMKP-5+4|)sz{ww(L@kqVYX1MBdg_= zljVXSPz#M6LaPsAAq@Eg1GQP8(pZM9pX?l)z94)m9wqc_7@U%u3{-mBa`HamgUUJ^ zg&!c~cmJp=1&S1eMN+7&jraZ`ErWAEQs$ejlB6$tf2gOqC$wwIi4j_4hFiRk@eH8D zvp}iBRT7MC%d7WwlC=1ot$I9=72ptO>8G?Tr@U9OCv8&g(Tgo}_5o_;`tn^j8kbcu zRTc>X-2yNyk5HNwf*zgSUGsEr=oBwGg3>ExCDP$jSV1M02$`8Wiq8%T=~1+_0W{&C z2nAZ|f6Jz--HuvG*h$)U-*geaz!xOS-fq zfDtNu-16QDf)UJ)^AFQUYYSQLx@4zXW3=@7>DvgjmOi^7g41oXtOHdKN6ZU$PIXPw z=XUKM#FP76i8U{36o8V7KVs58NN>EoLk}kHb4J||vyIRAf#yI%$wv|_FkgSP@HMrO ze~hE{^({vXLOY#!rbOcgR-$b7cC~x!=Oji+s8C9c5n&e61|O(5o)luK@D%0~P1flH zsfJ@(Li-1R+~tlI4A444FinnfRT9RRyZX8EKS3BW#2%vw^(v~IxN_3Vy72prb}|jV zMOZvj@*)KRt=^WzKVOO7B#$@^>0u@Gf1di#)M*DkwK2yNJ5SPuY_(R4wT&z?n&F)| z`$bV9X4ty}Vhh4MG5eNDZv5QQ+3p3T%@T{#VIvjp9X4^^u#kRGnol8u z(nl)FTfB21>wCo5y4`*>%Y4TkXGNv-X(x40vlWq@ev&dwy)b*N)>&9HbBL}ge~LV4 z0mh7QZm1%r)*D|x(tNW#CLXmdu-(#UWC(pvE8wAxvV3n+t-B!84?>(QpNwA8fAJB8Q?ScT@SxZilQ&HP4YM|j}(WIiqRAaFoRv|eHUa|G|v7p(pdc1 zJU5{({_xStl#th$*o%2XZzF+|A-gAIq<&QGDZ`V6v`N#klw1$^`mRL18?MU>+pnQz zz=BzC#4Rnr%VuJ0WUIMYf1Mr>3g};?w4OZ+(&|0$8-*FOr<7auqA4Aj^a6R2Yq;2kZ^8_!vTVmNO^DbX4pp1Tk-QGnZF9W-~J9?2r z1T$A8qc%}xpXXy>PWy&&gz#ck^EevXRqZ=ix~SX$jsV$sZ2}}Re@VCcBz#L00~>>5 z43eDc?RAqp$@3ed@#WdyRC@{y@mi>+m=o1h>4w<{~4hg8{-dSSiwq}^@~LW zV8MK)!uT^ZBH(gUe`2u$-omN33FHB^%vEt@X)@U=vt!ukIN4j)Nj?Pp2(;KhwW}v; z^MciT%EN7g6D>L_U0b01w3dU`U`gx6WA??Nh7OP{(iKGrfDN5EYm%3+H|RQP6_ z(|oncomGIN?@ct@hDkH5(*_@!fpX9xRAEggy0iI$z=I*iqD$;-P*ND|cUZHr+^PNe?46K^81Qk&=%(Cn`_gl#00J|o`u3%qGmgnqSID2Hiz&q@J>fP zfjrFf!ZcN=-}myGT$TgYo47h`p2z$OaWeZFHod`fBvTZ uKmDEd;cx8!__O}w51R37d-eZ_|J!(9@&Ej@{zXHuykGr%J^uqk5~qC}SBa|t delta 9303 zcmV-dB&gfbOup%40-cq4|9RI7oGX4+pfBW`d|L)z-zx2_c=KBxx{O3QJ=Rf_@|L6Z(|N3`*f9Sut zMX0+Xn3HiV=70UyU&jA$ppZdxA zMgHe4|M>Io-~XX3KP_kf(_b&Y`Wx+kT7Ld3`plH=5(#hKuO9W2SF32P*~imaHQN)r)lQzWwD$>R(u;mALSuj>G|6RuCxQ zu(*uQUOtf=LGV~Ye%ALHydb#@i@;SFOUYP-AG=m7PSLMElxss2#6;F|#8?2+6v%vY zV*Pwx*Mj8j%p{sYYQexx*t|%$RnUgObkGi$eCF3kYPCN@f0j2%A0ecyuS3<)wQe;o za;&RZ_!b;{F?(bSH4IUDly+ zK-E2GljZW%^Jn2E**V%5YZWB(y3To3535qBt079nvzA$bjs^GIgmJYeMo5c;2b9R7 z?%P7Fl)PTnf2h*&LSu^`VAI#&i`K+b)}}u~nUHB41ddD;L-f^s)*oLwmi1g27VCS3 zzM>e@&vcq`XYntaEQNMf-iW>`WF7h&GQwih$A-0OB<=7{yS>N=XjQ<|+5^@PI$CE1 zl~qG(i0YMWEvb@$0Qr(eiKGL$Q2BnM0Y!)23mS5$e`w36KE?s$UJF6{x*p4uFZMDM`b!E+VH02`r%W zFV|h)MT5p9U}6gMR`tguJ5?Dey=WwtHNP<2l5MwnZ3ZoBL2a7QM7H8GiKJiVBcYhP zOD0H++a8n|=av|$Xowr+(|T>ME@_UW1O>2Yf3EzHFvX1FVtz1SA3hPR5{)!r82&nx z3U^uqgjGI4hDbEuETlT4PW|Wn%&Wntpxsh$yEx!x8vfOYf!R9IOUey5s`Ic}%edevAD-28h^o%>zv^G?Ja%+F#ceL?nEG9nqOq8ZVwD_iF zmri>KNwXi0AZ2{jj=Vb!tHQ#>J~V!L71Wb?dFWPY=0|WHo{teL^N9EjQwp^0jx1G) zTw7L!OqR)_TcOn}Ru&8Uo=pU;tw4kse`#Zp&~A@*UM$aS*My}Q8P-=*)8^6xdlmX+ zZ46AYne2P3FLl7@Ql{C*nro&`K*rV_tjNt?u~Z|boKaGy_R8+6U0pb2wKh9fc*f&*cX zpx!8{ZJVtZ1GzXq()s#SdPE;l9H|Hqdb3Sx2LaV^Akr4POM)0~(3if|>AD59+poTf z^nhz;U)MEgQ_37^r z(8pgNyEJ_pR-$OzlPSr@R9lUS;RIbJg)LjW6_|V(TB-#K|Mc;X2R=X zLMsB@c_o3Ar6saU0ygMSf0W4V=Y1UZg=O$&cv&ay%8@Xh6m4NHn1{KnWF*dYsTec( zwKWx7uHAh5kei2ATYcA8w!#9D35<~XERh^`eteB@Lx;~h-aim-)v7n#N8>n2&gqZp zoQGPekxvarq+L2q(?I-c&|s{`jg#^rUWy*TG+&K*@bg!cT9Udae+Pzp<)rxraWLr% zx%oCq+BRN+fislP%FcLWD(Xg&c!-7hG*c17u<(#(sDFlUeiGNo6hR4uiOr>M9r_1! z*2<=tMOo;0k<0jJp^AB>z9gx0P_>1R(&F~oe8SA~*$1FKFMJK62LqkYI)tT7UIFug zK~1DA0&`(uLZ5&6mw)=Nf8@gd_W$5Q;~)N< z3xDW;gA08TK>_}95Mu_T(YNx~8~vag9o2H*&%@=uj_)IrGs>hItcvvg7PE?#{uZVe zhJvWaz3H=me+K8V%at~s_W_rn$5q&-q^%nA_@Gbi)e+i&6@v-JjwDbNd@;LIajGaB z_yT>o2wd05#Fay*1_kFga5f#*i9BX%AhN7AmhLGv@xe`js>PYV_I4be1COD#+rct zsGbkfnk(L$KVHy#y5?S#H?%9p25oriV4b6Ue`jbgky6mHzHt_wUJDFCeI>eKy2as{ zx$lp6X-MYvrl;3<4v+WlWuCsx=l8yBc*`kz0anp|5PymcdK|2x5EEmFp==P=!(k0N zor-nf^=cNGr438XrAIOet?NUh`qi#c%s`(t5-jJ@u2kCB(xP3;Xdp`j%Wa`DNu-6lymA zNWu+}M@T08BfR}L;~IyBC}dGabQ!5l4OQ*wZRlb&f8s!VwJG$BR^jnnh|s7jnjsULj!raQC<`*Fi?8)Jl<56d5Xf4B`Q z5H~hMaV(4rR$MaMAhBuWw8|oPV9X~12(x&j4D};O=N__B;AszIUG{F$L1+sj3bWzq zr_e{H#VZOLwapar^CCe|fS&jLWsj4* zsgY4wV@3@M4btPQ%lRQJ=LU9r^U3aja1Z*T?sQ3m``itHTE_|lMqfuT&hwFbu;k5d zL_jOA%q_!D`D#9jM8|CB4*oMuiM)9wENkRnowbbs|6tR}G0od$@vqFLe8!!cZQZ(8JufhqR%K8zx zy`szDl)p$@CX3)sT3Be<-A*YiMY#4jDLNQHQOb^Fy4`e0)X0=`bi{!w%{~9s&w8 zpdIxIW;gd#+H-n!WDAK^lf(M#x6ik*4zmd+jm&mV+7mXhw_28iX4syggV*3qmYW&D zR~l-&Jn(IL!iiqSsI$V@_JMYqA_U)04z#jD==yw43fDfyZUaV>e;z4*$GtZQ=rEJv zCTgzhAcci`PBSg>%rdtDm>qvJlV(+#uDR!rWwEK zRGOG0C2EHSukxoMi-Q9nv3Db#z;o&m&X)>e>zpf!BXg56GF-2=f@`dQ%Q%XzrK4lf z`VdMogSw)rS+f&nh$P(A9luwS#nF6e-@@X`*Kf-$PK5QJ1_T=Jyq>53#29Jo` z@Wg!Kn2^G9_<{F}8l~rvzMD+Naof+kC?*)DA0`NtZKOy!&@$#b?qen1s z{e%bPeG@kfjDz|{R11OA@3H}(e9(9Zibrc%op{R?hK$;3W*KT3-8cG$Y$in4t}uc4-WkwzxlU0^uPb+&pGsm{fA}WpnRo~A%6f5jb-ZsMH!!%M8AO*L z1U+db&XTcm&0g{ljOqiLK%g6Nq!3zRoxlx17_UWrPOFbK9jm zcNo_)%egBe{61o z(arQ=u|qURJ{tz7!70Q@x~Vu-SD++;2u~pj%siBAlrI#_wNqTFUS$Ssvgvq}R186q z#&0bZnxH^qa}EST7YX^q zNU_rzmhcMlg-&T&q}S4@gWT8OAI187-emJ+=nMap9;6CE9|YW();z6HpPi=$?4*ex zP_pSw;9Jt9N{vq_-7KC8v*P3)n>9+3n!7-z8<{<{CP!9#y{S#|QYZ}kf0Qi+gz2Ca z_KfObp?4H|KfdVDF%nDLrP@#hqAb6gG2-9&8>EqA&e)eFV+` z<$2O4cZ;FbfRlHwp1t6E2Xws{e5F`R!Kjyjf>hqpI+~iJ2&4KG2SpJ_0N{(xoEw5C zVYJOFozdeuag2nJySzALf4ziHdVtv5#~nU_6O>Y~Y~g=|X)ZeEQk!S!Do~TTHZ5U; z*RFye>`H>;A;0?u8rjYpu$Ya2gv`&kApkBM;&~cC^$;W|POthPVpEIBz7g4$+aAo< z>Rq_qx<1)rY2`wo*vUAOM_CV=lE8B~u?MAi8ug)`CU8h3cj>ugf6U;B*JB71NM&f} z>#)KGb9I>utD?sWEuq}7qQh{NxtD6Mbt8$jjy!sC-WOEPB72UbE0kjcr-NLTb~!mZO-IFKbDcd!KI+=*kwgv0*`89)rHO1 z(gmXNp&E!9^7|Kk;c~)jc6mw)dQ(1R`pl(la%8D(JhRNbozsW7fo@1bVz4IGKJ1L; zwF%Ke6rOlHjYXyj<#oL`gg$(a#z>#pk8)swla?OYq(@9hf3+fa?$^57NjS?PiEK4E z_Q55YH7FrhEV7(*#=1HDnJyEGTq*MyaswU=fpj5W-f}__4gO{%q`*3xQcrD!m?s+z zH`X~}TgW%eGI#!9b3C?CATi?*1(6lfvp$4X-TTP6C zR}+|U;)ecBf6r(#L*W)9^LOJ)_Kh6jzSQr+iB@L9Kx)~bvvfKkUFGO#LZdRzDLb&n zso@^y)it9^Z&|`z!nfDFc8~ELzbq;R+!Ytb(m*w&Le#o&Sxn$(a-=)a(BzZRq1L{x zk9gQgX7ObSjO-ynmVDCZMKF_8!2l64*&jX(eiL&&f1-U3YorZ_373Z+>G*JQev@N* z!+ZbE=POG)8*IeMtv;|5*}UO&lI2ErT@R1)L~ z59#}M?9Dt>f(H)p-CP-((Ai|Qg7CRbV*y&g^C*RzRj(6?Xk<_Ib>mJcQ0r*ILl*9z z%9elJf3suCjK1BezRVCRjSSXQct4@4QkeT-`$4 zpU)4z{T~1T0RR83S4qy~I&!Yp=r(NFFnk1~S2ncJJoQdfY93Ovw9}ZHQ}c8JAH}Eh z8Jz#CD!6Pk&>Iu@K*mP~Ln4Dg#xT9CG%+0rf2~x|zF{vUKyWh0dw0k+v382Ct#0dY zlq^&dF2;KW?m!^IbC3fMXwd$4!)KY9w6)c!8ZUP|&j+Fj_S%Bmf^S`_Xm-D^dA>~{ z0o-MIrzu$P;R=vRJrH?kTdOr#Mrk>zx7iyxz+D4EX;$t4MwEbM2V~k%Ptv9Xn_Ww^ ze>M#sq+KTDrnCq?Pw>G;$Jl!Nv#h8@>V(?fJ%Qz3x z9uJm!>!`%0q*)?dl!BH{p&_u5FUr5de;uKMD1GWT0>%BhK=%c1qpVu>idqL;q&T*D z3OJt^-P>nW8~5*c{equdQ+NWV>6|C^6~o@oH-pO=mkFY6a=bi@s+gsmaxd>eznth$ z@SPdNgUd)&x%IZ!>mt1iM*vwT6t1XjZM~Op##LUx^CMfWVsKK04K9z>3Kjx zbt(_MceREY!hkimh0Ah9zzIjWp&oiGC)~QtEDw^ym_^HEw9Mj@!{0(H^|4_-@8N9u z?|A)!pPaZ%N=;qAgZl+PIRs`+>GOZz!TyeyMj5i+lx)RFy=@Nf_;}%fu4D~SFlO0s zAp;B_BiPYh)`)%j4CM)0C(E~`e~a@s^?YIy1TYjR2qsHgt@WetoRa1$Wgx7%L8gYo z>M&-!EQR9nLRPcyeT@T22ldQINdRohVkGlCtyjq(?7d_z{-dvj(hdW9ut#g1$dCa8 z1Z>L2T?M@TfI5Gl3eP&I!4Lb*TQO=7Zu-@Nl134VEKo6wr`2eT;Cq`ve{VcJJYQA7 zDbn`BE(QLq`8+e9HD^C-&SmsxizY|Ag&uv!C-hm@QI;%+DUz1?>>rEQF5i5%D6mcQ z^*K0#)&CCW7yRVJ<*j_#_>SWjeCH6HH$(CH1I#b@!3oLLwrL;hh+gMwB#_BR8G5#teJlH^E=pIfAF0n<@kDzU%p*`e4G9FHZ!ow%Y7|}@+=ZT(>+DQEgHov z3jo0Oy}2L_^5UIrJ7@#ki=w?h|NFP!%RhhcumAMz+uwcazyIKm-|26E`XT@J!GHbZ z_xh{+%MW?E`ghv=>DUgbfAC#qdn>i_S?k+K10BI}4o~ZizaFN~b^(;d zn0f50jU-si;WzP+7Hn`HSmFatDsPZ`xotcmq={r;e`K6mLuRqkk40ha@O!4DK`H9{ zfjw4(OSyoJQ7P#qTAE!GlgbvO>_D9ULa_pwFSWwu1o^wEd57%^tmk!dD_ zOm9eld-|w7yEnB50Br}+I!{0f)4{I!7ij~8nwaw3$p!!<-~vTP6BSe=N@F&^Rt8lx zg3-N!e>B9yDZ_g)qlk@53Adhg8u=$`XP_O5!Y7jY3UvyoTZzbAGRXOq?z{^fgN|d0 zzLJMMiQ9veZYac7L@qCLgE2Z?3x$-BoilBohy@0SXD=dktpdg?B(RU!ytZ0^k|=TU zJPR&lFmvIS-iH7ng1hKa8)ZV=CPl7H@ybR`f5*;Mx}qeMbw4LtkdQLgL@R&ydI#eK za;Mhb^Q#@AAvt8*J`wFiq%3E>h<8tnFAMT7%#+t(KG)))UciGwRS}?Y^KuFgGhQQlfVzsdWxJTVx(1p@w2F|## zbfuMnruezR*?YI-qMz}rnQ(<3OOc7MxL5+Z>0G^z51zr5b6Z_D0!2mo#4Uf|e{hhc zS-LEiR(2p=0m4g*>iI&SMP74vK+G7wqJaWe8*F9p5GDB#^+I<0;im0XI~!3sfO;qh z?<*V%*L_?eX;EX8(+qy{>!CsR95R!GahPiBCMVGvxY0ck|jZ-H~8%t0$z zyk}c12RV=redb-!nz{Xu=hG*eZ-oCe}qle@FC+N z95Ip=Se~W87|XUGCA&783LG@@^64mD`DBMGYjh=23@R{ext&yydNyg>ws)6JX$4zj z>eklhx`8+|L}$st@V!hq1Hh%uF2TT0NC`E?=S2^4_UZw$N;xNBm7#=?no1IBWg>cK zixie#5*ErwS*z7fqK~N}fBSP2HwBj5(n1s4NF21?@m|fNippNe2)imt;>r6=%@enDWtuwW7VBOTOP~te2OsyL;AlNJ=rI_!C8lt9Vn~Op8Y{dag(vDl zyJ1DIo0g){&Sw%RqA9}K4ZH~%fUfew`tH;=E(EnrBI45G&eF#je?T2aeteX}7-k!g zRN8(5AQI#k2=tHiz0)*nLVU8!7)`&fj&6A{o*$N)0?D<3i0CQQF{dE2As_|3(xZUz zsTZkEn^9_xCIGvyGGI)tSju&WQ_ckrvZStSc`R*#(KfORCIGj_$!8-~A_3?Shk>#5 zV}Fp(A+f2a{qPbPf7Dy9SK}+9-U)*a(u)cRmb9xh>)AHvsu6{lv%$~GR7k=F;({>c z(7%D*hz$hqnxbHiFRPg|mrFS-`)aalvi1jlAPJBxM7%@(o7!q22s(nLfSM?-5y+y- zK0X1g8EmaGV!}I=T^-KP9e^@b;Tqg-f$gGzCr-M|06WEHe~}9~LQiam`L-)g^F3(8 z>8cglejL{7__(?Q1Dr6b(|5GJ-gq{s55ll?iT2`SFb&N4w5cf;2J?Z_pLT}>qB1q< zjJ3m*0~&H!1!r!sU zY*x%O`AJfj{jg^rfHE)jM4$&ccprB+5RYrWhlvL!L)bm(?4}m2c^ZbR#ha;^cu{j` zIy4E5C84k34%Av3r4sSlG(ULIM|nECb~lBv`;UuXe`xv{N)rJ9n5B^>2e{E%N^h(K zD5T;vjDGIyh*#Fum@<9roR3vj=gQcp{Yl~~eYZRWy!NGVu3VGe)bD!E-_~2c9+givIT5X#&j8JbhaOp@Z1IkU`TQOT2%N}3f78Vr%B49%rZ zI)`Q=m7z}f_S*Y>`rf|pjkTWZ>Uti}x%%B}uf5iP-}^p$|2bH#T4rUfWT>O31_RPd&da}94&WC6`iB!&C!DJl=3EuMhJ z3rV|8<$5PUd z1pbg?abOJ>U)dx;_(SH#fz_oX(Bbz^+4Nskkk@OClB3<3G$)>KE;7*vM|aA~?w8Hb z43-^<_flB$Gos|@x{_$46S7&(+r->?>TldjQdJWu<+jqNz5=715SoPo<;9_gsjnx6 zW}rZYO1Z5?sO(9gvri)(K2IsPT{U%ZQYg~lW2M|nHL1gsLXi%iibD&jKLGTvb#lpU z_~o<>>>yWik30QkIfW@X>Mqr~r*)F|>;Jo;w*PHGahGzRQ04Cf<6QPXu}K-Fs%w&F zN+pc^kCGm9!#M_&^v6PrPRvWw<@W6Kwa&{=ddRhz!tXckGJ5Rz)Mq;Mm z%-8%YCS>kejdtt_54pDI@Nb-iiFWMCIP(|(rb(D+$G-C+SMX;3&4Bq=8>Ft;PJy#Q zjtaQV`07kGpM>Yc2g&0Gw&fkw2=M;4e>|HVmgRCi02Xp`pRo|%KYWqY;7NhJkieM$ z*hLMU6vzV!^u>WxdusS(z+nm`P!b1nH&M4t1`Owe1g^$`V{55ClLEORfrdD6bZio! zK!)fy*h3D*f&IUzRuhg82L{6)vM>(pJwP>?6bO6B4ghF9Iq(bYA#3Bn&&}k{`|D1@ z519db$XjvXC%;Ly9st4~@^k5R z+;HW#O$;x$J(<)6fcMu$w8YM#4fdR?;O88Zq~=aMlh>z{`|d31>q_}=4`WtN&6Jg0_y63U{mo7L372x09uW|lkXpYYI2w&gDdj#B zFF<526OHwtKGIn60(#`D0RLoTEkdK>74+nN0a-x(YavnBa?pY;BvE)Fk>R7(0^ncQ zy@1_aNTb>YjOD8Vsyg7U_fdlAq)}Xp zuL9v(>V$!mr}`IopfL^<45F5T17G#~!2etZfy6Qhzq?Fp$X+`&<9{!N!OH({AxPnq zy5J{m{v>RCA#6iti{R{q9<&MXt@rMI|D$x@PU!1uKJHM$s`!apqrbVHy?e`kqA*v+ zu{6wt#_l4Ewux$7q%EBtc7gnA;|4lHp6Jo<#k+66KlvBWeb#m+-BrF~R<(NWX zbDNQ{cnG+6h`)K#(dM=wVeuGnpEv*A$+35luy_!-?>>JE!2W%w>FC&L*$LY_=-kmw zgx_h?@!b&UK)V9i8ozh(d7_xdKUAv2-Wn)-hAFiP0=o7_51x!ATtB!Lgi?qwfA#Ob z@#nrbS8B7@7X7~i;z|Ew>nA>mQ2O{j`IBGr*N(#*=U6vdMbiYn=}gTl;@?B%>h{9k zg5mt{FTQxKjrCgVSv|dqEzNZ;&h)~2b^H?FELXG(u5QQPRwfKu>QVOmCr0~*$7reF z_?83O-!7$I0%7o(xh`JwPNec3pK!LsYSn9*2D&pZCDPQDx!+K@tg0xT6aNhh6N{$* z{u`D$lw06${OxSJDGiCHwWk|rIZ?ZgM4X=|xU;-6PEUnmU_*Wn*g~$%{k7fl2kPh(AmGFN@nq!=y zo5BB=3+w;521w&8)8jhr1S~xVi7txMJvC^=xpueLLU$jBY%#}1Gx(rVDUQN3QIrb}ANOWF6zeT$Y z=zp(#|L)8jNIM}JM za9$i9VoiGo4F?+)7Oo25=V>3H;b5P_!XU1G#qSGSomB3&!Y80!@(|vg$n`r zPg)-={36Oa*TUgpn`mF4;VA1|9>AZ{zQV%wQAR!=hX^4A=7D}q2VYy zR2jfCY5mY}lpQ(+z<Z9yXeH^vO0V*h@(E zMF&&?6&jIOLBUaqqXK~Mrg5N0j#3=W0eqY`3Jpgoj@+PrZKaJv!%>Rk3;=(LaYMsV z?29-K53|E4&~Oy{G6%q~V0_SU6#GKM;o&neB9@0)ib(clHh|}2G}w_}L|NyuI6Q(I z6NH5$*%uQW9`XX?g@&VyoDYYGF2RUrcwy#TA7zKm1n|q40QAUFcBmu{4^zc3XgJCa zH3aZHObEayyIka;+Lv=wyr6p>p*@GCgE@!JU(SIH-dmjZ0?;QjM>&Y*=+oi3T;B0C zChW+O?8`auB$anRjmX?!W*y1CoC9Bf`M8lc>M(R9`*IF^1?JOA-l@aTk?hMk@HLq4 zeDYQuf{tci&VjGOd{2}2>M(R9vwjYk^^McuZq~tGLb5NKpu{+0Q^10ptbP%2l;S7{ z;5RS{XgEr7Gy^3@1CxS=qZCIF$A|65WT4?F#Ze81hf^`)Jq@TiN3k!`03L!7FKs}< zQS6H`fOlaE(9?oqUqo?ugfpfD3rDgqx&U5-DMQ0i*0~}MkJQ3cVc|&j#R7+i@nO@U z;RqvV^5Wm?gau=Y&~Stu%CrS=HZ}tqj<7?SsyIB{2~&ZFBkWM74}e!=GXZ?Ef}W0Q zUji}wjC!|{!4V7{$-V??;B=q)aLExEJD7B6a}+oY&`;Bd*C-}4N9l;>=(vqPm+v$h z@iqm_ydc?^Kq@|R-*oau9fpo%UjkFM(1xeWM?Fs}4a&voC>0fc})c zSBIe^*_S{OobI;}?q(gVM-=L5W$7=|aO% ziX#tzH(+z1;V8w?8iz;B!3?0`2=;}k4B*9>Av7GpzA(LTc%(393=K!HFU%&LpfliZ*1>v2vM*~u z{W^x(!ju>Sj#34r81antWM!Q=p(yqR^lI2K4|9edIf{J&eH(Th$A~wYVMdN*UqBCsC<$y8 z?8s5RJYs@=4pE8N8dx}zeF424A~s-7&~TI;3i>=m+`)*)bYbQk$-Y?O@JM59CG^Nq zcIXTMFU3|v!%=pqCl22+6bC{CU4azGe?<-=E%|7pKFsNd8ZC@ zPLb?OA9$c~Q#E<34naq=FMZ&NMt?2xULA&xWMBHgBaQwC;BMBzdPK4>E}(w3W3Dh& zfPkYEM-xzD7GUnsa1{Fz3E-zOPiQzwapVK_OBVBnhNBcm(2Qb7D&`9fN3k!UF~yES z%nurlVqZX$iYRZ)9~zEgUqHi(s0Ua8EF8(cfaVp^78ubNY_jV#Sm#Lg1vIjVK8ppx zjvUFpfTk9aDcB}xILZzM4K5`>77V#j?f5E_oMLqQXa zD07Sf;FA^fTx9z~#OaP?a0Ej~voGLjM!#yfNRmasE}W?#VbjGGQ% z*06Lm`vM+l^vB3sb(nca%3u1x6OI0nev4mIez)vM->6$BqkF0yG?D`*lT=U}POaFiYDhr^@&v2*~Rq@Z6(L$)tOoE}LAM=*3W`vRV3-1Gq|IU>f6W?#VL zjQ(pe7ucCWvoGLzM*rK`23R_peE|T4R7%{F$SGMDku8V&rIV9`%7o8UqHPZq|wQh-6>fK^2&ZHgum_)M%y>hJ~AiUNRZQlP#on|2>Kh^erP&^ zf03UG=%FiU|3K3b42--1L9e3~LDLZ&jJzPAhw0D`!O~GIjJzg6FQOfWrXwtNc{xB2 z$7n}j=_n>f-VD%#yJ-iY=_q682lSBTw1d!egq$<8?LBJfXXk+66qKjWAN@IDJ^ zQIL4FM8EbOc*dBn0T;E@YoLnDvfgYl^f8dK2v`?ATGhSt=r| zaD*Z4IxHQ<))dVLV-FRXxaZV=R|0*My~;z-qsg9AF!PS`Y)p|dLH|Unf}R$E)vud<|p^q#_K^8E+@-4xKb>q4zal8#a%sRaEX)QTkOC^d2xpa%;=tw@rNQX{1ZdL;ac zBn%DgiZmkV?`bu#>z&AGVCf=&99)4#S2RRF`^ z*+%w5gA)Mz6<)v`2qc-2J<;FM3bYQOp!hpVAbm9hTf6!5!k2XP%nYe-4A9NJwGo7IK zOx!^24?2qTSpew4E@T6>NxV3I0mB_9iu0im^d{N^uyvv6D9(or>ihY0LL zj?$jM(vh4G8Q6={oCxGUB zi2Od~3?>Y}gwUK15#guGVxsT@XwF9z6ra=-OdMJO(fQ~S0^hKy@B(PgM-d35d0>*z z0*KDX0th5qk?+hxts*q%L+2s{&XKRp!U-VlWV#X%NRcDoorM!X+R1b=LLiNNeHKmt zX(!9yx6~8nN*SE^4cgz=_ka5VLpmS202qF-$;7?a{-7f`A3Blg2bWFUd+iT8g7cx1 znZD%2z1RMrBRC&Ak?Du*Bzv#@?Gp9}9l`m~iA+CafJ_IV=m^e-PGtI_?qoCoMMrQx zbRyFaZ6$L77&?mcp_7@u85s&d(Gi>voyhdVPC_OEzdHg$J0Cg`>nC3#o3Kq<4+sII zqE9E1{S;-g5!>J9C-z@!g?I2qvR0XXxV1{jB|EXf4Iiyu65)QzFR~jOoB&e2q!amm zsz2G04Nd^b`Ot}oKlLd#3+k#%oM9yALnl)HG#gAEUI5AY(21Zw?L4LdEr8~H=tS0^ zJ{{A77eLztMBJaAf$2aCpgA8pk@%+skgwZ9ts+F{Lxlb*&&fA#;RMi}50U$)E+k*N zg%d#A$wc&@T0y>f3nzfKlZo^{O>yFvZ+~Bb|7|4<>wL)c-+SV=ZGX^FoR1FhRUr=` z^C~cQ6z4-k|DhHWw{81l>?qEM$o)gll5N}mc7^$aj^ccX&_7IW;%MLxI*Ril692Gt zG8%vyJBsrm;{LEks!OLjfo{it{0Y{_sbTiNNn>!tl|1z?N8=L@I$s~gQ)T?A4x4)f$*nh1R-v1lPTAlX5tyS7AvXL9y@X_ie zk@BbIlg-@V1kjuhk@BZ=VHQwVUE&O*IUgeBPv44J!3&@{A0p^ae}UOR3m`flBJ0ms zj4gy0KyyAs+@Em~TMR9L=zNI8KXotprY_VfLUcYv=%23_Q2#P99?zD9z+j3`$EGX2kG=no^?zrhKhl}sY&PwOUIz`+S1l}sk@A^~BpbZ4>++~3Y{?7!9u?;eh1 ztqwE`lyIk4lYQXehL7ZYn5tm-85-C+sH-kfng4DEcFD}X?{0ogTf(t7Z_jWN7{J|S?J>>LLtfL1cM1Az=-vU?ny09wh!2!S1B z2RS$aw34}$5O_~^k^9>c`faW7-s4EtYC|J#tuj|(#Ji|)!$)&Io5AoiZ(_kvmvv$Z zp*f#vKp;y83xyUybUy0|fdd%vMk>@45wCK=Zvs;wkS%}_@1#NrAUdBNKp_1iwjFwk z5ST)k%?yh3 z5h3V>WHbOpM{z!mfWCvD%mtw6D9%TRpofy701O?;`2-U5?uiqD|30fo&PM^zqn1M^ z0z`viq|Aru1_Ux($%b>2)&oKS?RM9k5V%V=or4oVE19uCAk&y^JO?L$Rx-H>fn#Lz zIXD5dl4%75vc$;-bZ`P_vCj-bAQsC2m#x3;fZx^%?_7>#t;||*Yn9c5WkFpOi6w;Q ze8j==zO*Tfy}8`CcFUJ5zq*Mcq|)U z0BsxF5dxpdUSLq0Kp$-z&jtcn>&bp#Z~|!C*q;z+B71`UZI}JN68zgX8S*(FrYxXG z3QpXh?hiVO^Kl{Qk&t=SzipFY$8JK<-%s44?vJsfIG;#B-?5r(Q3o~eD9(qEpf`}w z02Cd?`78wVs5xXV07XY}J~Ih=F&PTL(2<;vFQ7*YlZgNn9mVNO67(oC4w!Vi{%)KM ze>b`s2xO*Wg-{jkck^U;0YgIIJ4Q53gF6DWk{JpFvOF=OZyKBcTFDe91llm7bsC%i zTFG<(0@-F5(LD`L0L}Sm69OkNqJbKm09x#`6$s==Vx?de{cRKcwpMuGb0lkZy#cpY zIf+;q^cqEUKCZ;@`!S+h71aD7W=e8J+BWtk1O~7(K;Uni;NR=}MZ|tS%&CCB!;p-u zpy(*hXC*;D3YS+AV+WHD>wF9VJxZMHL=QD~6z3C6(BsHf^iXsZ=OakaKa1~M0bqN6w;O@e-h3u5V;NOlDt)EYY{8ap9V1nm{1Ai`D{F z4hR9HiYYG#1X7%6ZSVp}6;s}f5V%3R4=;dJG3EJzKh?~&&y{|K)(Jg)G~*+00fwKlpKK}yRVUCQpCT?Gkje+wSB$s-5Urb`qv0YY zLSQ@XCHxd2ZQ~*_Lf|#+6}$k_HZIZw0%^-=uP0hU|6YLg5hI@>0YGOwgZgbI#snR~ z_!OxF`nH8MA~O8j^8aJ(2*#&KhM-r{h`bPrj$nL><^lTl88jj+grXxvK1I9)J(or# zg-~<^=ToFg&_`)dF(GkQ5u8tv1fT~8(9XfGNEGK&G?$=vz%>;IV@G++r$`9ULl%=w z#V4z1#LS>MpCT z@DJHS3~q|hN~SUpNaiQIh`|XUIiI2_gg^+{NDNK@$@vuN69R0qml&J?lJhCTfIx~P zT(fcFB%?W>A`L>|I$X1HQUGlqOalU`>Jv8=``23G0%+E1r5|psl4!K|(3=3!`B1^| zlfq~p;RVpP@hn21o7Mv_fVPdLfIzY{?K8Xp+BP;K1gdHMKw#2qB)Ex0xCbs00rc(M zP`~iRSRc?)oR1Dc526u~A=KDWoR0!Qe?=qmLMS?l^DzhXV0#)77DCZcoDVlaze*#L zLMS?l^O*tYA!;$BmVvhSwi3wT-SS20Ig)20Dv~TL zpq0#-Kpjd0L}Rr0)bRPvX>Z~0Gjg=CIlkLc4ANhh|Wiw z5O@pMY@9gBXy11gO$P#LE8v=q69Q_Ak9w^@c z3K3%FL*)J`!Wb{S0NOStqW_c~7!_UsZ5tEmf69AIV4@T7J2ydW;ao(d|G}DMFg)oM z7|>Ci4-x$b7m}$k6dlF+5V?N{KN$%_(NUZa5&DOOl6f!`9mV+&iGN7<#9{CsXBEZy z5OII#axxcy8as;fA+r9^S~3)Xp(8mTBIpm(hHEOWkFQ81=R>6YVFw`N0HXgcn)4x2 z{^T;auJ>U0sK2>O5ftPU3AnEJqyU=pA%p$|xUTo408+`M6G4AUA6(aaQUIxB(#fEI z1KCAv(#tw=4v?G=oecV$$wp#u0!Yq>P6qvkWG^u|0VL-`C$j#uBXFI@iF1JFeCR~n zpDs#v6oWbfH0MJn694pQxMt(T5uiCAIuZJ(xMH$US9Y+9&|)7tk^86I#pEWsvj4VL z$j#V&aBG!nj7^6hKH4@WqW{!mm?FFY+BPQA|1@!I#zgb;`x*&4h9YD>bTa*4O-5Fe zUc~?%!THdM=s%voyhvbK9ZpT3?0S!(21Zwd@Wp4aeaKvpg12ok@AN(LdF4L zMWTJ%MJH4K2XI~Q!SE5C51mZ;&EdMF#7NF*pG<=R;)u=`C=b#))%) z=zNH{Kf?sB(>N)B^lcZNNc=O7lTF2-rU=pb5TSo+Dy9#0We2MW(fJU$f9iK^F1!HR zP9~!NG*8TEqD$CsYlYg3UDFGNkwpg12Q^bfm(2|?3QoDY%shZ~d80Mxvr zI3FVJ4=*Ki0Vq0(^C7bSh^b^K07FM|K19$TkpS0JTpwRENX~~y`6K!v;{dQC5uFd2 z@^j$2-h<(zIv+CS-vrn7o)kc(LrCY;wy(b0GN+uEXrYmapD{xIv*nL&-8}t zG)@YjIUgeN&%6)UX`B#1bUsArpLPMWhq|(ZRfOn#h}=J20ds&CK-sp-Yh4+uA*7(U{SrKSH9 z=i}ie5XS#NOQ@!8>}Hlwi%{d^&J@%4fMuKG><@ZSUU(ou4}qop(8pf&sMnfO27TG#)=-8g^O_ixsNmDWGDI9JM) zbSc&FCPfy|?9S!VtSMXzrD=O6IQV)?_=5+}t>wh<5l>wI{oqA-p%0$6Ol%rgIhF4R z7~tQD0$k9AEzn)HKyyz! z^{L=ZA?N?hVIUFFv|gnWJGg&3H@<*Eo`hapy->z-fV1G*b^M=|5|Yc8Ul5lR=UaGQ zY*laI1@J%3E?nPWc_HS@XSMS&E$gEWn$;GX3^TvApLJ80FmhXS+_`3C{e`Nf$?|Xa zFW#n|`HZ6L<(4)ubxq4@=_`znr@k#LEz+G`-Fx?vM|;woscL(feyq*ICmY8``qziO z?UeksxiR~|oZuI4Oji1}A2Ra0E77LwUh(PIss4LEjvO&8_HG=@5X1sTUuC{8zgjDx z*%jO_*`Ga4L|0;wWBXv5i!UYS9i(UbSKeCqIU(gFi1utb;#4MxY}#FGi*#H9v;8V{u-LM91R%7@>}) zyqM_~xhkA%KJK}_-FIrtJB*b$DL%!PL)p#dyL)Gje;jgXu9@ATwmZh4BFJ$_yV<<3 zcSBx`W<`+0(AMS}?T#xdoFSiL>!In*=6ie1@?z8~`j-v)`@Bx>eRQWrv%_y!jB!Q3 z<4~bb@xq}6%{6Kre)%!F740)P^oo9mp_t|x-Hu@u&X`Z};vq`2d2z2`bF5N_s50lK zkNc7#o90;c4p9{j+s7iYcX8gRdWE9Hkau&eRtG-j0UwKmUbVbY)r#U}Lo1tOH9DMB zI3Io7ZHEk+V`p`=D|0%0EK+;l=Z(&pApXH63R=7J2$u-BSbOb4LT77Dhd#~h;8dbb@95QQ;RqNWS?x)tLNLvhVDQ@X|#tiB#;?)6o!EXZzg)6tLm(cCMkT)8%@ z#cj5J)Z6CX)%XwiC))Z^gU!8$%9YRXPc-$TJ~#J<;y>V@=;}v}HunlER~l!vbgJt| zbvO4q;6G%ybZY5GeQWO3R<68)f1;ru)zjR&75@SM1lQp-_fA)?497pgb>27ky5c|J zpWr&f&AkhhD~ItVy>>wVKw*K;6G%ym}}{CzBKo$ zC|Bm9vTb8*#Ls7CSSA^Nb+sEPWpO84l(d&gJcUPwi6_ zW?D#9#m#3}=rSzuzhlc9yHhusST|ZAQ$`uS$1~i{+gFVL z9qFn#bH=zeD>jl9ix1bA6}y@h8_J4xV8w1_jWyPd+9z=EVGbs6gcCT~37i7T@ByCT z1C-$nJi{9(!{xkv?!wGkTzLUw93Nq8-ROn{&ejCZ70PfwZ{KVDGhD%fQM-UqtHKz^ z=gf~a)=)RPIDzAuz{#Zy7xVU62s7iPs$Ng88lTS?U&tD}S2wygfm2Qyj^Y`Pq71+0 z?W+}L_6sumMVWEZRTg4Z7BW@i_@HfAV@-9VP6?c1%5W`jpD16SD1Tp^Fmqh0Y8)TU zV%AuD-Kcv4rtPnPZg9F~Ekm3J&{8^}UqrYu8{FyH*9cSM@trS(Gv2 z0@-6X>PLSha|E$rX{kP44W>K2s`eNo&YwM2Q9t@NnWKpfua)X6$3Jkbsy)t#+sdx- zX4kA_k6o)D9ZcrPVZ#RnhmEEBf;5=nvzg)A%-1*oA3*?n>~j6+=VXo{m#Y5NRsF72{VS{bH&pentrFE`E|%z1 z5gcBg%=u6svy5F6$BwmR$9k}1o!PMrw)tg-#W9A(MTP}FBWtU2b(v}seNzR8?UFff z>SLC&%`Y*E*Hk&_GW{g_3S3kO3|fCadnlhE_1C!-(u;$CW*c#sXk4?;cjerbuwolne(YW#(`aPnc=>+ zs@S=zcwJTTsw#Zui&s@aYpL8yZIy|KGx%Co%Ku}3_ z>Cl?o9lS(EY4Vm3!=JNzaK`uL<*hG`3NGy13jTvx;d*-C)-4As6+e%SbVeF`#B*`; zj6Kt}7*$NZ?a5dtFOu3M&ajoIExx^+u}WTeanl^eGI_zK+uIm)dC{gO8pFCsK<&02 zV?~jWTGMRC(ju(vwm)Nikw{sSEMrj-&F{7gV@;8;Uy}*Lu}JX!?MQ}Ok?8v-K86)t zK>GGV#&Wulbkj_R9UUvU?aOeXixf0TG8WQlYj3Y+tfmXEZ8Bsy&;_5}4rRE~MV~bZ zGi;aw#i4MFT5s%F(W|fV|#^$)Q3PvPjvtP5W zj7*QswP59rOdZRrWtES}jpf9(w2P!s*md&+L^5`=S@U>B(rwu8j7{>?)J8TVLY{l^ zt=$YCdA`Ms4;Ufxl%`u37+d7|n;Hig(M4Qpx6&D2MZ9W_cNp7?c*<^_WNa>?mNkB4 z>?q>)yH&{8Sj6Yo*ue-ZqP)L#l@VCP|Gx1DBbLr3eJh#aN#~VrY-DVs^Ay}FW%$#n z1&wbRk#z30xAro8>3nM&pD;q{lxMdtF}BkApEV9LVwhaUx3U@DOy2Q~16>=dOac=& zbgii}4BYv$D{RD=sW6^n#>%Oh+Lv{mb*@UTFDHt1s7ksoo5QN9QtZp+XC*|4DP*Ox zN+M(wau&08M@T4SH?b~6$SdTkvC<=^9Lg$Vos5`vD94Xg7$J2i`#tMwguTI&;EV2P33AvxiyL5sIC; zqO6@GV&+-7tfM0`<~dHR{1MS#YUasK-3B9C=Be%7f+NZ`NxI#dBN{a+<=t{4vucuq zy3Iy(YEsARhX*LX#KyA~*-ay~*opnzO%f+ z*n=i=({o*l%6Xo}>;nv;oCey6)R}s_d3>)^4Dp?n++Sx}l=7YxIgjGUzW!ywi1{zB zSOJT~V1|NDo#1(HY0s%TH>Kz)TdR1?7?S61W`3DMPc2|mnMoTMa&8G`4Cz=Qi-h9( zcGmkZf+I73VX?xs39sw>S;JrWM^t{%#)RS$YU^LK`oD;d__ZtVUZOfB-S+?f>*5RH z@$j*}*4v$1KDGY5$w^7zjPI|d`ql1EC@^!>b{C;$4*p~C^2CPK!H>7zT6@<;&1d70 zZ3fcDM>8|>(~lo?o_YM!iVXqwD=(Mcb8&e3c=NoAdgbeqO?)3Re$|{fB4?1X?@ILM zt9rZD=W5z@eA#h#^UOlQ=bM`zZQZnQuTjC$jI+`WpI1C7*6&^4()UlNv$FT6iai*= za%ueMesf%zv2o^r>6vm|KN}|H3sf-aeHxmC~sJqi9VjxUZMJRXyB z=<>>k)>n?N5DCkgdRW9`^OWuOk8X)6&2`n7V!lMw?EAOgs@%Csw1+!f!uRi)Z|~I1 zjNK7;XUL{7zhsRBroTO{L27!m@iDfKWqaA3XV!X`#O!-rF-RCIyLXnZtv&TT{l<2~i!Jqx z#w7OyREOFJ3>-($WW@$FEP>(>~*b9n?h|eJmG4;RDPaLd6@5>w6)hohJT%Ucj)NswX}+h z+4~F=S`LKi7;C$Jefw*4-Rpew%b(>gT*&02Qv15Si@kdnRDJ&v%b&r2r+(^pnvm1E z!&$tq;%Dp458yLXy+1E1smrRAzw*gI)c)yr7rDK0pmG~{M68e8ZEVslWHoU3;m&e7 zvH7(`(P8etD$@IWTS__i%l*yw4b&@c#&c#_a(6KQ;dH7R^qF-q3;4GkwoEv*sKnYL zhtsCqKzV+Y@lJtt_~sXz)uV$4&)I+R5INVPnavrEi~jL7$h{`|N6-7Qp7*iCSI2+7 zP5q{85j+0q{n-25TKD$;*k5kvVwe46@vCHiQ>V-O9qQww!&jq?mbdRKQ7^ba&j>0J zU0CaPz3knb)KI;U4N-KTZTpPoKi3lb^nIpMWUluS*4xV-GYyX$&OUK$Ls_s1X1Knr zY1L`h`_=11KNqZ=dC_fP-YIV5uSPzGl{z1HUaHc+w7P2p+q35Dd5y8D?XP1K-nUzH z|M*s(CK>tG{%*xu{g?%{pXDDr zG}&Z3iL6mR9q`(6d{l33`&KuRPn@gzE;~o5Rk3%6uZ(z$B%V=-#dQkjGbJiGhd0+g z4G7n)9NSp6Yn=VnrSiw3?e{Os^#+I>`Bn3)T>h8vv!1eQ!#su6#`jYdb%LiI zF%_0!Yd#yh)A03W*Qc8I73+@vGGmk&j?Q`am(Yqux zcy*RU`7yOi%d0PR#|&XZ%a%u`t#39da}K#*@=^9>uKmZFl`G z|EuoB=~f*jKelYZkTXuAxYrPZj_S&-RTOKY`r19=%Vh>cB4m|kyfF-Gy zugrbz_@QXg!*fm7EFW2A^-=PetLo15GCMiJ{Ux)PyNF9o3DLiD`^w?IQX>iMgpURn zWk&30Gx<@452pkiY<)LQi#~iUC?Ip6hx()YuL|>?j2VT5?h}*lD*T@FQ|Rcf7jI>+ zr)hi5RATL-Q0$W4Ewr1WC_d1AFr?@C;JLCB;+BQqc79WOr)s@^SH>2$+nfi-&yO9_ znYrC6{ZiennIQw$ZX`|XxQHpJ7Z#@j^1U$3n3l0+P+W@b$dpW|4lv9}yj77; znNKOUuUNSL!<())WB*wLbHpWR?94i7(?zTY~qSG!L2R^-MP ze3w<{hpzU`s!(y*n&@i!Yt^m?@_HTBy$?53I6kG6onq~cz4lKa<>jWw&Cd%ZvDKzK z<5xO8`Eo%eVU_GTTctHddGS#L%jPs}nzJKDXXmE}>u0dM2K5&E-1jiF?K>uyfG z%fXjQ`Zmwv1s6YAM18X&MErpL@hvO5%7qpLHJh>DN>rcT%(Zn$!(*^3@4%;DrM9b_ z(-JRby$heVVw)|WW#qJWSz~j9t!fLBKUGFpw5kNV{&>^+kXy?21UuSL&*jvWwZ1|8 z;~$S#-%v_@sLI2vw=(t8JIa}Iu)AjAtfg-+E2t@Z|8u~Ff2s6g<3~q6bBXOcBWk*p zKg@nj-?=+I*G1&a9ly6aRjjv`Wyxu^KA zRAb`GdUI8G-+bc5)%i-Tjf?Lk$}YL3KhKW);mrHl7wN_^#S7pVKlk(3(?cWPVg^OR1RlhM>#$tbSbhX(Ph8xtaM;n6bsw z;aKv^i;>-}+i%H!XrpL^P5snsboUO^lCS^cqx@#etv>NZ`H~QQs4|ebyW@zke**-eJyl(I^2|o(ik|@o`40%%5euNSnP}K1cIM zdHwxsN;|H5AV0XrffUUR!DE#jQh> zvJ)5h`G$cRD^@SU`)~s2!bxq92@Wk^c z2IDJlUA-~Af6rt5u55Zh+{+6`%r<*cRXzB>E-dX7SY0%yu}ph8*EHvf=5K|&3Iksq zefmw@ImFYu^U4C5TZz@@!ldgKT|F0gqRO%R#P?&7M+!|>+>Q22@OREMnX>En_RV{^ zc8A_KsuTNSeRo*_Z)w#m+hmWwx7E%2SK_l}<7v-iYG;)v zj4PJA#8$fnuXv#w>A*{;Nc6a7mh69fKiA=W?qS-IRVy+5x#?~y$pfD#HL7hq3iC#U zlGet2UgDziq_aOiLfmt=_@;YLbn=dV`H`^f#5;{jnY_UU_B#*lpVMRxdBr}iKKfBl z>%NhyF-363p6--8gm5%bchr+$d>{7H|ovU&;OQ`_yL@ zyAR7h)DV=}HdS~*#TxFndffwlbGl8L`>O`DLU$A>U%RFpy>42YxnE0kT5;%)wpRPl zq1bf6v;29I&I4S+!yE3rxGA>fP)G}v+9bcItgO0LiT3Jo#JanETHAMye<)Fv{y5eW z_BruezM$WW)agkJkB{A8`+HFGcAnoJG_XJVUQ}1g2WxZ9FY^txS<~y@oj;nr+TwWg z!+VlNyZ9b1J@Ld+W^iu1chIIABEkEPi6`k*u1-G~aooseTWYxAGIvFbTmD`Gi-Ps& z9_8Out}0khy*9fw<*0c2$eG!3blY{Na$}?0yi8YFc>TII^6ah*wJmd4xU|!-*5OlS zdNdjr%N42M1Q{P+L(nYZYDAZg}ukgHO~V%CvPKj4LaZ<1X#n z>N@dss5RT4XN{*_MK?1@PA<}I4qv? zz{GaNxs>HU=gjP1oVsGqfWD3tKevkLR~dhO-@RCC)El+))dzf>GWf4bFVIzRVZ{~2 zGwwSX=ru_Ny!lmsaal}jX5mh%#RHuk{m(W2S#emvSXjARU3qql+S0?!FcU4Fq8X@;}1-6HXe;N{m^4x3y}*KWUm_vPZ}j3(D~y>PCguhRn8sty!x2@dDh3ocLc z;onVbSxPy0f0vxmouNe4p@{uf>?U5&ewq zO42_zbDd>FIKO-&Z~cDBgP+yB4Z<9+mQa2b+*%Xl{5>*VCa-AUK;=oU@`##nMOxhn ze$^YdyT43*m{t_Gv|;Y`r^72UgE6*LxR~UV(-jqB+4pZ) zh%VglTE@2Y7WI(+eP#COv8o^WZr)CPm&>I0UP}D@_Gj|(U58XZS896x3cGp!)Pl8H zs+LFUy)GH09XubleMY>gTfMQ0M1)Al`jy2h$NIUJsiT8Z4u8-){3?`JP9~~ryWm6d zR)%1A$?fkasIwjw3sX;BUMJMN#m6<|+`*#LoQ8gnM-fXFsb@#nG@t*VmS!ckdS1RI zFQ2jR&ojDTIiFN*^Ak#z+XtO`D|EO7lPdnQzeX%B_hXEk9o<^gY31SCsMfgA#AmN=UR?~SyLYVhudTl9o@x! zf8>I-x8R;pv+py7jn1_XzMOToH{V+9&Q`I}?g-7A`O|LLY+N(5?*64rMXo)I;zH%` zOjGCceAv@UR-ERPxGr#Q`nwmJ*~j6SO3QpId1N)la)O;!&$Q&!FJE$6wTOSUibaW*OwofXT5SPI@O?bbm#6q>z7+DJ)gf{IAgA9YW%(CiywlON>&}f zZTIV6i+TE54c_t`ecLXF@jY(qljGKTnq|K%Mf<6x>ey796$`}lf-pH-sSgU<*k`Uk zPoih&Obuv#;<|J+yQE-x;R?4q_sh;LzQ3`5%F{rdm=m4unzoeWdCXH0g%xQ_y)<}F z-Pb)&-cI>e>2`BL&bVGi}>!-C!AhOwLY@dEAj^=I`ebN={1afFZNy5T6Nd+m3^ha!}T#2 zH41mz*342nX?Zy%rEoCWSM;c?vpZ{(MF;EhiM;GJykAxs_djY+zQ>z&%}Z{1ZA-QP zg{p9!ZGxtYE)UA?^$6Je;rYfZt|A(3t%`#2g2vx=E5v(OM$W3Oa@Zi+dCo6yXP^EN zFN>pXo=1!7vscY)EuXb}_lrAXxAUVMcIwKW66+RQ zeQmp;wa&Sq2M-f`M76l9b-7PIII@0ovb=lb<&5S>dlZhCnH}_2{}F6CtTBCub>O?hEIKVF!5dGlixnO`RM9_u4-o>95*-9O6aqRcP5Tifcu2@NKL*lXDFZU&&_8-&@txg3Y@& zU^^pz;AQ#9$+Q#Y_YOX!6=u$TEb~@B@00hj!2`4z#-~2W`ouBjE9_dBzv@oQ2lKYu zi>yuLyb9N7MDyn=RdQ}Gob_J#{KIPx+P=9=5j@}LKBLX{`W27GQ<5TAH7IB3WKQWU zIi|6XPpTl#OzF_Y=XwG!_G_>_6muBw_~M@kKYG!+E_J6;&Ev58$WP49gyGE_uVLp# zr^Q*EudtBwKoUzJ1LIHsB=zSI@F}#;MJIT z-HiAA>i+AB0q35XXk6cPXw&;cd$zxJ@tpQ}Y7XzQtN&~;w3VoQ{F2XHBko%!|*EN-MW?$>xvT=j76*ek`jU!Skn+*2Iywon)! zuo%BFeqeYkE^b({r}*6X==;$fqO})Co8q(zUbD8?8>|_BuZX=JXbd#7ZEiXe){hAQ~yAaP`!H*rhystCA0!EGvti7r&G^vv%O-$m_%)R&AYe zPn>(rRrS&G0S6(b${v}R)RO1VN-VB>6no0uE?fV84_RhxGi6Q*e0!hksFswU!MtnS4Lnk{W4xoG(|wk&a^h*}-{`uuc$Ii;^` z7xk7!^4Anr*y_p{1g%p^+;?jC8or*AcM4fkf>mehD!VRT-2C{Z*rM5qtPAsp2lGsh zZ_^EHNiu)9CCSpNuDBvcCrGnld8yY5yTAy$75mkXF1Nkcz2{t4Ynb#BbNB7twLHZ; zQvIHP-&zp;?uql7n6#I!v&)3f#@gDrnHzd@ZQZl@m21a?Fq7o@HLR;iTi4$n{I%Fw zwX-cP?eKhN zv#I|4vBr=PWy!ZGU*k>-*ss0kq$~Gm_Ylu^#K?O^^Wmq*Z;uVR4sQ)!vRYrG1QSr@PJjdTQ1P)yAYr`H4E|rt^lp%?j7<>DPVk#qK_F z%UN;Gr8hh6)7WyA=goZfr!zltnTG2;bl;e6-jx@x(za#kDCKPr&C+i( zIcUCM>GF*pomwJ18^xt)58r*7wfEZaY#oo{7vGoM6OG(M(LEITp>~Vqybqexcg(2= z={(EYFL}6}<(d1VFzmtmI->`9)~h2niTxP0RXtj~O880Bx!bGbgMC)6wWg}ixuIPB z#ap1(Gs?@~y1%k?O}%4>JELKGxXO`wZpPh!t2TRWON^Idd z2frkITokvw?)4kU!}g4_{%&A*yMC#wq$f$o;z}65-!QD{@`jNFNYq%OH70Qo--BEU zph?zfVuTVefL?E#>jxPJfD&nYMzWh`@^2xviZ`cuU&(HVtKCG9+X3Gxxlt~Lwp93n zLo}Z;KX$;b1}fSX1kGy_X3-@@M+r4EK$84oq*PdzfZA-5Q)*0t@142beULVD=F58OnO?`e3hxy8trXYA$Ss=qX zju~2;*6Es#pdM8oCJYXZ7qAnKqBlhYsR7_mE;nNL)mzpDZqQfmBp$*3bGx*Vj}KDZ z@#Bckp@%sl_w91^3{7#EnZE_OIWlm#Hwc+v13r`2ak(GN6EviNn;K>flo5D|u<_Bml03|unBBM471XC~hsd@{s>eQ6U9gK? z$RZk`$JTHfTW2C+gMHwXgKxD&1qQ!TB3{6G4fJw}gn41ZJwvMw37cNdkBf(}5RFhr zCkn-=+;biz=&zA_D@8muOU+B4b~@V9L6;EGwgLZ2SiP7ea~($Z;|0UW;dIQ&FIy0A z<55uF1Ax|6lm3L$Q`ECdDM~R118i%Vld5RaBScc7JTXw|G4hQ>bg=h;H$%(Q)iw?Pn1J{E_sC4CFo$3%%c=6UR zr3FP8brHQg(*#!gn;uqW#>mc~0KoBCQTlqy9@DY|Z?B;mX)#8iNDPswW!Ts#a8N0q zP!a&%w=z}W1u@K*;6pZZarg_Us%j<7SCxUKsFIrOW5<#l2jlwUF&5 zBn_~gl%UJ}4CT;EAf0y6!Cy5Xv60;QmO+Vv=fMyeu~FGnLOo-GNT=X}z%I`lP@fPd!+g)(WP$>*MnP()$%&xa zX*>1ko(DAQZY6SJKrz$+J{8PxLF9K4-;j)?WJm@pxHF;PrR!o#<%ZEa&4U>~=(Q6- zZb>3j?x~M-)l){yFo1p)uz#TRLKu`xvP=w{(5XQbhk3BzLh|S#I1W5$fWvdmpw@B~ z*w6D=dx`SdE}Rcl>)hHEp{5?w3DF3$CWRc`#iQ1Zw&rjL}^ zl!F6=bpjGeqb{H;Q;DfrmAFKPL1w@Z=)OWd%GVd zg?J1hunptQ&2oA-psh8fK2McWaUzSR9q^-PI9s5_ zplr41$hi`g8m9n%Ee6Hou-iT=27sK|wQjImCPhV;^B(vd&=|>s2$*sDldZc&d#$BPG*6F^b*)8(LC%cqK1NE#KU%`B?%Sm+h}bXm zW8na+&2LeihpouARsIEF6D#vEysD8JWLjI2-%pr)88E$i)&g3jvxE!|(HeYmzW~xz zRs`X=a-f&z1~@_kQ$+!-l^koMOwoVjvhtSlhGFQJbM0pf%~!xOnfIut3_G>I@-cjV z;uPFmn!etUqiFR&yNa^~XuN%qw>sON(&(w8UceDJiU|&>DeX}%40*&r$_6&ay6wPVhR#$~p{wnG64tu5h7W#f2=S zs>9A7M0Kd&n0B@zq%bQ_019)G!A7d*StE|8%cap+vA4jMp{#2hC((f|N=44jJZxR4^>iD1o-Cg)rg z3iEoDx`rhP3g5zECu!V-fi?MqnFvI`qSUtg(Lw_Cp+Oks(drBOOOXQLGs3psYvHsb z3p}pvGKcV1YKwT~p*GzT4tH>tQWJ}XlvsgmgafpwHJ6a`u31;DL6j|2z6UheUvHH(nP`raPRPDLLb#7e z1dCUbu4k;}2svwn<_fNYhIC6wK!Ji%1OJSpvvm68?X5s30Ts5LQJO`1+vGezhfi_* zCezeiy2m~NbW^_Y0*K21${SfB_k+T%4jj!5kB^l5qe_ckTK6KSh}Yc0@}w-sBxk`WP%F z6p$z_`NC9hmPcmZ0Nk85DnoD@zTBu7*pzK3YMXJY=WPeA08HE>aI$K}TPoERGEaed z5=eovd;N0{mOW@K19A)iEwe?obWOTe;X)hP>S2#QPpc6vBN3K1l)*Bba!mK5L+i5k zct;oH{vEH?0H2-4g)AOnLnAd-ap?R?J^u~>0RR8Q*~bp^+IAS=6CerfNsvbfJW9X; zdoz%M*n6i~X6zK3*xOU(3H(4F`4PhZl=%Gj!oEO&AOr|vOAsY+@4eQymWF%Bc9Z0x ziN9eK{$MIn(swF`{dK;!OdV$<^>NsNA$|MMtC7wsP6!Sz<%G`V9+!ZlTfPSJx|)V4 zbOxqDGYAXa%51SxI-L#n(@jqLinmObs1VYPwL=DpQ3$Pe(1Mz3@$%2@DL5>@Ro$=946 zMbXY98UdkWwgPWBTucrCp^8@N=Jq3-o$Jn--jg9{76s$YKRs9nnfuA@r5$SxPo zSBG{Q8uznhypwGMG=sKo=0v_4DN@D_kr}t?WSWU7tV^E~RC+4CGW#S#$I(twje z&sS|{_yTkFx`p`dA(e3Z$k&SY!$rsCq&|SE1B9UMg4)CNbsZlk1(bG3scYEnHGpGq zvR!Nls{()TuSEt|tUU-NHDai|hCDQBfN$O%B7C(^;5 zgrlzI7Yw{KsdAbepRAlYh{no~{d zprL}}W)9HkUPZGSFr(F{D(!3@`GIP4(~{!l3@{bz$2=pUom0Z|MQ8d-3>;yy&n`(dj8OJ|pe=Q%-}FRgenBa7d+sQso1Z9^ z!!gmqPhfR!VSA@d_cAmuhCoLvo>096TlIdOh;ND@myT~Nq-@XtWNg<%#sV13gn(3m zrSurHgVUagWXb0jHKV++xs4&L0H>uzZ;LDi!bR*ugM!a6TI1?}{=@(H<=5lCJmD?jrQYqGoFg=fx)VJMlaIOB-^^*Jt8;E#^hNEM6Z6X{|S$MPy#5!3L1q_Jx|t zmIvoW$+cD=*b)iA3(Ra&lh>5ur|hIQY>-g$4jL#?##lh5mA?12)YGxG{g2jSY>9+d zXL+d!5>?=W*}MS34ctaz2RY$}o7{hLN{zz00_$^k6DlXe3xRtCEzYIj-p}W99ShK{ z-k+^KFIt+`4whQiS}Mos&q!uLV5hSx)wJcSvmNKNq}r~+LYk41WDa1su`4+x=YC`q z(SHJ{G|JZ(Q;C*p#1DApgSqpt*>7x}(N`OGZ>J;xokJ!Nr9z1iytoXDs}VC!iQO5O zzL&O|*}E{uW#+GTIP8J0^9Ur5iljj{WQJ2;j8wBnZ(X5`Ja-&mlo>^Air0Z7Msh5> zYR~88a@yl{I#z59Q3N%d_azDPNN6lx)<)EQJjziq;D&}z1yL0ZVYDcPoX>_TIAm{w zR9!RoO6wH^=ddKk(94MAyUuGBVmwSeBD;!0j5q=*?e42hZ{7yZ($H(zP5FQzmaA6j z8t|8CAP9W$NxKE?8z`VR^QJKJ+Ypr#!wNIGclyrv=|iA;MpuH>V(vW6SB=5?o9U6u zed5fx(wHGq4x7<9>(Htqf3P(uG()uz4e+dTq|9i!IN8AWvp}i=OdE(ax-iD7tRp!y zY?G_4)(P+dgSb~A~^vCG}6iX7R;ohBFWgi-%oSg$Y1XJt77|=2bXm9uC{5swP(QIz*YCiz=u|e>!DotfE{N zR=$6+*92Q@gOt2{YRyI~NK4$ix~2>%v1T$qQBIJNPbmi1o--bPpehzcoS8Iky=-h- z1H+ZifkmyiocERqOXwGxK!X=O?83}Upi<9c)34GN>?WE|fHL8&)yKosu&c+Fx%N+s zAJ2GSDek(#xKaiOOSe=BrfJQE5?)>g|a`9byDg5{+yv&$UVmi7nnlwJrxW-X-j zffT&}-9R+C312~O8bLHMw*VBrzvC7y7M5uFq2Q@%X*N({XsffGC}*w3Dv(0q%rjrC z25Oq#{8>h)n$edx(L#o#9P9#&pCb!GEBpNNTu(@Att_U?c4k_&?yZb8l%;FaS}OmE z@DLeWeE}yB>+NQ=Vl`a`R;&-!<`U)_Au_lm{r83U3+IVRh`t%vL&DSqt~9VxZx!i- z>1*B)@ixX@A3AqAIXu^{$pNoi&FdoroJ_-W!@VVlHv0mr$ALDB(oO;`S8plPeX~3% z+7rnD0!DHzdtSi2A`7w@ZV<+#7$DODFj&us3b>NkHqzn=+C#aIux@UPCM=pY$6Po= zw||LSNGb$-!(5Ig^VPg6YjN*2PwMH0`_Aq5Bkr$7>`1pm7!45!6T)dgd=i(NiPV=k z>U9!lINzjtZjA~+6H?5D*rN-2Ax~Z}bbX~DRCanx**`=HDVOUJHGnMg@&?lmoO^hi zky`~#G0}24QH*Q}2DB+#)w&A$*`!$Jmgl{lA&y2S8CLT*e^+>e=Dm(aF$>pn3<^+K z7^!d=l)mbmh)q?hF2wpgGw^GXI}`LKkCe4GRZd-A7s|KI6Cpv4X&W!)q%bISzAn1n z&|*68OS0UUzE}cOq9(ixOKy8nDP@imA{}Pg4eU+VhjZ9LSQDu-l;+_hvXx3(s@uSg zYM_OUki36IoFid?a}v!eza@#v^b6kKI&{PYN(%u*ak&DGomDW|k8mE@F3E&cP6)dY z_$5_#_VIAq$|X=i-&k4Jioa|dw?kugh3|`8YaRh}#wsAIt?QM~a;n30fog)Cgt~#D z@YVP>VCaVLjVEU@WNT2zLkBX4cKRq`4>*9qM_XBeFnFVV!5Nzb6gv~H=CIFJRFxHr z5|@XVI5&=bIbeh{;6SoAX^@45I|R6_6x%o+4&J=LK~G;MhFnFBpnfS*V4svYVeM5m zvw?|Q!P)|HG?N7d=E{*oCgeEPtw#){Lc_}xM*~W$Fy8IiL!F7GM?zoEq}1*PmIP-H z4LILHn}$^12Y%S+|CM|A{|on+f5ScMzvrHBYwPVGA3nJ3@RjtU0(Sn=0(clv;6U{W zRO{r?p_yawGZh~LSAwswXnSl%c6?cLW6JZ47N;0Ei2Pjl*i8|r43!=o+~z>6It9GC z872A2b)+2m4kkswOFjC}la0bc*oWE7LfG zjZn@qXGmqW19bEw3dY&)6*&~S%B2SI$M1BQR@`KVCn7D-&pX;X8tLJ0AH+daas?g@T%5B0Nq#^xvYH0dAi zS)uVS+_Q#8|F{R9QFudtb59KWKioqauY}_RbhkB|R^L&Z_=mnNFNF1844y{=g5wse zN8Jf#ZJNAebPd)DZfZ%$>2s)B(y^L39<~=lVdT)zBVBmT+zoQ0f@bfkQRg&FoDGb= z1|ZE9Rh_}^dovIB@~AR~MDVZR5WZx{`Al zqLu+0bbnQrkwd;{D1QSy&=F_CrDRB1`~c7l-#x4cSGyrtG@Ds3D1 zThG}i@mXqY{mDJtAMTkS_gpAf{-t}Yzj9CWvwQNtau4vcd)^co{Z02wU+WL|3_rOi zxqo%fR7-}655K#oc|Go_e|8V_n|na3H~(;tHw9$Q{>eQA>i*%L_-FT=e{zrY7w-A| zt9$C--7^irU%6+Uy5HP0{_39gU)_V7(D=hW5|I2K_praar-OfYPyB~_SiOMs74*^Q zclTua`LlcIS;Ut)_`^M~$36bf?&1G%&znF~;CJ`DeszzGrXvftgA0<&NU4`rrBs~A zqH(_Y;jNtM5|E&6p(RVpnUaxg_K)MUN5tp0TzCiPbLjqz)or z#zA+sZWis|>IO&|gQMTrds9}Gftn=@BwICYwd@>paw?b~@nV~omGxOo&szYL(EVjf z$GA9jrql)s63_INaoc=GT}xj=wsoT zLI*fkR7pli)ctlunDd_w)%4pe+e zo@;{ExzyH8-5QJP*hF{5c-bzVdtSTVq5zmO0_5knqrGwa0tyahP;pab`N9K!$**$N z6xyyml%~neYNQv+nyNV7jLEP)?i`0~q8qQdWJIX6ad@lcz^m%vdG27?v_1v#EL=GH zRI5-x{o$Vf_V@q3d;a+^-1E=>Kl(i-_4+u#OAr$v3`z;5ZgXZHa<)rD-i1ZpVVNKa z>buQVM`a`)4)FFy0sHB9zO8^ngKY1zbiO zGS{#2lUV7(iBu5VlS=T`d+%ZRl>pF~_l5a3fE?wm7l`J-`lvYHPbu&X ze1$@&Ui($EK)v}-KD~%|$cV57Tn{MF_vt*zylRLlPasA3x?CErd*2d+Di#MjT)OdQ zRO(ykPn^1*ou>ds)E6{y7jji3R22~|552RX(fA&gst?fKD3JrV(Av1N8i0wWu9JjZ z1%M`RwVUj~^hb5M;P`k0qkz#!u@=0_TlWcTy*a~f;Jgt7&fyEcT(FP$KlOZIg8Wm@ z$B%)>J}yN6)bk0?KYBhEOAYtbeSE$uA?Kw#vrE5d2^odTIbF#iURtWC_o-?bfRu4& zH?Pf1aVhgwlj_OBlB+k|N$(MZC8)tpw3|6a#BQj%hP-wJ_7?4R5KcZX z^ob<{A}K>qsJbqR`$fqLftVeJ%BxDK=SW=Xh&+q9%e@bvkDHrdZ{DM2Vh^vHOpC80 z(&@stc!a1}x!ktfcS3IU^Png#^E z$BQd~5_I61qrtrHvBB5O!y#jv)7_nDC%DWR5lo1bRTaQthrRr;vI6NHdLMiL3EZS# z%TGorU^Sm0;en6dR|KO($%W{e&uWO3Q`$SEfl*Z;HPxj#!z7R#4Z_mBf z#E&%lHHTlMsU{&b0B&jdGOt}@D_DaJ0fw?Z)dkr%$R2#?&#pu8#|nC~krWsX{qNzE zm37fV1f@4_15T77WdJDUzvAKS=<3-YVh;BUZd2Qf>U@ zE1C{oa)|F;^9H@W4(`tj%p)9{b1Rfu_($8P83$M{c0287N24X%@{97I)=(gO4D3)B z)Mf1=9`0f{tu1W+Oa(sEz&ckBwj?D5kPGGAu$7rskH)%Jeo-kbRkTX+6fu@MnT>)e z?C_0F)c3}QNsdEtx8XN=f5tcRmC*=!*r%ufBkU|as2R9>d2eo|pdaK_j~|g@vOPt1 zG2d-OC6%&^eR|Vd^1R8%G(M2TwR3xQ;N%tw(Xz7gpeJT;wZv}#o=a4i^KKsm{k^q1 zbS;6GVyCtxk`fjhmFAFAVi>SJd6Z?An9_(Lj?C17 z9&%*`cF;NRBl0qHoTms%tdg=tDTp%l@P3KRGnDFGqu%tnn$V0wqwB7);xj z{DQa%Y`_ZeoqZ9Q3A){>cgKd=VXZL-cCXWR|$U`;ikB+23lK;=@+3>bitZ#Zh=AZ|9=C6ODv4=MI(LK(WMkh=4R`iI*yyqia1bK{ zk3^M)8^W3>5shd!X^ywP7^8hA@NHVbL*P}|v;X|R*#G()PP+g8XD9s_|JzQ2e>e&H z(H{cb7Z0;jJF1FJsD7x*3a4IQX}nq|^9@arrf<@t%aWQ0I=m4Wfil*yF*zJxvhE7} zoo$B%R!pr(^9~7b{_`cKU_F*Q&Ak)Q@9j>=)rtC{Elca%x0t?*yJuOksm&WW9zAU_ zf6`rsxrtIX4OBKb7)zYS1oX?CS@s|<9HOzS#8~)ikeA`%ankrPIr?)BsbmbxU_WfP zNxu6KM^G;#rUfJeY`6v2WOT5hocXlgiuF>r!xC6n0h=`I=8VI7w=B`eCY=g;>;DD- z0RR7l*vSrrY<3>tKT;CeSwy)8uM)9fo-BF648>T?uwyLddA`J4l2_*MZcBC+9VCRP z1ts8o=Y0-o!CZ9^nN~?vnEq=D=CKQfKyP|8hDQ^Ng1FtZA18}-#0&hEORqJwWv!sh zxomFm5Vk`^l~*BQ)6r=T25RZ#L-7uepFR#=u9S^+nB{~zRQpX9F&1J28N&mq z?kel^KADdt$8Jdy*aQ292G+$_AFk+FeehjbnaE<|&!|B*Vo&7F zS(u6&kP7+*kOMch7vS_-JW(ZmvJAz{Q}ANkK-%I`mb=`7q47$`YUG00g`QI6Chv&H zm_IR<->PV<&Y%KK5j|irfB7;c5Y(9sqPgtqM?rwxv6dL`=8Q0od6>ywiNrN-AKVSG zvQblE-bF{Do#KF~qYnZibB@pxQ4l4DbsR2h5E%^rkSBtbRf@-*O4kGYtwj0@*hJLF zI0854ayFTzXp|WMw3Bj(?=Od3?KZ8Op%CRZFEG0%hB1MbOx7+~;1(+?sKutP-@A24 z2)*kK8we%Avm6;4%Qv)mIR%zThPVZ$ERUOwE3~a5$xYpr?O9RE<n7OE|RLM5LDpJwDMc zydPL|8+6pbpPjs-yzoWN6akEBk0dmDGWU+3FXsz8SxQbZmDt&5i{uunH^-Kry|g5thIL=#Ps?-LIiM}_i1SSGTCAw-@4l`b8lKu z{usN?f)XtOXU}#9|I3EQwD^Q6FZveFj?HMTx zWs^(Yk+1df0S|l@`vrcb2CW^hDeb290bTmE8u8C{0vGyBV)-c#Ma7#_waNp|QU<8~rVL{T%hEqPVOy^#hC*Ak3vuizRrf?I${K-NzpYudJeqrbPq2 zssp%#c@V8&Rt0R=?n_Jiyki#d-tN=n)p*7^C708R3%k}`Q5NiPb1OGq8!Dlbv;6EZ zT?BY!!6AQclFgnz)|P+r05iT4w09a1*Zr?03MW&#a=|r>{&G0LQX(j$93|PV1iZC4 zd<Y zbZh-mX7xzeMR(xYn*FI!i@I+xl~yTC zrRcMocN+V0beuIwD^GNA{DlQZM{ICm;|`i>@5T6bucsyH;>}JX5_<7?5Yo*5~~p$@lXHfkH2jH z^WCBU@y8$k{XPD}yZ_g}{`|*(``h_{dG~+)$G;x`-2T_!&eyvi)8?Q5xm?EH*_L|v z{qKJ&K94W8+kpx;W-Qy(H#qlIVa~Z%weoS|=P1~wepDwOoi??<$|mw~96ZAYMTeCJ z^qj_y%5z*U@Juc2gH~NkiSY)`VA+n8Z`~GC_V9N|l26!3VGlHM?Jr;i566~M4=F9x zhq=Bz4&Eicz}bia_)0swbKGyuPG!FG)6n|#tqpIF3`QZ6hYILL`dThzKboUV)10ht z%n)X9g1pAG^0_ogZog&#hU78^WNR`dqosSB2%#Z7EkAxalC3t?C)%SfV1GX45ZT}i zTIH4GlcpdSL&cl4j>lRu5tjVc%xtUYsCN`VV;pWlA4^^9uud_<&Ll41_U0(!T)vag zrZsu27DO{?P@UXq<|1@+Hv|v%Q$5xdSlgyeOwAo(IUxx6b|f=aLX;j>_>JCEGtd5+ zX(aTiG20ppf_9!fg+JHK z$R_mr=pivz;b}Mz*z3fA)I?1KMNf{TT^Bmaq#%ZoCyk4-*$|L~N#CF=^8wt- zP*f`k8@(QN1hJj6u?=*zSEyFPzWlAZ?G(w*+gt6H{Hd32LE={M$OH3X5ARUP*eU7V za(`#^zH57a-G;qxQ$9WPYqj3b+7lFu&pPf~b<`j6L~BXoI~?Hn89p-*J!83f`t6ko z5R>In%say)O#q^FQ8V5e&q1HkSJ@XgvIEYc(PtWSlSqOa^2* ztNRH`J`&rB3jJucICQG@O-NPL!}bi6vR=1g17_X09O0h@_upiJDV^Ag%f%GT$)Tez z^+&kL6-}rkIlJ-1u@lri^@5>xB!c%{`N?KIymkmP4n>(15t8TuI#YeD7~V+_Y7X$UB~x zSWG|v!ENkOV&3aEp|;q<;{x>1`o~@g^isB+?om;sBR&q^F(*$SIILT-oDdMg>ED)V zfPfYBUSF3A$N0;~inr&R#eVJs!z0EWZmDWAZ5EE-2qI;6z;ANFP#ij-D=y1LRfR4XP~Qbh zkAFn-6g&VIaxYrcN`!dD6aq|h_!Sz!`9VjEuMU*B%#ZAyG59?5b6FOIpBS6E?Z*Hb zJ@@IcV2}QY5Ja5b5Ri2d&HGJTL56nJ;FCfoTtN5?+ml0{u?mO03Xa@1y4#;?kSI-u z0KoR)k3{M};_uTD1&yAmA^!F!CCwyxWViq_`r-6MHjEP*rs*?y&!4YHjYk=bipuN2 z!6JjMCbIs`X}gqDp&lIdj@PmgW-Q9Om>@qJG!rScH?lwIsFFzC zAm1i`$R>lUXAC3+)1}<0?wHi4R6u|>$)Z5e22N_$i}|yw<~+dyGzKiwyQp$wPOx0zB|7jf@5$<~ej^5L=ix3HKniQvh6@NhEQCUzl7wc{0&2 zG*kWM7JY-35hhGXuxm|IfEEyzQI5;+c_So2=OGa%@?x|lF~y^uoPsA$tqKl{zlD%8 za)-Y7LsLE=ytXG!_5=l40NF1~Pcm11lh_X0(;V$jd=>mu<(QMuOxjeIVdgo*fc;E7 zn@S=a@dW8d+Yb*|vgyYeyU){cyEwO@eG(7ZjrCoZZ}UAc?H8gEhE9(7#v2jo;HL|z zEw5SXj8-&B+~Av7%7f+_ZWiR5NI7iYn>S_ro_^;0H=Mj>@yYk5AflOZR7k55B~}zE zHj~fDi@F0tU{lZ>FI(@@0UdnR~)e0W*ab6IJ>=uh`#n%-7KKV4M^9A?~6@ zGu7()NGrI$oEAb1(+pDL)|U&w50A0$XmnBEMC^(=@1RvYf>&nAAr7~n6zJ4BwDrY8 zTB{#*1gnK{!P)0L_lQ@c|1?YTiO&XXb`IpI(Za%2IYzqS*lY$J92Mon9s_epkqttP z?IQ;|E#|_7P9Vv4Hvy=!JjV^wgGo zY!V%~-E8iJcK*{!yo8U*LbA5hd|Gbj&@qn(Q0z?b0YSBZv9Fe|f1J8k5(khA^D|w9 z39${_LN(Cf?%By)CcCvBY2({v2+Z-+8~+g(=8uzht0+u;t;4q(oINO4zOjuq7#*v; zQ+zNV=*xs+TfnEU;6rs*aF+~M-Ly&_Sl8H|tvzP#f0cj&pr8xEGJ5@B0r#;3ah#@f8GFF6-RB9w!}`CgCE;Z#i0ArC41gD_}b&LaWVzZ>_V zl$$m?aUV4o@mr=O6P^*^`_s%ys;A6)))kQju+7*#Zjh@er%ss-$;H-I+EskU0}<$y zmy9}xDY~K&Oq4}Lz0s|X+=|&2@LW?S-h4(j^V)7 zpxs)0a%s(eN@t;Z88WE8uF0NvMQ0ewVjN9$z(g}GxwH)Vdbg}ZvVQ0WqvabwK&-97 zgX-HoG^!(@>8r&1*vdNC_8D$~9nE*FI7?|owR+$%sS2I2>X~!hq5Rg8;ZnwtA3Ij0 ze|;3eR#gVmwrBQlkS5ASR0NfroV5CHa*r~c)7Mb9Bx?)@#K6O+ z{*v;YKc+=(*NZF5gfI9`V7b3}mWn84=L&5psC2cxJkE8R)!^k%FW!IkBK~^uwh3=b zV*I=2@ceo)o+T0%X&1;`>UdNxD_WY0vjemL-HYRSgH!o}&R@RstqULG1p39PfA^xGX1R!{vCEbO31?{Lg2I-sK$_%(x`!)_ zB@C@Us}mNx`34DV$;e5wO+VCHM(UV%Q#UaEN;5Es#r#mFJy8hkPp&?ir;TAL<-D8} zRzh*MTi^!)zg%u_!P~{jim3`%|BVzbbr)^y#-n9=agpdS`Z&_BHgTdwL|Z#ScoH|{ zEaFaD02Za%JephIJql}76mDN-h^b*&4sY~oZlQr!BH&jGou@J7u7L_Ocm;1bJ2*m4 ze-xHQUV9K)xF#Hq9OWFi+o1p%i#4b#mt6PT^-$l6=^sgcrj*u9C>@VL44HFPcQ{id28Jtb0v%=Mhn5@md^lXV{_hb_eJ!fbee+>+0Y1UtF(-o2E z8*V0U$N1m8sB3@m;{K8AKfOr))r<5==-YHflI-?-ML~yx-e?=AHS8ss3jB8R@Nv7t zt<1T1qp0=<9Xe;)&UnApV8U!4aI`=q&6jz=KU@m@* z9=C;U_z7KD|72|Gai1E~R8aoKp*&!P-X;nBf#IQHm9UE&2PtK208sK5_o=vDV4}w` zdXhg&0{Pw#c}%u$_lki)$1*{zu%bU>^jUeMey4x>if@^>^aTgm<68q~+JcRb8OE}1 zX9J`^hnR*!ofa?DQts6v);sR-IK|8TG(hc%)u?w#4sS@tUl&|rv%;3103hok_cy3X zjZtOEMyPjRO|Xvg>?6>w+5Vp>T*MlE=?FcR0nCJ#wB>JlF42_51V z!fcjpSboMmCxbclaXc0zf2{sOmiId{KWk;9^9Kg%DX$giW^~ z$H+PohY4?-t<4BI;STxMb0DMQz!R+w8ryhoexp>&`c2XAvbs|JP0;9@3_s~eh6|aD#uDJz;(@i(ex$_;x~=@_tgoohiqn zK@;X%9ShNz&|`2NlVRuM5{r*F+tiF(`#@rVbsCk+`^Mj!?T}KZjy1iPY9rRcN@=LH z9-nnw;^X7}gMLWnof-uAg$*_0=0Z;S6DEE6VGjk=5N24T}xAFp8KXgfDG5 zqw}-GA}dI&77SO9=InV%fWzo867pd1(_iH@5|jxy<$5mT{DB^&6io%;Td@iZh>Ql` zqFCRSIn~hQIYlJ9$(idwY!UIb;l@K#~0_R8q_PXKdzUZ7iy!dYb00960teD9P#N1Yee?dhQ#Ak4%WRSkQ zpirsweWg!k>HEIV)0^wP69+o-z~OM92C3}5*ZNj2QEY#}N4;UsK5~o`*Ez3|7#2X* z*-8Uw6j!ATR540QJjkTR+$eU>9u7_|g(}mL;V#Rf1pXG!#t`CSgXbpV+vGUtfT6IR zt_fyoP82pyxYedD$Z1|S*bkjPz1~V&EETZLnM3#xJ+8~(q+s-K#z2{Fn;XlNrq8m3 zt^gM`cfZg*vn8K&ce-mLFF(pX>}y28`Snm$6`nA?5lpcIpH9jeT^UI=qb*HH*sn_= znPkw#lPjZ+)gckvU_}KeR#Z3AE;TJ=FnY=bj^>*R&Vk6DI;_DbzcbH8@%hmG)js?O zUx#&u=;7Md;Q*aG6X@Ru{(VI_{t34%o2K=A;5iycI)^sItf?PIxgAp750wv&8I=$S zioAKiPIi3r;Sj#8If8+Utf4P@W~N?0{7`42ir^tm3C_fHwLeS(?in$C|FlQL5p|d? zePY0}t(WIF-Cj}M@j)N7jpG{kmsFw3o!q_4>JYQ2?_D>!wb6#&p7#^quQrgepGRow zArk4dAhc#k#6@=vd)T5Nse3!)N1R4JZH`OZfqWkj*zFvmx?=SvV=n17gZW)4A~mn& zH^2?9ZQ)XaL89`n%`s2a6A#iffibE(?Xha|p z9aD&m2|nxc6RyAs%&tE79P-ppXoFPljLqKOCqE!9It9U8)4AeW(NExgU@Gsr{R#!^ zf+>NP1!9ZyEIOZtKm7vQF8GeX3BbfU_?f$T2hG}3BEVM1IS)!$lmy_Xtcj9>z*+ct{Rl;E}PA?$a)9Z-=jrH_}|_{gZVI zeALOxas-eHM?{QGdTO%Z=mN0FSX_-oC4b3GzoJyO^D8zm-vUa++R!$!PR=bY#`o_pbXs^f# z<)gPrXNBL7gI1fj9Z>jy02U=62grd^RuAtU%;(mz3EF6*DBnSX`XbAi_$-LR5-cUR z*NOp8F7=?|aZGi#G51Chow)HgI z@7%skV6WrVlCA_s!gM3doNm{z-w3-Y{f~&^#TWUsuLi{VcB&>il``O;JotNe5VCBZ zA?H@Zk;8XcKrWyOEuH6m{^MW&{f|HX`Hw&TnEvUHKmPtb|KZ(#`^R6_-~ILeH}C$_ zKmFzW^ZJ*+-q*Vyljcuj%FN&8 zSHd<$R{G~xNqslfuElsUq8|YlkUWfLILfu|m*)scWH>oBM6vlCrs{?3iwV;9#^w?V*;pzlW z85uc`;Yhv8;~iX0>YI&v0{ATA#SP>UBhr)O!p?|@Q8Zc&i5`R8KyLYA&F}yXu>{5a zgsbSUk;Op)8!q_pnN4$~8vu_u>d%@2@G)#y3fO$H7|ihFC_(=eMItNeV;-(&8ux*@`(K+>Ex=`PXPh7VLV+)s> z(>^2Pd%TlcxB+)x3>Y;h+Q?LWWmFu^7Hx31;10pv1B1IWK!D)x?(QzZT?P-X!QDMD zXmHoy?)Lb;d+%HC{h8BM)jex^^_hM4K3!GEF(`kEL^}Xb>B8jJcu)b0;uroCrHCb9 zhl2p~uM|XHiE~=auQTz3V!(q}@Bu>1+*W-vjY$FOs&l=?uFYc%;|cpW-^=S|KpJ}v zV-~uFcnB^NJY=omv=FboF>pbJk2LdmOeL;%iPJ{Dj%$A3{AuE+3X2aOdbL}$3{4*+ zP%bX*ugnbU{jpGsl#IyixM@O#yS?L3XE?&7u#(9BiQjyGwx6_Qmrm4T%8c7*KwtFi zVx4yW`c=}W*>R!aE3ih%3FRXGfm@T&mw2UiHJR=lbE#EBX##lGR`TJM1`17Mi_mr# z3}AgET?CJ_yprVpw3=k{JZr?pc^c`y;>go0CZ2%yPe)X181Gf1I{rN;*(G>fPU1>V zPRXVpHdH{2ZX>9$YiMCA0-%E9K!)Oe0@2FF(#~^GTaV0qAdJ8TTXtF z=16F>li`luX)Wq1DkqX26SN5nT`nVfC6-PUD=-FML!>_?nr9qK6Q>}E>uA)qMa5@8 z1%5xI`bMaOxa34`(P4I>#9isHC9LE-ZpUk2|Ju}=JN8JfG~cm*pPw5FU2_-hX$bWj zYi2XF$v)yXbA^RA)(Cvwwn-~RA+faR_z0b~<;1^z`s;UDm$F0hw1I8;(sSx3A|cET z_RPQNu7O`$WB+y{gU223dJADJc2pgGtzR|;`2jtt6T~N*AG<5<95G_vdVCmL^8x%o-Xm> z(Q1i(AbQossS2z`UUejD1Eyn_e*q8Fi75IbjxxGf$*-csU%}dlE(KY^Muv8jBu^m- zDiUffhxcR~@!y-vT096M*|&KE5K%(wSZcMtK=&(7w+k3kE4OtzTZ%i#Bwk@n^FmPV zhG&Hnqt?Q{-So5bnX1AITV#q$|4_1se7K3f6NGFZEzOeD-=CCc3|e2H{Sm8wlh4#) z0KtPD9{~#+Jlv;0#S+SCgcN?FkM{tokivrWh>01^vzT++20`MF+4=6RQDx(O>R^3C z!I3fPhj+hH+-t?inA~6Bq;I)twv^h&wmg~Gn56B7oG&S68FBfYMx8>cA-)b38IBrmkxWO}zAsU1e5W1;G=e_haW z_e6cj^RP+RNSWzPT{vdd)aX74C2uLvE(-J>J;PsF;i=+{4FPU6KKKLVK*-O@E9g*L z2<{T2#7dwjjf_>xTrr^9luxY`S#xYtFBIN}EycCrsG{MB?u&1w_V_dK_)DBZqVFh% zgb_Z3kCM1Bpxy);e!aLE&Rmc9$FfQg)7f$6NdYatr?%5ue2QW+9*Ufq7OHT!{nFqW zZ}Dt(Q%-ssOpEH&2u_Pwfv^6@6zx9G7Y3Ih6vuJl9^)ElL8+wvWxLo*-=v}b5Mcyz;(Mf@A#cG`0WTSv-*k76)A@Ux zB?Wz)YgoUoRf*_Q=e=Y%NTVfSThQM%jGyO4`fNoHaU6~Ye_F-W`5U8}&!QPe>FF4Z zrI8d2Q>)RhdXB~!nYE9`?y=neb-15|(*);}{UHX#LMwl@8tV#K9doReK$oI(w4wZ| za)8}?Dnu?vhvs<6QJLLEjaNZFJPOURNwJibe+Le~pAZR>r42 zo~FSxWyc0{HhkZR%@|AL*S5WbzEX~HUmj~DTw<*)<&LG(Glg+SurX_? z2Te@_xw5Ta~IzE+{M~Qodt1jTjMlBWnHnm2#cKj`LmOL=3qY77y9_pbeY>` zf0M(UX1%`PB%;tn45GsK>|b5x;>4{cr&oed1(l};&E#G@E_K&8xEXyxfcUhZ0eVKn ztsCXE5V%&l3MJwZzO1XF9G3|+>z!Nml8oZsA*Bk=8w(%@WU376Jx`f}`@an+@Z&^& zC9v4&K}3-VxVp*jo{Sq_LGEBJJ$z6YhN`9;6UN)o5ApU1?;Mb{Z8tnhSNhOG1scB^0SDh1>UY90&oPzknG zwDV=P3``E#=$@rOVHoTc*ZVbQe}{QGR)V|HVxQwJcvGC*^7#4hEKH@Jmbh6{brEkA zci(5h`e1O-VPPs8k6g<2zw7n3hlKo>Mwq>6FPeU>*dT?jC_=KUe=f{3kLp471wx znk8H8HJFW1yJ?zU%5u2ntRW!xQ|DX*Hlkmndv9R*^FsoZN@?#oFJ;gTZ=5I?ZZ=}) zhbq{0PAQL32}2e;^A$|6Ys4-;j)6|MORIY$$m5%;xTm`}Wn{C!*Efsthmd zj7Y!~yP2_lsHrwk`U zA~g8x`0{&w&7C5F0w4Hm1Lv1==yhwbI8kc(&=0z4WP=}yFuv%PXScg@aqWLI4svE7 zYLJZK7Q-{LLC$vQ6!cZ+5tt~XiGC|TJO(7Np?~>DB4in>BgM;oE8f5|UU|K1CYgNv zbBpm!P0U8Uq6gQ$?G?tN+gJf@iB>p6)h%Uk8Aa5M_A!z;`7hz)2W!Kd8s#!<2kTAu zRgyCmVVCwbO5Q&AeX4%l>nRhf=5dbfHD725hbz^rq}RkSlYZ7BNI!mY<~*;xt#(1R8I> z@ciwC$h#!Vu?w;y5YTgxVi*yW|16B*i2UB-OX>Gl6d*)lCsAL_Q0&q0ArIt>vDue0 z)4HknSk*4~K)DBzSDEfAlG^uEHV+Z)#?pz5)5yCNTM0YYcY&=C&}}EWG1S{3HKGaK z=fKVz1HSk>YB`4i&FMp}@5%fqT|tum+h|C>wS@MMQES-rT1nSGvb`2;AdCvnpl1q( za2tl;Tz+W(siVqu=w~IZb;qH1qE`EcD=x{9X7E=;8zO0vY$y5&u~UAa=#%6Y*fW zHWUAdJ{p`&=s(HI>&%5BXqRYIC!2aJhE8~^O@jjkjVTFWR1i|t{esTJdLjIz6&Oyd z`-c_<_}Qy)Ta|+JG|UC`ofPiz3E+FmjzSbK;&qd$XMIgSF5LYkVlf6^T1_vZBb-(; zu!Kp0<+!U>$87aGj)iq}#d9E@rH$cs%-Ex85Jy^A9?A3^g{eu%QouQ&skZ+Fs+W^m zz~M0C7*3|ldhhc43U`23@G}AJSCyW?@A`7B&PXp<`X4&lh!n5OqT&Zk7Z#eV%g#go zTTxLV+)fONp(YZ!c!%WkFp&d&Vc6CX?R);i!!REaIqf;JZ;Vgx7warOD$k1KYCpMo#!W+xq*hfBn$t}u2aP%OimUtZ@DT62OAB~f%cU2BqZw5JIAjp@IS!7IU*14HpIyH+iL3_Q3CU+#8rHj5KUJi2@ z!7rD@E>7UMWUxcKs6bJoDx%nI4D^u|l|6(hE+A9%L13wrTRA#Yp)>Z<7}P<`D)Qm# z36F%rYTO3}$W#45Y$@7*^HQl74kOzvMNkh}L$$b!lNPe)4|}fA%G?%@@)er$A|yrj z9Os2Z=k!vFD+x`7O=uPqL?fTV! z$F92wE%~_>3g-Nk=qT~ob{VRkUY!^9Ug7e^M4_o@!499oR!4oHMI24kN~E3(P+7zC zUdC8x20SLL{S%taK1imKu@5`}Z7luK88UwGOP@+fj;m0fUY+5E5yTN#a7=_WB9K_1 z$y&~x=l%RQ*igiyY)XpE#r*Tb8tErCQ;x;Zp=6wIbv}W_t~j~UdCU%i5g#e=LF|C% z+iA4>;`8Pp-g$E~>fo$RY;1W(ICddUl9i0@k%q2@@RKZ}z2*UPSpNpww%#1*AE-^9 zu3bE0Y7!{JcHqjQ5Jh`g(q4M=N{(7!DF)dE^<9h#*1WU~Vjmys1rfdvM+1IYX>f_e zaW9HQq3>qLi}8@9Zw$#cPENmg%P04(PmQXKv+`^5>A}Ibkggcba+|~|2w%#8Y@Z^m zvMOqYB9i|g5_QrgXY#d@?wt#oPk((kutM}PkzshoxEZj7@`J@`2JeiRM}5rs!1b{% z3rtxbgs#+D%3S&Vb5)PbM8K7e?+I*XtejE3N8hDUc|yV;`yEvd`(SJ)uEqD)D|X>w z(;`A2jn4&7Ijq5X(*qT^qg&3A&+U+HyTV$l6IOR+8k^#e7kvBlMC~l9;E76&h_O+z z)!McU6{HshwFt#9rQugoq5Si7ZOB0_t#6k%mgoy+Cvupmg}4(43Ur(iHHRI20T%Ni z@=*$VC3s69Oy>|F=WD*%PQc*K}6! zOPa9MuLa7vP!J)z(s#eWmHBVp!V|W_5-D79d}6|5N)+W3>84T8oKN zxDx#pu@kZbeiG_4(j;&)Bd4>ke%6vNJLeS6Xj*X~QL6X8X3Jhl{g+|jSfcA*@>wL$ z0pAAtuPYn2Sj*JzoSMoJ125%!j+mK3)~3ekG4*EYQfWYH%=8IoT+SlytepODa6?h} z>rcfbs{yx^I~3L4QzBnkcF+)Dbc>F)JwNw)d11@I@VCI~6<}job-CUl12;ptBW8qz z=!=%kDZ$9yws#YB3XjN6@q6D32n3qk1&p{H<#E8(#)t>!4~8s#~a!MQk;3TCY5t27$rh z*tqGWm+e`;PTIK%q->|{Uo%%K9gM-FX#h#rlCpl$yH9`Ey)qk;Aoi}=c{L~J)gw(pI+DyaEf zEb_&TE@OSrOycE7k9%?f+xFQsBDN(6qE95DbgF+Gn54& zo1Ih%L}ne|Mp{-&vWO91`k94NBQ>jc(>3Z6A5cvb`SM*kr!M7GBCjQZ%GGB~$iKHVE*@hwriGSFd2%xxVohi1F0a5L8ATc5 zbD5)Z81N6Vd8>C@+s3&M8}q~k?cXaQ;1(e06EMY`qhDRXTFL4s6f*Ys{AJDHN3mQu z0mUHYPgSR2>ARFk_k4>;b{{Y*UuaStp!zLRAGavcF8LI#F8xVGZC~)h3ab$c)*wxvSLoJTX6MJBvV@&^Gt` zWmm)Z%dABUAr~8lZQ@sLNuf1hTQIR0zkKi~Bd^P4*?nG-AW6S}9gYAAjtrgbF-EXU|#<7L&Zt zsV?lFg?_Bd46fFI^U_*sG{(Fykz|j7;&M8rv-M3|7*f14KB=m;)LhO#iNkOu!kMr| zq!^9urYpC7(hmm|7-PO-F?s|Yzz$tH{n=>MF$UB?(V44li<2CAhOu9Ui6@t0SEx68 z5ASKxKtI<*!wn^tyqqYh}ye5aOU-U`8%^c*ZP%?i zm(ynT$vnMWgL3_rA2;Q^iRz*2bLd9*>sIsQ>ow^cUw6%U_xSmZH(Db$+Yfg$rtt{g zLMv|!Zv9=27&7QT;C`ZCZjaL+^G$?st#|AOf{(|ECRkJ1!LfghQ?gWLN{>zkzduhn zPXrq|N2Cm@{}Ogj+5db`(qR0GjlPXk|)<&Nec z-?hXxR;LQ*FE$2Vd!>@S6A2_F8XG!k_9-uNy->|*pr6zR6<5AdI9(itt8U>+IC5q| zTugFlWHPk!gEhao^*KkCR5v*J7aUJa=|x_tI@YXZ+TFgkA}k|w)o0IU0huq<5X&Ly zNP`q@*$Cmi$?3lUa>SxGq18;$BN%#-rCn#xBkHmR-xN@T&^OI2W44PrmL*zj>Nb0L z9>>9y`T21v-5;;2zcv@Bu9lWKCh7oZP#|IzzDXRS@t!~9|GJI9Im?TIs9NC|w~(}# zjApC61|&+UmnR#`!GUtr7dt>Rxa~P%pV*2W$-r!eeF|jxFmz|bh}f(>i0)GkSrA34 zapZ|L0&U&CkbMt+1CCa-LZukUWGUqLf;^rY4}1Aprd7O~nZD6Pp$&-mNt9uT*@)D8 z5??C66U31VR%1!Hv9|%}LiA6!kG=`%6`ys8(^E6TC-fNDZ=zHUHtz$LpP{}Y%&^d%f?`E+n zVHR1-7bG!{+3dqFKiLVa$Cz3AHyLI4U^Y?y{B9GzCK74eY@1m*aW|lo6db296QZ-Z z6;c`ISbMc9+Uw~-_M?@6&=sS-LO;zEM$Dpj#h;DliD^D^P-ZB`$U^8ptISJWVM(lBMzR@3_p#2R2~6*U1ut5kL!&>&ra{NQO&fQV z_NtIQ=_(GxtDNs=K6Xg?@|MnTjf(rZXiOE|h)S_BROAe+@ynLM&9K+QlwXTAn#W%Q zhf2N~j1DAShEHv)_#u*`J3n#cGOMtIfBS;V*g*T9)Q4Yc<5jDBxgw=t(Au5@;kH(- z-@<#t28|SX@V@PiB%kF$(rKYXLQrC51n}O3gp3ntyUyO5(=&Oyb%l<6qLMyd(wro6 z$;h;r;weB*AGMW>3y>B0)a=IN(lG)$R83?MDs_;>yV7O+`Xv0|oJ?wrLpv1vnQtC) zN6(A3D~Kr@^QCS=CZ!gG)J?Fbh)$_`g$+-Mot@t|bR3^*;K~^CL4ZYYW_GS@0_Zeh z7h(4Gm)@U@Sd9di4Wr${LUm>Fu@kXEmcMlXT^y`NlpDm*F)p$YM8{Ekfh$ainI_Z& zy1M|>lqQNGn2Y^IMHmrjf;mfT8GoD#k7k#xa^tQ1PTy+v-*9YBu0;~kn!C&7Pd5Bb z*JRWyv5k{Bgz&vY(D!hXJ?J369E7|(3KCevKckp&2$FLcRE!7@6YNhLj~sZ$}r9Q&iPck4G+GKCPmZ zWKOl^!(sdHk2VR414SmS&kQ3TXM>X&0&eq`8DsAM_)r}%r9HX$CO$^_ivMJq_Of|R z5bPxY$HB}VR2Z;@#^Ah7&!zR8W*4i>u?Hpec=>bB{h-?xz=? zUsG1iftz`nQ+hag9Sk&Og`H6APxfenrm2^vWKl-UA4&ckjr$sr5$r*8P#Pv4B@+?K zDS$F~?yNOW#H;A7%tAlSDT-vNh=L8Zx;#{Y8YpfbrAem=Lyx|q!`D9~Gh*B@6Ui-7 zCFlvLm6Q2%b>y)0Y7@Ks<%(QUPU!4=t3YjHeA_puYnXI#2(3ToQ#Ss+Fe6 ziAa84`)3t(R0wz5H;PE5G{3L3SSqFHk`tC5YMpKB({1AEwc4weB5Udam96A35TNAp zdUAzWEUf(;8+4+8!`|c~)(jn*g?+GOW!_COyv&F_QnFQoYVTu5r&lMrZ!tWeSw$snUrn%F%r-YFAmBlfWtp%B9 zPJ(2X?{sId0yzZ)m)_V4tBr5RS^>5{DT5LqD2w_yWQ(f&V`bi0(#M1Q`+FR|mKoj? z*3^L<^PTIy63dYH`0$uxc)xB&$!}!g7kuyPolo(LSzFNs^HgY^i@0Pf2=+%}%?8g) zX?E(OH{;USZO1Lk08LUq)BPPbTCE{Qo7}d^v4*tQ8eZ>aB3^_3aeCgX&Alji=^I4U z55FBhft;|on%|wf+}n1ONFchNFumR#1>*Hg=sEIT7!uT> zu0uji-K8S0+5tC+RKU1*w+_>AJ;<%yb>V4-yC2@>)pWggs+cATDUCVNv1rRoXwz_S z^mM0I=y-rhXmHos|1E$O7em(kMt}bK+%aK9xAn!PJ$+tn8rhDV{5JRS%gaexjYiy= zaHu+N|46{AoFh5Q-#Q#NqfgDq3e)@I!fiS{eTGK%DLxn|Gyg-^&7cUFxh{&R4v^ zk8RJc@f}er1n2#u{&6*%&o((j5DRChDOO2vvd^Lm=%EPJ_D~zQHOF;>m$6YM2b~hf zQT|TNynD~Y#=*+wD1-mYF?5;iaTe(!CRvH1k2-N6k1``8W4^r?C*XK*r!{f&`^T)~e zJ(5Gk_nm(}6wedt9Q~6MrM(${8^IHe{VJuh! zb*qZXf*kS+Nxgx_UnWvlMmA5hs*4#S9?|Y$20cCTn+=;pv_Eo6e-lxOH}MZJwv}TE z{KUv4&J9a=yU%UbsyeXpt)ACx6l}ViEa`s}YkVVGubE8i_iLBqaCi3Y1lP}bjZk3t zbY8?b)yoeD7UK7g!8hPQmu=b-b`F(=KJzRIP?NL=`M+=Z@Hz^1s+8a-O2{abf@eZK zguK7-4PSZ0>SlA8hur#e{p8qZ6g%$V+@q*4@JDCPO6ctqV^$@~2m-mF_Y=&V@op{BGXa%=B&!^!QH!`NiH3M?i<&RJE$e zDHjw2R{7K#3lAnZecJhz-^Ywz7nY^KW?&#wtG&aogz8&B@=Qw=SeLasWxOInp!slT z**X8xom-K>%~gZFiG{JtT@md!`NyduoECUK6TsEk} zoL+@}RqS1`sSfQkur|9+0c8&Np03L#R{W(7n_G)UV@ts?)cSk#Rjb0+`a4q>#E6Jz zL#L^!|95$Xj5z4L-oeB0r0@e<0ik10-N`I3y|4PY9abCqbJv}(9scW$=k3ONmCXkS zS#=}Xz8`n}YH6XW{m#OtyH5lWGsPPWUYZRkw#Y_xCJ;vA2iLiR&$87z0wYi8qrQMf z2j*F7c~8NBn}|~Zx3`Dj>$Aw~Gg8;gUv-s?m`Cq<0zcP-F_r)XYXC%?UlI-73)cIq z7;xvEH+&_fn8RYn$>|(az`%KgY?W^j!S{Y<8g_Ul5?WiOB#U8CF4r_$@8Oo$$)au)j+EeST2vR0oVr;oPyFa9{~~OK{Wug033N= zv`QvHR7&_2v-@}C_?J07w@saF+X8{dw%)uS=G+!H;vTxI*;V-zq5JxP(tC9U^@q7H z^%t6B+famGYonl+IHxz*V^LTllieSZ|W4@SJSr~8-8zXGe9i8oI;2tQ7z zI_^H<@c*xeOxP_8qxW3?>mmFf9^w@Mo79%zR0~xfXeQG+q>zUrWx{5`P%SJQOQGIrhY`r=A#cb<04nI%zD zaxIaXSs_9D;x4sb8v#8ttW5LOgB4sb<_}Csg@1k#Pc|ff8)O0GO*C@Ul|FJeN=B ze0|CbbeQI~J)|V_X#mRc(na7^&87e`#lz+;WlK2K58+r zMR1>EnRFLY@a0Y_bWED6^QwUalIGe@BV#Je&-fVDnkI(R*R$%&ooiO~3RYF53s=~a zy%8;4RuIMnLOI(`QT{cyAy$fI0EV?Y9Meh47(4H{I`c%y=GTb-n2-v6^d{!4H>}G|rU<~3BjY2)bs)ZRpYw?B1>dI&8tcWBT@tqAUQC07}XK-3tm!QqT z{G0h#lQ-LC)*$a~bTKtOP@EsQ2NmKzAFB!2A9-p{-tWJ;bXxn_yN7BNo10g}(5|j1 z^cCI@Z?(uC43b^NI5yx(4G|!2w9v!0N(g*grg}`IT6eHRvmIlBUEq+0grzaew}$n| zhq_~*wjglnf^~m1!OL+|$yCI7jXrBbYj#W2k>F-CSwAX>ZuP@A>)S?~cAEM%adfpl z^4x27uvkC#DET*DUa+mF{(1-P`M^(ma?(qWySngw^-!(^O()OQYX%>3qreq*CIfuwTg(IkOM zE(EpAJsjNN;e+N6rAr`;LgoQ!K*YYjBUSGe>jCee<(1+O$Y^ZVrC7(DTfZZ@%*nfJ z%2oOYKT4L)Y@2zWUTpU!<;HzRVMn&+97U0CqN3%tE4ABj@k{xuDY8t@rdaxM zCW7AI00BA9Hu$;YO+iAJzWVtfv*5CX83pV1rX&+A-x%`SeRb3E+Z9$O#;%xD+dpS& z%^O}BBF601Hi#w;PbA+?uXeKwI=*A=N%`u{AE^1}FgzbfT)$Nc#!Z}`dCqp!eD!40 z*3lVHlQ^qRLx@|?33;_*8(m4Tzbmv9Vm~LlpYZ>Sl!`r`Z|xBhUmr(BXqDC--42(* z!N-F##*dWXOwGsrOQ0Gw8RB;IZiCz*e0&p{1f`$v>ebf@tM}nPeXTI-qQ@?wDsa{L zuE0J7J^BH()R@?PgmVzZ zUOvt?Xj9trFOehAL7e0pLOJN7-QP{B{SBY=spO1fL26DYE<4ttDP23y^*h`_>x52p z`{?=-E*P88XjvgP+uaDRei8lr6$EcS7UpqY!h9!qHC+Ap$^s6j0f)cO(cM`#!r}Ke zDxP;2Hmq2U_q(u|*IipQ>*k-(#i$(75he>1Im!x1h%J41-kb_h`7U{g?lzgZJm+eF z&Q1H4U@vEhr)X_nvh^dfST>vD-Hqq|*FPryp&W1*|Ce$&^^~7}+|j2%^381%HV+hT zvBx??8RF(4zdWKRae+H!*>AhLfbwNyK86_dRX?qm^mpW%BsJS#zBrbjTdk_Q2{@?q z&Yj%XTe!;$D=_K8mRosz-LE|Knr{oM(ri1ejvs3#X;|9s&24>;bI=YH?){o8jx0R= za;lH5+B9()y}dIRC)g_+7+Ftk49)kMR09DO4Kq$Yu5wLB7HSV((k|Pza;LLIQR#ip zKM7FfFEDYXRgpoaj4?Ybd*X^uokc1@oUyT`+dIN1#tNS(&gytjJFmuoq zvs7>gOC*apRUDgO@>-IQFrNLn7DCH>{24QV&LUgo>;=9tYPj_bv>#kQs=|t;ulDB+ zE*N->R0&Muf~rb#GKX#qozHMEk9Eqm6kPfU9MAIC zqw8)^jd6eI&TJ>qClUJAzq9|x5K!b`4sjL+5wivORBIB5Tmm3l>FEy740K|~J? z!PCSW)!L^Uq}B{BT9SGG>mvKgQKngg$6|4|u$HK+50;t}>`rsyp6@4& zGnoo1D)xBg?9Ug-Q3SIeci1yaoLC8Cq1=g()#Jfov#LPVwM4|i_$NmTI%hF97vA`D zB6tBp=9h*A;-I}O1IE5;63>IodyWj+H&dFKq)3LLC*y;|b@+bEc+7~Zy*#o8_tW7F z+1#K|AG_$WV>p!EJ!wqa5>9(c-301B0*jZ|lk2l~A=TS&f7;8})o;ztJ=^{5yV?KY zbW_MxvnC(3kFWs@aJ~z~kpge{I|@3358g-VI6+axR!32?iQD$F+-n5-uK>j1gY+db zEup9*qHb66`-_*F4reXC=Xf}eY;Z3fGMUtzqDM&z5r|?0<2EVjS(DH8e+LR9NFBfu zx8->E3*M^3-qwJQ9}AWX;7?8%RUA!6Z%h6BGy^syPeGo*h+|J_CDusET> z{bhm!A#DXw`dZ!zv=YUhYi{IJxB8t3LZa0_aqVqs{Fy)ck<)U27RHgoI+qRDJ54;d=f8x&H2Rce(rMwJ?5ew$6Fol(7)LKvOb&pg!@!zka{) zymNgjrdRn@UH!Oj#C(O_a5}u+LCYTJku@`}WZH=!#-1!UZp|khALkE!$qe&s$Ptp1 z`$vji9eC8m!?8)PSF*qhNG8xSm)#mHgNnQ0?VPv#q4sL4}kLfu^_Y3 zxeZlw!J}T4bdv4dO})WseI6Y+G0j`%z;5sXI%FVigNVDRT@b4sF9;>GQg3CJJM-HjJoao&Ko)C2HH=>6L5xH@J5 zON~B0bo08-vc?b=TY8noQ*97V`${FK@c#ttJ?J+9Ohf5QUM}_ByamOd#ogL8OAf?3 z6vgd-C){O-AK9M&$6(WT=efFhX%kxJ%KZG$tqqfu-|UZ#1!-KoRz6(=@@H3uO2G(U z+~>d9YkxWAur6z^`na%hZY9U~gyX+4CH)^6izT5_R@PSjgrZq=^rfNE^m7>!yzkdw zhoB^g6Jn)kHdYe{BWXd}AAZVdugRMOhTEeBS8JVjq zlBvSs*ep})MHP$15}_&a^+ec++d^})zW%W)nUAecCg2!$uyHGYzafv|e;~kpT}QXz zhoF)7zGLUDE6DP(8Q4fJ%8rBLs<%&Rx29283t=HEyq@*yeKL3ao_WHIa7$r62l}Ye zAu?P>(DU5_AkZrl@W%pR-0O)dFY+6J0b>3LE#Qnz@knP=EqYXKXe0;U#xXrJ+pxBKOellk6CIIo9eMCaBSz0RDO;A+eI;v+ii?WG%e`q z%FGA+-vOA*Vc>b-oCmvSmmxIW>XqFs+q3=(Sj3U2fU=BXv6|B=aO7>CwmG-4xx@|gw zFPo%HY$m3-%@Dt8O8e+c=r~3Gw=cW!D&zA3l6{s~WS#%#(UmaiXT*dK+n|OT^wE`l z>E|)blD`Z(XAIIWoSugza0(8=f0kxc+-()xoP6>ttzA~ zD_GJOmnqV~Q^g*wFkcQWnV};={ED|>JrnAkP@*if&S5?Vk&$xdc zr~T#^WW2itR7-w?&IA1hj~lY*=_-V|I>7kOR>BGm;KeYZ$y3-UCcT4bfC{Z_2QVB! zhb7SQ0oQW0PafG{vlz^kMm#`r`{ULJt80pOSoLnQ!bbmO9!x(a=DSw6Toa;;J4-kK zTb&`Hr*$wsGN>+rWSI;>&O_PF!srv&y@$@`(9q{PA5;Mqzu<+AN8oH#B#hmEU*XNf zTR(`ih7*{hj`-8F$nmP9PApTM;3Mh_d^CN9_N1o6a85Co$(&<^@Q{1UYcMR@i3#HFQcyRrRwg-^QOsN}8G2&f&7x?~t$k zrVed|@{c&)J%yG?DD$5-k`939=j-3+KTsoQYGs|sDEATRU-|kkYM_UGpoUlZ6EdJ^ ztk-VG*5N0K!`B^y5S0_gp;a41JQl{lmfkz4y(yZpUvb|+Je3`SyE9@RRCLPexuHGN zUl0emCufMs`ixut-F&8`*V5UJ>NRqxO3k^mc4sm23f}=oFPTH68Y&0hh**IS<=M*9 z*FFeWFC+7u8E(V%$C2*@gt8yslgmYepz3XVxw~3t&C%)gd2s*fn}S+*)5gS8%i2cO zj18}l5ZVt$V&*6f@nIfu{h1Gtl4wC)LdodGj291 z^S~Q?7c`xvYv3ytIDZ!uWKpmOlKxmuhNA^e*u^5_YybuB>IfGX?h#3YxlGbNFlAJR zjN`%~=hVpznbS?>JIMS#p5lms{-AWZ-uzef~fqW&I`Z+|g8( zLM5^z2JiFwea^haQ--)22SHj8+B-cB7s_l4b{kNPH~k-Q0Z&&=I>LvB-gmJdgwBTc z4gCg`1AJ-mw1CXcQ|9B30l$fEu$=`r+2OcY51{l8$WA~1+q#|exzKkWYfZA@8Fo7B zfN%^?O_BkkeV{{BGfKjfe1XRb^uG>=iw84^UpCQ5A7IxV+j2#@=#jUtyX`!p-==ilKl0bS{NJ?K|EE$;NA0YBQ+`83 zXa7p(@T=43A&hOv=X806ljlDa^iDa-y6>~s-?DF9(iG6mxf+}t{!59Bo7}mRLZH{K z_3yX!O%gVEQ|D=ZOabd$L&2uckT}o{G`)DKR+7_ zpx$_N1ox5hg(g~4C&;xYv($%_%4s($cvV#jNQ>e!7Z~y2K}DJw)FcLGgb7f*q-tB; zl;vi&VoPUuZuqw}CJjX1YmbcVx2?`>agL=+l5Qu=)YF6?W<&H(48*5r$(bmZ*HKLb zT6<&zcWwf*CP6}P+dd~er0?n_Ru*ARg>{v7)Us1T1RpVdo8Nbs$sy>zqb;WX(^;Xb z8MM_wDcm!JUdi)rvYi3TmMd?J3LNu}t5=M3l&9c`^ei`S>3*=u_&&MN(oy7)Yu!{Q@?L-qC6hR`}>t`Sw zK&MB}w_*X2(qo1JUS}o~U0=$i?^BXgP8bMgeD`*-o})rt^Z|guE_SK5nz?s#z5}s2 z^|uEhLi5E54rPFZT{}!{OO1yo!#M@swWY=1d2aH^shO*2zqxW#0}h%FWIwa?U; zZAtn;@OQiR9)8jWCvDPyyB13Kp?aa!{Hs5J{0 zO4a3f($VMneI~vGHukM|N;1JScivpDOqrCZ$91%fRN&{bI=gMVpAFkPS)S+jUwg0S zD_;Neos2;LAAj^+$GQGk{WaJ@x4+k2GpTpFu8(!y@w_T{?skqAR|aCPt~Qe`4o;CB zh~yD-u@km1$%b_>4-lmeFfWSQV9`L_e&Fy8fUdI|0@(KUAZF!<&# z&r-gMSDt6{JBl+Vc&~h{qU9DX;ISVMVH&olNFe2$Sid< z^$DwXQJX6pq-M_ZC}s^z$oH9u%|}jabvP`lni5pP6-a|K>?1DbsF3>O;hF?d|Q@2mV-9X(pWcfD=>*s>!cp?7? zS))t0_e+w|^k3u_L1JO3UZzV39Iw_hi9b)BBA9RE4<@l^R!F>!g>R>p8% zPN(taB~;%wQ8#n#VYL^TqR5gLRU%T9R(xt*wPHnTxkV_q;9%=kkSnG1lf2`1dH*QZ ziw(qCdHQ13jX|nj8n~PH^{V#}qI=*N8O|KKWAGRm)*Ml%_c$7s212m+_$C<697gA( z7tS0i<}T~{V>1Ky#OpJER{{=aGd)%Xjyj;?Q5D9D_s^{UFP`Lt+(2Y}+92#5yn1N5-Ip1;ka0RmFh~wl)B0mC%3?KR`pmiMsC* z0FmADz@MAv& zrmuusl<%NeTMas0b4>ghgZP-Oit6)N;kz^Fn*4|%?rqX3`I`KU;Y+jahr0b3)doz8 z?_sr`YFh{vx_n+5lr#J#61 zr2gT7*J6`lT=xgfmhZIu<_zLNvme)|nn9GpER?G#BN&2783&?KqI<3-Kg-k>1jQBn@z`Q3!d>?ug_k{o7I9~u+_cx~6M0 zswk=_1x~&+qWc~B9z-$k2NB?GLGnvqBWu!fmt#@0wfwX6`^=>O` zNP8v|x@`w(&tyWkB}jWF6S}Q~v}ZD*+xn<_rr`Y2ZDUAKzIQUA+qy{KQ<%_ggP-V` z?*IS*|Nq?BK~tMR6bEoSQ#(C%`WZa6r^FbQW~K)ce8^@~Ppg2r8DbMR>Un0dp%?KjNw-ut`6*RLR+>UP|X43nz4m8-wPfNC>KvrN|O{+U3q zaG>SI$88;`Hv(%Ow9WOR(O=v|1I;^XuFYuRDxrDXyt}r7!1mJ>gml@!|lnL*mb>!i_}Gl#T|*XeNQ zA*2dkr_G%wkg0f`6Ygw4c81qU?X6QegUrC|bhwj1W}eTv1-?(C`s(H%Dy{U}ozN46fTBzoOId_uEIh_=v3)QUtvnsF< zt&<9;4lF_ITnMKL3{gLkoMYh}14GnLB&RE!Q(%bpPRZ#Arw0tt-YGdf;S7P{?JFbU zOd&zEcS_EgaORMp+&jtZ-dWH25cL(=>C|&RM14heiajMqnr9Lzw>?CfXA&v5Jwdgv z?3~Yf&WEV4?3~Z2mh&O*D?GQYaz2!KCXsU6A<{gPNV)ALWENUyEw|lZo)c=hZGm}C zsO7e;|8Y)u1^@v6|BTtm4#doQ7T_R3lmrQ}WSv!z7oMj`S=jB_?WsL`=XsuIUl13> ziZvI(8vn^bBnVEhRBBbrQme|Y`kuFXv+CL_=SpbZ;&WC5ZshGK4^K(5pe0?#p$JML zsZ<*XlxdwaY~o zXKBNS%>toLeF4dP91{gM{|Q!7V_K7fYPxqim!nXlb$U#-+6_J1|Iau%RaWI`U>L4o z*!cWojDL*pKmE<0AK!of>wh`EKl=ao@jaf{ZifhYn4};2c=LSBcZu8aBdyC{K@%$> z^1jey%ahC_d;`0ilOTxDh2%4n#1rrAXHIzzDtY7ksefyLarDVxZ3BbYXV~RVj;&K8 z52HBnKI@Y$i%k()8}i9@@+tBdu_4=9LwPT>2)HTlg9M28bmG_nKl2Bu1Kp8(m$4!(Q$0TGx?pu1khW1)rUsT{ zYi6V-MEoH?&$fSXIotN;$fsQb{LP|jsjadVNu5J*Cl_X!4R*+F3xB!l(Mz{iQ}k(m zMBbjA4~vlXD8N@(eH@)};=sHibRuuh>`Njf8IbCOU&0Cs_D^O2_prtq-eLe2G#j%C zKdhN5%22*$ItF-eCc>DAE?+{jL>F@A%9jA_i!OhTuoxtdBk1rOBu?ifU*F042sb{K*U`6`cu9O%C$b`|cT;>tWT(F{GGp38X ztWzd)0s3&X0Nrz%jw`zc7-(ew)F2y@yuaBy&}1S%9YyKSx{+7~3@1u8r{t%91P@(ERLLqic!C|{LLTlrN*sH|>Wq2HxNP*W+LrrmXt|0W;R z0Q%==T;nn&v_CX$@-v%n*6*JIJ0+2vgf@ZV3r|)^{kVe((>!$z)B}w?5YXE`xDhN( zPNiEg5LBOFMv#HO*a@{;{qU=71`M8R#x%e?{Z72k^uC0HhXE+6CZ4LI%g&O%PCI~Q zrw7SNTHbquu??*c^l*HH>@88VwxE?VOtA&T(JfGg1>OYFz~43S;mr4Ny|#`L=m)M= z^S0s7(Txof-gAajf^qBV-};*fgs4T|TJ{=zXYT_*Ub+K~KP!9byrH1%KmvvhWY13w1A}7Kl_(VVOd|=J3(_sU%M}b*c?g<~0E!gRhSG7E&> z*Gx|jX06zG?17Q0K>=SG4o<=9K-=A$!GJ#Bile2_7%8yA<72puivI2}75>l)#;*`t zh$Z65Q>vbTq+^L~kPreV9Eq@Dm~$!%^ck{x(wg%X@CpWbq&10b1aVmt{me7z!+u`o zoA70JGKrTsh2sgDBTU2NrJ4$e^-l$%wj9{B!N`i@i7K??0)8)9hc4nd>aQpy*B-#T z0C6cg-;3~k#Qot?SS6U>Lrz#ez`WKOouJ z9YQ}QM#vOIrCySOfQWg*5PJ5Vs{|>W6~zd09?zFJ>_A< zbg<|r*8xGB5$QCF?qME!zpAGcgPMqbO@Wpv!n{i{yF!bs7BK-R?r^z+|8}73Tys){ z4J%O;E1;PH1sO7HqR+eE0@vE17?>UYVDxcXX(@nD;cAo@TA-|}Rq2zQ&ol;}VAWH4O0iY*( zi0n1V?7$*hdtRrD;zN8a975WM)V3p-&Oq51jv?D34+y5p%yV#9NX1}kr0_S7>ks+c z@yIha(Pv_%wxOhnHZ|!%Cn~|q3LCJ_#FK3DfC8m}m8HxNSOL82c@XX|uqVx;CWBb; zZp#vdpC7E~Oqtn*f-fGkNMh2?k3F=r;zA6Yp!RQyS!yOve+WYZbl3RQTtw0J0>$>E-V>DAunS*ycJ_z%oZr&EfyKf2qIz z^FI8`|HFrW`Dc9y|KUR@Y>u|QSZk&~cHOE~2NUIoA-0*l)2X#u&YpjSD$ZLW8bcVs z%VLnpuE?XtD3GOnWSdBLiD$u5LtC!8Nta&@HDH ze8}WlY%Q%}GvEe2_Dmua?5NuTglu^F+>Rbwa1PneAZFqwKwvW(#Qco>IGb4jeT}33 zg?K$W|6DQ~U7n)R>qs_$;CnDR`uzc4#}sQM1K#&Gm3ZZ|e4wlvv$ouHCE&LqK6n>> zs4QsVlK1OMsU#WEj2-(+m@Ue!7=q12$piM9q-P zynQo}KX0}6QD2)4*95l^b7O{kX$6AU4-K<+`{F>QC8@!t@ zHH*2a(D>B}-FAW}Y!j&na{S5@ip~pC6llaYm69_|V_;hT1BaP!8q0?(JncGQ2q)5f zIH|9$$ZOgyU;Q=CRr0W?*}xRwyg4S9q6m)>i=V+T5YsxN&9v0C2Xr?#q;Kl`kOnG8 zwCvl;{D3+r%z>~H*w-f65q9uERKNq2813q#SXev)1LXUw%o`h=xhh?VNg+noeo0O< z8wX9^`1@I$O`Ke)#PFjoE`XR}YBl_Bkci|qhD!BMXohV7&&J|hwLT43bu@mN02+Jk z#4i$Q<1N;tUYC{f(8XnH5h&9!YjzYlv}j|rfQvbhUUZn%z*&+sYYQ#QR~(jW@853z zgN-kC_qeiDUS&ef{Ayl$^Jm2;u*uTo2be%vNdvO$MbkE(A$V@HaMUeWEkLCtZAMS+ zfoLt)wYUF;oBQ3j;AM4vx(Hx&k*ecIYevAk*^lFybn7s!9|5#`l%6A?AC z*@7U6H}niixhg&0+U;QH-C@6L6XsQvD84S&(?OYIAS~qbo*Y1f&UiP+r%-sksO` zg%kOB=VERiK8rc4e#^|7EEQ6xa%(YR#~IkXmC z?gS1m4Z9)n_1Ohd_wotrvDGWm%;vTIn0DDs{&tjU!KNW_axVk8F_FY2WA=`X!^nHi z6TY%7&!M&LE*9n0cn-&Wxs>h4JtFvZa64PjHq_+ zQoi7;VJ|lvr^QDkFzNvbud!t1=owK`I)|9&(E8ymkQ|2%1p<~AwTBFPat^tRR02C8 zqt$~^7}ogG@Q`SiU;@ZVOZo=6k&gNU`kpXkTJU=>tU`2zvEF7fsGX^igO-6h6SNlo z(sBX&yh^UFlBf!r#kw~ZvIOy+ICdT3h4Ln`9dvM?ErMl+i7d^Y@y#21&Wmn#p`YNT zA^Otr85e{nXlHx3Ur){aGqd{h=n^8T#l9u>_$$NCj7xwcUp`d<8r?KahKJD&Mk|Ep z`F))h$q4v$4rg>rj;(^`IsQ-_nDil0(;&A8AD4wJcAU0qL;)~l1jw%0A%-FSt-%AV zD?PL=>Y>TyXdzTObgtmJy{3-j?j|MKR=KIV){IB!1zxr4F^k4t#U;62f{=as<7B<^O-3$+ZW@u6si%?xu;c93c zl(VnopMKUg)aqUgXqj;yOAut}kj6ht=AE%jd8<3IG}k^LlkKu3wMYXn0F%jKo+Me2 zP*477z{ZcOb_I(6)?%IM?5WNw%?PI7~$y+!wMzx5d zI}46^CnG;QGI^QRF4?xzPqY%PXF!C&9%f|kLsSM>j|Le4BSo{^PT5S74CfK9(qlue zNXh%EwEU2oy7fIqfe3mO3DPM&dBX9{>-6|&O7zoc@WZj{%mI4JJthL6w9|efOu7y< z7E{kta3gf3U7!^#kSN883g3NLPUBjWbyJaw1k}`2gL4tDe(gk$16^fr!u~QO4t@ew z`nh|&5ySd35X_)yuPx*rUJyC1RR~{EgM#hWarv^CQ+%7x?VJJwS<=d;bV+jI@4KyT z`q;G&^wxfsL-j9|2wv&_p~jgP5v%7(T52{k#1E_zt9IC-+oZ8?=k$J$XRZZQWf zk^#edSQq{qspRzmQWd*Wa5O;pykZG5}>)YaxHL19T` za=wOtrn#WScP23MdlKxC=$W3u*~l1f4B`}gfAjik6?NWBn7Yt*ih>G3{vbyM# z)FLY2jmR}Wdzo`CTm5v16eQ22UaSc0NB@3VMMmc#<6%0-d zmu|w%w(51_9DNxThYDtyt>Y3HAC6kI!AJC4@@GCUUFJ44W7+0I95Rz}w_4p*n7&xh z1`z^yZY6&57U5F73gWA7E2n2>BQ=RpACRP6Y@ysRdMAY+Puqk z#TmX{Jr!@nPcDQ($#`AGpbn}El<yI1LNjZwkz8PLOQ|5y@X(^WfG^+ncoirJ|cN7c4Z6ByvJoezI*0)fBl z=w<=8dF6TV*zh)**Zfd|D((;d=rV2{N1*!Bzxx0_XA z$O{pQ^l(qe&s?G`b5PHSo{~(IJ)yq}l)wz54`;0JOd_`sMN8V(kA|Uv$=~r?pXLPF zFbmxsM63JiEz>+;=U&j@{Ju`AoaX{SWo06IX>fDi0=LI8-B41X2)Z^E^ik3 zL^*qJwG<)>a4N0lR_I=wz1O`D=q*K{FK@c*1#nyWlsb<-i9*&qVo`C^or*I{H^&h? z@|)ba^`QsBKu%Dt9%oO=%(EzAEK3qdm=%u9g9$jBwAPe6@^L1F^gwjl0d>1D(&Aj- z@Cz3*U36R8pit8|kV)7&nzt18{0{Nkw%|l^%ld#0ZJB+~6v3^z7(nq%uFk)|fmC%aoUQYJjuco=Lft4=f^X;oO3Q}2tm z9^x_1fmtVtI`lkE2=%ZXP5KE!m2S*%JJt984x6R9ozXuQH9Wr;(gQ){$&VecY-yulz=%)i@102}qLhwoY4{R^-#SJP{R zNtALzssD;hn7ymrY1S?J+>WAt0#(R_^OAr0g z|9^O>6QS)u`5&e)+tkl?%Ot_vlSC;C9wVKq;!ULEyuO z5Pq&s>#!M1F24$br=AG6ntGzyB@WR?q1gUNXmpd+*`hwljOr7&?t3pe-&4gtxsRS!u4kUv65 z_ip+@*TasThQ_nU;L;7p-};VkTOI%Kvr`CfuC3aECB5jI_W66 zS_{1Ob+`sSr7q#un|9v@5ZDBa>nf)SPmPMA#@7k6^UBl2MPj!1y~aQk>MO!DRA7WT zb_YtY3jbyvLSPK-|3D(3Udb8>p){<{v2Ih?Pld!`gQhLMQ^M{Snl@r zDA}?1XO!NycP?7ZLQ3DDWwMwO7z5L5DTT>S|ETnHhi`iM$yoXz%>CWhq^vbhzgg<` z%Uk<+%8qOw?A=l=CrnTn+gWQ4UxZRW%8xrAzl1*f=fzAtMHw}Bg z1wB(ZpTIfJMq8DA-xYFUmP}oWNxcal{PTTBq=&L^PS^uYB17BrhQ=(06+Q4=@xF;( z`)?v#;rf)=qU)zBSqyR5sRyGm?{o^gbNcn2q*-uEw8Mrc>Ad{|c1*h7)u3W5DSX6C zCfQZofhh90596NxbcaSZ<&%nd`yldS*xKaD7{2)hcAv?)Nt;alOgp983(>7#FO|LqXx2C?OsQr zqnabQp7RGSrq@nz=V(AtdH63{?^a+nmPrzAVG#wTtV&fc8)t@}ThxS{w2~7s8NwVl z+}N4fbz*vf>@uK*a4+Q`H)!tLboV$FX#RF_AA z+1P7m2#$G#Jt)ZNai&NW#Kcr4p{8ft#g17VZGD8@^xIvqdgxOqlFX&sJF;H*g1`G{ zkF(b%94=-)^h01BMOng-djLBgfhL6h}_3g4EK0Y>c2Z zC5IKxCH(Oj)>zR<`z><|w}&vjBCxq1w6#>QCS~H_$HCvFHOFT*T|M%}z2KI;IH|C= zrX`Ep{^W5&E@<+WURQD}lcpcAlw$EN@0>+LPvKfo`AWzyK(reS~k8}#pqIGF* z9SQZhHVw~kubbAu6l+_Bi0siNQXzI_@chUbv?w!E(bYbLFQE=jmz-g7!UL8{+X z%q?b|FVd{Mhv8fwY}6tm_bRJbBI}!5Ohz1ic}T%JG*0Z>f?CGHo7SC&KvWO7sO2q1 zedyPI_NjRvFp`sCq49>vV;I&K{KY1HGaa$9J13Gzdcp<=f6LfA*X`1thnd77aLKMq%t56G48KWB6GeU=n^qQB}1xi>uf{LHps%azvZ`V zXS}_eK%ckFsXEdCJ1^-Z3~bupp5U|HJo*WaQDr?C6Q$fdK0yC{jIVJF<2vMSj`}b3 zFqx|#B_<)hJvhxKm!d5@=-=saE0O)XGSQ>sMP5Y4xZ&XpCGd*;e2rlK^$4>@E-pN_ zS(%|qh_rL-TmJn7gh>a?!+`9dv$`t>fVW`_=d0k+FTVI8k#|J>^QH|T6mKu52PTz9 zfsMjD=RpuPbAz?ZO5Gd*@+~bIJw+U)W*Iq#|Dvr9$c8T>UM&_Rm6WdV z2?vcQHClTjB*|8kd$Tv4vo$Yph#mUT{lH@tILe(=h2o$8^^ZUP@sF$h!ykYA?e+S* z>-pM5v@N_((e8daH3sNo#c~uB=7K2rSOp+)ejE?mun=>(rsME2ld{zB4B z{Mmg&931v72=v`}>BmbaES)QOgYXKLKQiqTg}z0NbY$T@Hhq4;)oExAyvt_xa0ElG zOvjvjIA6N=S45Lk(<)b3`>;H!TjdBO+^6S@C@utf`u=_e-X+${Ak z2ixp9ow`>gl104*@Mu6b{ATwcDW=wvC!*3)l;Ej23{n}QyZ|-&j>et#@z?4la=|H> zSGToT%s_iiLzda$+^hwBjkN9g?*~?t<6R&xwY2VQiTuR0x@C%Xfm9`+?TVpXtc+g# zc(=@&=|FZPNh%v%$wap1b_XZ+1;9NjPD&`}0?gRS!HSq?6`?g6+#&U1P7 ztFhRAX!i}(p7=NtTxV-3&kxO#N$aKF`aUn!A8iEcPc|+lxT(yK=Eej&up1)~Tox&J z;7nLAWQK|F!_!^4JliI*dQhs_%j++e-@HvhQdH-4q`T(#LEo+{jRt)ULC164uISj3 zRJB!qw{8ALq;;|KLQ|aa{F9Y|MXShrj4P)xx?Bd~G-IjH)z>DR#JgS%k=d!59*A#( zk1XSxj`m>efbBl;r05U+dvS5w8t8{;``jMgtr3>`SxkDqEfUF2Fo>=K_9?Yl;^u=U##?g`EZ5+!27ed-6ZK+_=HX0M+@N-~`7a|G3Xn1t>7 z?b1KvV-TxhqWY;X*6p$P$3~tH>dn#}bLrh2?sV)B)P%3ApX$`_+c%#z9DaOyDw(ez zHNPUuJldtSNHRfGYaSKHcOL$>ktRqOJE~+VBwJ7E^Ksm_IU>4>9gc%S)zq}2afGs0 zO}KZG89L3)J{>Hup9-M{?v%u)ekv0yB7LL>2T0&s@q&Hx><8&d&}eW>7dbI;^T#yz zTv#4`k+O$6ie}GU^&xIO^;SJiGsmZaiCj0&jdg8me3gf^&^ss!<$&Z8YhyT#;DgkA z#m0rk3cpfq7;!{};Bn-bK!H0n`Z~p?px*P2Y1>n1g(5JSI4xWH2x%*T$Z zUZcS$ktV1DVWRYagCX>c^XWffMdY-8zV?O8tI*&1a#n6K zky#z9@6qLX^~zmp-49{9Ci;()(;&s}Y&)+Hf1U%^PGB$GLjD0aJ(_c0 zKKhu#kEEm>;dng7As#pf$g{sHoV8tW3SThVd}~hDMt|*8SQylkVL}YLp5N$q%oLX} zZ!YE}rgGzoF^H;|Ingu4@ioeFtxl^z@P3%N6PY?&$03x$l|P)ik$Iq(!w`yO3?n-; z#;+PZ1zWIg8q-?v#@(+fo-kZqzI`qnQLY{$4}(`0!RKu4>$tvYL4WbmG~{Yd=$&WA z*;3KyK6iR7F+-fI4_lz98y5J=vV+IK>f499l_9GJLN3xObrQ#b^-qV`&G@oL6oTrv z#BL91W{%X+>!!-tQ{0?KLfawuwB!i<6kY4UoI4&?d=N$pl_@t@hleRmu)kr#gDyw^ z#=m8{xlp}uxKDM5uBaIiie1c;uMLO=tvjB-ePi_=ukkrPXv(yx_%;7Dt2T%I``(Q8 zeS@eiV`|Nb2g;_njt_W%h$)?9%uW@c(7jwx=I^wYT^!9tzcd5)*8>t%12rQ&w(wF= zx|0FtV>d;=7Yj6e5)=9H%1rPIG+}#1JNKM!3&9lP8aYDhe)%07j?z<`Y2*^m*7m+p z?Dpa8@D552*h#~`8Y!Y94vUgd_@Nflm?A$0Y9cAhy37~L@d9zb9Q6G-U-n29#O9iu zK4bF(2y}UzvD9Gpn#237h&ZP+uO+QdkWlXemHdUqtK{wX&hiF}u$%m#UECr_c9U4! zn=^ZkrH{&nq4mJw>(noNR(I76OHCEB4j1Ws$Ki6Q{H4+bB!?N^;9Vf}H)x8Mn`VY} zHvfp7>SEPBub6Ju4NKt2LU@L)w6?mkmXb>FqXI3wDL6=c2T&DB-+nuBnz&mfiyG%G zUmQrkowdS&Z>|M~$bRD(E^e1e+Rn@1%*Tl}t#G%kZ_nS2B(_Z>!ko*A)Ba6Z4$5Vw zN)+svz5E%K#ZgFJK4vRM;ngF7sNqE!3YFxvP1{xw(35JM`a)?W)!!|oKeu=6kOL6= zC+H7EIXWHV18}<4jf&+H8AG!B4|IyO=eYK;ij#AjN_(gvg>?9~Er{ke7Hg3X9S3x* zVfHxOUuV1LLB3xBRQ}uVD>zRw_NCP2Na+>vqi=&7553D-{rmrL@F)ELIhYOqHwXXO z|Gzl6ch)48LxRJFSS-WRc6j%2s`^*IU$3v zH|W-Q#Sdq*_I_^ysSZiYFnm_y(@1@3!&h3cpX3J;O(@SBJ4$C!IlwL z-OSl{f1z?2(7>}IIPv>eB2;}Nxa8GZTh9U`&U11i8s<2#7^C=J7tub`^k=eLK#pZk zSR|SWE56h-;dpEW4F#@a&WIcKP^n@BHd>^GLIJ%z6s||l-VYcezTi>F^iIeZ-i{-7 z!vU6ka$zGUvG64<@8fFp6|jMZgMu(V$}f{*GENkLLF^jq?2*4j{uDR_zM#$J=$3Fc z54T=x^S8eF+r9fRy~>rt-r>e3AR;sYH%sODU=nPjOofU2}(STTRK>PLNx3c=-rJWAT{-SymvOY z0{@$K9viauS$6p1E(NO-$F2;U>YAZXHNbIo^4=wGGfXH?riWx+r&`u=gv zu|%7yu248PpB$gsQIwo^vXGmvh2Zp65uKGPKU`MY;3B&%Lzm$lqLJ`dhmt^UsdAfx2J#!VCwo!fMiKj?xEuM)*QeTUY;z zvuw{ARhV6_!tqYG?i!RY8) zI)~y5XaY&L)(_VnG|&^71#!{)>&ffkZ!{U4!McUy78Kp52F1=r19vfTEKJw|#COf_BDokxM@%pD`3V8Vk!_)#mnrQ|{j zfo-8HN#r>yI%&OL_Mf)w32l4l1pB6agCKC5+P-Xj-Uh%Zf&KzXMs9N@B4u7b%IE<_Nutyz13 zVFOxG$P0%*_fP0hRY`D4Z#Dp-Khtpg#`i^DyOQ)E$)5MSSr^J%i)%o!rlLp}doi5- zE%*@oFx|j&&?=p#Tm)u%T()5*1%JIK9Bj9EBE;`{QY>2isl=*t^+|5{{q~rs2Y;X- z<$lprNo7?olXOf#0*u9DQZ&Dn(0x$;bD zi(AvY1V0DFIalSD?^rOwUo}*l#giG8*9%SHQ-lc@sgd?-?iDt&-lorGR}wTIkPj-D z^38#L`HqQ1P*c^ErCg(E>k`EA4`<1*qfgs}VTU39icG_3H?w@d~8T zC-~~p5Wc03Du%+An-;>@STC}zoKwDMPi_#_^t@`5SC`m@CNZ8%rM1cO1L@1ue&b`Y z%IBV4G=(A5vWT!Vuh}>@PLloT%Jv@5!@$tw8d<01XH1?y56j=u=LugJ@Xrf1Bb~l# z1!hZJV+h8FsM@amUYART6`Uwu!U(44RL$n%*G7>E)u2eh@3KbspgIMi4X&9JYAt_G z3M{xJ>A;ZDuO#8I$$&5#fcpsWRES9?s4`jRY?|3FtN7beASb?;G2{zF8=sKf%5rhk zp{gO>_m-V}X+P}ar)<6J8>gLi8fM;Y^kce2xoOcVS6w(#0&*RM zXuxzmi<=Lob6)&)h3(l;X$>dG=UJ=l?qE5t^<8SGT1W!g5AmJU7!BQDozL@{Q#t1TGdq+AlqgxFgz-rglvGmnkE9in1oIq$+z zOO_3ETTfY^9D8j8r&lg`m(Cs7Im_3{F=-n+U7-Ww2gO%m#Y z*(W>!E}oRwhg*31%d?UFU>h#5qX@EaRe8HL8C?_Ec%L|s!9A;2m)E3lf~)c6@m%xp z1tgqe5In#sgUiN+W87>pyKhLl8=spGObr?Rj%PG&t3^gliF1D9uzJFR+;N)PlFwdq zMLGPM@|*765KA+^-;;yWm+wzw>o6oXdUZ31XZsW?X}qdM8aC6aCTVf8u;wd&-O@|g z65K%9=3dWarL#hFSDL?nzigE+r2z6fiEsLrnKjLya|-kp-WBOIvD^%5dLi z9hdoiN?vROKcx$&_PT9;FXk6p;Bp~BmOEebEem-jEt=@90Z+c2DcnYS5;bbvMz~2;S!L9vG%2nn-(#k%*pQM=45_E8frov!&(g%rs#*

asCi zX=|ozUjlgCo;E}6sbi^seg}Lb$=ReyO+JpWTXXFyo?YNMBrGE8$t;TIs=m~)>6~`s zJ=Gse%7ysId5){_zjtC^BFeSt8n~mQ3fF;lzJn`&woph6N6c7{S2OlOPvPE79~g%K zq_~lhQwb&ZteSM;rh3H(g8QD=FwL-iCyPwJO%yI)NdNM@$o)I1M2#r^a*#?_s`PAj z&XO3C(|)(fioGvqc?H|w_;vymU;>g4N6p`;ujgga< zpKk(9hq?sb7M8M>^UAK`Fw0O?p=~P>6*l4X-t$Sz4BH`s(~G5jEe|k~ zoNsXLsq=oq_P?ybv<{=Wzgy zndyhKiGFueSsbonsN~|qyA=s6#~qGA^aocfq|C}C_P5Iga2G5vsVkf$tGo0@dEdSTUAw~HuugqGTj(_a=ckaXeIGGTcl;>?Ii0(2MATr3*wme z?~~~EBK?c?&E9pp{2pKV9H^o91)lWe?Z-h%S(0-!x8QK=A79Dw-ksluY$<*1g$%po zqQ>?J!TPf`x1KlaJ73Er?$gS_J}njgcD?v{2FI}mJD%b|wrOzLOfEOBaV%|j-YBve z&A1V?i}Xy(>tCXS`_I$ky2DMg|L>cLa_j4zxfhWl!gIDTlQl|-U+&(Dv4_9&StlFe zj5iJ5k^<(qPyf~zGu!@16#JUnfqolG)Qtx!!je*2nYZ5HKKseu^RQZq6L2Tx&Wga& zuC>Z6IifO|1A&F8UVdBTN~w|l5_`lXmP9pmqM8b6&Vwwf2@|hw33I=mZrcs^te0Ui z?-$A=6!;x2XhI1^^OkS12y98e_r=FY z@2mpL>>|YGCvwR7_s&>vQHAlIAzc5G%*{5Y(iN&(TPT_y0BRj`(v^%RBPmy|CBbE9 z{DzU4GZ@ph{X{Oz#-khw6XR4?CM3*U$-uu?=)NCXFi?ojFqA!!Q=I2Z_##hGeCJnx z4P?wy>q|<(M(+G)IO$n2%|Rcbbh85PUXkT=f1FbDG>+PgAI9?Rn)fHz`K6Z5;kp;u zuDUy^0jV)jd>LhlERI-;mIl(C2Fbm(Xf36Iv4Xd|j||yRZiWev!IM8Hdwdps zpmt4Hw2})W(dRV7=_w^k=sx!@FICsRIQk6Y=FmdT^i;O?} z89RF4cE!Q#Ry=+@EY;YmM`X;agw>ICqb%>`ljVLlD(<^WPuxVS^U*j9@zUuIWqyr{ z=_02`N;_=UQRhnrHuVwsY;D=Yu`GFs|=zU-gX8}sMnZI3}53HVg(T@TD9=jP^>4G+| z8#mF14Z6^99WQ=>$lP=+200Wb-RYjD+ji{_x!`jbANkAcJw;z z{fwGNyGI8-i-|QDmX9`o-Lug%N*<;LG*6COG>`s~gv2fUTNC3u84YN8XEMDBi}y^|8+i&{RGzB-nZfH;-s)l00UDtG7Ps(6|0-XIgjbO$MLa=Vwv z9sQ*uC781*%LynAYA55I6r(3cP=~=MjuF9QGP#1Uj z-kXgiWbD1WIlPJzME36Z3kB)cV+k(eT-tDL=3Np(9*RAO`V#zk4SRA=c5bMg<;IE& zt5E+&4$DpdzROP0tXrYb{KB}_*L{cswxwVHb&K2y-ng^Q6mD*z4{#eB+SfVqBIaja z^1E38s-3U~wm30)vdYux^~+;%l@Bfd3FaYJDiGgG*s^s%;aS>~_IRMaPVkw&~P0d_a~r;YAN9 zAJY7TqkFtN6VtdQdw?~6Q^Bkz?-xq^eRvg=b$)pjE3C0N)DA)z#No-qR1A0U+twz^ zLS}voNUtTUIJqshvh2m(fDU&;#1v~vG05%bSWZ9TOYizhvA3B%RGL!r?EBj?5lg7i z0&G*%rMVgoOT2QOfN$1$#eVYY13Vu;FslR8DE)N?q;}%COzU!?CX{NR15AJx>uL z)VXgY6Q4u>UC-nMt@Z0LTRpa1mB?YRySS7VPFrHYMPTGVytFw8@w9cg#6Q$HR1sPt8fmCDszfF2IiG}8(uEeo&#ob z3swQN=3lw6p5Re+rnbFY0lqRp&BE+l?j9FS^@Dta8=I>EzgI^$zbUBk2K*`?n7(r$ zk+wQEVa9D`A@z}m$UfSX)~)gu0z8P8$~fzivU{!r%aY*W`9DER|Hp^9wL$am*T|M1k0rdZBh{wt7)Ymu^+)8p%MBCB_Zdu?|J`!7;j zfotsuW4~w~b3>}LfB%Q07{YwXr&}67rLr2Dtn#fDK_tS|-#<*f{b6c*}#X5YIkot;cWT6c zoJqVCjemK`@pwcnytTQ4u~FJIm%SURF~0eemcnY4$JEPCu729AEMBy^e5G*n@BFg? zA^kkm-%%Ftg1*sDHTxv8l56wEIS*#v(>y6W^XgB?36JCcOB~&3TqXV0w_t_0=)5k# z-MNv>@5G7?FW&6-%Gt{r~tP-lb zj1)|B7q-v%a)V7k6(8=zxjmY_$>QTN+<&XkWJTFeMw@O(neS#Xp`L3jI~QTMPZaTX z`c$!Ouk^bB;}8Gf9|sat_nF<^p^8n^bme^LYJPLtr81@c6O>N}N-p`l!8AfSPP~y# z!&!P1=Fn_c>qTP&o}46Y{jIaFuCDJPMg4KU`xR2JVp>0$)VOn}G68Qf%w&ekP&UA= zpK8F>k$nWNHaO)yZmBetk{gywN-vU6#Eaz0%?8=jBrOHP{af<;O^7KS@V1qp^Hnaug%p_7i+p6M|eC3@le<_j9Wf%dd)jz!o6-PTmvg?jU`o<&I$C zy0clETP_3Qe|mD8c2I=TJ>LB79+x~p{pUNIAbcgm*0d^fWrjypi-|jEzT6bQTKdn{ zytfB+!9kt(RpFTew52-Zh%-9)A1|aR1*unfNS9G2`^}6`DunTV9tgLt=vhZwdj79p z?=w_b`(;?+DswK2Z_hQtUlVlJ{UYl}pskd#n1&5vOBm&2@Z)Ddl*6W}y2sLwg~b^E}+k-2eV~j19^+ zqED2c_Fb0M?w5OX28|FNr&Asdi+x{`E}77#%PWk=s`~MOk~vG$5L`)(a%{GUq_RTVSu$ z_h517ouk5d!*k|D29E<;!2-7;WueamV&Hx znytOD*Zer1gH`cE=>1x9 zZQ=RgXfgDUf_@XnYUB-82d|CVPqxXwMH>qJV}Ae>caU~W9La3&VML|hRlHHnVj~wm z{K6*2v2Uo$@dRWtGWY_I9ERpYN9>KZr*4^>7wzx^{kkMFbgcq4o(_bPRZ8%bi8M0L zq8+s;O@Cqai`OvR^Cmx`Ib9lgx1^jO&I4%SvUt;n1O4;l$HXL??Rf^L0?JF9mEx#x z6VMcEv2F$3-bwD39(ba2+6!6(uPZ?8vZ$bN)O_Vts|}ZG^lq!JKru1Oo*yU8_t8e- z3UH9xGPzIc@8X4s+Q50*$sXd>*M4z`@ZDgxXkK4hi(CqS(=&gQb?hT}9U0i}so)WHUG|D&=|s^3HiZ z`S3tK`2T!BacL1icBt^_p0T|NI+hYPuoSu?8my6u{(@Bv#&ffD{$mxF7LFq&Ps>!vUYoJerG9CM!3_NMckZ|rnzW${ zp<^+4Nm{m^1mEJ7C)f9RiJfU}$YCx^-(A+ieS&Z6$}?6QjALE}+{W&SL?q>k45Y zT`Zk=%#hzrF(Kv+;C5g^Np)4&CaUf{iI=DG-^-sj`2mcLlC93#0$YGIL1#yB&+;4E z4vCwv+siqFImK9gy&o&z?)*1iSn2OT0#XHs?g#zvK$LBKBKXo7k@k-3uOs6oRPEGc zIzSuG$3^@?-a{S!{iWVlVHgfV>L#LihgtSd2!rfcnl9M~ZTpQ(lW4BS!F`U!0onC=axh`a4{mOW<`C^#WH_iv-@$XsW0eNf- zNz*D%Cy9=2$@Vi?C*&mvq8ChUI%@}*I(duUC5`3D1Gfkd7Q!QRHbz}0>P=Vqj%tUm zu`*m$_Bo_~x;AI)zir1So(VfQ@EbT6wPElx&wtMJ&Lbdurax>iJQqsK;;(v6m*E^5 zxtCv+5~ejzf?^5RAme$;;e)S`rDuuMvETK+ShLbpGG4w(H$kl}Y z97TA#FFKqEZB>%92)^yzRfCw%)stdl2pM*0VkckxTZWm7%<#`tZm-dV@&_U{lw{cb zE!vRI{|5j7|NkUd$Cj%~4E!J#q$Vv*#^h*VM-C>L3}644`xbMWV}x32sY_L(b@|(% znqoC82_*_O9bU|@XryHTKJ^_-jsJO)IER@+TwgN_*$>ds`h8Wv;*+drW%hzRl4!j$FqapnG(&v<0kWR5Vk7>$4;cjB>oI=3|F4hp% zr0-o448;~GUeW;k@)awWljHl>a3lWnr=Sde565gR_ZY&6LNzi9xd%h~+0t4jeZT1{ znVQ5h&BXX2L(wXwoiOidB!NfL-B_mrTq{3G| zXu&4sU_vRX6nalw6NodIqT*H}gV6aP>Nx}B>Z2`@k(UO4OoXOmMBO(tR9E<{jtK~5 zl~eHWfo6)Z2Bu5+%@QEr!#2=z%)BxrSq!p?n)lgWEv$vo%~{R|Q3!`p=N1bfLi-ic z(#r4Bt#BNm?Y60d0bpFC=GsAlM%CJn4q#o0B1)3QC~soe+l1JmR~fq{sVLBfB*|M@ z6JAKkLwtus3%ltl;a~V2lJL8c;G%?rI;Zg(veGcf#d$~kQX4QI=DXsHa|}N6`)==_ zl4X7ow=ZjYgK&lIjHDx^WtkgD<%>pvwe~NH++EP_d&SZa6|Nu5qWkM*&8_4Yjx)FB zIoKWE$2=c8`u*Nu4IM)6&~ZS<_uTANjAGhsF% zjy91G30w3ghYtf8=yT3<(3au*jG>6auB2ad5MIJU$M)WsXd&NINN7iyeA$pBEX`^! zYoUTquV?Dg#L01pAw*4TS-WEOgP`LE*?=}jnWL|=m7e&aH{I~baf;o}iY^~DXx+x` z5yrP|%9=$|mmF{+V=0V3yG9fr6maizr~`;!KmzU=VBs|Ll3-rf*T_7LG2%{j!~DYg)_GLGqcVQUk~8ldVXZpoB)y3*nqm%V)wPj!P)?Ja=%1{*kZqeaY71>7jKKy=nS)4%6D$)^l z$~u>XoASCBR+YsD*6VXT2ku2jy2|1W+&{~492qdsMXUgQ=^V?R3pk9{bJ)jL<}3H5 z%f%~x0h`~|P6vmz2O4{VP7!$Lv8}|`2-qWP3gI~)dX&u<6CR^n7*KSKVsBTZF15|e zWRQ;U_$~2Tdk+kisQ4WY6mV!8DZZ%VZaMKqEN=E(+ZpF8)s9R{7CY16%)h;B!eV` zXK`YVz3Pw`lTGX=KNAZ6?053tB7MB(n4=fJm1^~6cgHNZh%@pJuaY!|%xs>}>;v}N zRPgFXU23MIEsa-fOc1RPy8(d-9(Z8m#;t7--v{BL4)-JJ`T4dB^W{^zL5voG8SjIl ziKT8d%5lr;n=Yu~w6h|BysEMGHh8`j(NL_+w2vsp!Pt61_ zx35Y*`6ePf9N%UCZk=*4r*dI|y04p`zgwknsFvVlfx`J;YFnXm{N!~HICt2TWQWu5 z!S7rZFW<5$`;}=V)~8VX#i6&ol|H0QM>1}#PtUmtc|L#G%asiK+w^?vtN@es!eC8{ zsFsQICDCAXJn^W}K4a9aT*N^gGhu-yZZjC|eUtSldLaTUzw&0n31o<1ghc#o7>QS0 zdttw0Af79JN*gAZi%Qh8vOID%3s;W+y=rK=gwk|)f>bxffeD1~#tT=h7nE7oiHy^^ z_boE;uq7dd*j;>GEhdo-_xHmyfGn*eD!;#dzCHrUyfUtap~kToCeP`C?9~UI=@786 znllq#*B91SAkEf_G#fk$BVck=zq4?Ol}wV(w^iQTP-o4qyYU3$6X#_VFRb6+r-Yr6 z4zPSsL1=ihIJA`6$jlHkBuZFum~GRI4;UWhB%^H-ZKA2$wexPR!a)&Wq^$(84e%lI zU0Y$D8#7qrHrI#mou+|xznvSM{k@h?lmnD(sP{&yE&zB)i?A|LKbv+Q7MnIn@aV`amK<-W~FWWCk(w z;F-mKUj!vf`8xE`@0HUEdR6fsT~msY&;u~;;@Pbz^Iup}U=Pfz%HDgi_fvHH8wQ|T zbjTAv7jecZ8(0OA=dm@T)PTslXkZV_4a03UYoJr|7h+WHf$#Xhh)ivHw+y#rw2IV| z$01Zg(+W3AaY%-ggkmUKyMQm|k0F|XVQ18X6lU*scdZRDL9R6BL`n;W{Vd0pd(DJ* z!zErFQIR!{o;yNy{+lU?nS1u>kA%4(`h<3G(~i5;qz`japC;qd6!G@%bM%mk6_@Pc z8knKm{{n%W{B8n;>jHz!qm`ZEXh7AqoN{wkT-g$>;K#`;$wDImRRb#XxHWP6K+4}w zxWC@!r#w&(S07%qz|T$ISJ9L?c+JP{qf$Eu?;@LUHqFV9`2bZw*k7jpsHE#mslS}(EZq; zC{7pVj0iR=hi}{jNeqsXVyUIZw5rlv$YQgox=PbE?Q+Y(K22Jc z0-?)ZT_L(xf%5PfdwzzrE_iHvv#K{>av^M+8wu@dwZk(6vI3L%7ISS&wx-RFV92f| zV^!!pQEBOHh8OS1gu5Q6^X5hQ*(yZUDTVT6wi^i8j&Am=m$*du*-H+;W0>F6c zzUX7lpVW_#us5ph_EPFi4BC6&#~-|(Y@j^}WWu0DsytW#?vF)4)3^W7 zx8-9YRwBR31= z6+?sCHVwbE17=EIs^u9x$ieJ-U)5lQz93{w#^B5k_U|7W=VrSq)3It+^~f1C zdxddjR}f4=lgkgs!+O;aJh~@{A||M(1V%=MekSB-pP=-uLK~K;L`tPeIc+EGF!uC= z-k3&O4Qk+!ewH3RcsaE88rWUKz;EsR^vLezj7uAT9?6=Z;$VVCGC>)_M%n_t2@0Sp z2SHD9)*pI?0Z9-!oi4?NuE((B&T?a3DtRik6)@dh1D!KDu>yRT%dyePC%zeA$zLM4wo$y^+l zytD%|_*vQcj12>i*S@ctj7*V7Dsq(>B;Q*IRTY+ zZqqs((0((#o*UD-nI*emyS?NC)$3ug>YpnWHl(e0!3Xi=zycP28Kty>}rJ(p?(oR~U*cjMAKQT!#xCQi7fQOIL14i8H9L@r@=4Iol2^JLI9W zR+7{>ViFop-lf2tBQ9E57?u*gD>jo$dswEBL9Rgv z?-rsEB~mo^QLY!ZdnE#$G>aGom_;fHQ~x?Q3n#24t)4v|egKWX0!*dT;o8u=={wob z>28EQ$!bCY=~jsyp=2pk@v4m2@s?nc^-!NPrQfDSUd}70^N`-?RxBBc)^g7GX@dUH zeDbj%_l$kW*~JtS^`RB>$&&?TfpT80hBd zvW((-cO@dmDSppzAp)lM-aZysU+;Xp;i8hc311@GH5YZupOFniD&6J|T&L>aT>cQ5 z_f4+=Hp^;G9hp^$ciFXyw@w}_kiC_Cb^xQ{RhDLPLo(p#yqXz=vnW?7YpsS}yIlU9 zL;I8x)%5f$$iDDB^qkqjZcu3^GJSu=$MVA?Uq66pNq=-1{*Y}YClnLUyEOcFeNvmyoUbWK8<(_2pjW%WX=^v1p2cA~=W1 z;mm*LfaN_HZ<6VbBZJ2v&R?H*WVq1N2Ic=|MCmYY{DVd)K~+XWWbd=<4|#|U#-Y#o z)_o8A_nTL^%dd#Ydj(;$7hn3C6Rlc!dDZj$MtvNbX@k-LLq$49F?*JWaEh08`KHE| zq|)%-(ccd?;MgQ<_>Gn!7>(R?D70M|nsSFty&%kBdfa;U0k}m(IGhAl7G#4UmrUiB zOg9%lcV5(l>dM5Gp8h~B6}tbv&5P@)i;VkAUbrVlT+k1Mq-#p1Kt`iCL*9*8Gh*Mv zwhk`ryaG61_T?(WkMl+E*hepF1suMVN8KJM)l}qOd#G4HLTyz`1vXKX(r_P?+ZaL6 zBki#enseuonIn@gBHj@TP_biz+T*WTa=D%{(Lfme83@Pp_#>=;{>b8=KiLdW%Gmwo z!+0k}81i$+7zb)$*7V_PrBe|#9qav}W5|1CL?NVo4@q+9RnntCURu-(>w^t5MW(l< zAM!^pATP@dEYJ&E>p6Xiu)!*CXs)q75@)W1Uq%+dciXvGKsV=e$m3#o2LYNQeQ-~( z^tVv}R;9~}Rhj+psyL+;F3m++cACTVm{kY zc+Rd3u`Gh_na7MQK37ye4n~CRhD~5o+Wdj&c7amOV=}wbBfd^G|2?m_3bxYg9^{Di z=Sn4pQ#Z^P;)PLx%2wA&mG^XLCTri{aW=PBPbYd7HitmAo*-%i3i2 z`|^$=N+BlcWZ_d*{CQWVqMY~ZGxr>n{H_-k3ND&OHqh`HQ_HCw2i0IO9*VeVI3B8r z6vz7@4)GdJQr2mFJN6^N#{1If_I@M{t%pi>(KXNyo~CH_;~yoWZXy*|@I&Tb#0;+4 zbi3rF&_I-h8)b%N6OZ&rD^nijL%8PKg6!|8oTYUb-!a1=AM!uD^B$-V#&DAN-Po4o z=oV^uZ5!#9^S>F?RXrn#p7;z>!#-Q$E0%`OL~^A+x=Y2~4Iw2l1e6oC{s0@319lHI!qIy!n66EQtf z*5l;5KP^~~>MJFP4m)_=dlae8-p{+C>TR7gUi=q-ZC*yc#oJ+T#}#VEyKbvy=M+T! z*?YW%adzf03mCf8F3eE`bRVENAbuOu?-W>dw-+h*qq}am;3wz#Yf~&uNfx;iM4bZF z)bG=?4h@j0^@o#&e)9p(oHzxInSv1z+tRS#XEJ4Mg0P-um&dv|_qRH==lQ-D=YV#J z4xlGtw>ktOp#+;{clS7i;!`^L1wdhhAE-W0!SDWo#T+q=t$dKXwA{_}B1phHn-TAKSucUpMs$?j0%P3nm(SIX97x^)QfoRVVgq0*4+Lh^VP9GrDizNp_s^ zoPu(!iNz}c7HH%lg;Ombx6;DB|0x@@i1X!j3x{mAuk3k0f%lg;Tl+;AhxWzI#>vRj zI>oXCr!l?ZclRr6XU(P9jSk%O2KMP8pqT;=^T4xSd+{#m7OLI zep&7UeV>5GAH}{YZ3CZH1FR70SxAd>DHz$i~C3Mf_;I7H}8aOy2vRT((N`#7GDM=Rm}X z_`itb5%zRK4JC%_qu^G=^hB3bVEAH9mkX7C+IQd;28y1_QPRQqA!+@|B9T@`LGHT; zalWR*EgMWi_r_sC0f}37-k-=*3{@8G%$IyWXRZbUgsjUcW%kP2=nl4n9lUAH6jQB3 z7j?*&6?c3bw_6|Y?rNt(F!hR zF9qVw)@E=6onEpzdsH5xfM6r)mZ+zdCp%ZT8GkGoS|@g49f;=w8NPScC^g${;46C| z!Zr%rGJof32yD!%x{qHMHgSuv+QcOZj!W)w?c3I(b*if5Z9gxT^zjsBX7$BDvpo-U zupT^`n6a7{AOPG9yqqkh#F$b>m&9tlzD+1Oxf`Ic6jez5`HD(I%n>oCCG%Ihi`(f% zvNLM*?35++I&GaI*8XdYWW~{ETXcl`84LFt3(-9ZwA(&_;wd>63{+FpYD2>c7c1@d zZa!|i3)k7$%=Lokm$ysOt87x;n(2zb-r3;|2K5~5J9csu+}7=!ee!6o;XI#lc)}h%vp4!;S0x3cuoTZgJ>d;(AEqx%wR&0YhHtLF=0I z2Ia9EKuT+X9z=<+?cB0F2v#3c1FVFzn>~_q;Ko9`Rq=w1qIxDNPkDM(q=h*~^eEpb zeDdZ12wnhUi4u|63bKvnAvR4_aawYU306tj=(@ar`N4s|=2eiK63-RCW#X_W#ozwd zXcm;t&5nuysuw8id07c?zik}2`|G}7A2h;e=Zls=#>6dgQw2z5Y`ybnu5p}e5G3fb zVvegZtMa~?U{UtNxtK@ojxkoS%P%ge-Oer{>#0JX3!(cANs|5QAiaI!YV>e(?gm`c z+G9I@e%H*+qn_&tvvSn%(?_Ex5@5#Sjxn;|nCsN74}4_#{lW&ihi+esB+4oM5O&^b zne5ijh^a4GZ*84082*J8tDO;tb--nbIqF9(UDbF))C&vSzcjv%P{i1i0SsR(ZEJHB|sbjB@+{^5H?U>qw}T2Tl3KJ`>t9z~XTW#`ny_*ct)v zjK=6G#xulxVSM*luzg{BOc3=0RnJV6IDk6u1=g`XZsW~n{WX?@wdi`7=N?ZWphJ492RN41yG=%9mnG4QT3(7#PI!o_mtHUDjZ6fft~5>O~Ost zeu}%qy|Io~K87?vEk~uUacf3wvwVQSgZ2&3ChtCV{TzS75!dl4Vy2CK=bhLyg;RME;dpB4oj;(!>`Hr+?e@ zbFEH!dsv_KR7gx~zjL;uvFl-s8Z?%`gRel*SW8kXQwassw6D7JSP)npK}7|5KR9X;!l7LDXs2zEp5g-$I+t+_frW{PV#N}F4zdf`l^FTG0y62+}yr!*+W+@ z0mZ!dVaNHih~8HZ+;+N==DoGxc{>nj&!gB-=0=!gZ+jEoa3%-15|HRyCD6nEG-Xs z4*v5Oz@7uPegXEf%fsl;sjzPxofUyA=KO*Cg7K6f3WmMyerokWsWX)&zt#6V)4O+9NW=;P7N>z6?;GP1|rJ$yxC(pV{qv9$IS_CKm z9k(Ufw7k^BN5#h>j91>7OoN2wD<-X4dtkp<%EvELFQYtxHtvqcaJ3R04VJo zyEPH382~Em4l{4cm0rLjUqurJ3I}Ts^eke|=Tk6L-d4f`C01KdLdzH^yINdv!%G^3 z^re7fi;Vk2PiQ}gY1Im%u=-RL)fOQwMsUcTc>U&ZEOnN7p&o=y>$E_oX2jCzlQcR2 zD&Ewy!@b8-smVSp_(I|PB9f#)O70|6rzDG4~3T5-IZsC|x z<9g*IR-}EU^Ig(uE;9_y$u&)JFH7dp)=0`HUE1-9|q9i2W!E~tYsao!y zyo2o?vthn21C?Hj%V|Y5D^bNf@0OS}`l>kI8-WpvB`HW>DhrulcDmbzfq1EojLWd2 zO62Qfl23qv3njP&%-!Nk2UUpFkC0u`(ju|=#(K=_By!^v!+p)*PcV5hhf z_vw&7F1!vMbt35H`b4sSfCX4cZ3G$W$PtsfQ!sqcyd@ix{PBT?lXzmJcy89UP>>b8}migiz;+phS5EskTErj02R8@Yix@@bo zOy@UL_kkQSl#@cICjr8oSi@oq)=@!EUfL6DOUtLc~r>iVJyIXvWJL@Q53~82V zvNSICh?W<+1&%A6D$II~Z?r{eDmJRivZCW8@HXVH9EinN% z2ul~7r5NL+1B9iLNtGuA=98p&$kK9{WEz;r?8FwQ) z(QU<#)}R%^gFw_dxyag+I3LZ|y|g}ki`2!%4M+l7e276)DWem=Jj@q;w>kW|)K9IV z@Qfyddjp103oHjwH5;p#+h~q_sOl(qQkY4(z>^th-7!G1430j|SU`1gs=<3RfzAqX zKPxYKKsz}Qq?w7=X-P9Qn&%kt%J?oQPw*<696J(I4+0?ZE4D?4;K;4X#uXL7%5mZz zVu^^Qd#>R{fGTKcQCqy8jTgu~Pab0v%W7GyQAVR`Neb&HcQc8f0sJH$?nho$dZa6ZgG#(yv4CjWQlR5b=Y8^6m;5&3uPP{V9r_c!Op#kzR$}+i6l53#J zkYLwR>){x;E}C+!MO!F?7z3Zyp#MJa(v4I_P6#@&O7Eh4r8`Qke0Nn+SrKVmgF05s zjG%X9f9*0~>N1Y2X?jDfU3zQesGY@7c>7dK;iQDjzQd zXC6SXjxlzi!_0x7z=>vc{Q!`4ko`3EB;!=)y%wMw2W&oE%}L(H2;NbGMP<&^3W5|^ zQuE;)K8TN3GNRc6O)sp?6wsQ@17A;Fhs!6B zWTD)>X2#lCZ^cd&!TEZW$^o~PmI5L3T2@Kj#`K+?vF|@IqSmvI_2%W>>kZd>f|14( z+lGG`?jCdq6(D0%LZRQg5c*NDPdGb~xC5IMY}fq*%@w?}APe8o+&pAxk}woyXDweE zq{^fR>0nq>&o9y0l?<0h^ElsLZSD7l9TH;Q+R>^66D7t*)K%_*I81#O?6^0nYWVCn zmx4--)`*fqoyV&b6P}zEFEgi4E7fa#?@q1HbPFT|93umjglK0Uo2ni{4=5fl&1#3s zs(th2>`s{(Y<~AEEhfs|2@DkLvE{(%df$riqtvGNy~7bm*Ck%uGN{XAzxx=lJ388+ ze5-t!lPZAzgw+V|>+?FrCkXJgDr@-m?d`tDx4-+3AOGFo{o#N0cYplt+3(N44EAzv@82`uL?tlD2(SM&W{~!PV%m01<|2Mzgf3G@c Oy1#$td;Av=jeQ+Cy)YL5 literal 144862 zcmb512|QKZ+y0G*y~z+I87s=Hs7N6SNm0=(WK3nAGbQspL=w^PNFznVkql8HMRU}N zgGz%)3U$JNuf5-=_t*RXVXf!$^eGMBYwfkyy7#rOv-fSifz>(#L)j&23uV_ESgAU@ z?srm=-LQYRud|1@n-1}Nt4x4@y2_a?v=@B0`8QN?MFnMJrUEhS@6OXW0L^3)8W$w3 zp2qfGl*R>cYbL>Qz~NHF*K)GG52Mj0=P6!*JlGU&g7>A9HhU@_eMFjKj6QcRn8x>a+#pqk6RmlT-=~1u}z&z zbLG$JLhpCYms{qqFpce8A@{y1fLzc(0Rnhlh}&%nAO|$i8~}s4J*EKCpn+-t_@3Kq za$plDG|-&@)|GLWP7XBVh6YL#z?zlZ=cfR&Lj!FHVD-DHfDQ16tVaNE`*4>`KEgHd zha5%#tJt`UrU1epGCKjRETn+z|Ll}K|4{|G?6=68n_i5w;27LKE9CfSq`3G|@dRZb z@sWe}(rbPNp8U1#WXRI9;z=94glsu#Z#6~9E#NI=H_)KH0i&E0nuG%7BA_Q|9aBOR zP@w#U?1log&MBdB>NNPn=O|=1>7xxy2~9$Q;)U#MtZ9Q&LK9G+Gy-~`_G1dD;svBR z6)0q1dy@8RN+{CVXD6VmDCmS0eT^dg!Z!tb-HrPy7^TGo3*TSXTz#!dlgc@+Z~u4c zdr!3VxeM9PF6Q|Pu;%|28}-d{y7KRDnu(U;;@keuhMJH%t&sf|AMb)GsH2EfPJ$Z5 zt2jCJ0_s@#2x4)b7ZM*h}2; zG`}fk&&0yySEbDk2& z4hftFfC5thc@qQ&VGnsd0sP8OBbW7r%Z32@z#g(H0qng%TR!O_10d`ny8+;)sexZ% z4_S%;erct4-eiaD346%92;irHDYhPQ$eyr=tP6nB6mVjzC6FNK#Sd>_iiol({)=`5 zoS4a=!+yRz(5}dZsEX6$Xi)&Vj`%^{Z~v#$j7s3XySzL``_RaLxh)I5wILMTmObM) zKC2z4&c3_d$uL7R>Is{g6Yb%Y104{AKYAC!XiDy(6#(eO9Y8*2hL^hFRON6-Ah#|feqSexDYP$$O)cTV3<>4;SG!n;WM*w9tISa1AerG)6Dke zX$RN|chVZu_06yg--lTExGpUd04H8f6?7feLFnaFcJK+CDvkCCFeh90slNOO>mDm) zmujV*n{1%VmYF!d&x(K_=%FWUo8ovhr(ilGF=Ghk5YH08oOs#aZ{UGk_B3MI_v+G2 zr<%+FUw?$XNtnxN_O!^!p+n~D%!}FJD-+=@bym`bAfR0EP@;zFT%?Tv=!7={l7mk| zEkzRHZv=XXB3gK#S9nrt?IxcPG%9hwe(@~tyh*9VSdVKUjg_dQr)Tr>1L`K?2UYMt z{1q*j%bI&VFcUO4e_$G&ShjFPhsC3*u~1WV>wAr_>~~kBeIGP@e#P+T{tacbPIk%u zPt@8B(#)@>yy26Mmzae-wDA%J^*kG|44_*48Sj5ypg^5AS5?DQ)~m2XSH2#ipdOFs z`8~xns4C(2)iJa6G4RtcjhF^3llRtC16IP(229+)=Q;DRCLgexqLOMOF9D8#A225| zVA)XK?|?jEiQzT94|!wMEJEA1NO}=E8WdO+hw&sA$TMHU|;} zd73QmeL&v)XO;cEE2L%r%1Wbo`o%)Vn)bi49M_vEl7|B{^2FBx|7ri%LD!c2Ljaf-w~VRQY-vu?6+W@YstF)fK30{;dcGKrXIKC`llexV$@B{82q zIy~e@H5Pw1)&IRNG_PMb+(evs=<7le;fOO-c4mYnh*WWgaxtJlJ5J(^SJFI=FIE3*Y7z{9ReZkCh8K zGyms4oiFkUTii}=8$g?=ZrbzuLw~SV?n%_mv;Ev@R#PB6W-Y|zu2NL0O~oz$n( zTmGz_zt`pejx-grUbH(ZNlq zJv&woOHW3k&jfT&jI6aVV^2h)3jlftRtY=yR3y4IL3c36sv+q&;*jX=>72Oo{kt<$v=)QG!&biOMCJ3b!@hu_L&3q=Vc{A8-i-A_!@*XCh2sR= zcLhd%?hG|@uv1~-N&tQyBR_wJf`g3;3!hEE{bpf5pr-}wQ&_kTfX86N&~UI#Vc|3Y z|Bn5HhJ#%S3!hKG{p~UGP8?>=ucEB;nE?I>8-*SDRg`tUlz<25VdJoH4U~}!5O7~H zjEvS`rbPo~~HUOXM zQkP(nqJ>n@i-m}SzPke>{rXf^D*@4JB@kB2-W(%MJIu(D>`O8DaL2w9Bf|?AI+A@U z1~&x`D%ca)Sx2%j#iD?oi#>y-BiWZ?euD0ZV=rLoNcN>z63~ONR!BOUeJSPu^bZ*M z*&4)Iy@9scrxSFitr+?I`oG6R&DM4Wum7YdG29G3w2Pn;LbIusnGI8Fm4 z#s$Zr;V8vX6~Le4eF0W$b>XgG>} znFrv>xF{?f$-amHI18T%4M$n$ngl%16`utQN3t(`1l-RMCqKi3S&B&ZMH#>^<08-_ zN7IGDsz;AXpU~4T+HV10s9C$ay0t_K8|wSihYKqquCemiIihKb)yb*PSNZO z_*BYi33aCqLr1eO;FBq*f2dn^2s)a5apxdbyR!&&uMR^;vM=s)0sRo%%{tgiDE5UR zM+Ccm*KzVg_^FB`2}daF3`YX)FNek$f$P#hVe0G@%94^cqD5sD+jihu{OQ6KC= z!4ZlhV=;icV_kt2*f$KoSQHtYi0I$SXK*Ldr;|@^2lyN<1I7)HU0q`80d_8Kas~tJ# zDE8$50T1HA4WUPlVqa(g?uW02hNIXQV*u~QjbY(P_GLZ+Kd=#B0}V%6=gt6Ljjx4; zBiWak1U%p*$*1*UHjxI(4h78) zf;Ql0VB}L3^kiiFvVbV)PIgpq1Vcx&FJge+0+$?tv7^}+ErRZ>hfBcD448Fzb0i4p zmvAXSpUNC1BbuWjLsvEzN$N%&X4cW{iwrSxmqhAL9fpo(U-SX}7j>%+K}WMMeQX4M zk1KVr4ns$>FMYCr-U@fK4%Q=*eVGHQ06)GFro@nNl;XG>zz^V-&~TLEC=B2q@XgS0 zl;XG%)UPf0R%kd%aa;u8cku1da1{IEMZgbe;5(t=DE0*d@DunhXgG>}0sR?*1#nwf zIFfx)1n>}iH#8h&ox1|~C)@!Rj$~iN33y-~ZVe4b8Tobs9<&H2AJd)61c2?YfwDuF z0eAs!2R(9>9U4Ty4@|@Dq2VYylpDZ9Kp;CQvT8h9%$TSLfxuQWsVXN%~7#| zE8Cvy)SWua$dT+zA9$eARi3(4hoB?c7w|-*YbJHC4ns$?FW`~Jy_|42>tH=1*%#1I zB1jA03sVJ1I7)E@%_V{g@%_+nl;Q{)O&k!x-J#(q#St`}I1qt*Lc>vtBWOTzpda^! zhNIY*Py!yj3-^VFqu3Wt0B^$mq2Va@WfcJrS%wF~!jbIDJOD4k4?x3F*0}=#51oOB zz`~L2iwFS^>cjn@;V2`wB;W_E@c?Kz$_~{8@cVcWG#q7zf@T)M+ITQD9A$^{0r(j_ z6u_q{=&8u|g^bg$Q^64o9nHRgry2Li!zD*x>}d7{JkGc$6JHNIGide&JkRLLiCe(Z z(d-L&pwZQvx>bjncclEK4?NN6+DYB3Pi2l$5zSHiDp$6>8>m}#h>;`O7w|;m-fHSz z9fpo(U%(@c`_$lW*1>v2vM&ojiLu8cVX6QLM=6dj0R9M%hK8dQM=?-h^zc|{I7)Hc z3g8#}2>|doJQ*5}VqXLSdGw>Com^K$czI8^(Rk}hn>$!7NfBhxw(bc8Y~sYMn94y*v0j!-8h1xdOmb`qM7P$(tUNqReW8k!DY zDKjKx0NrmLRtQZ;Ff)?+B>g5<1WiY9GkI))?yrEIgQg?cnLJsNegwM!OGoiDc|w35 zz=d6crX#HPyoDs)8!LgOqd1y8UO@LX!_Gp}QO2%7(#x^)&~${onl}s3{T5&sq3H;F zHBXzQXJN(AbcDT{#|7yAoY-YRpUQV6q1qbr4D!+{f{`g63?9kWm?x0=#gxV z`7shdfE|RzBiS1B7=U-M!w$jXk!+3m5fa~mMZw~cY>jyez&q+;F|c?fTVtM2;xA!w zka)Cs#ykSxog}dYfS<}Wp>|ag6(?MiQzDiG;8WQeu&GdNP2O~}m{nufq3I~4QiCiv zsu&%bj#4UdlAep*gr=jEN+q(GVc0EbI!dXWP0|CfDrh=_t;y3N>F=-_XgZ3mp#ge; zB~}YfN3k{YN&0Q7X&lUYN3u0D0XnCrC_CIHpqNCJEVUk`kc}ujv=qU5P2++M1p;ja{c9eO?NP0HZ zilpc$HBu4KeYl}kBt=K5k>VuX2Wmx9bd(yojHGwMuSn9+z^+JcK=-x4nqb#E8Pvei z)cmWY05W5KHffqpA2b!cnK8`^PkX{G=2>5_NR5TOs!0koaGoD`_1UWkPgK-D9(op?D?=RSUQUHu_gn1zaZ=_ zG#w!gu_gn1zaH#8pijA7|3o>^70sH=?4t&$wrUfd*sy=C6%j-sSu4)jyl2>>?Wn$L zaKlHcm)2x#AN`Q(tp+E6R4=W`aPYTfK)H7$?!g=i0ZKhCxGO9tjYX7RurEN zzl4ySk2M+L$420i@B&EA$65{){n$QS8d?C&`B;krfw-NxEW7}c^RZq`3N+wzp#{*K zk2OCKh(1TXKnt~s(43F83J{2yNxef0CxEt-$>&>QBB>W?;RMij@(S_@zEbbf!U>@5 zWDXz@yKC~-Y5!c`|7{Ko>3po`0=m!1$s4i#MMrQx)>Ni1IC&$szvu|g$C}LaeM2X2 z#P$~*!TDH|nZEC5su9~nm$1L+2+qfv%=G=XQ|SN{9l`lnlbOEXJt`W2q9ZsTYbw)U zLgfN5bR_3PX8Qi8sZaolj^cc%OkWr>5%|*{7~c7iv3`sc)sbz=dO!-G6@4<{487xS^&}ckXe6xG`h)VV0W{}B=Kisls5fxo1kiRe8U4r2re4E^ z6F}R^WcnW$JNcWqf3Cp)_7#S8K2-YOG9Dlm2w=R-#Senpe_ zaQkcQD9(q>{rzW9J=`X`!u&-?aXw_|?;kmNH1HQ4#rcqlzyAOg4M2?@#rcqNe}FBO z3&7BkoDZ4x2Rx)g0Vq0(^C5%&z~zvMz@N^-@Xm({`c0^2Zd2BSKi!4l1*o9^D%H>p zP5`ZBl0kpm9IC0?L?Gw{x}xZ*$qwr&H0ci zfBYVN9n@8qJi}M4Ehrc@eR-dh|Y)1`V&gh`H-Q1++OOZA|9=aWAQtci{xkoDUiO$FHW|--Q!E z+Q|$qW8P_O@mD5)iTBSn5_H`}xDqf{1G?Xj$=kpEMMrQx3^_pecYw^Rz}OL-55tk9 zKc2k(+h1cxa6SxCKo8KT+P_V70r-oK;CvWXB>fT<4M5QmoDX9$pa)7!o(udnb_D0c z@FnT-R4xEBb``B1PnhR19yVD>XK&|$@wriNP%&jeAN{02#}l)!w?80?#IcOO`!zP zoDX9zDbR+KubaXNplt$sAdqB?lP{b?37|P2#&jSMzW{fJKFMg#hp~wi$i(-+3!rUd z4Iq%fPPOQQn`e-|Q*FB71kjuhP71uHT6IlSC;nW;K$k?6E5TYoC%z#Y+2b9G zj^ccjNP044UIoUE;(Yd!bk^jZV`o`OF6b z@wrqBxhd-bDS%e=oq<3CFV#j4P5`ZB&Ljo=s8(`t0%#?33n|b=wUdJrKr5L`fk2`K z)lzPvCG^Ky5sk=^tkvsg!dfNX!pV10;f9aqd<4MolN9lTP!~mV386V3b5h_4PQH%{ zbp(jcM-2!hbK>M1sc-^lo4}nE@Wjb?QlSJ8osTpSNZ5#nL!Sdg=VL<(RN)cu0%+S< z4+tbGQ{BDbrU-2thmitDsSaOo0%+Tq9S9_GQ(e9$+QxsbGygV1hWxaPVF2iXrc`7F zMMrTyb4dCP$h_*`M#!*Z-wo(N@{>26`)g)UoR2U`KTI{9gPIu>=d%&e53p0w02Cd? z`79#o9#k#>MMrTyUL^eu6$-%6k(>_(=)q=_Cj$R@R*{^KDM>GfOa%V4LWa+L6oEj( zU8?)sl=a|GJ7jnPS0Iq6L3N;m6F@7O;-o+U)rAgD0Ig(h2Leg_R3|z(0ko32j1&l> zy3xT2pv68xq`-Te?2b0k4)|lOh&JX()~ce0uvW>Icn;J>kz7J(&c_H0Ke-0ag%&_` zKJq{yMHMGoQ9+#m@+EfoP2fZd9K*?OR8Rtl&SwS?NDRi0LQfH*^Vv)ae87*v3!rV| zB|so)GoA-8fVPeONP${BA6@`$8&3lQ$?EtCATZG``*S7uw}&#Udsq+XK|WMu1w}`3 zKB^?W6Ed&*w}&$9*xdmAfCbfC9%}3;&PR%*S5nR8q39^iXBVIcD^t+`6dlF+=#umt zDi?sFqd1>XKo8-eLID^$lJnst>3&oq07Xa1I9HMMZYmC#vSj}0q6}Y?=K+Dle*6qn zJ^0f}8D78v2qanKWYaXbBS0&eBBVegPWDZM6F@7OmOvnRDNeRdgA+h2nVO`)X`Jky z1}A{#e0+dFiV#jVP=gadi+%V=fl$13vZDXTS`kgqk*rm4BVnylKH*oP*C?X%Q3k_L z-HMals-Wfv(fRBn1@7Qv!zw5NMCT&`1d>=ff}o^aIDK$O?*%;(QhWdN3bcUPX=_ zOg^mhaUtnJR9kwev75{KqUfDbQI@f0q9}V;Nk#sMJ`7Bv`ZZbB#YzKF!g{EKnwakNP!sq zHoO2@$&?`l2Jt$00ko273j|W^aI(AFRF^GkiqJ}?J}K}JCmXE637|Qja3GMXgOfeh zwh?uCvc65!5uiAqQb`f;K5sGh0R9vpr9P7LfIyrC)(iwD+GPJaE8+mqoRx$9A>t|a zIP4Mh@X?Hqq$WB1AJ`LU0W{+y$p-|YUrH&sD^BK9UOn-KQCBn1K8Zx&P!dy0-=d?eLLdJI$#dy0-=d?aN^ z`gf=v_7ok#_(y$FfmP#h~g0n)At1AqCvv`ihYkUb1yFbTpht zndev72ly#M+r}%v5yY8bpWp@1wlN1Oa24yFYzh7Ad^8XvpS-z%?xhd)-AuGdI)d}b zn@-X%VPs@D(enRm>$PXo}sB``8CgrXxjpFEtT$75tz2t`M5K6y$ceHbH?LMS?d z^U0eH=sr#uR7^;oRRrggr$f@8Vim9}63O|{0NvLBuBkW}JIZ4|dGkqn3Ds15s)|O= z3|i!qHxmd%R!|imP5{mMECm8l3UEcAIs!E3BR~pdVP9Y>8YO^MGSz@UGzZl}3~q|h zN~Sa^;6Zf}gA+h=K6<18gK8uOCxGUB*nvQdDb-61P5{mM%pnD?!!;WxPcowO5e5RW z^Wd6|QvzuFU=b;hHhELAf2|cEfRV&t*kKw!#iBx2^1ClBb}u2A3bg!pzO#LHJG&SwTm ze~I0P9y^NjSpw)jMpPsWH8UvAXBtT_n>-Kxe=zPeyKW;r-vvKkyqkZ6&M<)Jp zH{qI%lLCmb4;lJL=i<{QD|3IW6>4fV=tNkn7+zcu(4kHMV&+5U{xN>IFuVZTHYTJ0 zm@ZrdUI1wuTa)R3tOY(}vJ>#<3XIyqnN0tE4pYJKl-Ec=M{qvYWc2ULPNl+7bOh&P zP3Hc-9#kX@MMrQx)@11K`-aMcq38(C$C^z1{mdp0ga10K2+qfvjQjn{saybR>O*aSdWcqBtLGGUX58gp32o{<}zz`B;-Fe~chp*LyI0 z#P8f?y%<=lm=L(G_mlvV^RXs_{+N$&UGFIYq>^b(1^rv#y53U)XeE;h`s=7JVpCpK z$a8??e5|RUe<9UK3{C*a`B+my|8c697@Po-^RXtg{&*a&(>Qq!(43Do8TZErP#wjf zjsVU1Sd)o={9CwY^pClV&xg9QgH?nU`&g5?f2;oXxo^K{^R&@6?g%(ZA_;BaY4A+Wb^aq8VNdvB0TqCO{M>pRAe>fRSeKk zoDUiO`zb@_Re+A-e8}A2F9#cgo*5M9Lx%qTJUAOP9mV;OiNC)e6%9bmJBsrm<9`2c zDi?sFqc|Tj>krsSg#s{iBnuE#h_;f#rcq-f50MK9GZ^ee8|K7&?;kA%p(Fk8n-JHHbBX%w)trv%WP5BYR|{CT*p_mluy$s~jR1Tm_M*pwGV@*JQ!A2R4q zh@u*a!3iKa9|qTa;@z=?0jif6oB)#ZVXOuMi8gSZ#>sPl=6o1(q(Bo~r*TRE$@wrG zfk2WrT&HnT0L}R@M1erOIKB<)$_`c$n)6{;kpeOJ4tN2ioy=HF3Jl`b@B&CXnc)ir z66|oB$*z%qtQB%I_S;-UGxmqL9iUqgKmOYblxni(jVfxG*?P4`^+SKZ6t3}={qBmi z?}LUv$_#(*-%vK|WS49eS5#0oX6jBRKC7=`WWye~N` zbF{PP_2+r4!e7-qb~}mx0sq~sa{iE&%LL_q+}iNt;s!m5ZR%W_D}PQGdcSMFTzT6% zq1kK~4sw%EQB8jE1M5{3?_WF!fAD0eV-$;>0;8Sa;A>aHAAA#W@F`!o$qpP7AG`n; z^uY&#gD>%?@k~CQyll|KpMZF&pT-4Y`pbO3eq%jz z3jZCTs`k2K|E{vD1DY=D3p4^=3u42F(4+D7(XYG^;!>(+K>0@ zHnbn^t!!w|?G0^c&+Z*oouQO0x|LeUvUD76vwJ_Mht6$#xqu~Cnmu0hT1$>)>{zgFD7mo; zYtxcviIx(hd)QdT-F8EcwZ*aHSnun!P^GpT@~p+B9wtLy8mlx z9Xj4v#nm7O`~3R?_fg}Pus8@%f_)Iw|B6y>R>M`E!4KO-(+aC zu_~>XCv9|Psm$u3$i^_MlDO#IK1lyWq$NGik)Ds@q%+Uz;avVxXZ&NmM zE|JWsTXPt-Mn#~XS%=ava3J2IP^HZ?H=)kL{6x+*MHbH-E3P8jqk{1yT*faX34slwc3j);YvzQCuT*N zwyp@N`ufHvOueI=lXHKyET={LiJDMPrkdOpU!wlQQ4BN&G3uK0^W`;R3!>pKL#P6?ThV5tS&G(d%pr`UN?(y`A za16&su)HEz0}(7Nf<^rLpPEo_rk=cK!ECw(AESt;Zvl7T0-ioij^UgL*2S7oe`eTP zX4qb)-U81833|aydVw^(g^$t0)5pg#938V zb1b4}w6N@pt{F{?U}bX*tMl~P zVvOq9^bR3juZL2TxxI#_-^0c;E~V0fqYn3a%&>jT zvB;Xy*a((e1nWx#E0tqdhNn*-WAyVf!e`URiJ=5B!(5nQTbW@2%rFaPmpvXY|GO(%-vUwF~TM29WwNBVoagTvDli?)Cd-51dBN2RS~SZ2vz~dus%;;IK~(! zki_7EnPY31V|$om+n8g-k*3y+7DTYBIflb|`o@XBBtain_moj!JRKjb^z1n0*-`2l zzP5AhS#9Wr+R)Fnqps1cr+mXMqJ1qYjDpQ{{R+=;^UkXEonwsJ(V%G7^=Q^0-|!cF zSWL7}U4>z5MX#oNc2s$Wn|6*psU3BSW(h>In)rsdiuRSLFan7Gl^C|0>D4zq!wJT# z+R&cb(Cpe#zi8HHzTsVb!&;(!9x99u0#oi8Zq`|~vvcf4ZRl`qXliX}OKoULZD@b( zs9QAaHQ#W6XkS0^S2xr9E$P)2o*g$l!!0_;+G|HcqggDz;Zc0pAezOj4PDczchys7 z3tdp1F|5uIRA88h_VLW@qG5mTJ7kg+R@9kqhD)B<7!76YDdr3 zjuO9rw05+$HgsL5-gQrzt@KoN#sbkk5x(JWe7Ku$SOgy?er+1fdRrU1wo~t#XTcV_ zg*wARiD99}Am&VyZ+Lq&tG9MEvv!o2QS(l{8=m@?JoPI*3%1f*)EUI2@$n67;=@MK ztghNn)6S}^p0-=)>gtRZ6-J8^gP1jCzTwT$tWUM0y|tn1JFBjH+HR$ns56LplHeQm z!H3sJv&y4c#F_XR&3a!udZ>03qsmDG=L2b)Xw2iG3vRFLZ@#+j=Kf{N>+5c>uYd9X zvG;Y~MYZrFzCH6>);BNL6jEt@(84V^G@d(y_kO6qtitfJh!cz++9B@(G2%DEWY3PP zjflDOF@?0{1fo}UFVt2Mh^_19)t;LYHLqJiTPY>xboVUn`6z88*o;nb!iPY*MwD z$$=v6NjI360wvm00+`1G#oCjHnU#Su?Wuyy$PppEq*UhVky&~v7Riuf{n+icPo!5RmGHaON`8~iuUMUKB86?+uzMIGAArbrhCDNVpvQ;x7dh$ zShQ`o)`)6YY)7}?$h@(r@LK(D+pi@fTECZ%agN82*M@h8cVr8saB6c2#INdnq|Gmo zSl9VgnvAc6bo83H4r1Oq8W}a}k^Q|_wdAw!k zGwo^SiBCJfYjZZoX?8x)=4(!)E<^f4wL^(r z_H=Ev2(zwD^u=nCOMrK`HfzU~&F&+Cg?-mOMg?u)7DmZmT0iw^GA zqpSDDvbxy=Wu>Edy5|HcNXNu>3kS+cN1Jpn3RIDfz1NKe&drZn(5)D#lpj;nEgm>O zKiZ{xS)f{eY)?0L;2fJMv2OW5MVpxH?iqpdHql$VmjtTX#J=pF7C5gxN~>EnP`N$k zMz>Vpg7)ZuZrwoj_SoTW&JkI?D8cS|BMN#ksof$Ya(dAg-7;UrLuMA#^$c)_2;0`` zcQuXRRS6}XpGRm_@gAM8M+B-8`#V`9>|t>-o%cqtu!Mrno)PY_c-zjGBh$hXJ35C) zILG4jL&L_&o!r|Ry(x1eTTJIJt~(sPTkh1lKVBlVfB%)8qG`{a{0z8>+l)&2lKMN_ z^1_Wn)ow5Af1uT~qG!7KikXRbPlqOrmk0EUj3rewOGYHz?{y3a{ua6CJ?1Cb!!*|x z>*)+(h>J1*%%zZ6r#(YtxVF+uh9NdwH#)$!LP)SSazJQ>s9;^47bYEHHn3&|o?7ql zb(?j}z0QF^j{LXrU9#o2j~7Qv-QWPnEupPUBl`5Mop%E< zn}qDncY)kC@fQY^Zp|*ay>CG0mb6EWgx9nQCwNB)o6H?Qy0jK^6jt(?3$tuQQZH4VnK&}NDyf8dVPtkyiU%`yWM)-zKeJ*)x++zM z89O2zmQ=tj8W9gmv1MkD%m_>FVBQ#!3M=qa5XGYnPj2|%pGNyh(T7 ze5;{)eD~?H(_IY@-Ol;CX{4WR`NwjJYEJ!`n9?UVKfQQM`8Y<~L-*X3LTpT{y%+M& z>#Z`sbRbT|^YiNayI=Ax72;R1k)$sxu1sVJD zs3Wh7a*WDWW$u>tU#GV?sAoq@t$AAKv&-Tc`KyaeAFO#R+>(E7;D(v5^tA7Xy`D)eY-(Q~^RJLailqKD8x~1Ixi+8+i*&Dj8zklZTuqC?7a~bb* z!oww6M()*J*}m@dcxS@Cmo9E8cIB(z&0Ukb?}RmHiGS$xe|VbSy)3p|udz*SM@7nF zaSksh$HmVUW-Q&5vQv+*Wls6(FFK1tjzoGt&Px2bj{BX`7PUT}`u<{>a8KPTPu;$Z z#O4)|B4GxqTXKfExxpP4Skn_+L4%+p3nI=#SU7xbkx1By=M1ayuAFA zrg7N*->*ma#tv?Ns9tqBLfptSV{ZJB`F*EHOX_?ZD_ZeEJB`LuwOxA_6@_vqeRlqw zVPwnQeY5@M%&Q$yU9+QFiskDb(7I>4?~1U~U0A&5^UXW_HM-^bmL?A8r@!69w|?ot z2Rtv;^h>ONzZ=g8tsKv;ta$ChCpKs9Iz}B!FW^<6=ev`YOGO2{3QfNA^0#a<$cRh1 zoVDxgZw_$Vz-TQO_@{LSjd|U1r^xoOnE3s|E3ar~a4KB4kLAD{S_2dmhIqUd-d>Tq zNP zP*qKmRT`h_VYTFa=V-x91b7-+G!!97cz3sXMCW%I=HVR zd?aYJ^C_!8pVeQGU-F~JqCd6r%jr+CGNo5MN}g`>|7lxgQFsa8F@Km_QLxaOK6pu; zuKLv4D%R#<)|pRFc5@zH^1SbXoV0Dd*4Q}nq^-2^@v6|&y_w4bA1UXGMJrXt#_Hq; zHEEg^cHCW6y&{RDDwfCEHpq-GD^yVMTGh9iJMl5K{H^Ww#<%r?$9{6RSX6)e{XHx2 zmswN7`Ptw2x8dKnJYB3S743X0*^I{|uU_xwbYuCB8o#&F4r&=okGNzNZav_?^msVu z%bo+9yMFlyEHd^9zwr5=~1wr>xLHF{A2!TYpK%r z=c&T(LAT8G$5!b7xKp&uMk(xP!FRWcq?3I2TTlPY-WSv!`!l%wSgP9L$BE$;Rjfmw zD{RZFSRTc7Gd{Tr%ZmNDP;RdJOLC_BhsD+wuGw+Q*B@Qk_iX5O;$<6E`cj5vuZXGe z8|Q;Zd!)~M4?fwxI7l(m-bhAI@R8mAPxqY?)|jVgdC%V&di&Me_p0$1J%xVC)@QCx zGmnfh+jBf1ON%%9rr+(#hbyKi z@OPAFTjQ{zOklMK-D1H0$comTaW4loRsohC8L*OrG~v!_`wW7%Q@qGh#ozczD0}$dYwURi7nO1RZ70-%Ib`sAO99{)VEF(8p+V%Z#DMW2@fuZc*Hm z7#Fz8b=MY$Q;+BKE2ViB$cwSkZm+)h=;Gj8FL9MgnyL1DIn*<4aBxQ$hnv1_A&L6VKFVy}Uey^iEHIsT`I(sQ?}MSDkD zq+_z;TTZhbyQ*{|GhZhzH}s9bVP%!E)hjPL+(~wc|7~O`x}!y+c0=sp^*>wiC!b~{ z&0NrS?U=%8*Sih16?a>#EU&qI%$ojzPuHNzP+sV=>y@qou~rejH#5Cj*B#)v9FWpn zFOu=YJa_Gh(idk0Tlcgjvv+RZg9&d_4~)81W4GzdOy1N-?Yn>PcorehCYKdmKQG;7 zk@tdQvt34{y*4FD8ant9eujyFvaC#?rF7D8>w>z2-w%d7RiAf8zvb$T zYjUTOYrPh|xO2TQS@WCn*GD7YGR<|A;@^cRUkrMe@4Dlg)Xj|Zagk*m@%wn^TjkDk zXnpZ@rBW}$KJbK~!;-x#-8rA_KbrZD{r5cAO5*u`O}pcY)`7x+{K*U zyHujGT2sFF)oC8~G--~Cov}{kW>Lmj-w#!5jZ2ii*fWcc2sibdTM_rO_50nETSR3u zLVO~Wn)iG2<`nJ>+0)Z0ZWz?tcJj%Ui%A+gkH+weKdyAT`6_U?`-10h4nMk(Sdew3 z$hT^EQ zs@_UDI(&MYx@67bn!wZV2ZnBa;a+C>#O$*Cz^a3(8a{SEbS$w1q0t#vZ}hIcwno9O z{bqxy1IOW3U!C1XJv1rK(<>$O>Qk0*_6erE z^EuYe5=_oo*Y(Mg=SkTGx7GAMwt0HY$a$;7Lwm#|wHjS@`ce5FN+bbs_ ze@4r6$#ZQ_Vl3ZY)lC=P{v~L-Va9cvw#T`p*ST&crWHE{Z@%_4zDQ-wc^%rJ#tUCe zb|!W5uG8y2wEKIE=_b8{hwVyc+pQcY%~NliR`d6oAU0;lLASFSzO>Ctw=IknK5@wU zjFWkjeA}Xj8vPov4j*{+l2e)8fllYH@HHi~&FEmeV|V}dtxKwp7^M zn}6O$BjICd9eQ;;iZhenJbRpwmT}wTazg4oj?)G`)3=yegsj!fix@bO=K1>hY5uG8 zRzAsXQp->_YjX(RCatZj@Gcc^vekOe@7(M$w@9L4&CULp=clC=({G=@w z*GrJ$S{A68*K$)mPQ<`DBlz*Bvopn}hsKJybtbQRJ)F(GbP4qk6wkhXQO(i_< z>AlWh4})f<@(TLDd7_&fdHb2@kNUTZ?f7?um)#yTzt?uaf~H~m`{2-4>B<`;?=PA6 z%AKyK}{liRGbrNWHM#Jtna)f|7E*PEARaWCkBXlTr=4fQ<7rIZqn zzRJI7+dg_?IoBWKo~yYS)Id+m04 zW~ia%i96fW7AiKsy4UOTc}+@L!I0u31^eucIn&plR99LobK~2}7Z!)z#BW`Z=#_U; zKlMnVKgl92GNR+Xi3@}^5&*&c%#7tn`=*&O_TTDfk#aH*fIXw+_Z*AtUHeUIaEi32dzLX+d~k7-gV3g+dFk56fp3Z1c*)R7B0Z}`I?Ys03TIm!{nGV7yPFh|Rx zS4Yj)J@sVC@%p(VLOXtj&aP^EP_=dEj%PV+HaTWeg^l+TzUG*5N3{NUf9XJX^C=~p z4Obj`4)B$`Tw1Z)b8TcQ_ovbkf6uP(mu&j;-`tAjRt_+Dt;u`xT$$kJH)mEB{`2FG zSKTdj(WVpYj0%n2G$p#-dmqU9>D-gCiSdp1b+(l8c<@Rnqw$z-70>ptaEprr8NDs^ z=KU32CC}%_JvFJ`?ww(ONHwSTROpJn_{CQn&g=V?DvHaBE4^cDh|uP^{mob+@8;7T ziHEqpc0JHv6MSnkr|q`k7{h565uA(KjIt%oin8kc`Ia-Tc$}BI;Bj;JVrxvZ*7>MX z{x-SWrxJY(=UDyYHlTS%@lk8>bHSGhOP_ddIANm0y+GJqvGq)J;b!mfqdG&e9iy*H zY{$QSepxd9`yuhG-*2j4mxTZR(euM1eA#&2Fl)HuchLCLUtesS2ivO4-VayDKCKwe zJ|}H6{;OhBg<;{YrQCey=-XdE>Gp7)aVFLL0O#j?)92}WhmPP~W5vByCRfeldKT@p zYV$E_)z7;4{#`pyYENI*#xKt#n|M>-7rQaClMa9X&D>IaL+hq`{^KnlVxqh>muE?u z3d~&EZrSgDth8=6bD3O$^r@34m+e}!GM2WZnxUCHXy4QROvlu#Ib~VJx|Cyf5i!la z(@WKi&JO+K-1O>hj=_pEQEQy;>|kr`IdL+7joBMSSA; z)mC;ddy{wgtW`6Xk2GcOcy{2e^vtGzK7HU#72YlNt0Pl}M*{IK084Zg@Z6*Jpb&)2dr-&`1F>QQiUXZtRh z6~6Nfv|Vn-3nu9woz)kq~^$$<5fZm(ev6nVkE6~cAT9S&EuAwml|}&N8MpWHekuBk0;(rKb(K<%i-ni z8!Qx;o;KS3?%-E(&8V8?8OPjdmP@X1U+m&IYIj5Lgp237cY)WAX{bp&l-gLix&CmC zrr4Z0Z#MC6{yyLSS^Bc`CQO-Z<<0p?Wk*Lmzo~t*`sprC^QhK&vB+cv+rTh)&{LDL zFB|i=G`(mmeQG^JchJKsa_P6;`Zc}DwwGJkxML)@xZk;v9QW+LfK`lVqE;eT(VaRE z*Vuj&+r4M6+;C6gveI3LNi4BSzVdx%{I<|}k4~xSW*)ulbK+g)UJ(gCZ8l36weOoB z)<*L@T^pid+SGXAJnfl?d7MPi(OuSJ&FZx)-^uN;Y5d;kpthdQ8zeOpdg_aZdGPj@ z^cVkF2e_yoD)}PU^KM?5{L8@d*32_6K9_xavFn%d(;=Nj1)7^_ySfeDSYBltP0V{z zC2!m;^fKRhdT`#cMnfBRjxG1NZK4`{9-AC5pObsx&UAk9>0QUreEaEE zqShHH*D{J$^4G6y2(bF{Pdv84ZLffEb}G+SL4#mJZU+So=lI+0`AasH%zyEGsBD46 zyU6aAp@+Jy**;IalboiF%HH~Z`@H3gA(O(#95>cYQ}JsSJ5=X6>qXA0Z`?m4QU77MdX9|Ai$YzdwXbHsYXt4-N~Jeze&w1Z z9MkrE?DD%_Zjq<5#N({A3v+DBl9NOI9|q;tZ#}@@&bN2;;r+y2C3Wr6c11$h1EuCX zdApEVZ`B&3T5q1SZPD5@(Q}oGZhGydV^Z1p-jS&5ZAKrJ6^>c_voWlJkz_*~I_;3Y z(e3e~Y{di})@pW8g{eCgb{@okx*^^y>wGu4L<&277pO5^!%U~vYQ`jTtot5$mU zja`|I|L3!cUP|9?fBk-K)mu%o(p`7&i)FSO&cc3e$@y~diDpY)W!)~R86V~Ltzu8K z4CK#`4KaJh%ywQ^XRiC5UsTGmbiHiG=8s0c>(2Ailr64Q9P!N@HN5WMYRcbPSHIa^ zeSV)3-Fv=|m_y{%nB_^&_evZL`X)T{j{3q=wGtLF(|p*P48r7I?!G#6rgBu={b^@S zRrOB%p1p%7w{OARvx6MJKQAp5=*sKgB%b5!_UMSytl;1uhfi^FG_F{x`t;oIk8$D^ zbMFge9$V1x>VxSYy_-_Ra>DhN-hAq_{L!B7U9q2yZ@ZVg z!#1W*Q*?=B2}!QlWPX1qZSMSU)8kmW4t!0O?au1*yuDrZSf7W3|{&a1X*Qq_mP z#m6~)@Kf5bc8SkN21Eb%4Y#qYVIhOvxiTHUN8aDl(y#hC@G#Y5tUYuvLf+P*GVS|S zhw?Oqn!}Ap-DBj!BJzyhtkYRG7XItK{#b&?*hqEA;JxZ}kKXF8+=20K308lj*2s8g z?$7?0T0AaeOFHBlmf4+qeofT0T#tUK^oGg$%(rI*+FExXIGoktB4eul{@{pgmx-MI zXP&6}Qg>+1&MN|O8Fy0qJzn}hX9s4addbM;K6vG2x1Zww_LjO3V&J}3-(ze(TcTtWG>4qvq& zw&W)`nK@blciR2i3)o+$&Az>FgHt58&-4?A>hcB``aa01%iF^AJNw=6DlOY4#%yq0 zuI8JvTn?L;mkaHdWWG<;AWLltR`wy|)akUL>oTpiN0XGL*4$fMcPT0LnC8yZb?yzS zw7n_YQX1^vhlaRSZra1c`m(#pQC>46EYM8h^2mDO!?K_D%!!!gt!}s4tg`;g-PK!7 zx9u%a>)fyW)#}Z4$!L#b2NW_r7qL9XUl)vp{C*fbR#N@zX~Edw@~XOmv2Oj)-$mo! zTL#C!=8t!mjJf{q9#J1(VcXxCeLZ|Q;N3R~hMQ~sr|L1clPhemL<$Q3GTc}ZaIop? z!sV+DpKp!&6np-n=cm!bXDWP3_gKzw9h2uYG+JXLbN7nc>x6;zp|4__TD=PudGj~V zZ161J7xUtb-_0}g&RS%}Vv(!5c?vL-$GN8>p0RyhkS%eg?8i_yyVl6&J~`>z`IWjm z8t(BZ_KkSm?Riuuna=VrKM-?9`@w_8`EDuvl6}(*=eHhgSuMP#k7tl;nxbrZDVP3+ zwn}h?#n_h9XVUW-1`3jG(gM0N<>~pyVYMFkudQ^ zd1q+VA>q)=$$EGQ3(*L5bfQp<%01^ng5Nb#Z>5OGW~q6JZKtCxU33W%Z5wb~!s^8& znd>mJA1@e24yR*I+Mj}muUtWS9{^fMP5Ki~Pf^bg=h;H$%(SqMTb1Z zh3i2hRJ!u9PIZYXym;%E(t;w4x`^JLX#%Tbr-xOUF|so#0C0R(lwUpl9MiG`+X+*R zv=}2$B!gmo66zTfL^=f*1a^7efck{E z8TR$PO(rN1YZRn*o16%$opw^6?s-6??p7iv1{6aL;8Vd27esysG5l(glnlvW1$QPC zymVckQn_LDPV->K4|?qckXw?-lzWPmu6oLd83s^W0s99^FN8tKB+JCG3Edh*ahL}S zE+mg0g5$u41~@#|3~DV;fxmekYcN|r+lBL?YMooVBGlAlIw2ZC)})ZDdwA4((bgQ^ zpx8y#Vki2mYNL}kg7*xB=SKg!Ja+3qD9;K$l0zX}eIVx)D)E-qZcwf$3Ihg(%vm%( z+YHMzJ*_zu=Uh<6n{hlsQVtG~j~kFk8g&6(nMzD;%Tg9IW!Dd_TEu9q!c&*$NFpbz zNiI>YqhV!ml3)E{4QoUlnwSmk2rIPIts|ckh8LXpaBxF!A0{Tv<2oVvRv}c5TM*fQ zxG!TRU&l%?h5~YrlY_T4v^n5~>lQg!xv#~nLJxl7hNq0jNyM~AE|7@NkV{<SlR`X(5ZHn7=JF;V#`Gr+xCT^Qn&}r7loFo;TWti~jKF@> zS#K5R-#g5mbR*hfz5$EbKsAMyMH!us*tT2_D?~IscMJl+`f8}1fpF(_LtI&z*wrN$}1w#A@$9CjP4VgSgQUF!wAWl~ghxo^Pd zfW}B3M8J&GpKRSN+Hchzkh0H({$j7EUL`sDk$vdTQ&)B{)oYj)g>H$VrLBxKctc3#~Z60!L9=0OeR{0lzO{~nv@MewFAk*5C{C>iuSUBm` ze=MLyI!nml5Us%{{}w>H%8DQyR}S>@+yF;tV5%sfwUT3Plqvd;Tvpyv-ewqn%enq$ z3(Z%+GMV?Nr_5(+f8}F*`H53-b7}f|Lyn@=1MMo#7NGH#e$wh}drG6Hih6-Y;3y_I zq^5L6xiI7r10`1ntjEu^`IQFMaWDOT2D@XK6$FX;*w`psO+N=Nvq z%1UmBTP^!^+F-O2035{U0YqQ}gg4is+ZN9kdRTwqA_6;lU?tq^$H4sk-~UU_`Jev= z=lsK8aLzyctDLj_!8zC;oKrXqo7CUL@1-9`%PC)9iSKoo8x68}x{la$UpR~2E|3O0 zK<@hwYAahF9fp!?tv<0e5&#CwY*UlBl;YLwqIPVQQ0g%k4c>d9N{XU{k0K_YfrxoQ zZg7(s>7JTA=)Mo&*LTOGl2%Uv>l1Y1Sp0gtb8so81_6sKj7?$jkcx}iHf7t;W8sc( zy8)xC3q3ifH1ghou+b=!(Ji)xZpMFAdT4QLk`5mHb`Uc^GKsDG6-gD ziuxqCLG+K~wfO32@D7<-SR0}_wMjpg}P18*vE?zqn8h)D+2{=5C33~2hg(n%e%057(Qzusq_>g&_&p>TCrhQ z#$|{((zb=BSAsylaEWpW$p{${Q-zt@e(9jqtoBWS+-_pn-8L?0xnhcKKi04H{W1?A zE7k`8>5y)TuFhI{iKBb#2Njx9AJTsBJ#t~y4Q@+8Kkb8Jk9*)JK%qK8wf)14p!Wt^DmD#uvEtQY zs9k%I)yFla?1e`~1=S3J9fOvU!j-OTZKxqv(Qy$2mIG8WoNuEj!H|@Lsvf!622_-X-BCnd?*xqu<2y~Pz(vq{@?OIo9Bu`mQ2qcxtAPZE2 z64!=F)|1R#nI=Be!y&$9{0liT?dSP-f}8T(F5ry{cy7^a3CeJN#B`+}dXAxlKCwA*%#25x3Uv~LJj^p!n z?s0YQ3)SCB*pa&%?=JfQwvrZ9R+{y_BvovbX+PN7%Ou^)4)itdU)B7?z$nn|4zX{B zN6&>txYYKo0zcid5e7d!X#2bdFRUNk#Wko$r0N*E?`3esg9nQ~LfO7A{CIc#NA&`GX*iSZcAGs$*y_mz=6 zHpkA_ABiCT{%tm<%+z_=(rDNeT1= z8e&-ZW@ZODXZ7@g4{49I`<>FkSDRYgq_XE`^(4@Z6C!`rXqY2NMEprLWn9m_-+>ee zCkWhTXs=CmNv0pk(lva50>&eesrgFFA&xm05~@X_FDP6{1U$i*%4KiAaAb7m>s?vc zVPbGQgJeZt%(z;;xe)n(%B?>4;WXn+ok$}w?RBj-!L4UnoO(W$Ee_M07e{GU3?YNA z@?wq(#&}y=r*ZQE#6<_CTH*xLuh4@i#vj^*Hp@&4Crk@2NqMp2Q|EZtYe45vTDc?_ z+AGzd>{}Ux)%=Qxn2(JEcXB3_{p>nE00oq=8&wO)G60iw*-_zWjQXtacHd7M8&sm% z8}Q5i$TU^7b?-BAR+Ct`E71SUykLi7sGY=H+`?&+JscYg z(~F8lFv!CU+`E2~CE-CNVIY4!+h(dO9^UW6J{IM=-KphhiOCp%g6@5SL%tM>12wD_ zmC)1t)~V!=yOWsJ)4(1_^`d8$i5eqR{6rERE&;5?<+g~_hJt5F|K7^|mwfZT{|&zR z$G_m4fBg6H4fcQehX2vVU+@iVH%7wF@cQrMn-XA3jPc_I&o96@;-L(}Hdi$np(t=F zs0SW5sFGFZa|5hJYF98$TVLXis+3TOlpK!7!y$7bU2CMrLSm2W+zFMKh^|J7#Gv!w*%Ud*F=Fns9E-iv@tN@MyJ8AV!eK^! ztqv*S_bM~b=c7Np^;rWUyEtU51fz{0zX216jz*xMT}lNltbabfqXl6xFIc!1){qIb zcGYN{Lw~dGLZQubUPZ}6>2*g&7_N1J}b}w!G zOm6A>nt`QhgJ>MS&ceWtM1SJk_|CL(6_)~<%T7--qX8G}SQ|&RKZk>s0lA#~+gHh1 zBdlr&mjnjB&;~sK>24ZpMjfj(df3s0Dd&SJLiam9T64yr4v}DXX!`TYa|T2LIK)kH zY=r)P??8DuHs&2t@?E@^;qxwbrEHh^K2=*h(gpT4fue&g%k!xR3bd~-*=Nu!YEzQp zK(Z||UY5mNHl`-p5R?YQ@t{DjwJ$sYhiC%dRY=g}2&`?VcU0>P3hA!5_xIJQ5e<`6 zx~lC`^vVu6s5&#tP8~-IB3dpvB6qrsysXrBiP5bwIg(U*@T&#$haSuC1S$&T{Rrqw z+I)_PKxjx?J2GgQz?CBx<7M`wM2MiEZ=94+#goL(*mxK9lO>A>w5eFjt?s-ehY(Jq z$&g%T=U_ncOT=C_WA-0?Xacfh)y|+VKbs0v1q{Z%(TMwk6Q_s%j@L*Dv9e8oJ0o@~ zf!(^iz>Y#YUl=Q*fnYWAFf?jm`Nt0OGW^6#w$9x1l#9127g&v{f{T48@mE8GI@nJh zO!Kk2A(wjll!s7Wiy3c?8k^}Hc#Tce-O&U?% zT?twGtyqAaB0|Q!q*$&^Gm=vu&c!FcPl8lJu$-u_UsKFc9q1)8#L*u+u;dz^vi8}E z#zIVddLDc}u(mPq=!L$Cypp*1;;bnE7z6D=U<@biZ5z%f?Y6XU(^Uhl< z=(fQ2q@N56DFvW6rn>HJB$cN{ji8TW?THuBdQNy$R-CqT?FqQX0>o)fbUGYbDwXWmV5OHyZ?Gg{R*!Ntr|G z7X)2z$;Mky&HxVndWvM%ECZ*tU3jx%nem;^%dZg>>;teYzTAMGw@$UD1q5I#hRdQvK~#&}9t`jz~QUC3=TM`rAIV-kABu({cAJUpHfAeatEOMMmHR8%fp zm)@op$NKtkXcTwV(&aR%hkHip=lh7)k{iWnt=$BYR+C2;Ee1}1h9f`GxvuZ7)-nt*!h6vYcMPG@lY2^<93}T zW2e_oA9H80e>jWY+14F_>{A+P&0MDn68AWNn1gNRBbWD;s zLM7CtGp*q8*qVB%#Gs3W)+@^+S(S>x04FF|=A54SIdbL4)3-WPP^!cDLPK<&Vj#%! zQk}%9kK}M|ms|0veLS7$HAWWI4^Xu2s z-n{=1l?IQQ!51pNm1>8Z&6{(X_vKg~g&NymFOyqT) zQtW5ahnh6%GD5=Z(f&tA=ocYD4n%bOBma4i=MVn*?|=QT^N;h_|1baiG5`PD-}y8D zXo4=*!uQKcjo+lRz{~TW`KK_?V+n&CMYF`QW#0Q$8E^L|mK8b+GWjk`Qit?3WBWm` z5cWv{5Fw4!W0Kb5y(9vyE%_7%`IJS1xR7gCGfzs726l(=3nauqch%9Trg*TzB6U1g zT=e%bB0FHv&}?_{0Y3r#nTmZawZ%=J48PlSuERe_h=OQ1KGKaKc?3&GSZF~O<-rK? zkkoq3iu#(PyS!MfVy|;^$`^t@38(;0)gJjv=1Q#P2@*Igc7~m~04G-B^AT5zeYRrz20d!%4oj)qh<4`daD`-lV zKTkl-T5@mk(lWnPDJpd0`UFV z-C8?%Zn{yhL|dW69mzL{vE}z%EC3&q@A3w{2Mjr9O;(6lAM@sW=`lUli4@x;HmzO2 z7F%=tLctIqWV#UuUQh4}c_Lo@M>cqm*t%lZqlOH=_rNWPgtPZtj!T|sN!H#;`5>sS z9wV3WrO!RVrWmZ7Ch$Z-`vq}mR(g{tQD;;5B^wD${uXElh?omcX`Cu{@;;l0=sL{L zf>Gr~O00ZPdeFPvTVb@P&taGrxZ} zFcXm-O%oyQGubU$%?3dCi`@h;i2g;uYsSMYFFp^>??7rrCpxc_?F?iLl+>46C>PFD zI4i;u1`h43K5Wr{Ea}Th@h)wz)DT5Y(9s zqP?7Y$sj;_??SjHvp^WvJj|r11p=Qo1@}U%Y}J&Xcfpluw>Ti`7y^V~+~eyDC}t7k z`Wr86d_LFhp=*Pe)q=;pN;e~H*9z?d4iOD8{yOh-Ior&XHE`c(qDO?^zJRXDWg{8s zvjV`pWxIE_keWx3%h*{ioCq^mdG!XnZ1BhXtdc;e>R9Wgfr$SD00960q}aC(!_1Z# z;A_A(cDFDLm#&PhY_MQX3v9t8Qp{o|JLa4-AK6b~{{Ou;aErAI6BrO9LIX*2=A7?n zWBX!`?I*Z24yuhurhS}f_(Y(bWJA%!ORZ#(54;Z+drFF^b&NK@C!-@wc0<;?DUka| zGSXEY7A}Ms2T#D4=70GQ96CXz99%V}hT!DOz3bs@i9$RP4Ek=5Lk>%nUqKram$W$9 z)0_mhC~m0G=SR-lJ<$`yf~nyvM1?nikO$U`fVregh30bEMbXX; zX93_fHkf|D=e&{|);!8I(r2)pzeO*CtD)kL+K^C(c0-*58_7;TXu+8{+YKyXeSkmI z%z}IM@scWVbu^m~McY}t_OohoGe2LU+0%Dk_Z2J-HYEs!BMeH?9!S#I3*5MuyIHu8 z&$y3^;CsCKzD`EV8bMKKlEFCmT5w_Ijl%X;3L!-R>eK{?Z5KZig1b+Bfax(s{<0$5 zeLQu~q4sUb%Tz)Dm5jYb1?bXCNp=SSpe|C5@CCw9Qx z&a8<{V;Q1&ux;M(*{@`vMM|KiIFIEOWdhIi(xU5f&VibSriVrriS3tV(Rtb*!VjTs zK9LBV08F&(Gf9uT5xtBuF#bBusdG<&eW)Q7i|uxelzAx0Ni-FQS@B{j(@g!aIpO>_=u_CbV8=SU!=nt`b0QTY@@=7cjiAE&wKG1)wNj94PxOJD-ooD|d3JwNC{#+=XC7FbA zYNP=J-IwMUe~z!zmq|j}^0^}AQr3ZIJqZ&~0 z7n}(MCb0wDo?!r&MKOiHKc4N^^v?VubO}fsesDz3;-%kvHz>&JjdMA4UD7YdX|fpN zukOG8>p%aGzx;Xqr+1kD^q0T<$M^mZ@A&tBefcl{;cxSQ_m2PiPk+7tasB7N&DXmh zljdLkrC7$^-j;eO|NB4Z^5cmVeSAIv<^-7a3sZb3;2K4G*rf*1pEzg%WrAgB8v2EhzNNeW%N zZ?tQBM^Q9M76(lvMCe^x`3=b&s1Mp#=x7ARqGyB+=!yzR(6M+Bslm#L94$n2*4=5& zLZq>FA=QBHilX0l7)c0;J<@72n(K>KpYC zwY5480ujm`Vh0Q^u2{TWy83mbdq&BBacWJsk^krt;~rS07EN&n@@t&U*5o|!qmlIV zT9InL-2xwZjp!#w(&j`F0|wMiRXQ%DZ|lBPv-z={d&b`iGo)Rx1_tl!H|GpK@%c>w z?+>?QJwk`401_W~na0B$6tLNN%ML4ng=-h_Ky%GyKA=|d@i>4kLT{a-j!Uck%Fboz zyaufra$2SxDY|ld?tZ1oRgZN`cG8Cf>~YjD?gl`p_b%FL{mQY4+Lw~H5AH*qq}z}W z)wD8CB|W0riT;Mn#RHsRvKLPYB6krd70a?-XYCoU7kW731L;>aD&|;emFi*C(!ES7V8JxiFT8LcF#~RLS+p7mSwPLP!QXDxhLRZ>7V;b>6PrfzfGsix2ku<@ zCvEOUZtHzV4aqYr2n_F$I_of|N~%EOs;`3K>H z#}P)-H;}h-tUEDQ9dR!k41ZBKduHHrh@Sq<-yw?N{8)L!@9t`Yp40T7)pZ0Gr|3Ox zabn9ILb2?`FQB<;g)d2bYKNSoVMr{aJSrRCe!-K)BsA@TH^rn#CF>5C^VlZP50nGG zN*Xjj6p~b_H)iu(7xBI)zkwD_++GCm6<-?N1LNDGxGPum#20#EgW`w|CYkbRF5fG~dkXSPaS?A=+yYx0ppd}^TV zx~AN;0cgogR3dGp&+)-Qfway~R5K_Piq89fE|Z)?@41ohN}yN88Rc_soC!YG~5PvZXL(T zS`4v!)lrwknZewLi-<$LEssxy%lj`{> z4y#i5YQFF%p%u~QY*5faW}H1Kw+rNJW=$&WlzqICq?}e)fvzdD2d+_Uf`QZE4vLmn z=*~MoW3!BMD!_+tzPJGaWhJFccDkdlhQ-~qod$a|K&^nlln?Enxl34g5!=cJMy4C8 zPKfGdg4@D0c>b_QDGoE1Ts^%q7Qm!(`*3H2@`i?P7@LRU^F`hhkdQ6_Ts>!A0JrQ! zHumIJl)46`Y9VtSX&%h}Q7~E$t@QiBRn#@!9M}L=Bv)|X{cxKM(J%x3<`|gyAM` zJfSHJEiN{t7HF(Jj_He8y;Ieo7r|W)8xDB`%<6sWp^!INcLR2} z2TJLdVak?Hg#k>+hH~d>QQ5d7;UV!<>%pafe9d55$2(3dvh%14*!Y0fy_&!n+fdUB zzzSsxykN2)$QHMXF`>*e0P)tVE%*&thig7@q7mjYd{BhuPF4%l zMy}($M^(MWqgnI%=v0yKD%9hz7VuC@VwS2nqlyDEv_)xN)V(CW_WkR0Pkj*NjNxzg zZU+|geCL3}9sCiHu^_*JpeBxZKs6Mk_(I!}wEK&g0?Rp+3rCJDnMyz=eU<*uOWIR= zmdCVQvQLHT#3wPnqyf&T#3wVKQki;9i^vie{lbE1Xsj$4o{c4Xe^)JQpyl?4$I9jt z{EiyL3M8V1&&nWfVJtKT><<|Cj2tq5@5=x7kNkFwA z3t(kxTQN$>?lj<0g_tLsr>a7YYa%ur`Ayei+ z^)bz)iQD_TFw{Dvh0;`mzt3)Ou|hv|NG@KC5V>&D)(SM+5ZfREGvJ|Y1}v3sA)?eG zakl8q;P7}VA)y4&2tL#OqMw4@K@88DKlxft2h;(5q6eazgBc-W;DQRUDZ}c9@i|K@ znAI&?(k#3cOwpfH^IgyL$mKlEbODRXEv`=M=!h7#sC-e^A0aIo*`?mEL9{C5+!l;2 zun2C4uCE&`Q2miZ(SK<)yHRapM0BE5BX!U~R-4F}nh_1Lsh{q<83EB6OP=v7=RI5Z zxNyN*CvEz_K&7nXyM7Z(SW2n4%nv(FY;rx+Y-r+FJG?@~=H&KRywf3yA8@g-#>)?z zFtZHybIyhW#);fqI2M=Y5~;|A{JWqz_udaGxwA2`BR6n0GLNv94r8$>?BHLnGkX0Z0ZyH+!rRx z?Fj11ePw_KEkJ70`a>LjYK6pGm!iXgK%&?OoO-9M)X;0X}-zM=EtWSNv zmB{wirCxe01DIv_;~yfRHm8B9wkP-%1k2Oe)}I|9t`;I?jwRU_vLnsL7ZLwGFXU}$ zcwVK@GB+EQna<&Abj>iz-ljX~!9hq`<+yjTSYenB?U zbAHzeMrW==w{6j=9q1>l9wgX|)O=AuUY8SWA8ikRbv*zAjDYQXi`yg)chfe%`%h>f z`>C{{{k@VP9^WqB*5&laoWo;SBpHWXbAbQmD)tl$g2))a2T7S@U6#4-jt0z_L5VrH z^Sr&k0>K_2gwd_>IWDi!2xRKsG*QWRsyLXPCPK(3$#y$s|3?qNV?QMN*1F5=MCxc4 zrnbX1ITOf&Q;g9e!BJCgIMdsXU+?NVicrb3z~fObV(f{=xILKmklQ-RZ&;+oDC-H7 zG`K5ziK{9};_i2qz+Y+`sAAt~yHYLHL`JhJw%>XO7EhD0EH#~@BTs#ye8AZ_d3{Jj zQ*V5@Qkbd>3sZ4Q+@~@@-b@popnVI(vd{iC$n@Ob<`x-EJ~H`eHT%A@b!|Hjl%8Ai zwmoLB89;j(CQp4TxUvT@mliQ%C;$v}?Z^sdZ@l*C4aWR}zWc`Hj#@@WQl~;OFl?ig zv1X^df1`lsQkYDA10HWgJ@%)Q(}~2 zd9WSfMdFKvLA2+c>5gkn6wLPUG#OiB-DG6b%n-mqzu|X9GQL4x&3F-4p-(!ax+0+0 zc|-_GXfq(8cFq`tW{$%(NN$-DbbsZyge9u4;3hB?J-m|fv)zZSnA0I?*nRlPAKczW zQ4Wfoh%-ZW#u40dQc5L!z&1tSD!}3UAw=^t=m{5phjT*wq2DpoED1 zLVpKH3I!LV^;^a|0-`@Yc8P#J$+MYX#oLZSFw+6)5t8tu85?K9;OiE*aA~-Jnj$EC zfQxqI{wjbC)BUzxd zz5m5BUU}Py#*-JUXf9DjFOvXq;ykV%RjK%}f=wHa#T?75ptK z_Z=*T`c`UnVr%#T7%=@A>US&N1Pte`c9@${;UEPsQZiYgI1B@wpnXo^du=hdoi;2F z++ZNjVK@LDcROU4H4jqU(P9hF!3EhRK=yG-9HsG;kr8&%m@(+v8|q)kOP6>W$ZSGI zgl=V!OgTX7Y0}NPi*kxPb)zpHsDLR;hw%0UF=K_c#dWdz2nf8mxa4T@F(=hR zN-=9yq#+Ck^$TUoD$b?KzarY>u;PFW;*!7hKc}jwi!D`tQriG zxemT}IeRa8IO(?S6!%Oc@}3+ObC|HZp2DW1hN^KRH55q{^=m|69^wo066s`&Xyb$S zb}I@ZL_Eo|IB*Y;XmYN`A&OQlDiG{T^cvY=d>;rS_R{FXz(DX3_v_Fm z9$}ZhfaMM%wtc=lNG@xZPS3d*&bSC)$<-TyK7q-knJ-!3chuxBRo|^|+^Rh$> zQxer!i9+8NDsNv`fN$0Cxh#KIyu>IM#u4~7_$|6w#|J^Z7>afM9K1{+xJk=D=9U^zc2_BPK2WYIECSz}CC!Wn33&7MSPCPpwvektcSaoy z+|;M6ygr=TYHG0Glbt=#;964*?fn)2HvanGfCy{Z`OVa04W{iE!cpD67Y@< z(iuM~kF3|C%mWf*GN1PeF)8!nEMK5ZKw2{+zDmH)8Vv!=tW}X($}|1)da1&ONfNsM zr5G*q5R-}GBMH`Ae$b@0M3YZX=hJBiH2~Y#SZ`;;hVKV+Mtm4-S}4}-B-`NevTM+y z`;xxS1J>;gEq9yBbSdDwm79GLdD}1T_N_+c&k#1ZpQ`|YqDngmE9me*^(1Uc1glKZ ztJYjl{f6KDTFI~fx0Rk7@8uMKGs_=V!atewLsuYEPMJ2*ozmhX&S<4ia|w&2nd?k|Dr)z(a0-}nHzxo#v)^>3rA%%S$MnQV zcGM|3;FY)ve^{yh(@ICFJ#VfckX@B*C?wx4jIbe?b1M67(;MyN4;j!xK}zx-)+DkC z#2@wlW2O2}D+Sr7^D`se-1uka%@=V`=(vU9Cll0mA)AhVUn>RtU#%ql)k?r?CH`+# z@`(@#j=)^csPeCAk9(TaqDcb}C+&y!RkiNU?EwzJ;sfvby1%rc7D@b#uBuoO`>KOf z*X$Y0AT&ws#=5|iMghurOgMGbgr|B*Gl2c_Ve>TFRxIfB(+@5{u_>=^++~QfR4=1< zgCPo=0Q}W(3*?@Z&HTFk0KS2A?No@vH$d7rr!V~Kq`z5d1M=rjE76jxz9;XmRzkUS zqa+u1ILtXn>(|nu#zewr8goAn$q8bl%f!a)is}Q|BlMv@{|f*B|Nn%TM-KGRa-E+6 z+Yltc@ESC-!2xp;ph1&t=A6kHb86?=Y+R z?SrVG(4I+NMk#E92rJe)dD(hF(J9bO86dCSTtqH921=FC*yRMj^MPkl2X6t( zF&BghxW_UqW&MSdSQE?1q5E~Ik<>9(fDp=jEF{h?By7ReN-`(m7owBDFch%C;|wkn zcca`7ZdKU<`)oQ1!M=T4SlsXgMfMvUm`Riu@ElhUw}2TQ9MrquH9(eeGAwQf z)S4|7OD+a#@w2styiVzrVc$LUAWY5hs%U$&8oW3@B66Ae<~V3#*qs7JkKgBb4@e;_6CcOz>=7B#;5|y`0h3*T~i!s*M>h81OVA$ zjwp2j-Zyc?-BcLUDBMJZ%esFX=`tG_58~*ds$=`@g25H#aW-t*%LW#?Rj;}UQomr| z{(t}F->(1hu7CR5zx?IDzx&_3>%ac{&wu%E|8f6c-WC7tzwdvp z|M?&H>)nrO`w#z6E@SU(OEXme>+cKs@dcVb_^*#GLjiBH?QoXOcntTe?UE-x`ZwEZ zClxMcm3|{Dmm8TA*S_Q=Y2eI)bwcT?cf`2@kJA(dg|vu1?)A+}z}hAEv~8GMp2x=z zaysHZN7IoI!c<+#XMNCwB+8XuZz*uJ?hO}G0YB^e44k_{GOuttae*G?>wS+)-@Jw{wU&)6Ch@Aldz#@udn%7r&|Qxw{rlOu2M^ zu|(h|cJZg}W7Y`dzkG#6HA_X_7{H?+7gWr(xzT9mj##?}N59fPr zT~-KG`+9ob0QW8ij3%6k7tn@;*urrK^p%jgN_4?kI!HT`v+bkOd>=a;Jq=cEdT0Ym z25_9eDyCeOS(f3`0zX6}FR|N;hc;)8f|&J*$t~hbeY9p}F!s4j59^aYj=60?$_^c& z3)3ueKKe=R#}KGOkBRL{zQRN@X}=hBME)uVGv(g+;q2HBaT%Q_N+>#D%UFU2YdFXTF5FXXOTTOaZa~ z3uxw5TU5=u(66*99*?Chvf0bnnbuH1G*^C^@^et(A7q$ynx^I$~^8ktPYo9rY^o`n$<(UUd31FNkFqLF(`Tjlr|03{Jzt?=g7y|dgcca%Y5+ZsZ%sA1ks_x1)o`=kIdBgV8blM zp@5P}iwt}+yR})gOfX}PPqS(AB?E5(i+-v0?TD$9yz8l9GR8YnI^cED=|+qi7t!C*kgcipqfvB#k&67aZc5t=Cyp$4Th+~e@z@>(d{jdSdY0|L=e1Cb$wA28LM&qCIk;KND3r+dE2cgNC;4v>nczo=xE=1HJIywD#? z&N)aAXpeR_Gypz+>Yh6EbDq1P*eeW&8fVp&FIgH<3uTqS4*H$=wagS|BI&-MZC*!b zoUbolt?(Jj5VZpp8s>n$x7&60O>69@MfD2MYz+vrOPVG!2OS+TXV>~k2BQWw$eVDX z?*Kyy6~qOggbB?vsRppbhWgDyiYN4(b9Pz zh;HWrTbb`}s5w#N2<@W2L_1ETnDXultj6-ZV?7*+PDcO>Jb0(d@zMn1N z5MMKtS3^NH+pMVsVDH8x&v2|D3OgFwY~(Vq0ec~CSLX zJmfDU5kK^Jyjd5tTyd-}n>Dr4vuJ7SGoWkv>Kpo%>D2j!K?|Vovw2D&KwSK6JeLRI zh|~mD@-y?u<_b9FSg{+TV6Z0HtxqNHEFLs;j4~xMMY}39lX@!`Wc#gZG1<)-tx=AB zEJ>ltU?Gh&1qREZp@*-;=cqbJX@C|jSR7gZzg+q^fA`n9^k4rIm;UQt;nLvWxb%f$ z0M6eB{$71qN{IZ1lX*rR)u^mw0<*{8gPo{Bbb{-1;3?j+VxwMN85A= z0L&)9rTBu~>;`_aXn2EC3>wS{3I<{{?r9(%2{uT{As_JeD8;va=@(M>8?vn~lJ@ea z(`ue+UDBGk7k>|0flAcCIdZnBbmBvc)6RCCs@?Pegd`Xr3TSd>KqL3(oeb16g9I}A z)gU?)1L{W50s;Gs(@y*HY5&|hqf~`k+**8Mq}kOx#za^+?%A(cVN!J#k@>@?^B+DP z2)bURp7RGbN5S*>j1oF}PxhQCY_kg_n4df4 zJ79#Ot*j0AK=Vo{@uH5KKeAU}stcu%*rjEN_sDmWe=UzcL%j*)98&`X6fRVTG5OUd zmb?%*Cj11IEQyER!a-jouWqo%(=q8S2`o&(dux8lC0PPi=Qj47*op=J#w(-4=@Mu* za^gABJzlea7X`O$3TQ>l5e+!FqITIV4f&G0>vEU|6}Z3RJB~-D z#M+}&_mb~&rJu*dUIb)c@sqv?e(JT@O~H>p>i&yPW#&B~oUK?l(ln+DlqrJi6#?dn8R?HeF^+t$z94ssH<6nb^&KKA<`y$L8khD()+NlJe#9A>Fna0@= z6&jJ?bgFeSw-z;uHh_IxZDPU5kuLsm86)Up4kVZ4Scx-&3?Ba3MM0EJlgHpOmjPGA z$}@?gsZ=N%!PZo!OI_cP-$fCSgumvU?yT!9lM(@(jF!?K5IV2_!*KS^sU`v`X7q^< z1#jp${w)N>mOhM#>5%QmP5s`?Cv-CUyhb4Nt>n#zQ z()1Il-Ha9#SMehiQr$_ony})=KnNvt!%$qV|C7z1x*l0!zV?mb<~!@%mCJ`-mQ7m5gLONSVV00Q#57OxxxCt%d z93JTw_Q0v!TN3+ph1#;Q=u!$_jf%r9pliU7e&+h25vP3M-BFCGaj#+U`=;FG=Yq2t z=>=YAV~oUtn@gqQI_jXmcV^F&anVyRhU*K`c9z^W=QT@-;?H^^>b)K%!=i=N9cVua z(I$d|E*eyVu=plei{3WlRc>N_W=q zB_v9UVc8K9UDuHa!r%%0=ua{k}1ZqeuKSlqoIeptE5?*^O}EP< z;n&Z{0ro6-*Ugo3;WoW-$MeDFn;`{lHyp2!~h{&rzeqGI8q3M?CdzDXTQ@xye zRY1VvIVtL7oi6#yscUH?=+i?VB|&(Q%U$YKUA^t*S@-TEp%>Ut!>hm-Ho+}kpVqI|2*`e6odr}9X}v0og%XP)H=8r-fpYt zksO~d5V!0@8<&tBWnC0nimKOFM*}@>YhyJi69f~L3d(8MHxSiyn(SZ9ODjMP!sU1I zIO^yPm%(>ENGkf7?>Er8C9I6sveW^Q0Rvs4$!vu1F)j=}7xZ)HuqamtCgxlptV5OC zRk;q%LOuLEWduJn24!OPIsLuqKh{lz982wdo;xz<3mH}-C8r$GLaMOM#DyzwBE3X6eoA#T56uL@Oe|$Iaa0;+B0>=wqG}1NGO2TE$f|ycClug&IEW%=kkO}7R zCvEUsh|W?*MTFktAMA%yPQlPp4p>*(uSgCWcDSXZhYT%_l;#61@eQY9%!>>qWU7_L zg1mV`jej<#oVR%BqrY)9^3yDgj-lFAk8!H*wMGKFBRJa;82LI}2a%r?q7Naxk$E z-XcR0cYdN@#+?4Mro=1A;{=S-srg$1*0*-212N6kM zEcLUqUz52wO2n8J{ox+#r97$Eu?C|DH`$PWZ=+^Tw#JuKXB5C5)YI?^2DfI0K#2SaQO z%k+ycqleFdn_L!?1tbP=3sCHrDEwiMw-q5$mwwR*$A13Q?J0bf1xj-*1*&hW{_X^( z%rv9d^bbm|?^&SA2Vd_ib^H1SZau;EBLYz~%B)s8OcD{jW>Sd$DNHX*1!dF!q2pr1DX!mGY&T(f;F_~Hzviszy&Q}V zv@+rh%TayPqJ2E5NnEUJtII7OjrnjlSyQ$@SE<=CK)jzQSqtWHw0S8;q zu?yRJ_a_KZa88$h&rKa_p$@775kfNj5t+xrK2IoLDT7Pv}t6EN{*6=_>E z8g^Z@MV_!#h5VN)4IYf}Zw+1pYn5G1VMV0h%G3sLSf5n)zVG?|<<^@Fb_>p%CU!lPOY*EI+Inv^G)p>^#KAjm5PN0r>Qw#ZtMRWh)W^p|XDMP;9zyGtN zN53*}AKQpSC2uQaEl%!CxriK3#TRv@yXkr=6p!O^KfNk2uD zPJ>ZGbdMy*qn?i~lEP_@)IQOPq0-s~ss;~5R=D*5lM#y(+-#aMVKmbwFMc5@8r~k$ zRr5FX=EOGKhYhw~Y$jAivH+7LA_N3bH##euc{A=!H*hXY#G zGXT7?IBp`A5P#Xo!z9@3$lCr_W{3>JZpmSH=ItC{xt|>vq7RIA{nA1H3Evee_j2r`S#aAwmB@rzN+2K5Vk6A-!S;tJU>LiXNCh_iav|l#!9MUQEAa=` zH~H~YVNquWI+?r0Qpp5!plC>DJ#^Onw2eoYgnKM)0v!wqoRIRZUBW>O0W?7eBkjiKumCb$6y7=1wvq4azw zQMa9Tku;91KLbP^MVB7RY$2aTcCrckk263?*zcphXq*^@rCIknPdCT#6DUMA8l$R$vT+O4hIwWQ zg=c!U!0&YT;$6R|6`GR<0v5QUGy;`ZA2U`w;FQ9G%7PrfyiSQH)Z2vkkqnCD)j>?< zyW-1-)KGC9xdj=I+=fYlvb$|5OcG$Ss(=kT6X+dgt8kFwxb#D8q(op%WkfzI<#GU~ z5J1RSF07TKMx;3U8NI9QPN^@kKoIbir;VQcDD+QY;CjtV%EO(@9{CTh-Tm|Ba6xDG z-`sjUe^XfPON9K;tp?N@audq3eyP$vSfFch+tu#`GAv#2*d@n#=qiOnblOBOw@hy(?{XS(X#PpV%4+zz581Q?h8w*cd%5;iRd<-3fvX4HM4+f;9PVHD4zZ3NDWF80=|17Z z_42c$;FXPj5R;v&Pz?!lL#iCCwb^aA!CCmt4n5LBz-gkY$vg>AZ=KswEb@@^J?x zUmte1&ZxT|d*3Mtisw)jL@`OCVlOU(qG5>0Qi^ziET;;yjG8gSivqcqEo3MWg&x6Z zWe=3nvfJnH$2nlP){#(nb`k6_Y+uXRa%}G5h8S(1M9}R|PtV*BU2O8xXJnkgMtEkK zGcK~)?>gFug5h*WC5>*ba;eQpOAGN?Zk$Z4?fJu_-6F@mMd`vwilsf>LE1)+V?rY4 zOH8rl{dvt)S{+ODG(ly?naeE#h-6$SWPYNl;Qi4O5s2w85_*1`7TmJB~YC#?|eTqS#|3;fw3S8J{sF3+73?wN_gEM#oFl#7)k_053If>F`~OHp(|!e^*Z zj(YFQX9jW8LGe)wnPcM!|`Qp z0I;Vt!4y8Mk3xt~O1nc&^>sFvwqXfX1i+a&{(6hDDCViCMg|0BPTB2eMN(=^+{3_r z_%4-|ia+h5gHubyXOw0zBmnKFT(%W?A9vyN8vQ~Fl$A@$Ank#V%E{aZn6qsVzbbdI z&d0;8MlG^@W0Xeoj-e9D?Fag-uiz4x9G+TsAuDq3yF*G4e&I_FQ#u0nyECpGp`74TrIy^wnM%3vTc#zgWNQRXk{LbdT%N3 zk`Q-Gw7#Lh-D+;OU12P+v)?FJ$FJ=-)S#k8dv}Y5rq+jdV1}j7E{$7JACz(9V7k4om>tK2!%#Hpn zbGCgG$0}MG`JT{m^P{a0)TSVtZpi=+ep_x=B~wm|`iGZE9R*}QX)6NyeLzG&c!WAt zwc^%tIcyMo{J1d)49t7;h(yWeD;8+c!L~)n_Qwq&fSk^Avq1dzE)P&?)H?u)&j{AD zO$*TE>(tu-?(ig@5}uh+{>05jkX0UQ5Qt!^VQw$+P-3VuZI;`L5Pp|_hsvKtlXiT! zfG}VzF-vkvtvRj9?yesnaF!vO@SfHbsc3h-mpOp_vFHQ+&^)A(9OYBQd@v}RZItxI zJr?s0GPXN9(mydT%u^8nDf(caw|1~YHVT5GtR5!*69ZQEI$jdnyL7a#JF?dK>i5hIGbo&ckY1d z>mWBS9a=a+hW_!;fOlplzeUJ16iAS0)zPF0r* z0YmG1!(t^hkuabpXIO9-Kqu5KT~aWftOF~4tgF9!q@#I~Flv*TihZ)q&b0Qn8d0!jF&Ygp#iLO;9gm;%tjLD=6~m*Kd%3;JOsf9$~!MsuC?cZt}X1n=62s;{nf(V zu=c(Gdexr!Z>K4aEciZzCjc0%;&!9~n6$S28<`I+GhA~{UHVTz^f48gE&=xY*^(`+ zhETjy8qiU?UDDiLV?DHV&;$-7U3;c)W$ekpmIQ)(2%TLAb*zX%C2Ro@RZ8!c+EQOg zISxc^GQ8)Nfd~97B$rZs28{a-1sfzFAm3~NMpW@d?p%SUFd~F>NzXL|S~y0v*ASa= zn)SF0XA+dOrxGHT-O}2lFV6s8v@Se6mM&Ti`^p%^M=I~1xrnU27veJzp;@U%G?Z!6 z+=j$#klN0fpO$9B4Q@{)F#JP_PbNN;vi~x|XpQK*&$xMgN7e5#Tmwyk09lJl^yw?( zWXaY1CdC9d*G)k6Ly<9n7sj(G|9tjCDH5vHGJ^{DKm)Lx?njokmynwVf>7 z*z+n)6aIkMp`~nv3OGCk<6}Q?X65x|-5H}X&@~khs8+5Q_3`?ua; zl!i9MLo;NHb#R4D6W1EaPkOiC4KTpF>+v#xAFw=g_XX7uF%-oBc)QEo@g-Q_wnXZ3 zoPunaQ^5fUB}@*!2*%^V%jK?@rDj$gtlUR!O8mq8TEw)GkK-0)dG@`-GMN zr29QW8qZcuxB;0;-DDTcusW3ywg>)%xN<*X+M_x@a_rNt%SfSuWL{0$1HW|th`LLm zN0hs2Y{15F=eH9E4{=*h7pUW){Z$JBzvLaT;h@^lBjP<8(0!h|j! zDIZ7M84J1Oo_cH`WWW*om#iiv*&VPYV~}*qYT-s1&6{7?MXv==DGU9UpMtb#;(|%7 z2j`y7;VZmn9gY2V33IO?P7Z8td0n#zQL%QWH%tV`>yq=eq&ZGHA-jGL`#OGMCWcJB z{$VXg$T6?Q$Z?TlD5Rve9zh%IjDRDHBE0PhU2m_t*n#a?z2Nv}s&wzE;STm)Ew>a> z=GOjG=%I8poHkx7@={XR;#cq7jKYzG!lOI$9Dn@LZ$A%+e=QvKwQBBR);9TB5ev_Z ze0x(VGt1qz_v`70Wy`#W)Lkvz9Z?DjeXa6#4rC0#VHTreu{uQc!~iq~JXC6pS8(xBn;{g-LT{&{^3`qPz_0Ki`Ak=U-NYUx9wLpZT^i`>}h}tbLX<@JVv@@z{sz#A<#}h@!8GR#n zXyg3+QQO2ZV?4mL7W(i$$0C;cJ|W9>btv3fi!zIFEd}7Sas^Lnl}CA->{?7nN)T|R zYk-4J`8mX(3+~ivG_@TH@IDV_!JQfhAEj%5sh^@jrgwGWkA@16YYckEE8z-sVQ*XM z1WD!<7Z#3XZVV=pxB==G*T%`o9FsT>Sb7EY@nLQz!}XIrdz1r=34uPl&iN9FQ}&zT zjZy}i^i$L>dAaizW%?>(0ocR}QkqOo2q&3$4F1usV6O^nh8aqs2r-CX;?9BFpz}05 zJ!8;pCImvO>ESm@K~XbaL%3fMmZZH|L+NZT13a%pd-F9Q z?pn{yCB^*`>%9A!2AeX*znSQWk3&&bN9vVKR~Gu?vvIt9&XIt}in2s*n2 zx^h;Yn@c+Sf`Y9S37Lj+oWcMC#iJB3OJ@bz7DIge+v2U;re>=vU|_``7cBjYC}HM9 zl68USl5hFT0VZ2%@y z!j&6-JvU)%;(z`h@6saUp*+46p)7P#dEJIWl)_+z1dNADL*iJz{A0U zLs;Zk0Qf@*7%yF*jlXtUhCOBtoE}CNaq4_#y%PKb84vfKCa}J02^HHYhq{InB*jre z;c3$UI>-CdUzy|mNlES0$L!|NXFi0j+WZP%Ck?cU?l}ye9 zRhVk-1e8Y#7$5XB2j{yHoo@tQ#x(Z)x|>hCE$m=6qP zLNOiS(^sHSy%pT$hplf~r4Fobov))kX5-s(Kmkxt2($*^IR-pSU8Rj^dFvR=@XdTf zs0+w)TYev(?nfBw^47VeoS%qL3J%x49=^w^n507vlDP-@pn3V52(YPc+=o(j-kijH z)Lg)Ci4slthX8h^nYH+)OY2!zMB>3NWA?a3uA-cK`Dch8wszvK;y*kPfL;zyUNK< z>hfrMX!Lz-WfN@s4{m`S&3CLgOL0ZDW@It34&AUGKIgha`K=}6B~KGK^^8DQLlnVQ zT?X^EXHGSWGvy&Ff{JcVT7#Y3lLY7VH8vf|SmWY^ueniJI%j%vnMoUc;8AI8Qo8fU zw5aWp^T9IV3%(Or8g7oEB1+!bLR$(dU7c?p=Q_=3@bYek-@Tup=p(q3sJBCWwgt_65-C}JZV$bX!8vs zYO2D40UlDlU-W8*yqh~5|5+C<#0k{KscxZyr&v*5&2j-zV~;5b63)=f1Nkjqfi%fS zbq`k|Wx*RUw2n`buN>k=&xEAA0_w9UN^EY+Qn%D zf0IlFs+~N1-05*EbMM_K>b*tB{za-Y-mf*7F~&`}n#*F(yu4#axJ(-ZVTJ+^M%gg$(ZuXDh;Nopj5@7G-8F`B?+v+@YphP*vGAlloB=q zC|SirDr^^+=rN3*WMzpUH~1lkN!IOMF%alj#tSu83}=kKoNP24htXGjOPr-IILI7! z1Dt6GwmxPU%etK{kX9}+kA*rf-|$WIrf^_`>y3|F&@7$?s53Jf^|s{rnq+Ky;1ZiP zwhROSSr@s#MoqG;cy1Wh8?bkE< z+Gtcfgm)S|5CiYbvAGP}y?w_W^@N-9RvFw29-|OU*YT1ClgzS$^0LW~Kwi^`#Xre& z70|k%)_N#dW6>4=(S9-CZbGcXsEFcfQ7kiYrQfL5axJlVylD71O~gh@Jm-W>s#3%xhkz6`G> zAKmLT7wepVnce+Q4*KtZ{?|F^AN~ag{lotc4m#cc<9+7-SKeo;f4tA62J^s&JP40m z)p&?n$yeA>bTpu!oH*>Q3l^!-!5Gg&3Hq91^*&NsIIRquoSKvqS#sN`=>Gr!0RR8& z*vAU=N_qz1W3bH_2IFg(m5mn4XqK;|K!)0@@l22T~VBrOb)j9E(8t&36>@#Yvw1VCSDl*#A@3xF1r z2^-Kuq;U2^20(peh1wP~MGt=M;)qPuAv=l>`hVIUctoE;=tFwf-5YJ?H+~*jD)Gp81WnvL40RhK5G>}wi z0!otjm`GmVv|GoncRfXo0m__ToCh%{5z&HF<_i}jM4Q3-ce<3=1tr!3Q+(`+ zWV0%Kjo6HT7sHTDx)o^GC~GLT)mKzTJ8@S8_N~=84pYlc5AY0qF3lHdq0@^yzoeNa z$3!eTW#g8%5`2rj-{_1Cr(L=|XIi%VHF$!Us4>y*`*Wqm`@QK=U(h63$V^dCOhmOj z=9fXEVm&Gm9jy;#i%VvovzSOBW0}kDt$?}IV6fZPz~wCqp4lnExS91<#jfP7v)TE! z4XAT0l>{SGoMShNX1`MkAaI9b^GhYFCemp=ziEgyT8G9L`j(36Zr|dx?l^UZ^15V|+T&)F#-aqvs7Wnggc0 zmtT5I*6DiSR22pp9Sn3E+D42+*8Ai*| z>x(z29<3DtE>;h7Ook0sLnJ0`eP@Fi0X)@C+jn%~G6AEuSO?TEbMHHw+_Nrm6WRy1@fn3+D}`v;db3>)Dvs43 z3V;h&P_dg(XSY%A%?(ueot~OR25KWiykaxShikGi zpzrZEM@{W_lYo0xs-IPPliPh7yGI`wK<1y*2b!#OsVQOiVUM6oKsE>ya5fK%xo*t5 z+}VywSji7cL+iriB^r0a&c{q<`yJ7U=HYQ4oH<2l~OI__{_6KMDDuu z5Y5@>97D;`0o}87=pIc(JUn(K?<`=Iy1^jr^wnW=Y*wg8F!+6xz<1#Vql(1Rr|lI{ zV{nv+{Ve$)OUqA6cRc@3<$XukN`XHB)RP6(;T}%kM(TAQuc7)?$ zhfJEJN@ha0VbWI;%GnUh)bh=@@BlKKub*UcTmUOAEA8B`IWYnA8VhkEnymp_k|2!z z)6b&lvMAy0?^MCEz~oYL1H^+CYX(7ULjfG@#SzXl1F*7UYP0G~zY~N-tp}W^&gJcR zr(}lv#?`U*w;e0HqZVdB0(PKSRO*XR<(W`?))FP40Us8T<&?~I>mIe9kAbp_8uPyG z!5|haxY}I+8|AvXq2fA?qq39ciDv3ZDfgWPra>*?NI;rCQ=^2)+bFeWhWC%Z`u7Kd zGIX1a^aW0IOgl(O68JXfASP)Uf9=+v{`7}``{mc`pP&0bfA`BT|M-m0@XO!-_VF+O z@aOs8J@BCt>=2iOiLUP+isQFm(U^A3lsnvlkkpM7YW*Mry zrWCJaC$&+%vEzLngnO>2JVY(zTu>-F=+Go5_UqCF^Qrh?h`)Ua`s&;4e55pS`rWT` zYEX7$%1y1H*iYa5^vzG-{PfLF-~9B=Pv88%@y)j^n0oHnxW`T1Dv_KHh?MA-5`}L% zBS9>zH!2Kgxr>a_!gSx zDcQ8#IQBUVbCk>++md;A{A9e<9avUqFObPMS&~|$173od7V~DF{Y8=aWb)9`koacM zIsz6ra0IWH*i`HdoF<`GF@Mrc4t9Y9GQ$S+9B>%s*(OT#6<{wHFp3aX>p%*yyHCB0QP*E9wB{%kZ-LoQG>@? zxxT?t?$^}GX3k+9L+P?$ZJRWhVW*sowQN(49}96QHDL6&Jr6H!YLCQyZKo&p1g&yH zxQ5pDWtVWmA`>jDI%imeGP;# zXfU8kEP>NoE^0BumSdxg_}K##(e#S~L97=AH6595<3z7w@4;@B?T4ae_q$+*?1M+{ zX(fdfP#G{kkG1C1Ej*XENC|IKv(aJT%TGl2a~L~M=Tcez+X;L!37E^%))EZDk#LDz5+1PxkLe*2$akj~5mc+<% zCymU_D9{=W=^%@Ko=tWJo74U}yeg*M)KhfWn7I=2TS`#a5S+lCt{0d2ur>%BKE6Ll zVjYSM%*B{gWINF^^!-G!EWrF4@twGpv$O!RU5BI&xa&LaGe1K)^b#`shQ$)GbDq#v zWFlVZ`PpFznl*UrCgUKLgeMFg*2f2s6x>EK8J1gPs~Y7#3a%KJHfycOij|dX)qOTo zp;#v}cnNP@DwEw+$~Jt7ZcDn)0|Fy1S-o*CI?UYKbt)f!pOiN8s>T}blFOG+BYvp}X`|-w*P5pt!QETylK+JhnDk0?gmm zAkMZiy7N*u)l0ZET&^aNzH;&5Fbs;K+Vnm>p1IZunTvPE?jsyNCBc}l{8 zQ;X&I1U-EHY?+GiV1d*&2Kslt;4xXv)?1_Tf)q{lI*0d&(@tsQ>id-PCiK@Lo)7%{ zB%!S$zNC^5X{7H`anlBFS+LdgRd)9i6Yk2_M$rgqs{NrFLdG^;8lPfPu;W+be22dn zhxksYrJa8A8JtR@LNbnmjpY`mR@% zCmR4uECLM$a#i<|c^CTHMzY8K%!@OQ#FjJHuS{_{}(NGl=A14XT5@sg#b>KQ z|MkVo$!6)$DZ9<~m?jl0u#cvZ5Z%jxg_%p&?d}*=!or7##WGW|prwy-#-fEvVENTJ zN-61VbdQGk!#G^^Du;76^6os>?p>(csdlgtRGg%7L}}9=*(}3Yz_56R1JE4z^Yf-> zAGJx!(C%Sxm5YR*PIysn@vydZ2TU+Y`aOW*5iAloKz4f#?JOT9#XhN3qNw{K`%Ti) zt^gnCu17~mV@Hw|BW>%Jds4rXWWVF9TLR8^pks)nSwRYT_&yI=cgAx)xHl~t>l1(h zEIN4-38LUEbt_rPejuhK0(~<>^{`IF=F~+C%#h5sx9XOD)HQv;4T65O`{CpQAY-)L z3bH6Pcu4B$!`Kgt{d&&y`~Tyd>G%KRoay&}+hGCq+xg!(tmH?62#&95W7nUKZYe)&H9fSjd zdK9=NFhM^5c$FuBLYp3;0g8nC{3{O?b6C{Y%!Ei)!?|hTcyI5W-z5^>-JEFj-igeX zzZY3$rnIt9K?EBYXBQyNH@7S%JxE$4Ot~1sPcUuPc~74VObA7F!^9Shpxiu^Y%im! za1IG+Q6ewI;=@+*U$B4=4cUYvsw`0gmBc=3NFeO9#%RlvwiOc{&bDAZ%N!dXfwt1I zRs@v+hRP}BBz*TxyfMT)E3(9wQc5Wcj_55>%`e6egKoUMF+TEwK$si0y{;~^2G}KN zTk7Iz%_s~+TXQ*a^Z_CqOYLRV0UOt@ws=;a9OSktCwIFoYlMR^qn4R*1y2e=b$FbmLeeEuTO8Ez=nm64ZgFO zkrFCjky|QkjI7Yi2gUAX3iaZj3yYOw?qNqr6AL`mQptgP=qM!?z9g|Owqf|v`(_8J zh|r=e73f+&E=yAy;Z*XgW;%dT9|U*1iT;Q|INg^SGk0z`F^1f#1kYmeo@Z1VN@Mrn zcZjU52ypWhA@WMSq`L}UL$c@OIn_3;e&^ta%K{`k;^M+Q4kL3b2tP1DJ`9_$m{1UK z_m7tZyD`lJ#5@Es$e<+oWLT0x0X1^X(i7pEw4U9MGoY^4O(9XaRcmN*1}%$ziB98G zwG14Bno^FUr8uJ%-lwqkwxH;ew|8EvdhPmPes9AN?3G?`1JWJ1yY(Ng{7?PLa=VZlbPZXy@0N1`{(FEs*-P5c)C00960e3{7#g_5slJaz&Ux~Az+oyo8|#?JvtxF5C(NI zYo9`<_6dj&ZsG{U9azYa7i1~UC0xE+$S)L+T){+7i`a11M0PkFVM9`>5#fRcVmY$(x{~}k~0ial~|_-p}$@Q zQt5g)B4lZaH<`g(pO_y!Iyb`lAQb#;xT)?xm|CX=ndE>QB)=j`9fWwEpAly%iF^Ed z!KLH^Ps86g`jj*_UzV0p3&4Nr848h$vcaGE)qW_YDyPu7cOXq+U_sP^k!e)K&P<}} zAZ93Lr^Emo6am>_28LplUQ2GC!)ynslqyd^MQ*1_bpgt-C^cEfnIA}NPzz>(^~1nr z9BB`WM|-@Ffp>oPMT9>j14teb7{y4ADmjK8=;^=ALpv<=n=m*ONg&NVO1}DmT2=9c z`{NM`+8Nj~29WoNlKCAEodb4c&YWzuWK9605a4_LqW8NsfE;tTM&p@v=QRNrC{4N% ze+K9)AM;0hYzaR`QcZ#U<7p8KuK3TCL#@3G*8d_gO2#xlNRQ7%n^+HK5ksFORCFT$&7HM%pHjwR2grD8 z$GOw(@1F_gMR78N7%DeeViF=A`n=u0P6w<`qrdl>c6gMwxR)y-L)$|~t=3%Hu-B{C zkBMQ}{i#kfdxi!J!B1V>IeI!=0&{liaF3o^kG^Yu_&m=OcVtcZ=mxM4?Q!+qj~N!I zsf3})?X$nIBLYynO7mI9w>f|2==FI6K?^bCgKrd=DrP_%Gl(I9q*VBv#Hw>fdk?`# zCN$KX*bUhJz%U63RO@0eN1!=60D5i2%{i$9e0|DagG{CRY|*B+vplb z28}RULeN0p{$oDH&lJILu9{S5(=878Fc5?kYTEmvY&tUZmzrd?(dc3!R0x7|G>dV; z-T=8skWLFYIjDsZKIC+HpotY@$y0pdNfT)h5_kE4#^0W5h=@Zcqw*xm`O3VqWGFR8 z0DybB3MAknynRUD1OcHg_4`Jc68jEP;PXHNKfo^LRLFs0O%7c<_@#_nCNjD9{pS^g z8i=;C&T=7KhfH`Y{i?|m!BFZU(uZog!}tKgkq3T6THvv~RS&ms_N3%5V1p5qf>7t0;Q{nD8`fWerAAs6NOKy|z$AmXtLuF16zZiJeyn5a zkZIOx4yp%rzAcmr;sjdP03Kv}J-KxR*=I0(z*1Aq^d2`Jow9Qga|h^dL7a4P*z~GL z@~ufEVIS(C$H1XRja42;s`dx3aFcwWyK`*!cC(&rgKoqB*J+QG#mpQA60WQ78LOd@6A~ze*S_wrn z9>p|#mP>O1plIj|FOj}D0b;GWT*wJ`z-xS7th&RONH!l1)J!w*9Wd}9_y~n?A;c7v zz-HQX$l64K+BAIf7Nrf;uR8M}kQlmn0HuP(sWy4r2K8NNpn}PWYpJxb>!slV`&6+% zhR#^xyOdfykIAVYxkefmT~paPE}BQQkrL!{lcPTe1Lnge@=)N`k6Q}A3Py%_yiTg7 zMA#H%fMZTtDi3kLE4(129k=+y0_!mKPf+6u5kPFHaAeFZH{4=;<_VMQ=gJ%t3_ZKj zdjyZXikL&a^NGZ@MD`h}fc2NUv>&S@=c}JdTrJsQ9Ewi6y{_YjeLGz=-30q0M^jD@ zvpj)M1H|p>%cN`3mb^<5k*-y1;+(Q$4R!9BYdGyJFb$Y~aea|`>wrCvm35~9KP=Ek z*wwEz-s6lZkQQ$Q4|hQ3SXH#%#@q*hAMTuteiEfLc=bXm5tgbbz4=wI!KDem7+HXK z6C(b)v1ylAz?TaD{uC!6rzkm5U?ewKYw-}bsVm}&W_o{dK2#@uaJ2@jKQT*6|KSzz zv;@@1ekZ8VR#aykKi`T39Sr11$qjL@r8Uu8WqfGdeQOjI<4^)lZp<=~8N6s*jAJY9 zWK`MK0G;v`6!c*0*TCM1{GkZXY>Q6OB}3|DJ*UED;a@r_c1R+nNn1>v7Cs&P8E)&$ zY@L*VjTBnh67Zui6R@h#9~#@FBE&wtv_RNgCCMa@2WmUd;Wf&hYS@ZNw5Ge*z|4JE z} z`_B`s{W@4apq{9Itd##{hX!YCny&U2tUW zF?e)Se+BKam186^LCN<*;5J_x1Mp};qKjgY^$9w|M1aH#wPEU!b#}YFar`UrnJEGs z>8h{~s(fobV&QS;Jkv7L%oj9qZ1it1>{!S>MjJ`J4E1J1E(K&5{b}G60DIv?@cEeG zqxgXH-Yd7F{)+bNpqmstd<`JCqGXb=z5RTWu154&9FX6M;C9e~X}8zd*Z5EOA}vCd z3j5HWUON0Hr)MM6`3npbH*QE2k=tVn!;wB?VpQ>7V_c&S)M!WD7el1*(!b^=uGJQO za4UmuM2fKw1ZGxOdF6tY`T<=eQeu~>_WSmQT>2s)eHwNLdZ;rklDQvJwl31pQ2+^s z&1b@k^N3x#a>S2E+WVO29>c|qK9xVj*dE8ebrz86IHjCtHxGlZ`lnzo>n_+L4XPz7 z27SBo3jpKS zoCBV62a`B*Lw3du#H&vTdvUsr1gj3L^-sjU%A&tEOFpdu%lQEZTI;A`air0a+k!Hu zkP07+QzXEtGd7zOg<)nmd6FNa2Dv_Sxl;;m{Zar@vEWmY&P?!bkRCoE{dgtLda(=>gr&JTFz0Yf*q=vlSw;eZP^$=Dy4H?*0ek=J-KKfFH zleffbo7w1_s1xNUlqwSBy;V($(G2pO{pvlYN7(oVXHlc(o+hX(t^s1+{q&F?AWI4p zt_kfyh>MLiI8ipC0q7-#+ge|0W&}S}?&!$oU=EczBC+Y;)hH;KlXsObfQiBi@y3>j zvJG%(Eh@)A0^$UwK_Y=+<~w+Ym+OfiTHBZ4sW0dodi#J%Ar0m&I4+3 zAK!K^Gm)Nxq0XO`{+X>&qQ^JafI;R+#u4`RcT!*`H3#fMfLB4?S_usR%$Ndvsknfd z%Zo@N;bq*Mq^c=A(jv_QOB#k65ut0HSDSv##@AjTJl$vDZpI+BraW?i;p`*zaB&c| z!<}(-pR-Sb(W=@w4PpBe;e+mEdTgarL+yo)-x&cTVM3XMqn_pCLq|E& z2!`5VSc^qpQV;gMoEmo81R4F@Crd^BNgL*`f*VpYYxM6EpgwjpHB> z`MMZ77Lc@PCKuA~|T_OrNIGawLxJ7Xm3MA@g)WUE$@x_EgE_@+PT@3{7YnU?Io`@qxD(|e9u}kGItuHiBGJS_%@tpW|{G}W- z3ghe~9t;-@%SG&g%X0Wr%ftmz612g^jJvj$zuak6VGdSsEDW^6R}`grhE(k|F;gZ3 z)>3mm(&neeNH+4{;zY&pY#7;P7&MP6nGzt`ofPaDG;J~ zNQ8=^G=@2Usb;HR>;_aZu({Cw5WJJq+CzT`=z$@c;tYjZptp*puEnZ?(D|EFO4l~b zz-$GcH2{s1n0cnjUYUDLy!9WikH3mq55iGGr2u95(qsJptb1$hYT+{y@PvPPUN zD&AI;okEiVX@eDvql!bNZ&IF>t`Xp8s5U1{ba=pk!lhqL!AkMB1!MBcLOc1WRwNYYr~ zsVs1D5uM*#48VeV`|P5-klgD9np5E6i&v)WtfICv_DPvvw2Gnd7S?^~G&Rsns?jDO zU*UPP+oE)V9Ib8-dKI3#&vakzpyb7Sj}w7e$%BYbV7)W_WHgCXIA_LYR?#V8C`p!p zq;R=p=BZE7lo?$Klo7g=t-_4A_Ip3Q*#k+BTem?MA-`79T^ImLrOW4<({24zbNN}j zOzfbq9EC5h@hv=EbyypFu*HhIQ{0{65?qT0C=Nvn#oZl>L$Tr#+=~=A+$F01=&gHd-!D^ z=2=G7K{d2rIZkbO83+1Fk1GNg5uqeH;+W=hln}Jrk*dJ{Dwj^Wuw*!cbUDt-4`y~> zYVlVlD?@Q)Qmfi7D;Ukta(7N=!R-Cz26xl1KT8CJ)uS zXtq63W5FM`4lEl%V&B3Td4^;X74}H_uXfQhq%XhJwcC_lo4S7S{;~TJodP1^_iZSX z2O|<#gBP#0RQa9(T}It~S#JMVAWK`tk_3nx=7`Z52eYC|#`I@Dujj)+@X^D!3w61^ zy&SY9f=HSdT)Hqn}T?#wTJxi3$Y9M z7GjuM%rFA-1|^42^Hdb()xS>stX}r)SFXozF}_5EB9izqN8H)?;XHf6l`3%qhu~5_ zRJFU;OLffEwxgM<#K+k3%T#4j1ou8AODJM}<1m9)OTtj*5@Cmg3%@jMyZqoy^zkbo zfJ0qKV=y{u=i<$yv47k6mQKNXZMbq4)kO7)OH#$iQ}DD`z`tuzO#>-1%rsKG8F%YG zCQeh<3%%v$stwV<;yN*Bdup_r5#V**LnYNE@rY}ej&Cepnc5QQjzf95Ae}&E8+^8y zkDO+-+sKUavMq9^Ksa2$E=wKh@r=00k9@O{{t`|5Cn(zU3XkC;DGXfO9hxk(OWDP8pP06S(1|INf&2=%|J`VWM@UM-9;FA7cV< zub*oZHPDU=*GPf8>G+q6*Qu-D@0bn-wh=hyTk>T{z6;)cCC1j*nsQ62n7_T#CJ*`Yj4K%9Rqy z$l8I!!>dC}&6lT?o>Q_9<#7=C-mr^1)WNxp;5&ExJmq(s$-Yx;7kViM>(7* z(apL85kuH(X)C?2k?@9(bEJD6gcnWD1ZxTLiQCv>lV%xto^oNK{q0^O8L8EWj4gfH zZ`;ayM@C}F=xmbeXe{sEOIy@)s>0nChNm(y>~OA6c0J4_#okPBv_GwuJ9YC`77h_q zGTBa{f3DBFlTGU3z*c?sDFkR%#?6mDBQF-TfZG zr?~$Vtxk4L^-~D<81?Kkqtbh^pqNvI;MZupMvm`x&E-KI=W*YCoJ{U7Q-Of?X?mi~ z2DXdclGg{9A=R72ByI_kO69>K(nxES1VKAA3Y1@3syBAey_;GysB?@>c;lV%9a4#A z7Y;^!+EU)_CVUA6pOVTo)r-uyh}&xUm zPjL4dgmvvjEqYA*@qMKYJA;vGwtkqoqww#leYY#uX|0F1ZlA*Gh@Kh*N<8{TtQSK3 z#?*Zi&+ZrS%tXw#rAmqI*0N>@6-C)skk_8Mi?@2H{NGPe(_L7F{UGe2t-g2&FV0}BtZn|fM7 zwjX&?&eJF{k3|o#e-r$+Re_u#V-*t|51vctt89e-C{jeTjjk<#*#ju$UiCV@E99RL zibM6iE!wiPj^OlUD9qO`r-;lz(%X|csb;3UR;Lyccf>9ct7}58jg!Doc_O#n71?>e zs@4g+DbU4VIVE{`LqG^pJY^YYfzU-}X(gq$pwQac!UZ}?ifA=iQSk~R2`cbG%GHt? zbV<5Z{~$eay&~1WjU2y0;@@%>-(KQ>@860;-W-j7XO>xxs%ehuG7l&mNKYSU02cys zX941F25&9Hf7tB*{{Ht?z?$wz_0JWL^~4`cRZQnZMyx2YvYlHBHIk;?{KY+*Rcfom zoF(C^qdI#Uy&I)V_X_uGZn(@V^25D9hCY88=Njr&+R`v?W6TM)21Z@hOzK+Mp%<|)3V>|XUjzED-u7U?I!Xoc_7_9YT6#+2SKf zTHu4yhN!LY!I{csO&}PUwffmvLx^s>7nniO&Caxs-|f#}zWMLgD5&Q(EdZsQ>6ua|%pNR~bCbfyCtHg5s!U62h#@S!)H~J7ptE`#m!PSi>Th#gK zj@zmTYyZVh21K>5Y%{}=77GAs64c0X>&c>#Z=c)T#ZrM7T_T34)S)G`3QPMRK40r& zk41iI^fcXemh7CUo?9z(_9m~s#qN}zkeRgzZk**aOVfus_Y-!JA zgNcpDw0g8(FGiy?V#fcQ3RZri0?~n{O6JCu^_qq9voo#UV;3ljKY2(`utE^eQ&!wP z$<229$HXXK{Qk=DXR=5$A^WU^G3sT_3ME@W7vN3@JUE$r_vqqoptkQOpnWp^Cg8FW{4~}*EC>poA{QF*5Ln$p%K(Rt@xp5 zcAtfNdJX#`W_D=FpZWJ4UK6m(EvnQC4ahF@j+ga!!7jqSSLE;kE7HG6~y8IqcTZQKJtr&DGau=B%#IAOnhy-6CL*tpzglr%WcQzchD*-h@~I+>?t zdN_w5NvM>g{ZDMGie6_ae$%;PA+hUHm(;V7QR`#$uaOR*3U{W&4dP@y2SON))pOfN z7!KQ|CTyL5|iooHZm>Yjr3| z>6&3Q{r7`RelA93Sp&J)>!W?1Tn6wgU4e6gvQqKl;5;vn(%XD1K za4SZ{*kU0}F8Lv~If`+5bDbj+`}L7hGpSzmN;_gYKZh5=;^C%@9qUru8*=WMug1OD z34?2=LI^aCHzD6fy4N=N{*daMh;esgXN=*_Au>f zP6TtZ^OEW?nnI}{U8KY28>jUe-uB7RVUC-J-?`?unHmbtwT=TMIOPxGO~Q(**=vX@ zgPJTsUs&79zZdq?!MO%@2K_w^^$ziX=Qpn!)?7$Yc^|^Bnn;saT(R~`zGKf}h9zMF zhzuLCw5f5vkbPkgR~sM-c!?Co!piytonyv3s(SZ5g*jEScUf@K0CqJOt z8afM{@X;R8Dn1J?H8;C`ViX+%AdRH^O!a62C&TZM3)UrU*V6L#<9Uo-q}ClCeVkhO zx3s{s{n9<;R>6CHQnX<=_&zEQRCZphi&x549$I8RV(ENY?FQL>x3He&Ir*5@gjxxh zR3a+)1tf{$zf?l>j4(a1?ksii9(<=KrA94f9Y?HV1}0eRc}rF?OC@xp^C0(+@trU_ zit0gT?2#_ACMkbJUI>$3DLI$XR3CG`PJS9;|G3?Mxe^B+g9OBK;}ASkqqMxBLAv>4 zb4*Hm=UWW&7yP&kTzW|d%)NuH@@hQ#>Rx-xKz@KT>>;GUbga#Wq!WordVS4B_4+%4 z=6gHVbB$0iB(q*j5$WUf*84Hviua2$)k@PKN-7a;Bg)U5=M^=m{Uksg(PG6E6=ZCLul7 z`!w9aK-Afc&tfvdl6`{ppuSExBR|J_O~0G8c(Dds!{6Q*QPM0q4hByjI99|)8CABR zZ5_q;k=3~rT8n!+Vi;WPc9clu2y|k9-pxGw?*|{HL?}#7UnjJ6b}z_>pn3#|n?%vDmmuWsQ&i&&xYY z!1T#*sRaNLDe)v~_d(GMwu&>G+P&^_)F`ewAHi&3LDi zKiY})9j&-1RoU8U%a{}3?!G^4)19RWE88)LOU>sqlX#T` zALVgp*NrK0VtZ#+^E~(kq%vSgq_8^V#Q(uc80F@Q8Q`J<-rK2rTwCJ z?)XGA9aHyo*uv9EptlUj2we{-jQQL5;k@%KoAB|8LvD)V-q%0hb8`4Rr?$&?u-en{ zO%g2l*9~#@2FX9+`N-8FjOZFEz#|J|dAsd(wh$=`udvmu^ z$7!9sSD*3FRyeZ6oVe5wy}*EoXlYgy@D^CnY%TAKT8e+=p8Km|+KJWEsNF$Niu!G3 z*MB%J_^PNzCb4&R_nGBh3ehb%j&5vyqxrjN{D*U=JIv;o>c26yeT}P=YweG+nB_B% zXAeSuyKA50`Q*wexmPhiGRAD3I@OID#;sZFgbQ;xoDS9Z-02zw$Vkjt6`fCBQaVl0 z%4M60K5BiC_g^%Pz(bD%SCE6Vz9h2*o`h^Vb?s?2_GRGE>~|5Kjx=NmCWtFP=X{(w zOwA3(Qk02nGS7y2M}d&3a&0UQ*4?PNcTIisdD?+~`aP|>rrtv~#Vz$lom7)0#0Z{p zHCt1TBs^@p05&=fO<&{u*J{kHqEZ)--;f~k3eBHg4!b`K#nEzt>xVy#xjyV>c%|*6 z?Rh`$D)^*rja}IVUiH^(>^)d`hv$k|o?p2`k{(BrrbM2O!KF7N*N4l-o?<_9MMgp_ z1B)NN2adUR>b<&f390P5@u$5%9=k#p^Va_4`cfxSlPe-zj?%?8xtj!`;TuWYvkttX zD=PV0CsL@IQ#mKn#in}Bs4A1333>C)dBgZ;q|MrLPh6%NKH`@348I}YHF~|xj#;J2 zx1<({L&@|!S8A^TkQ#yv2agTfIQ&F`>YN2-v7mIPXTu0xy$$9_RL^?au?qN2ctNVX zvuKq zv&q4rQ57f*BROnN@P6bat;879Li<$K$?M!GG#xn*9^%L&4~GikJRSwKeFCdrvaj8YjD?70K>D&pm$avSkKXJng(Em zutE1H5wOZmXlMQRvX~;hg26v?4|9Ft}DE z`^!*X)8f#hFJCK9u}9p3x37~TOQS^tSjZD`j%y0gzQ(M9bp8?=qTx{iQjJljRhhI#***q{+zkeQzh}NkMl8zdaj>*hW{5KOHhPJ zkRdu{HDu*viuL8JcuiGL)n%QSs=Y;$HlWwht|ik@aoRZ>I8$0-JwZnps*fTbDRf+8+E6e&N5VS32u$n41RL_nF`LT{fxl^yJrRf9@I4q3c*v&2Nz?d~eZP=n2_w zSb1!v@E+vVSE1d(beU|KxE+TMb8WugSejvWKs^CKEA4}~n(C0rs@10J_5E!Z0X{lQAaF1doskd%# zQrQ}s&|@-0cK!JH?0>!HcywJaW+|BcI$fSVemMou+E&ic$aC+VF2~(xvI1o|A=(8W zzI+}7OWS>5eaz6MgA z#jFlpx{n{n+!I#?j&(yFF~2#dc(vlR?F(kV(OXi1Sh3&hGbVv?L*o_>6(H332tSkb zX1t+;0gv5^UEyeCkKKw~Q41uFZ;EH(onsfQl_0n>QA4c`+53g{(W#tsE`0 z|J-Dyf0%?th+Z;9Lm%AgW|V)zGXdJTBecl1KD%i;SHH{H2Rc6CK;0(a)i~Gz?4KH^ z_V)e0-&R)JBJU9zn=!D@QEVKuptLf#;Spw|`Zq;9e}2^l!7>-6YD4?_ZA|PM>A!;7 z(xk(R1UBM@rcFgog_tz3$|s1I-<@{v7s8+|OVY}q-WFoqrFe%@P=7emXufLl7s_Ie z;>uX8iQ4x{wB`=tdbIx6RaH!F7-!P*Ys>D0F1LfKp*_t#b?d*Z0T5FHb+s0!{)0#n120f2y#QT<-1JF@Lh` z{O)zJJ$}A-DQJ&G+exJC6WkT#RRL7qtdnI?`qM?XZbKeMRhdr=d07 zb8G*rB++cpXeaBQ^W5_}=Bpj}36GsiVB+-A0=&^v-ZqY71wuOPntz;#I--xO)UOilsF5B*>^WRA1tE%92uEsPY^zxxa&9xN~- ztmG8H{%}sxZ5l8%WBrZu7vS_0MVoXs-pMD5Xef`gCr1!Qx_&bpm5%?a6%g6k)XK6X}RZk_NPsynXIG>YLRYTPxk$75WaL39Br`ZZAn zxg{w9k7T&-bi`HSeOJ+Sa`oItH?(;&Vyr)uT38l0W2kR1H!Q5WBzvM(-8R|&XAJ%` zM@nbO#{UbD35P5R{C6fgHWk%SfM{3M!SHR($m@OoQXPwzjY%AT2`(Y#6i-@GzzE1= zdz3M}Q&&tWx7<}pv;Q!IT)Tspxt-%WbLeK&d@S4E74=keT;;XFPj6iPfkT_r=n*Tc zQgH(`Sm-1A!B;_$m_A0GyCsC1OnJ;`y9IW6n*1TzQZf+uG*?yaWBfHi7G12r*czQG zQZ#RD+-WhvZ@pmtplMG6Ev!X{>cL=i%(Dck^-0JxXAHGt&-?P?@epe~UJ@4c*KBY>aD!_f;wE_INb@FMS)CxpRDWC>>Q zx-a#1(hpUMyMx?|3+BdUtG<=Zs*F^Ya5TJusqrV5@s>T=c0GA@gRG4?v@DZYge+pX zOOZ=|XuMArk`+wJHiN2=-tygKp8s_VN0~nYmsf2TnVyulHGK@C>n8Dm#myG~xvR() zxy;#$j#;p!x*!|J_KzZrWt~+~UO+Wp1B}b;yql)?R5?)cxI>)Jz7P(?jPqHoe$jax z&;5T;Kv@F`${IiaV+|J=g5gYgAvP}Q?-oD!_+$Lx7m49F_E-mYgIx~rZkIlmXVDDq z%^1voFHUUidTF3I4NN`nj}w5DJBIh-$F*7elSsW+_)BIP>x1;X^o|R73}&lXn(iyG z9Be!q*SnD$TwB(mY^G5`8nHoj4Roo`su(mBSxog&UZ{$0nKig|i7cvJ15=i};pGFk6b~{Rc;r^%myU+yRfF5x>%-sm*Pkry-dUWW zZ>cesq9MEP%!KPzh0>f zgt$R=fuztCb%pxaZMs|ntqzP0GMEz6Dm56DCJJ@^7UNwu!;p=)_KBhn1%l9=9D%T% zy_I^EK$n4MXQkp`5C4>OD}f`Tg9$uQ-4CYmswT@`%4I_!NN_g`tV1b_ti*#5G{K}K zxc}+sUC7%v2MN~vB1>jC?)MIxm#`lOI2)Nx%=%6c`HN2|0%x1-Y|8}&c2vYh<=0f} z#qZUXIQ<-TPIfHFwL`&48j!66yWVK9_Z8lMa&*#R_MZ?#1N$e`D?CSn?7gDYnj+bW zE}n3z;mNP2B!fSIc4hTimgH>wqN$U zDi@ab_P*+*T(26A9<0uKHBF`#%Ms0z7)~6xq3xL+rRkfl$W*QCcMfY5d@x*ZT$X9a zq>hCXj31kJLZ!RwHY}AEjsaI57;GP04oQ9`0xOQ3KK1lfWtE8Sq3oLTl;iQYMPHAa zV`+N)_;bJ;q~isWgfs+iZn-~#X5o!?+`~aUFk;=ubg$E`h+_T6=m5rd)p_pwyDd6m zu|XgIS?!0F{m1>$5IDsJ3H`iFjpqs+mZfk}+Y5DvDC?MO!i@Y9v{f=d+*3*Ojm&h3Odcny-dlof^~C=`R@U( zR_m?U513@{tm~%{Svh+y3c|&%k2BvAZsxaiGY=I4*@hmI8a@-Nn@6~z*7CJ7l@xiC z_v@vxN!Mrz08Sp&;az8@ck{=_No93XUPthUFZ|vvuGiWvI#U`A7l3+Mtdk2zznfg< zU!!LK0O9&S9^bUO!qUkclQ}_f<-aco?SmN-(5q&*!GHwc25_FsC`^&WF>mWNYGmkw z&>tY4Jbe7M`Fe&Pl|l2s5cH`9**P7VQVk*Zykq~pTOvsPmf!17pw_X?x{x|PU&1)o z3ui(5$L6+=NK6F*S38Cb#z3t9wzR?6&1YOw?3(J@s6z0l7bx{*&oA_I&#@az zDZ&H2zU4S1uS<|J&*e(U3I>0AgBiN~&@2bfObqKG9TJ*8DXpRD3b!eok+8Zif33{0 z+k|eNGZMOXNBp0`hnfXf13lSH%evb&?KA2L9_Z2ys(;N&*_Cq71AFsrP~Mt2ba$rw zJpuF#VB;m74cPxpRiWwv8*%I3Kq4XyjCDb_x6hC}f>j>+iUV}63-a&7|ANj2%NPs| zB*S=n=^vTWaX-{6#E)TNm)OZqm&KvB$7=ws6o81_+_b zH|CVu2$CjF(QY50&MXfD=Vb)SKj{}=(Z-eWH}j5}_q}b;p|4NXq!(C8s^0R))?SLf z_1!c5rP!>f@&1_E(e(wcwc$RlEE{+{PJO=ZzEX8f=t5F6YY)Q3M>S$>GzR%I1#G(m zs;&`G$*Xuu>^I%0Coce?g~OO@SQf_I5bcCCFOb8rGS?&uS8fEVrfYA3`;S2(*Pn-u z19sWQ!C_XQWMQOkvj*UA_fZy38Gl(PBPR$kaX}Z2py*jPjP#riLTMi;tsDE6pohc> zLPosN#k~in=ahLW-O6^ggd-V!NwT}2bO1+`)kFfjYC@scl4iFFWyas)c=t(>Byrtmq;&rFd+cF5JX`Wis^4cIkb!ga8q)+CT-6jKs#lG}dm@fP5lMl^f#>}N#qV5LPb65xruoRz%a>9y9p6GeWX zmJt6GurbD#M%<`FnyV|Ne3X$h_Q6Mhnywy3Ovbx(9SIksCyT*e0Avk5@#W_%jIWxT zK*R&JdRCo|D&dNA5Oohf7Z_cDwfa$G9CsX4uQ>#CY>`eLiVJyukY|^w9eHJIY=1t> z-f`mT;9mo2z=Nj%QBFrN9TLac3J{&G=6_@(8C=aYfN_Qd&N1H|amE{-Ox;*LJJGGA z`|>U&-;E=ma|%%IR-OO%+t9NA8Czuf6E_piEx|kqvLy+}-%$fe6z1r{m2SRPse=;Rk6riFJ%ZCl8cW-kjpwPze46;G&kkO9@+4 zcn)!eNr_n`L53i+U{xiJ2$l7UQ2yGo21j^`nYdsApqG(T2nm!w%JcSDe1NP-GR)^7l60ioq$5XU=Nr0CEt_3y&9mSXxgXjZawP|6h9klaKtv82{xXZJhSXA++wWB*vt)*=CmLUn7`J#*M$vnn8l= zhVd+xKQi;4p_6=QbN?_i+}o}ibk=HFKNdZ3^oNEm#?HrJ(EH|~PFPzU&xw>xu4l@_bOg(p zQRShWAL+t}XA99gdJRTWQhj4K8Dlz{hqjW2>dOi4f!r)q3d}GAm4vRwtZKV zRN`AIm8W?Lu-~7{KM{8od+qc7Ab1`>uK=YMM;9%6>I|>;!N@Zqz=;qrpZBt>#_ewL zP{JBYC*z0G3ey0*(ftv|@dv7Hp#!vizl002xt?q++|-a{v41^Y-0Pme)6blxYl0B4 z$CU~nDTHsAv;jB@;@Bn7FP#KY??&!NZ)Lk!q6!tX{=*w=)E{}FyfFbXV8WjGmp4f8 zy&$8Z!oF$;Rv-@7J7j#Od({W)H@ka3=vNOKR-y8sl?JffRe)Xe6#d-MZ0{o`TVW;otQ1-wtI1|JV8?|dX^Opv;nyFDS?l4VP0~&J9lU~TrO&@LC(b^BypfYXQHk%l|@7I>x6}`=PxuV zVLYm(EM6ie6o`OwhRD|qPNye~laBjW?UP02x11H9i((3cxg6%GTis1Z5YzjJECM=n z@2nc#dP=%Alc!(B^Vw(BZzfW%%X}&3=%^%nZ8of;!*f|DBviQb`SR8!VT@ zh$(AL`gux6^Efw69yJC`;~z4~uUpPw zB}TGrJV$}QCHhDZINi7fg-{+uZK(DLbH%6(UJ$|uBblJ;LzD%@;Xlsl(3P@gvu{N{ zM(?64S{lH|HP@hr)}yUS9cQDKVyyM-*nt2-%n&hhe&~`DH>FZoQfR#Ji1r_lYpW3v z9_ZqhX{#Zdv}~>MD!WV3fz-P_CQu)-)_^S!KTC$U)OZ#1gniEz4167Upo5lIbV?oG zm(+f(sQ56kesW|Yb5Fj0Ip#S|eLekJgHpch7YPaJuiE$Xf`lkK2tx@)(`6N9{~_zxlG%CDCxP zNWl~#0v&Ce{AXc9>mt8YalVpQYU~tGf8w|F`TF$vZCh2YeW%^Amcis(hnP?8s<`d3 z>HS)@K>N$Bz1D|COG{RDoqAIBUnlk-$Q>7AM#l@L1!IPm4^S(t@HM|$xA$8;5B^m~ zGh_D~^IV?lK+l)oclx1S8iJGHhWc7Z+;Y6Tq|lX?lM--Jvpy5!ezb9S?(kfI%$);I z|I;+7epW%zHf!A?)B7aXkwKh{Ne2>Vgf}%J`-LRu40iGN%`X6CMhMm59%+uO(pak_*a)C<121i&BSQz08!GJ!B6k!z9=d?85KBY2P<PX!9BCONy!#0oOEU?EDiln|QnhajjE^{<2auhXx#7qSNyLUcX;-aB!V zwcP|{hYM$-bjy|z(lCj^44 zx&wSho?hPCmH|ZJ%K$UG!_a8=0am56yBKNQa6TfoO=SH=6RPb_zob{vLwHW?mZ*}r$M#_ z>8g$(8!?c>c*`r%_2K{3x&9v?|5pe_Rsm%~@gWrs)5~#OiP5!;@a4N+oglLZ6dz*$ z;$vmG5lSDcm@~-i&8k*>Ja4}^XNNsz6SGzX)MPw#xL(IfR9@HDl9T+n56FAo$VYJ_$6s8ru*I9Y7Pq27NR;4aYy7n0bwksF` zPQ>i9hI;nup4Q*Fx*Q%pz_|Hn8OW8M!cG3B=oJ6^(qVmMsZo>ZvpzRA0SW0leUQ}< zZ#uud_V6{TjCK(b7S7VNm~OA)PVEv_T-&qz+YIvGK7spi36S3Ifa~f$F1lv4MCcgY zAwz?>oqq47fB5>>))J9T>bPh|4=!dJ@a3=rKDEI8u1EtuysU-^oah#S`0qxr(-Go7 zQqmdP?h(FkRVUKzv75I6obPrQ)OaDd`UL(F-8u;iy>S0X4mYUeAT3?f@sYnziPbn` zrG_d;U-5x1+`<)|oORXh?0+uZKO1a8v}dgOPTJk>9l(`9mjyKvFA)6pGxGd9eM_L{ zb=Ql~_9Ye=Y2e|a2EaafnN9kYSi6Azqo2LZJ>?!5v|}Qchs&z%_;nA^AuB%HZ4`lyM@2AcBMUNwVcuZCfx7*)~QX3l^ z|+G!maOZ|dkWGDjg_x4=Q` z()J7aP})GC+$Oj6UhV9EXP<*=PdT@@!t@a0{Rb*S z*QxjOepGkBE?3}aXT3Kpo5V3)Z#j%~gQp@;)h(1CTFr>sB||C2M2DuULWbL9{~aYpaTIQ{Dd5jFEV!%;9bj-C*fbzWNoK z#BjK;l0lWnO+eSNpP(;8TH7hXOwLHLg8}p`52npp0C`^q@sp-#*bMJozyH-43e|-x zBrsdi$s(QV$$TB^G>A8dImyBHg1mz_FX-rlyd~#EH;8&t+CNNF6XoS*cdGN1}vx&*&G@lN-O4uxVV3igJH zw)z31Yi;n8DIVEKO)>7wfV*syl@h||i-#S;zEd=tf^V1N*}wfE&!=zm zBS!r(OPWKpSyOU?0la5tWT#hSLS}iz_t%|r=fK0l*?U51VWZ9L8yw962hiQvNJzy- z)%Bf=kz`|`-xX-qPe?`WlquH_f^H0?)EssIosDG#MK4wHcnhJaoeIz{SYF?iC~8z?*U&=#XP+G;|9T@nI)+CqlKluxrid1p{is&QF=b4AsCpU`gRO?J9~PX+3>X&@> zldulOGuWCdITgcpNQc(kNu$zOEQRYS7^|z32v7Z40%XpR)eH4$y(?l;oQnn`p3|c? zkfw0D4lCF&aV88MSYz8$u}vkzQV|@!{^Y*o4b_>I({6ds7v^B;BAI)h-kh3AP|m5n z!l3Lax;uPa5)Po$uw0*zAh%UwN9P+?#KWm0533>O=UzfN;u`GG)bvySS@Dt8R;JA; zt_=rM7(@Ggl+lR;FK--&^oo?Bt(Yf#O!RkW#@rU^Z5n+1dD9}*Y2`VHiD~31%{#ft zZcA4CN!$_EAeOT9(A~a6pCl|ny&USHM5ev3Xz(WHD|ndQsJKKU7}^BU=2Z$7+@BW2s-2=MqFOPcZSY#R;nC!ph#oP*BZW8&49oARea(sp>VMgB zbT;z}HSkFD=0v+UM<|q6ICj2F=^sRyJLEb1nL>GdzhQ9KvpG>}-Q8l>KR{fmGv*eN zy_i4np6`2z3;bcO2-}p=OWEpE#+~p(B65Q7x6IG}bUAae9!&f7E`50%Svdh(069+? zMhxyn{-bQd>ZJuU%#m=uMnQF{aY_Dm`k1nG1s52MFYWU6zpyPC)e(_55QX%mA}e=( zlGd{3wVBJ-XR`l%tW*de^`#of->StqqcavLyHfB;rFKcCLi0qE%SC{<_#=URZcVRY zNu-`$@7DTA{{@)gC2%p$YcW5>n>TpbI62GGT6|Y94O}VvhRyh`T3vF{-A0U@GGZ+x zjIqQq(${|&b43ELMhc89m3^*mKb(P3`ZZP}W^Z4{0$_|eSa~3V?bLMf2hJEK&`r>p z;^~{&!{Bn6gkehdN{=Ei#9j zcQ+%Wm`Fd9OGo)~7C-Y3x)%y%8Q_J`x0EM+$&G6B`;4LM0QhjEn%OSf-?%LoZgC_p zD#!)S#X*uRE9||1pQ89q>`sLDc7uEU9PAwfIJ75qIRx{b`h83 z5IY@6a;m&ze57f`2L=qtbK73;lEG1qLD1NC zYN+l2UCo65>|MU;D6>UBLGn+-xJ?Tkrxij8nbaXH@D0=rp=>wt5CK?d6UvX%m$xpGDNWc^yl ze5!Iqf2vU@gp__}U_;B1K+$WB&}2C54A$~n)2Ei`u?Yc7>H#%GS>??Ul=39t>qjf5yANrJIQ3O*kZpDKP+Pn4dPjDOSXOKB*@tGYWQ9iY{t-MLp+imB?)@ zLq+V5dTKEsfmagjkso!WJm$>sa+rItVUd>zi+s*@4AW4m5Nr#TAkJ|Lay-Su` z60Qe4r>qZWa@8t!zCSKz8m9gcPm(yH`Wj3#|9lNyVLXkGfp91>2(??_JKp!Q#~G@g z6mC|NShY{19$Uyk>1?-qJqqehAEGZ>v}7}3Z?woG%l__vYtMqFw=iPsJmch3GW?}h zg4-a={HD?*nw38fFqx>0)$S*LD*9~G<3q%zuI1c=AV=8Uda4Laegkm zUQ9jo?W}~fNo$MI(HO+Fp`DkSZa;Vs6M*QB;`f_dh2~tHY}q+9qGhbM^~|#ayhvn% zhSb@bar5)_5kEyW;wxg&(XAOKF#F`tbnS)9oSjwbSY|1Oy%UXpzvdE^%C!=7Mo!ez zJ)nTjW{$iuT#P!@UF>k?5^c=>-jeZhcKz(kzruom(PrCjmTm4E#skl)i+*8)v)&0B zY|Ue+RSU_NGf%_1h}B&ZE({#fQ$GoTnG^&on7M^1n@A?-I|AgoxjS-}xXZua(Z)O8ttY;z$MKq5a zXC?P;em4(Q=V|R9E?5&VRpU)|tEB<8#98UaaEklaDBCp45PFJgC$iRxD&1WVZ9eO~ zFW;~={ojHS;fQ}2XUnZjZ$Dfnw&T#|Y5z^u;V#~@aS3oCZ|wv)??s3!>Pq#_2bBi{ z$S<5#s5P7r+!#WvIMSt=@UTS~5>R%XM$Q@9;8{6lHt5YTe127%xTq>A?dbz%lw~9% zW92-gr1B{<&4ZDj74#(QQcRXE+q+;#gEz+Fe-#*xgBuFRA9Y|`OW=5lTX3r_7BOf? zanECv?-wTvzuN<9zY+&-gX@8Adl%)T4MmE6$Ith$eG?*;#gbhh2nI z{M6cx{5`LB2~M40ec6!4$bvt;0nkigcB*Bd+4z*)>zB1Ign|l;kYIh)bU1sY^lCEc z03b0rizr4I`#XKUDsGmB9}skxpI>YVL0nUah*3U(6Fwp~9TJpT7DULHHK5A9a59*A z6pDT&{oX5c-_!qHkwxBdum1%mlKlD@ z!|o`dcWUwV#YHrM0;HQVkYRpe@8qpLY(cQV=!TU!WK)l@P$A~KB+j_ zI6-z2XM$0}nyrnBd(VwP`IG3SW+6~=86u0zD-(|5YT+Y`I7PYpsOb<_!>PmWFCj{A zy3n28F!;+v1{SC@!|EW9ioT>V@OI}~Af8Z`22dZT=zAPFuj+BIR~do&uL zpV_B^X*Fjoy{Xym#mlz;0b@X%zxI~_-E+S#CBg*a1K3e*C_|N6gb&rx9!v?gFZpnG{1ED6`0s=G9@IC@qYFy3@PL+3H|o>hv@@*Ki;P|&Xr z_~A8j;YdWM!pAkVIqUxOBWA?N}r`rP+= zF{0&OP@vl$+XpFft`A_#Rd5KXeDUVd_0dB=ScBBoid4`g25K!*sK|`Kg1i-55rY@y zB0%L?Yatv+0QUxq1tVAVq$EH`bm&OX&cU+RKkJ+YnU#YX>{oo1MrKqnEC#H? zg*`@Y{orM8-)zh%XTZf$4Su@j>_Fpk=uwopgV`(c6%&)WTr{ke>VaEYXQ%IDGvE3x zOSC?Z{2I*vS$~yz(>okhEbH^~9IXR8XGK%`1~rx*;lZ<1 zt61j8{w#n9zs3jzi5MqIx-2d@YiE7ZWa6Cbf&nkD- zI^@eti}62r?pg5=52Q2Bp)&;97IRa7(7ys8ls45q=v{EVqBjZ)++LG^o@2V=fCgRK z_&V(#Mi5=np`cYFzsVM0Im8#NVk_f>t&YU{;8a0Oo{JH!x$MBHwDsY&Md4I{h)fop zS<4D(JaFhIyCHn_QXCk#|KK@)n-Xs(Lj%_D9Ze`6^IIZySHCPdqWxI48jBk_?y$7l zvig}7i%BBs6u;BSF9wBo7{J`o$=q(mNw zoV16{`5agm0FRZs`|fpFf-rNqDO|As>I!{doH&uugQZl7LcrvaKeYzsN2V!GrIk~B z616T2>PPMSNZTY2_Y=GY*=lQ)=t5X(IjMvpF`cbr{^<Bx zkViJ$tgVob?lgXN|L~Jv;!hMGO?o+f*BZA&E1Fp9OmtZjuV*g>YR_hkPSOvk;m=@g z{7|?y+@3u63&vgdhXrKG*>sd52?yH%<7UVk3Z-M=D*NG+i!0sJ%uxA!epT>h$?k}LuFU~<3U7}Pr z8PGy9Ld@+D@yUl%xM5y3n1hAwjKs7Y_3E!j5h@NZ8|R4_t@k=sO#}VS3uo@h>_>~K z>gvTs(T+?8F3=4zsQ$!}Sg{RT?l@|}Q=A@;)Y5=yfVZYsBr-wWFy}x9G9!e&D~pS| zh;=iG8dO`Sc;RI+KLZbqq4~iY?5pl|GVL=xUEaKyQbI*HT(I_0TFH4tcW01L=8}|k z4NtSkg8xZR&j*iKjeJdsmUW`|u0TV|ImFL3I`?on8}y5B;#MXw6E`-o4CoqodjL{! zi-QhM0;%XOhfi=$`z=z70;-kt)$O6mCJZU-;JSu6VDUMYZ=voJ0*T&8P`D6kt{2~k z32roO<}oA~byHPE=<5t>s6Ni;2NJ!ty_5K1Xi6o6co+rr08fISMlBc^elB;+NLUO6 zRphO@9yTW|=sv-UUa9ucK$Nh1VAAAt>W<^sabKLvzzFBW8!x%yr>O{*T!W>RpIc6G z3TG>27pM$!My9Z|H%=>*(7=5RS_TuCAm<&P;bIZ?oa~eX()zl}IUJwWOMOaRZITI4 zm99}oVGTUn!dMQ8W9Pu0oL@bhy%9hEKY4R zkn!<3xG^_L;4*PD`iVaXPc4O`x)d~6w-pIXmTy4Ms=y4!qO5V4vU?OIT3 zRY;Ro5$V9TgDy1 zUn<;KDL@pkPGzOw8uB$MXtJo^&FIOAfP>KkT&u`+yrsG(%LG$5W>%=FWp=M-O>&rK z!4hCWo@-ATAPYUjx$0(OWwzHK+20%Qtq-lmYzHG)-32dLtENwR9D`xbSZ!V!s=F~FSbj#8D$PUx-wL;Q+ zSnXKq!24L)qB3|gyQgh_@aorl#JN!GhDMoZjO0$&ZWe@%S)nJoE< z%se6$yXG+)wBm`3&fu4Y^TzA_hQ1L$>X)75Fg#vX4ZrBF#Gmtk^?F0g-KG*tBIjXT^ceR=s@DLGQ5(`S;HPlcS#ND7a8i|jrZXjkxszf0dcuM}G zfLTy6en{2s3_3a@g(eSmfY6~8b5Qj7>a5?wEDz5l>8xU+>h#trUAU#<&U+TR5hL~^ z@ZqSRDNDHd`SyL?9qW@-KRr2H1rmZ$A=0UV-}Iyq(lazoBa4V2m)=XDLYnxTGA$5J zbzMPVpoBJRNZjg%K?74g!;3z&E`)UL#1#SiZE=FH!aO=fJ0*JGP&8g24Xl4P>m*lG z^Wt>)huxU6WRT0go6jnM>og&!h=%D!BA4K_`URiL4APLFYYBczl(tE=Zuwu-)$Gkx zV(@d+!N6G}l^Clsmlku__aPBqufjo5W8OR$=YPcgh6mi@I}O*Zf!j`r_mXbANIQ+Z z17gTr=omR2WqkCb71@Voo~ktcp@~=QIfhfszB+G__4VC_G%}u2Oe=mXsQ}=MXoR)? z_!N)!6)latEG@q2BxKwT_#(Dvs1gY&{1)T_B4y=r|G`M*@-c8{3-cK#mYoA$MgsoK zNWP!FjAU*p|Eg~>Jxu{w8!g!jGjSUgQz>VeVgzQud&@?!=n^gZS*NFn;MZzZ{7@Ia z1*Z#=rzvDcvn3%RJGr_DB|JXkW^fEDrsfzfLyHjRr zTI0mP5P9scm!)`H9*`hp`le_LZeK3$i~O zOLawHiqb&8TzxAZ_>pZkFMT-zZtZ^n00960e3!=##5#7SdjOANcwx*l^vYu`lmi>+ zg-WrMQz@;iSdvOPOHbg(w(hkzGr)`hLLdudQRF%2|9+e%;+>Ymj;ftna@QU!yE4OR znP1y;{l23Eg7}`9$y^yA-nc8lhslzMZ22hfPHtdJrT0yy^F?^o4FG&HLS4g zy-c*S0>z%eBSc|eOE;+qg#*3ga1ru&wX?gY7_X9bu2)E6GUYi%XOV zsE~kshbW!-JcP5p@${asN#u5QHSz!oi{-r=Z>U4!uWEV&l5|5RhO1dyoueH{6QLVg ze%}2M=Dv!d%_@Ah<_H=xtS90`!tHJKL=0Ci)S&QN$npgmrjW~!rawrLscK7i=xq1g zE%;3D7g3nP^Xn(0B}i>rhR+sw*tOA2tUT?b7IJIYO7<_uWcl<0=N4c})j78o8CEy8 zW@eRD#b22Xv*#-UW9GAc2f26Iv0JVj2?F?RpoE6{*iK7D2opp$Bv;H07o&(<7`yk< z8z<>})Pym~Eep^FsntSWM%nL&N6w3{ej_n6lSts5>S}vr>yBoc6z?3xnhv6#mt6F! z2!fsnM1c=-U9oQG8tNOC7F|baTXDa}=uoP}B*=%f2X@_lfng$>6)J0&-Bm9uOpaK=Px|D*>T17o@Z_d0`TL`N z>m6Jsp~4NDr7JhT(E)9*KK{D;Sd?=j((m%JTsFq`G%Jvy8LVq(&2P+vr)v56Y&AO8 z=Ru?tt4jNconB^jmNvP$3E{sz@TP)>wzAh0I1&(#viR;(d2wC^r{mfn?INNGQ{l)p z`?O%$dquVdqv(_|k_>hW8U^^WMKO5_qiw&KR&$NX+rJml^OIf(vv|x^jLp>Z(O9rM zsYNwW<5hKAONl-AD@ejcvmF1Tam`7x57UB>ScRCwZiW1md2pu!Q{yu|V-Zo~o0i@3 zKDk*z$#jx^(_kdJgADc>Q*%9PD?}}hii{9v6E*Bhcs}!8NZM2j{nVIcFUv#VukrVi zuV0eNF+jJsadeV6EwzLM!oWz&xD*m8i{_C6+%&{^00r z)pFp-X`K09?`sn{XiAB5pg>nleU))8(qMQomFodqA%eYuO-)|Sg4az|JBg6urWq=< zhR-=rL*FcDP!cd$6qi}_rJB3&F0=>>u}O+di;nM(rX^eWe(k|*A#)x^-KHTUhzpM- z77u+tWlS!sYxOd&?+4^yEMDu+%CM^)m$^<&(Rccl8WS>))(1vGpFvd0A0m=`A>TByfLAkmN2Q3A2 zQBAVTl9vZ%p?5zm5b_kxPxYhnN}*o z56Jj8SQePNAFTa|FB#Id}iUeV#nlVU|Uku`a0i z;H$PfyYc9b^8m|=08{XUtyK;#Yz4^sFBOq>qM=kEGk^Cls-viADy_opt^ z9bw0rrm@%M_6_7%d_@#|8z3V@FUeuQrk8KQG5_&_8w=19-p)u5jk$mX~Z zVa9g%_jZ&aZVBkaG4+d9A1!vmcd+)tdnfMi`}jic1{BJ*6Bx;x6H}b*2V>QTvFE&p zqw>eZoj8JJgz@#=nD*cQ{@4Hgmp`9>dD_4K^I!h*kI(y`p7sy_HT;+V`QQEj@w9*Y z=l^>D@%*pj&-VsFvq) zr}r8h-*;E_Q>$*9x(+pIJL^_SC;v@P6_2G5k^yV&RN6l{Y9Mb|#<6 z?CU74B{m>P%HW8?@XyS``!D=ykS+6c3(WzH;X*!?JoZ0({SbW#pg zCKtrvvIKZ4`KIV0iGzv;c@jd=zMn+msR=W(^YV{rMg}vaELtXI5-7KmHftV*%(UM~ zMMS$KyGNObWIAwi6zco;hea0Xd7Q{>rsupvusbVx5^BB6S4>!TXx2oYB-Q5UyhCz| z!jVP-X~x@nx=KGM?%sK-2AZs7(zR8zi(J#0fX~Gx94W+1I`-S+B_0=r4v^^~--zyeVpGWgOKk6Km9CBW+0fr#<%v zv)=xR|FHB$OZD2~s9KoLpcd~HiwOa)zgfD~!E5*CXGggGja>!~ne=+YShTQs06lZO zdRv(No#CQYk+ydx$-U)Ywx7Ma8O~x&WHRR6d zwep`e$o&nWhbK=fVT~g(t|M?~)VA-vg?~k-bVdS%TU>Cv6+arI}K$8lfsT8nr|JBAGDno)-xVE1s=K!Tt z6jr#ZC8wGSpHt#pB{Q^XyB4#|2|JkPP!LoUMFb7Ri)v1&ZzpEcH5u86aQeDCwO$+v zJ|A-uC{yKa6v+~c99>A>lim$-g$8)0Vx17Gyw~D*7rD5d)2S&tF!;TcX=0?+u?Eo#F_eYbCzxgs37|$doJ_42o0m8mhhQ>_w?(on0 zSZC<9>+5?Fy0X%yX4}f^+FvmhR1|!_evKcj__h#{!V#*T_y8ejh|-91QfP;;NK>zA zIv@D1aBy>dO;SIaFkZ@4-6+_*(h~ z_O2vxKXa(Jml~M82r%g}?UjM#o2f59fFf@m3g*c~wD<_Uv~eP6Zp}&7QwE*cW)K2yApd>0A&zB-{0!sOL5I8YU7G^~g)JLfaru2)Uz0JNB03IdB z+0Z`e_$z65TE+>hb!IU}py6Jp@D_0=>J9Br?XRVvu}JF+AmJ7Z#`345F821?m0tJ4 z&t?HJRjfo>_M@UjxV7vCWU{m#5!`kvL;0L3GZiB-YG^4tzs?0+e)$jE>UK%tv>7Sl4TgaV@c0if$NA$h+3!``r|5Lj@`g^Y0=BwdgW;W~ALED3I3Mv_r-N(X&QGrFp^<;G@`(l_%c4m;zpm|8!Rv>>IIf8} z@Jqi0`2(zY-rZz(e}IL;CI$R3+)EmQGqTm=y7sWpxG5MgTDuN#npa+u-Wn(=IPSHb zE~i*X6N}hr@ybGx%JEx|VS4YG+De~cD$k$-fXvBFyxioKfgTV;%92J*%T%;@Cscx;I z{nYIdH$y4vG=Km-Eo|M)qx4ETZ9P!aF`6Q~uNd@gf1cmI!{ID|=a6_8auD3Vyd$B{ zC%S-VAzqZy(?efP9LVIF#ZwaaRA&rvQuZmgk>@-;nEZIq_<%op*8zesJqBLTH4RBE z-&gj~z=`|vUH5cLruJ!&cxf3)mdzQ`-sDssujH1^amR|^aMLLyYuSX7K5JIx;Q2B947>qZ5%4y^tx4I890DDYlJ zrF*`_Dxd?8oVEfi3FEEURhSm08w6Emy~Y$Nb1%W2e9z~+$1!=hRzgz*OdB~COjsko zcgNcM=Smyn7M&Ery}V<{-@*YoXU0h6fPJ z*z0a~#@@wqZag;Zf-`vbW;}r99MOd@G*fxMA^@fPev($oMr4?_+bil6I9}t%!Di%$ z($m~XjE=_?$>$ngdq>@`70C=OQ4+96p@KbRhv8Kx73IS}%dbPN;bHKj-~IH_74Eo0 z8uwG@wU&qegK#k!AMf?l)M*QF-h459gwgAqZ}@zT)SV(NVXYo}o-#4x$AG87O3%fU z!%|t$le*`pwIiez6B=sCO$kHef~AZJpZlIrUDD;(P5I=$uMJ=PP|H(Du~=gnQvp~# zk&1i1T-N>xz#g8z*mDKJML!k5^8{_nk;h`Dpp-c^kQa|a$njx@*V=^m>x!P!J({W~ z;@`DeCp^yZzSw;GJZEJ>TqIz3?doFAh(4$yMw!{X$@2T)eG2 zH1zce6I$=EG4Ht|w32?pu$75@aVwMc5m-1h5sp4~!lUSu(3%V_p3Sc~N_OK}eCU~2 zK`2p9SI#kZTY#pe)8eOUiV18dcYB=7aKmCFbElLxSS%~B*$t?Zr(bK@ja9&8a;CLb z|FI(M*U;mMb+db+`F<1krNZy6hq4@*j{D(pz+h-jfnuBTpU|0l=Ha^*!A3}{Qh{60 z@(JDbwf|PAM#uI2V|$f&e}%$F=Orsi zLrB6t!9G|01nEb?ppH1MgrB|R)j9DnpHN-hjTzwEAWoS-FUXf z`_TM+gRsuX>lstawxsbV{>z(NqryV+)?yY5Uy>G>n8J!RoZLXr>ELzZxYaCBZr%v8 z(RFH7sMGShu#Yb&YtaxleDHlFnSNlNg!(YGERWfgkrIoA{KUiwb=v*O#HgRkr9S*N zt6-I90lAOThuIGb>6!k418cB@Lqmuy^lE$n6l;^P!GCv)9BeOcs_HiZTx-J+-B2@V zb#Pc4auy>w$`ZB#($G;9>?HLA^S$?Z-!Q?mM)Q)QbG7TrpfX zr93>sll)lO$&-a;W|LXOkL#{EAfXoOb@)9g%+@3wHEJ=by|1ECTWXkN5*L^vq6Tx4 zP)I4N9X0q8-??i#+#q!Q7V|&cMG&e$fy*FW|>Z(>*yl3G$% zb(I^}P+p139sRr675SyxZ^Ex#VyacC{Vn1z^Ipi@Nfb%Q5c`1Wnm^+=OR7;SUv$oF zNx{6E62VgXiBgOfKG+agu`4E2jXlV32hjG}<~ie&r15t6CAuDAv`x6?6eFQsH1n(E zkv``_q5^y?SHFzESh!-X0fFvL3kB!q*>Tbi#(B-=52S%sWw5(IY)5hn!*jrLg z!Sr4DH36IV-wQ=8Ph(km8>7}5ENdg96!OvMb(K+_nh-|*d!eV5R91{o>GVTAjTvJS z+b)uY-k5Ijd))M+1q3bphP~xni|U<#NmFZ`KcsX_v@-bdn~uOlXDeGd3IgyvrL&`8C5Slp100N+vglh^%_KO-;-SseET<@1D9jTCj ztwt4h0BF^d0fk87{n+i}Ns?NZePdSZKJ#xyNL`b)u5+FX&dAz=BgZyj2W-0+;hA(3 zci9jTgV#C;!JcLrZJjzC+nLR_o*xeApz0%Vq?!`ALE>~FieN1$H_^N{>Pb1-;nR>| zh`x^|XK{WC2Cg;$ghYW;*+dC;Wc65Tg6Of0NU-1iTq$Yk#*O>%n2QUcB7GHXO1HIy zeKcYtf|%6H36%U@N0q$Al{_ag2pLW#M?PesrwVQ4s+n+<)v29Zc;>q!*(||`ykcc{ z$3C!G&W+Jn`gS>=jnAYH4$YfKX-O)*?(_?xi!6NhIG5r;y>F9Yw!kH+7k(sJerDP= zEyo@Xc$2Zk1+s;327SQpPA;pF!oge*(&_Zd@A+sG7SJX8d={aILA%2sfY^CZ%>;R z0I}QC%@1E*L%h~Ve|047Ozn@0k*{5)*O6*)q&dNfk-vV1iVIhyL6_}gcGbaUDDQVO zrjQ@rEzXM3P-xL*PCc(`)+Gq4mKQWVZq8LZ*FI{cDnP(^neYo;e3Q+83(zxjg4m4J6zFgYqy5=nCS6zFxGCmt+h*=k22CI7 z2Q0H6tHuVOpuJYn*N`@x(8XjSBtl{@1Ew+3_Z@M9nWY^CG%q}dCr!~`*JM6Pz{d2q zXOC4h>uUFTVKJE<9rH0(wQ=dHA&w+7tqnEiN6y&dKv8+0O-cIg>%zXH=hILqRu!kM zN3uP5_cqJleEMToTc-gx=G*+PGGrQ;tJv!kV)rA zNz@FL(XmZcDI*`akepuY57#DqvUC=Hrl6mLq;e#p>deAGzlxH`9NFs8(mpb=H;a$U zQLmRBc!i&TZKX$%ZV8li7S7cos^BR4h=9ZA?sy)l(qwXP<{CQ=(5WA!#Tv$klrhJM z#GWmOk6@g;ap|t3e>gH$ocDuFS@a{oJ&jhMLwxKnX5)@I!8SeOo60HK)Hr36Qo>GT zW~6;M_=QBm`Q`*QI=j4Z1MH%lCnz0*ou@YYh;Zs^MfoTUJnIJlmtHwKap$y?Ft+Dm z0&v7BcW|b3l`&H_K?#acRcQ_=zi=5(2f^|Ul7T4V;2i?jJp{;tf+&H*2isjJ5edRU z$7|)Y4*5J^^rto+hhX5pQCMI3mbu6jJFfDeC5jst6widm#Bc9;sloj+K4)fPnc_&< zGMw#QWeTjViY0QXzJEB#H+HFdd_>BG#ZJx0`-h~M(cLo{ZA~M%JiH25u)57IPFH*C zjl<^55!*)zRice>AQn_k(PlPuBqjzD5eH2y+xz?xF$b{UE<$jNp%0%l_N&e*$zVP& zb><<;P3{)jJ}@p}i|0NUFgz58$5tDuxIX&RLY*}C#~2PFvUFG72$M`G&BU6SqakdB zZp2L|3N!leeWOh!R-m{%{7WqiMun?Mn)S#l{k+&$r&BxYq^)wneX~4AIieJPMyhe2px=g*P?aV4V(h<qqsutxl5X6?b7K{}FUPHMxH$%vjKl6upxuLHv|mW?3q+3B5m5>oqh$k_ zTd7-l#|&ndz{Kux;s3|E7joLpc^J@>9Y)5ss(qk8-oXu4c1~|W-dcH~ zJJ{YReCBKK24Hdx*d=9u$G+ULKknES2>D98 z_vJ+!r-a|<2yXtt&w2qzd9+jSj9caGB~fOymSKp73;Dq0PhjE|Z)| za{Jay{7octwjBBm#^+2#t}Ju>9bAtY$FcS?7n~qD%M|xZsqb| zDnyt_j1rdj&saQ4T=u-wT#VR`aA{Jltfsr~*|vo-3rA4Nc7BGHY#D{A=FeyVri~aL zK9lyDldG6l=AM;aD#uwQn4*G~sd~ClgDEoAWhAQRgw?#DGat7)w^e=)HxMc>Q5l+D zrZ)YEOjw6E?c+;}2xa0#V7;@!e3(vm4y#!L+Fhh*f5tRahk_afk zo3hAALE36t64rvymMyHuM&RT!Q@Nqc#2WxV;YxHUF{jMfo!F}wPE;QmFAZ8)xQD%` zr3PbAJrZ;F%L-4dO@G7LyDs6Pg8kU^B)snG_PUObHjP=FDX*mgnSP9^W0^I3gtwO= zQ|fS(gbkaKA%EXnv$kSLy^pR;Jj0WMccJz43k<);YdES>Komm2i0(&k=8hZWML7aZ_Zuk)$X20b81t3u0B-^ z%0xbsBx8*bpKTm>>|yF;fIoDby8Y)^C=8iOz%e0wY*(t ziznf?aT_S7Ft^9YAD{K(^Fv17aXA`S3m@MDoj@4Ra@_m!lXs9j<4=lu;` zr9T!pxjoVp$_YQ0dEGUX*e?-&r6alduQrLQbo;rP^!Lfyfkx7=+wOtsH}L+pjMNC!`Gig=y@8!>xjNI#-rxF)q)-Ve4%M-vXudO z7y}-Z*@6dY6WZ<8j{72EXer?ScHkQ~ANlzTLxn1whK|8$pu~%4mBCqvPm-ZODkn4} z#=uu0zB+ncDpajwyiOw_+WVZ^8F>ga9nMm57JI%*+5ITjKH@AQ48Js+3kohg5kiyb z>yZ>}jdpMJtxeH{pMo5})RrHZKb4%M$eK@(8pe=%g}5B zJsF0M-xXd>XA$x6RiL?JU$$u zx1t>Fwp0pz{n+VrCumf4u*X~jIudW2$4$IG5LT1GjKBF5u96M>cvDdyhS|$F3U7@X zT2o4UX?t8YL(we8(xCI}eO<7W!7yo?*sRVUmJcVTX z*q9(gq12<|mWWCo3ss2D5;$iGvF=zjQ2V}sFnC+zhtPy5Dgor~Qy8TZfZ(G7d<8d^ zqzG>7&T}c=udxu3FQQG+lSbC^7=|b{$e_e&5*R5$IcM=wl=AGho%Gl8{CI!53WJUS zd0%)e8C*~?Y=p1Eak`CR{Qdf^Q%XA0i(6BxU`ZSSO{o5XJ zINEF6@v$mDWGUrOBAhii`T3CEXLVPETSGePsGUpj_=E((MvR#^`v&`-5|Ev6L>aEew!?84mZ?Lhd{M4yTBTuh$w5pz>% z=wBCq4V@9&-asoHr32qL%3v{DHzo7zsaG#_+%7DAP|clUtwat~9R>#Rp}rv%h=Ust zHFXre^zldy&YC-s4V-nOa*9JLn^)?mBdwL!p@>?{L1!jv;ka%8iYJ`h0)(@| z;Vv?ZhR1ahtz>dNkPW^DQz@)=lt1yiO+^SRh;Sdk()h767v{Cl)N%w%)#Ks)Z_l^eo^Bry`LsAY|%7?tS0;(|4!I z@n-~#12+9VXPaqISxVPAR^Q~E6W9|E97ruH{2n#9@fL~$ek*pBS;G%jyt#~O6V4HY zH&b<65%?1PHN9HFhDMR#z)`-)_gg5^crg#H8heW6y~vP9+ygcFBHX8sa6L=WGlD+; zj^#`oDJs*N@y0F?Ugz!hjUFL4n#lle0#7E(nIg?^oP819qT8RmK1s=zV81?TE}KdO z8*jOrBHY}tVUW*?vv!C9vG;fck-6?)ryO3SK(nOkQsjY9q@sWAs@!&dggohk;bbo# zC*OLcANV?e{!++q@(e!qBl)ZkIT5$6C)28oKF@p)A8+`uH0McQ4K%+wBW^!=z_FkG zy(^z;$LT6|ReI`SKsxv;3Pr#ZB{gMLkAh%)Bh-aD!I+yOM1|arm(LBmmaJVpn^Y8W zzbA6JjEWnyC86~-(YFX<$u3xeeJf+p=$WCvwF39RgM`7jyTbm62Kz}l&92>x`l!|8 zUgzl>VZfM^n~)_RQ{)r>$ZtU>%kQsniZ@brxZ~91?c9ksr431Twkmj z**Www^BR*|bKu0oN&Jcx5zU_wuFJ|Vc`k#7QeQ=rsbRR*8=t>2Wn0PVqntUqq^Kb2 z3_NT|TiRlZC5Rv7P?{sLfQY;T4A2@Q z{XX@7PmhJ=k>ip@{|{;$($`{8c2qnEqUuap3jr#6I#QC)K|iDiDU1u1S49hm3< z$FEqE`u+m-P1&eG-u@hN(QJl!;jH4;P<#!v4`rJ}&``Rty}0WaUF<5N`A9nG-aF7b z7es**BOteYKfR^b)PDOQ#17xsb2)tkcmsFSK}61qxEv$7<5&w7^W*L(4h6a0()RVRRk(vx`u0y|9=;;|GqnK|8=O&_jVl9Wz~<7R*o%x z^M$}N`Fy)a0msOeYYXHtojUyYZ7hY_r&3VNa%yf&lgC}>fA=f5pz&fTWkFbL~x zSLU&x&uN-5sJw(5v`5brlnk}UYcG&=WlO1HLahHbKD5MCMkClgMfhefXH}ZLND)vt z9J!HxQ)M9$Y;J=fyt%P`13A)=NaJ*v9&Fl3%!&}aYvWLDrM+{aHEG`Q*QHQc53x## zLDksSCW)dX$e!}mR2;6>)Jz1#x@(xqVGCvb?)@6{wQRMfD^NeDTtHmPxJBVz8Y+XB zh{5fI3Q1WaTD393+;_Nnv!vD(HyNR z?ETu*(zqebDjLz3W(&96Q>-Xk|{I1IbNi2QyD|C$h z9{>OV|NpIbN6z$0mfc^4Zb6L(gkD3BByd3Q8t4IC(tBo-%o)8&l1cAYprvS}HEAh| zuj&=*Rigk2kO&+Em>I!{YtD&#)z^vVg*fvA)a2UjqxC!8){YGpi;h(qVnXhAHl;a= z6oLzfCwJ0ssv<%^50WE;x(Epk?;h#1w;*fp;7dU)U127rx=u^@7A038@510edJ(_c zBgPrlx2s)G3H5Sxb4~r%$6GwbvaWX_ijC9I+z@{hnvgM$_$max2L6@{g=gp_@*sO8 zl;>?#a3MNl&4s0dmF2)V38fTCce?`je%-jM9}5_KwAc>BG+f} z#b;E+U_U)PRj2&29K6>#?GKL%0gDlI?%7-i6@)iFb8yGIjc> zZh07pk8;44<*#&f*x7i-mT~aR!X?GP+mK{z7|*mTXTUk`JnEdH82&+=sKO~7iKy?Q zoMQbL_F(C@sx`8l)()#rYtdW_u8(4dwqVYVaQ7Stp6z#cA81urWBBBmfeBozX<=t{ zVG)Y&H1PQ;ET&tc*=4y-b?c0A^gPQxy2qlt)5;(rzUW*lzrLs_7YD}UWv5uT zm<{|!A_ATbLP6R*bGve69HqlY7A#^BF|2s@z1HY~t1iXhqWumPmR3IPPYkWnI`FI} ziw9kms-+u@e2ttls0CemH1-MZ&j(8Dp^Qk|Z$)K-HIj7$?930mgKGgiWm2Y;@{6b=4el0Tmi7i+?Qp&4v zq~+mN7Wc$b?ArhHc%*h-;n~dZq%4$|DM4TXtL~YnOZN7($^Ba%md-hm<&?&c4R+q# z%p!;vW6>yZQ^(BWM&TDDqA2vv#m#+po4R*Ii4sM@pQJ36*PF541;>-Nvh{IEyB@vq zcz;m$odH)@BtEDe)51FGdv9Xir5DO?U$K;ky)1~iB#5E(0T!YyWq^t(OA1Z6P<%t) znM361LG`IY+Q~!b0gi#}jN(5gIr3{xAy+QaBm&Qk33`E?>xQR7P3w8V9xioMY*3;e z<^~c6~GWGb_-Augm?T7H$pHByuLh{ zaPWOzCm3HJ<(>{C$xC=$$`enrrh8B2Wbv#K$v5%L_BiQq^AXww=kKJV;DZr;i%O!l8P(NH&8!55UJa z`TgFMH}p-il!pA)phU%_rm!z9ybVVj7;(4_Q)2DUo-e_xuJA@5I=Q~9`-Up_#eD8< zWc17d=Gk`JwoL$i7FIZ{%*$Yblgla0tCs6dSk#~vpU@9Xi6bC*Om%KXeOx<#rfVL| zP?fxFgnHNq0G>STJCSXUp}fC>^hAa#;I9%CC*i}Y)yEFYnHrlA&IhR-d$bo^$=WO} zl8A=er;xoUt;B>ZM@0Cr8u$>IgZ-2Qe_1WuRyVvTDw7K#!?7}Bd`QBBOjo)}#%1Nk zW^IIhD-c&EP}RcjV<`!b{Q{FU2Uw_Z_!2{Xs5{Fs zi(Fc^VF{(#Pm#E9ajQz%St4Ms4A(7O8K0KRs3$OU?3{zc=9d3>kh(a8VCWg0KX8;e2P#k z6&xd$rb>DYcaI*-8I2Be4%e5egUCc22~t$H5y?}ivE@&AvBJOMAN-ZqV72RD0a!6G zVs%?N_Q(Azo-S;cJI(J~0>K{{FFg=bQ7^+yBrP?#r(m{DJjS8pI!ojMjTr}oj*}yfNl_`)}e#JXrD#n$W z7U9AgiYERE(=rOXYWPSjJh}0Mk-0{UEouS(Es@3Rk$T* zf|!6}fP3Uj#PAdNcEiIk_ngY+Ddg8ATGPxrr+A%cUy-N`KmjBGiXzy*M=^*P3j+I% z7?&?&hX)+u-=yQ-O*yR=lPcL=4a^~ZNjTO>+;w0M1L+EUf&KV`2WgQd;LL{t$5OyK zXXX8HsdudC5MdVul;IBps{GVhokQeGmOGHNQH~aH&=lb1q53=E(W}r(aKR~9L;Sph zc@-&TM~jM374sk$fAYcPVT_jmhvP7dn2Jq1d?U)x9-oRmO5*U6>F7y;T z-Ycr|#ThhD7$nLW&UndLz`jOjOz7}ER0C0L4TFAr60iNb0<`o;!O}J_YGpI zb34IfPadYYh2Wv500d!eX~AK|&;#?a{j0)=5WEqfadB+@Xb8r&z-P#Ow9HokbI5n_ z7meT!ayZ1>%lMMyLy&{I4vB>uT;j!%3=S%_=4tp zi-TouUqEd7=dmyY@jjd`9H6}2-c$izdW1Jo>O zzH%x>ZWFUS1@}ic&!T}Ug>{2(2Y+p8Vq8W7akgGW2jq||J3X(JN%>QLaf^fC5O|6Hx}i{3~=5q(078)a*J` zC9@Utql=H>!-}>BO$dH2`E3g&%GnpN^KOASV&b30(fQ#v_>bU-CrE^!^FMaZxhey4 ze{u$E|D=UKxgMTys~ng5W9yG5a^**nJ7E7$u9IFs)a-YY=0Dlz{+JDT54PwqOe%h~ zmMa0jJfM4kL+)z;n=~{7Tzzfj3gJ66O2{xcH>^p_CRYFc@BjMWe*O9{zkdDtU;q5; z*M9=ze+Kx6Uw?l7@wfLs0Q}E?{`2_r{L63e%hi9=_TT=koWH%l&dpH$*MBXv`z0fr z^N>Q~-IrnPG0TBl@7k=5_@fEDZq|}HG{$$EH%d4f?@&K1^&Y0jIS%`mu4LI$?V<%_ zKZo`tP0WC5h)D{=({YxQ&R5f@A9feC>{=`LrSN>>P>&e$Hk{OCsg`CUb430S zYYn6L+d*h=jnp+qXEaji16Jr;su!YcK(E5oHCB3!{dlB4BN@m3>GvWzP3iM2}ItfV;NBjlu^A`}}W#`WWgK=>iFkOryoLt(V?VA*~I zN>&D@5i}2bpwS_d4wbmzI+r2|PU|}zmSC0Rv>eE8_ny4bzs`H8*CzLDKraJ-L?Vp88sZX0ae_SE|lvPCs;F(CGQqR~qza#ph}8Q~R|v`x79!e$jg}4GmQH`Dmdj z{a#<=vm5p{B_cwv^!I~l4Gpe_C9%dXhKQ)ixJ~kod|DaXHk@o4$jJ%(r8hU*JC}ll zq#4G9z2ghbMav4loJKh*P#hv*i`fo2luE6*;EuHQlcfp|v3V@N(|ASt5w&BdZKdZpy;@co1R7JK;NjG^XKM>{P((!XC~K`J`JPm@)GaJk-Zr%Hi2`9hi> zqeV$(mHN}nI^D3>O3Wt-lcWY;cECiW^wx738~2nN3?f>Y`a3`CH~l=R z6^`?6xAiF$*Kh|tAB9Bk|2Z4G}+>`nTuI1cp1V+X}>H(UOshx()SgVxQlALa5P^RfKeULEuU1sBg*WszSPSWm8bP068;H1_f^`;QQE?TSdeL; zbJ_(X@YGmZB-+EGj{3x}68nlbBNT%|THhtQ9QGlyO%y=jf2ozf$o~h6_DL z3Re&EcsOqU*iSekiDLMG`p_T~R9{r$~3J1KI1D9%!UqRWD{I_C9nQ zlo9C{q$o0LVmA*5$#`emqpUsDjc{=N(5ZtW50bPqh2ICVdir>L75Qs^VU;K&b&p6#c?><;w4QMe^_;QtfiBQpxt@$-&c+ z+|;{Ud`LLqk_s7dnl69CM>N4Ny*Fqv*a)QyFT-=aZ6K{+5)t^Zc}H155GY~`$ADg0j{9U=JT^o~VV+6mK9j7c-YV%_Xeoo+-Xyw(NA{`YYsh&7 z{!ws5d^WTS-ScyK9}B$7m0ZMHArfS8es7GSZAhm)`u31!r+v^dYQerXF-eo4`p)R6 zb0IQ%U0v6l;3kRr`3{4=u+)1ng!?EjecieC^9<^h-+{)dou)EWBIrhBcwVJeR zFj8^hs+H(xdWA-+j(feUA+=z-wzmic>Y)YLlE0FkjR@v@kOmZeHC%uXaAhb#foNwM zF215k8~yHA&V*;Xe)vUYXbZ?WHFb%(WJG4xhWGfbi!X65^73`5ZW|t+7P~FcJ1&jI zkk~xQKoY~Jnk!_tSRGy+l-KyZN@!(YUVM zDH%9VxNmj*wa)(^zy4b1|KUH>`G5TFx4-=UGoSh0{6GGkzTns2eCHqjzpwxAzgz!L ve`kI4yZL|o?fusuRP!(EmH)&3zu)g?|9|}L{bw`<+yBdVexCmg%m9Ba>z=(P diff --git a/matlab/scripts/Inertial Nav EKF/StatePrediction.mat b/matlab/scripts/Inertial Nav EKF/StatePrediction.mat index 3f6faf511e157d1616c7e1d45a08710eac54649f..abf15241a0fa024db2085fd88adab239999c1aa3 100644 GIT binary patch literal 106832 zcmb511y~i`+Wu+SLyLka0uqvfbVvv$k}8PkCPZ2#q`O-{um#0JOhi!GinIzC*nw{P z#Y93RbQAwsGw1a?e*aHc>%Fe`I)}sAzkAJ^wVt`>-ZKxDCbkwPrjlAJ%OovLY?pd? z?{Zg`wAr;i$ir{XZhicJTWO}PsVup2kNfr@cQ;8tUwz37~+ruR#)g;w4^ffj0 zm+48WFH_T&g#E|tI}`a2vzaA7{@>Q%|ArOx>~L{8&*Z8t`GLvRgoDe)&BbG#*=45Z z$~@IAQ+1Lt0q!cS5;iTYW`?S^hDryXaJ=TOT>tE{+AW@gNU3dmhf~H|G$W zdHNJCK^`yPIX#h0l*LJ z0W$+1vO)uWabQC^d)drDb9QK;I1a2`!G3WTATu=32?y5n&IW9PKV%~uSQp5Cb>6 zfL~4lU-~ac5+Vi&s#azUEUWT(DjML)(#3p4F$!t!N z6^K1^RIM0Ont9ki60pRyZ4E zC63#S?=~Dpv+%6hA$iQewtV2w2E4!RpY2VS7CB7MfQ6jhXROBe4|_OA;H*G4NT4hL zc5?*J3S@xv0%WWTrkR*G%{^wsc1>T@O)JC2954s?hg{^&iKikQW=a2yBFzn5=$ zGiJDQ+aiFM+pn1%hJg3iMYPV$vIX{>OXKGpo5zte^GsIK^ciu`GpT`Jua(PwR z$1s3e;s25u)qmfeC4Ju{HvBw#lTfCp=$8L=d-gXs?a5ojTy&a?XGUuM#=s~vDr*t* ziWkt+-?=zv8*2d?6|bNdo^pu->R$_qyt1V-Y$1un3(0(Tjv4^` z>$>MMdjM%vTY#}_8{&`$yp6w4{HH%|%dI4>0v?(3D=02)j>{}xHm=X$)KFihG1vZs z`XKW?gMB}SO|)A z1F7xugYZBd9LVj*Q3MX$_V!_G%Z(jQ7?D4}SbvbSM$}y1E~CC?PaX;@0SIuIJ#v;$JAt zO>y}Br6MO0>;8RVwOCq=Jw#bp#rVR?6XUD{Q#&Iz^f3|^kASidbKaUA+l++8L!fMZ z2y9Lh5*7~u4~}v+%{tngM@U#a20XNb^TF)c2S`{v2t4$Z^AW)QeW$6Ym?@j_np>(g zt0utjv_<%C@U^5=0Jh@qU0g~O^SI}dwOFr))bfyqYv5x5{lVLC`5$4uKlVCr$j zdcko1?=QaCOm&t$uJ8QXC-JDM_K^+s=)+phxx*_qKH;`|g7ucikE~e6df-1X+AtoY zr4F-i0JOhdN?o}^;4^boyyl%xWj{CLYzfrJ*U&XoWp5-<`q{$oAG~12l(eo_@9wx z>tv{AaQ@}O`hQ#lMDUgAQb{=vOV384^W*gGiWK5<2s8F{B)SBkAEgjR28N!6LRVqJ z>8@Oq64;r^M52QmS=UfXDJ(q)iOvP+A1K5ZZ4fh4k%mN{kJES9QLaOdy<#sCoej|M zQf>nJ-z(q0J2P8H6AT`*@=@jS%C~2n(g_U*V~2&$$KinyVc`3D*f zb}B5K4TlGrQa(V#!A6CJ%K&&O{D3yTpS)OPWb{22ip`Dt_k3KDSgmzuuEa# zJOKWS(hm#2j2MTeY1v7Fa`=Y`NE~9po25?4U=t%ZO1>6+4-lg1wrK8ywR&W{B zpftkL(d>&5pr58R!_v|03pY-86QmGdML^6uqJ3Ei=y83aA3o6e6#Jf}<2iaRASyFrY_{QXGu{e3~)|4M!=C%%Fblrc6V_QHtYY0Dq4$ zL&H(*iy#gUF~eA);VAY+4Ztffc4#2Fya|rm^oKR*`cxkeiP$@9y!Vmorl9iWH1aG zjk~2{7v(3*c_n!CpeLFG`@qSYdO(f}E{>5pa~^ zxDdeaU~{42D8+F(C^3qdFf<&cID$An0H3X( zr=!{zUkpE^J06q45eyy4zW6HQbTZlyPq z`vMB_HU-SQAlVmR4t(V9>Ew+%3?0e7_$~qTaq>`)&7|AZNVkwCa zhK^=mmg01GPq^d=j2+FsECTe`7$5A+fLVt(M}|1vV>KoK=(CxlEJSmpy~3Nx<2rex z4m0a$_C*>Wxu-OFrw&6$voAt`o=4uQL(mcJiv~{jVkYm^Vd!Y~g&WZQ;cnK!dPK4> zn?e0Li>-nwF$5f?IBJ6`Fb7)$4M(vrp!Y&p9JUS`j#3;!ABM1gY&|p_r8t6~4B=GF z0ve8DUqF9`@CO+2jP-0~oj9Q=_6786h|tAsphu2kUqIi6h;tb6Ml;OFk?afT;Sf0& zvxOZw%9lrU(9a<<0ox1JW4^`_d1dX!KSl@6}=GNcN>4Jksc$4|lT;)+3UAaRBw}3FZh> z1qe7wanu7P#t?IchNIY*Z~(uAZHI=V6i0SYzeKSe&~TLE2%1quq+;&Sa1{Fj8dF4! zV4l!$6#D|2R7CE;yrJPJ_60PohCQ3Ab`KdBB0?Y z#gQA-uT@wSG#sTknge(l76T1Ou`fzEJW3LagNCEnmz@BfjU_#(qQ38_62nCh`5HuL&H%<&WXb#C9p(jILZ!P3*cE;GBg}z zhspss151U5qwG*m93JJ3r33gZ1-&8-*}f2QdN>&z!O+p{3wWB*>l0LRM2sEHzJSLW zz3njv*qK4IFW`Ab@B7#`SUQ@00S`3#Xpy(-F!PRPU%(TMK4-~$br?EY{sJCp+$luf ztj}VO@Ux267$63J=4fXEd9MyJaEen6drPaQNa_CMKPPzwQx2IW*HgG9ueZkkf)t9L1yw`ahH-&~ya< zA|?dr!5b;Zpy>z(MofdC*HQ|g=?D%+j2qBHR46B4=_nRPOo^ZuP)72 zD5qiRC?-a1IiLsjQ1YSaC}ZaY^q>ut{LNh{3Ys36e75T!6R9j?85->x_}Y@J9;E9lbu80 z(zV6Zd(yIB3HJRL{DX{?lH^cPr9l_QV@Bn(K1KB4IX1$}>ngV5l-blFxJ9d`wEvt{l8#a%6#+e9)68Aa{-C4G z`vQVq2el%}v7^kpKA`VWg<6p$9i>Kc5cK0vE0Uz6)W{`(9>@)~B1t+*jT9#6;qWVx zFf_0$Qk$TEq*TMMcOs*KrSk!LkR7FVCVI?&x=!M|i9>Mp(24+I4rkA4mo*$7DcujK z97ZP>@XJizv6&?PoQ?8-{W+T#?nzIX61S7R&>a493-Vud+%AD4`Tun>{cGD$aWMSE z7P222oB-Ib@B&6aAZa<-6AexPY*}~#W-60NB3p0u&&SLZysD3lJ^`UO<5mXr}yv7eLzwqCg;3 zn=%0{KzJSaBhUi^Nh0KnuTUqMusiSq?1VrP`SvTE0NPHLB?N}Z7hvH8(01}XAdu`t zz5@#0euhu%nj83prbgSr35{C<_2ni&{3SvB7**P z<_2ni&{3R^A)p63kPXyk@#6Re40oI;&WDwtH&UK~tqVm*aXw^VuSIzQO-FG)L|`9u zhVlxQj^upEz+RB@2AYm?heZVT!LgK9K%aHH{*H3sD;km6CuNeI)c$s2WB#>Pco2nT ztpa!8)+%Y7Y^4S_e6)H=#P-SVWIHuD0knEaB=^bB$(Cwx0%-M;2=7yj$+l{60%*>M z$nR4wW4!Q72+jEr5q_#D#t$!m=6v`;@kvd=1fc~GosTLZFpLSo3!ph42_TT>g3W^# zKy*IFKp@$Kd}kJF6`?sFDia}4LcTT&CxEn*sggh-Wg+?QESvz+PNoVF0%_#yvv2}P zJ6Y`Miecl~o4NPeA9MugLnSi(z~Y&Eul+$sa6VKr z)1NnU@3lYZ2+oH}WcopgWbd`VUBdpLBRC%_k?98wk?8;w9l`lfiA+D(nT!UY=m^e- zN@V)MkI7sBhK}NVsAQ(UoD2n^=m^e-N@V&W7a$XX-yMOWoe!0W^^+*+mNke%4zhL2V+iEuwP>cJgA+hGa3Z6ziTFM#BHs6^18R*ES?3!ph4Dv|Z4 zFT#}J1<*DD5%;HOU@Fi8XwHX9B>pKo$=7Y6RuQ7}AwvI@x8xhQZ~|z~hsga?SCcQ@ z!U>@5WFq=cEhFE&g%d#A$wc~}CNcBNx4*Bz|F#l_bv|VJzhmaMZGX^FoR13dRYA`n z^C~cQ6z4-k|G~yHw{81l>?qEM$o+$_kZs%kc7^$aj^ccX&_871%+bIfbQI@9B>o}k zWHbOZb`zXjRD4Nd^9WD-Gt>MgR5+uu$=%)izO@BfWttuDFX)+%iY*~krU_-OT# zNcq$Dlg-@V1kjuhk@BZAVa8BbUE&O*IUgeBPv4E1zzd)`A0p^ae}}Dv7C>}9MAo0N z7F!K3faZLNxIg1Mwia3d(fJUGf9gT zkFldTA0qA#TTJExFk?q@K19|ZmP3XDP;`{_P6Yj7laPr3(JC1Hi9C2?LInM36teZ( zto48pKr8xW&>up!e}fZ1E15*lpVmXRfP)i2Dw%Y)HC((*={95=xWAp@n18Jm-aQ=2 zTIDx!onlU}BKyF>4Ijz*&}G2zGZe8cP*+{z3?n%ox*H*I7~2XjfaHAWbAdo68%Bi| zKyyBHTS6cJbAlH@+5~h>LZBUUffhh>KJ*|UkXA#!kdUna6WV@pyPjpO%*IqC^~}kp&JnN{WCX<`(tJhoDV$;(D6URrU5;61m{C%A?SW& zGypX-2+oIYO3>TLTmXuW;C$#(fF5o>b13lN^N!+t=&l6)78we_j2-0(XZjpKkC1~* z1b(+LhIT&mjX)q>gX|hNYd!eg#u#2eoe(%lc8-G+Kr5MhfItQ>**y+U0Ig(Vgg^w@ zK@Ls;tz@nz1U`~opVep@TN_c)TZ+IA1OR++XK@h&Rd@X?%)4;X%C9To_6Stphd zn)6uz1oo<6!O#MT&SxtjkdF~>q(V&*@hTVmCeQ~0SzH+LPAZfDqVtIW0_mTzJWL^cvj^cc@33}Dcedhj{85HLe0_fpNWS=>xnL%+r zd<6X{84WG;wdO!%E-R>F@0uRWhb8rG^B{K#HWa^NO=img;N+vTQaF%R7 z2Pc45GEIQMUO}<}9h?AK?6a5x2MCTI#1TuxNOn3pbBcKohaab0- z0NOS-BLu#Yy}+P0fjZhYRsaHfx03z9-~`aNu{R;mNcIH#+b;WkCHS{(GURhUbWuPL z=bpJi-5+!m=i@-o!y)skf7>R*j$MzSf1J5R-5+B|aX#UI9$`nesDqk!6z9WE&>P5T z0E&*{d{zT`q#BtEK+#d0k1RniBtrohI+F8o2lOajG7*5Hqd5I}1U-_B17_W>zZ)mR z-;LSmyK#LIgfe}s9;En*TWCjC)z1uOOZyKBcTFK-k1X?hnbsC%i zTFJBo0$Iy3qI(*g0GjhzN(h|Chz4qK0%)<%ZXl374=Vzz=x>|gx3$9io+DYS$_Ct8 zWhY?8&}$UY`8X28AHaxiRZ#PTnE4n2fgCDEG^~OWKy*IQKwz&Sb{2Yy5HlZELf|5H z4qgCl8?OWcSt8hZcmcF+EKLX`VHe>A(6;doLSP8H3QuoDVla|3*dwP;?aM zV-Dz1+sIr1ijLxZln8n=84AGAk(|#?K#$fT69FhXit|}W(2L;W0AfXIqGdkYfWY2s zSQ$(`AO+BF7MBBoEOG2QyZ~Csj3fjyv77J$XeE=A5E#dZ?rO7Lw#X?$E17G7K(;$Z zG+2WZKyyBFguru*=&=STfaZKWfk2KiMl`j86F`f7LYFrfdfLGW+KiPq1jOiT!W=`C0ss)s%Phw|`=K`=gI(gb}kR1bTS zj$nMmgb4aCs2=tN9mV*FX#jeN7gP^>l8#_}#JCCiYqE#^tXC8;?`XzHObG}icT*lg zl>3rFoDjG}c?vIpR58Ukfk3JPd^F=DW(a$ftmfpyyDC zq!5aZ;Cu>X2>K)iDkdb(DuVMVm<#BEJ1HfwD-y-|6lfCkR=B3(VC*Q5`4sQ~deB<3 zsrYOajhGoU=To2z1QIuq6(3Fj$@vrzo;k4=uIQ6TfaH7%48Rd2Ev0nAR5Vfmtz@zg z0>{V}VsKN0Rx+i4Kr$!UMGQ^=$@vt_Aq0ZRMq+RRNY1A~oe=0Edx^mbAUU4`3<#uH z!8IEvPBNPFDNrN?D&d-qlLBb_U;z+Fm7lq(*uT~a7eKRCn>=xAl|-R@gx&;*&W8gG zKPiOr8D0Qw8!sUQdMIDv1<YF`VIdS9#rZH3^jj1n zDTJbEZ*;Swb1d^iRy5190kNEd1L>>ttlF^*cJVM|E*+>jd0L}Sm0fAI*vX>Z~0GjjRB?Q9Ac4ANhh|Xsz zA)8{wLb69QPtrco&73hLntK^dy3zTmF zg$Ob8A#(o|UW^T10Bsu+(SJ$=#sM#YwvCDOKjkCFHPZ?Botq%Ga4sOy|3D=&7@qYC z4CpA%hlu_IkCLe{6dlF+5V?O4Cm9Jt(NUZa5&8!OlX)-{9mV+&iGNVf%wg~!XBEZy z5OII-1~M0b8as;fA+rA98Zs1sp(8mTBIplU3fELz9bb`1&WA|(L-HZx0HXgcn)4x2 z{^Vk~uJ>U0sDHUj0uiC4&Bxez>mpqySRMq>@4Z zHnNM@te17-93VL#DjD=Qk&VRQ1dyB$l??i|$X;S_0!Yq>N@V?Mr{Ow{6XyWU`A~_t zKb@cKCw49aLvYvBS3RLR3h|Gal}NSuIykHp~XH_BKJ>ufGwQq%KqD0 zAva@p!>v`S4z>t>_-Nahi2hU0ViNEIXxo@b|I-Aq#WT&%?`tIJ7>bbjP|5V)j*P5k zy@~-kg7cvg(SJ|_WL^d62+oH}J}aX}8G@b}1m{B~LjT}G$}lt?!TC^$#6N_Wj0T|Q z9l`lfiMT%`lFS95=m^e-N@V>ZpUF@FhK}NVs6@~oY7f^`TpeFCD9(pUr2L`xAmaeA zBGJC>qLL~9Gq|qzVEBm6hf1dWMsQv4NdYA1L)9nl)-SCR*?F*pG<=R;)u>5t$#jT7ep z(fJT@e}*1hr*TpM>Dw+Uk@#nvBb$mrO%bB=AwvJuR7@S}$_`c$qVpkg|I{CtCcFUJ zP9~!NwC$MoOqa0V)(W*5yOJwztzC6V%{y@Km{PYR$pA68(k(oNyI-jf1oC6fsH)31_U z#AdxH66XNT`4B;Wh8WpM3{C*e`4B;WMmpI`3{C*e`4Cxu#wc8;apD{xIv*nL&)fmm zX`B>5b3R1kpZOH7(>Ni3=zNIKKkXW34s~S*s|eBg5V?Q4IA#eifVPu~=s!IZvxXNy z+sQ=wpFWOlnCTk%+ghPEWB=-bTdNFrY!jeQmoPDf6$HHsK451zf5p%kZyWeWAtU4b z`M0c!@>qsTeA||{ZEYD@ZEaa?j&B!fL`AaQ414|VD}A`~BR#Z(@$r@NTXolO>Rih7*U&T(BZAk93Yj(=&d)4fe*r(O(l-YNq*(tRzxY;SEZ=|_Bu8+65 zJ*_XRxjm`RvblY4-{a=?gubQC?HPSnn%h(Qb~m?Y_kC+_kMCR5+@9WdytzHO&#}2Z ztFNuOJ+aTQxjnP5s<}P2FS@xsr*E>^D6WsS*(j|qvDql8Z)LO5-oA!rql7-`W}}S0 zGtEXReLI?svio|PtA$(T_C@b5ySj2T-Oc%M-`Cve=rU_528Uar#c0`d5Mzy7$C18G zP1TfE9a)BlTjBcA$IaF3traqi&2AmX`rhx0-c}~EKYBrH@&4%LWq#J9i<*oQ`!t%X zrCUR#7|LY>7Nd?$M)`e#P1Q=Rq0$U$*?`q(xLcw1s9{sJT!?jGp zdQ_+>MyeGbbF-Uqa$j-Yq-I&6)u={O%#zk8QjAtNJqlm1~-k zX)Tmuyl{(6>3fnlsaIxfJu1>PCDrOI#dzozo7{IbFIu$KS(@?HEjF>wFK=>bS&ijr zXw#HRYlk$0;Wi!DCy_TPT^4IGYTY!Y&}uBr_~uaO8b;fMyj0xzhHuUchqz&-U zRVj2;UV12debhjb|)m9m8e(_~;#TXf;~?vD-SQMr$V*#WR+(j^WG!{1^Bqbo^tTJEx{_)Ih!(5mKfSdx#zE&V zzYbe}2mb#SqIJxt#p?J^J9Wlv>Wm5OoSLkik!*u*5Y-q(}!(;W)E?q|F z{UxZh0XrJM0zFl@KT@Q>0UPT|W~9|e7uH9+bs1gsmvE#FY@-d>({dE(jl%u>@^pzU zG~@IB9X0;3{#{f1>L*VnGnkVZ_yYvjeQj9SCywb;}|;{J~)X@v>YWm&KAPP(vumuR6sIgD4B7# zeln>(dQX>8k$>Su*v9aW2 zhC(s}AJpmk=zy;3v;NLoX{t)}!y^4k*x12j#>M*R;I8U({?6NISC!~*MEVzEWBB-A zaF5||4eqh5WQIdBqcxeKm&~}8%m`0roU4xx?5ZyE@7PK!bf!7m(D0%ADbZCG>8dL9 z3X%Th*x2!8hHNsUD49`GA00YW^HBWGm3OQ+IKBB_x0^?%joN&xx{>P5|3>^&RnF+T zZyVm7xiR*t-8ypb=v%|~F=nE!H12pgpN(n7v*_~O?|p9Wet#*&<30W#Hyt&O;Xh1W zVf0i5`mQ*+BL4K`wp#1ejcWcDV%&}Q1N^CC{Edwif71dkx%+1R8w+^k8WsH47huKr zz5TZq@D(?T`mdSbZb{PUQPx#zNh$9U)0JyU4(u_|Rc%Qf?qQ)xsw8puNYUg~QZjqy z&}3AS&3n{o$||W3doY?*Ns>~JB2BR*GUTux?^a@ z;&GhaCSl9O6H>dkhv|yPukGFtrYWA-*c}jNa3W5w+bm4|L_%@5cbNW(c+YN!FzpkG zAG^cDjGW>`x>tv(IVBwKb`R5Yins5!3)6B+eA68qX4oF5(`^~1(VkGzy*q4qdwgiO zW0+2R;#hZdn6XhDfA`AqWkv}(-8;s0jpC>8#&+!=pKFx$q_ccn%qT~-Gjn{-)I#U` z_Jej&yv~g}gO*X;9rr^A9i#X=8u8o8d=2&b+6J@vr5?C?WU_|6~C$5R#(d^@kMu#u3<}@Mz^#7 zk^)iBI)?!5f<+%|^#W817JjS?4=^f_5UFJkSWKNSQnxxljVgAyRyII^y5Mk~dw?EQ z+`e{RfGkzizRoT{i@NAdtyaKN>cTg5!2yO;37uNr0BQRC>5SNhnw}*z1>cnX9%FxQ z`kadTD*+4X!W9kQ0yyb{q4mcDMCkKE8`=W+=|W@mRRI!ok+Fu!AtnO>{`$lr0fV{x z4GlwF26J-i&kW5s5YB1n8DcXKw65PjG}mCBb;FAx9s{8#_2oli1|m-yhKE@02&mR) z4$ZkUSGD2c5O!zI)%r_A3+@PCZTLFGaYxXvK7UB~&OE<{_d|Slga+y>hs5uQ3^Xu? zn4<(F>QjdVqvlF9G!9WF8@$Bkm*B)Zp*tHmS~c6*NN#l$;z+mCC-BzAO%jvG$J8FyQcYfL57bo-4j zpNeN?pQ>T?cM)UbyjSP%FUFF3_msbv7)R>8F8?qw=CyZo{oTaa*G@K*j-c;t>z?N> zVktu}H#AB&3XLtQczy96i}2Hn@iJUoM_f;KVwy=z@rPIxXaf&r!|bYL;#bLx({5ZPiocrwp+8%8 zJ$AW%fmotMZGbMbTvw_;X4N1%E_k_Nr@wFv&q9B`mWHqX%qsQPoyCJ1<9ZV;F_god z>eP507on1RVQS)T8lO(*lD^udG+w{@ZT_6?DV6^G{S7L2Sou2_Phc^;HSrzw1D#`o zoa53HlqsIr_?r5T&VfPx@sCYXx$9)+q_6s)|M*d}XyR+zqPD4Li{`hre;$k8lrz0{ z>R5FTpJkPy|GVA@UFx^%$9GlisJI-SbM);6k>hE0X|k6$)@SVYv08j6Q0j5mgME%| z2UqgGx5>DDx_Ileru(-&?7zP&`^+|>_ITMF&8l6DO(PFBmObBjZr+QJSBj5)-dLKu zAS~6f?PlQX&6YdozdFBdC%d}GnMHm)OPysLN_kedtV;AzrG0TYa>{Yk?ak?Thdp=N z@4jQ6`>I-hQ|0$xZf`Qad?~-7w7hlRM#r8)#~Pwq)89Vv&0i+QIcV|j;_-8aE3Mxv zc%QP{c7b#GeTo3*GA)H$MGDs_0*90j3W=XhUG&Rfd4Dd)&&2Caua6&k``o%o$LLpd z^3cH9XI@dtU!!+a8ug71Jot4ja`V?=-|6V%z5Flo^P8ofO!P{f7*Z|Hy>X0Bqp2bL z-df>-s0N3(6!jy=l9)f6`5(W_!)y3YuERp3_MR|<+K(GTPK7SZlphs$J#Nux898xa zbi>&j=VZR+l*}pfooB9^&1xi~yM6!7x#iq)>-T6V&^W#^yL0KD_ih>-{qc3w(D>lU zrOW%z1i5<|s7vl+^YXMe;`X!Klb-dJ{==c(+spku!)Vcs#;?A6QZIay&t2}Z zYfrIOpmP$|+tOgyzvPY5`>>sbPEO%Yd`&N8Tjb63j+-50Vv-TIGGF}0f8dMhM~lVw zrJ+ab_3ZE6dtTboRdD-|X^DPn=E0px|6B~Do%OZO3RJ4N`SJDJoX4>YXXDNoyRj~F z?b4J68MAn{WcGnL7Cq&0!|M$)T#wz4nkFfv{JNrEayg`JM_5s|(iO)X8t;Js-nZ?q zESE`rp>f>UnVnmlt#saTj`XOeNEfVJU9GBOYg^nnG2t9>NXNJ zeN(k#X9ds6QWptvhS-jQ_=BmV?=OZisT!Wnc{wFIN(ax~emoYuA4NdgxDM z19Hjr9l6EV*A$#`mHGXVrl%V6Wp#0kB`cU)>BkuDG8+BMTj_^6H=L}EKe6VNsc|-= zMXG`I?U~xT@ptTV(=g+gdec8M#6=tmig@|8xs&vxDeKyMj>w1ITDrw7%i9uD{QUYe zHQO}n^=GwLJ|aO^H#;(VZ7Emm4YGY|v+nRZJicuH%SE}w!eQR@x0sdiqkca0 zobK_A9czu9?oA!xH$E}lUp_t3IPhj9U*gHbS2nE_jyK*7M%6IR-166sbFctvagPxKj<{L$7$4c zb_BX#UK7nq4HYeYt@1T+@~Q3z7wrMfB)_eC4?j8fSSK&> zW}Az1pg`|fuW@hZbT{Ldw{O-zIa4zB??!oFcBMWnNI7rCx@P>rjo9y{6E|tM2W~09 zK0ozfq)pX7dQ78aU`navy~z7uk;M|+`BxtA{vc={(-%Ck?(37Jt1WK>w>{!z6o=_* zKR;$vkm9yk_A0Mr#qOkI&m;J>R~jna&@Yvp%fw-^bY*l2<(|@Kv)#6SePM-F35J_& z#ZL?GX;GNFD99_~{%Fs0w*9uB-w0GOSbo^G_C=jt7O=Jdji;+kh?i0RRui=c29m=9 zPt81nZ`TR2FI~sIQf9}Yyx_0(t5)C9Gj(NtYQMmJD2{hjR8OtZzLLqSw)l{&(Fi?XIETPqXpir{qH*|uBY#BsT}yeevd=@kJ2aJd5;P$PHeJRcf;U= z$kjFXB5bAfw@PFPAAV%CLoL_zzEtGx3KoxziFLl)SPxeyhxy2{^_)9&Im5ATn`im( zZpP`BYc{TXE&Q|Fb78@krmf#jm{_%Zm8jnm%rQkFaFL<0iEiihai4=B~KNV=pD3w9u@! zD(u{m?bqj5867qm@wy`5e=XvOw7OU60;!=5JnP)o)?RMeEpYVI&f4TNKGLjv6mF+I zmffVSFl3){Lg%03gL^XC?X=>wBj=Sy1TS^lwVc1bcecZdS z@WjpiCrn2i?i7B=y;TzR-QzP;rpinI>IFxXU%kInR*^Vu`@+d--%9T}%)VWci`0%h zi%xF|=#UaB+OsW3C|B+Adev`FQRw?w&KO>H*yb^N1Jc`>d z_zO6vNj)0=xS3M^@Yeo^=Q!nqCoE_u4Rqu%q2K~L0*$f-_-@@b$Gw{ z^t?KgHJ;LCzkH*(!!Z$+B%9}*;;xP23Xjd+7arVO{!(9Ob%_n%*Ao}b_I>C+<6g%j z<0@Kkmg)1HPix-wo@?X3pIH`H6@Iqr{mDK0M;6y^`gXl)t%!>2vR%W$D<-9e+sm7y zf6dW3745RHa0A!PjcJFj=)CVeIk9DOF(=JM%l9*fuJ-XI&+B);yEEjW*Uc03k$GMv zB{*bZubc15gs~qN%-l|DtJf-NAB>_cS;!h8QKskPQI zyTcYyEH-jmU5MNM*6!JjBNlExB_)UMC~_@Pwz=h@pXGMl`-OBw<;Th~Sw}%BvD4U? z1K+;PojY|aBwLw>GuuDBk^8o~$Y$6x$m6q=RH$QE+J{|1DX0GV6xZ*d8Gl@&t{~46` zjuysxy2W-a9AEXa^PjD0BFBRiDaV7^bNiI%>~?(;zsZ(8xl(O@c+-YdQQ6XphImt^ z9-Twu^690QGP0hh$%$M%Z)A{Zb8$5OwaSt>dg)oYeT%xh-Y(w1?^rl z&QR@jY^lWowh_+_o>?qXaIY?})jWSsjIwT%p4R%fCVj7kE?i-Y-OrgPY@`aEHeELG z;_KMqkUB^rf%oCntMCGrN;k+QfCe z*GHsz!}!FCCANVF9eA35b@>OD3Pe=Gu6R-d=N z)u|iUT}HL)RJ@(acVyrCxl81o*PIf}Sy?RdRl_Z{og?jXjVD$vm|F6S?b)9DO+K6X zPu;p)wEDjO`Ra(OS~0T+-)&wzWmdnwByK~7WSH{9s4Fg`W2Ls-4b zxwt~O?xc;NLZgU5BgJBFm*nYtG3z|1j(%1VFjn5vyENYVPTPy!zsk6cMik|jO5E*L zIq-tbL+2#(w1I6E=k5b*+br9kdKe`s>vvs<+x;tjXX`o}KJSCLCVqc>lr^v%y)D*q`;+X0V;XKAaVULP=4 zky1X+J3XbVw&0?6IVg6^`|8zAgKj$?khFiE*m5xa`n^Y8D+_j*+q$)Ce#=j0a5a7slTxs6ke@t~H+E*F!h%WT>0Pv*l2u2RGg*c6Rw(6-Tim==$#mqFy=hru6Prg-yp>lIZ@yck$(%@oM<)k& zB&b;KEc|ujac|u5X6E>WEkZ2L`va0o4>~pa2(Wcpy-c;}kT^BDE_&0hgX_)bSW0ad z7M}cAq$O3Fv~o>Bu4tu#N!861TiU6Y`O0Y{Yv&7?iawvCe6p*OHQSYC`=gAO(f!v% zmlxBYGEbSiUeb~Ob!QcinbpJbR@*pxgO17^HkX&IbDVkt#wp&bT8!-*G%H_^ZOjbB zx`abrw|kbToocE+Ol8A9iHlaXUr@SKRwj`3^o}wA>TMnKR~6mmIHCSjs%!Er?dN`{ z9oGFfi$xCJNch(KEBV~M6Efe*m9|fW)RkT|wBIYU;&i?14ehk!r6GG3$LTxO>qyTH z;|tolsZjdt0MmMz$AU&}GSS%@7Y^MSI&m|3mky22!*)w-@P(|%gVj%uaS6XoeIYos zl6%(!bCdjnli_yt7Pn7+T6VH6m~G+w$nHJd&jla*bN8IO|KmKzk{5-%92akH;c43C z<``6RyxTsU~7S|B#(bF`Bg)s)|Q)5)5M$2F4)Zzeu_It>?3Pdg9C_QyW1VFlrA(or40 zyYC{-US-OXludL2hYQ>D-v5wa1SWmIH@0a!<}vC@A6?_#|r`zbZ~QT3_<1 z?udQ#J-#`oAG+)~=BE{6l0KPm!F+yqbfm(_j&l8piBk5$%`Xlp-xl(Eqr6c5<_&Ax zHJn2)*|fE`ilu&jV`V*vMXNlv_bz&oU%BM@`u%}RHYb)1U9A?3N>#vaOZK=Q?yq%l zet+EJgrvup!=IjPYV$rNUn$7TZkd<-XfFG`Rkn>gVnnYm&^|fm*^B#ILTGNhdYS2S zzbgf{M%yksyp<=Ul7m(id{1M!?0g-D;<2}fC&qmEtG}{*`E}4IAy=X0+Va)qFA7+= z=x5%3f0lMTi|1XF!~)mHEvJSK#+-GH(O+Fq!CG8Ws^_zGMduIhld|pGnGW&mpVT^K zWPbQ7^~vF@yP20PZYeJ_x-M&?t(m2E>BRLPq9LEt`c>D2*8Uj${{BL~2x%==1H)N~>6tb?Fzwj+UjZcU5G&`0#)TohPK$iWAck9?HF<5$f36edPi3 z=9ONZt{Q5qeMV2-9NQoJD#%vnADi2&;vzNId$N4^VROn{J*dgTn{L#(YFCSS<@^=B zEI)jsy_d5kX-U*O8OQZpI&a+}{P@MHrG;nj`+Bw)?GbR!z|H3yC+^ILx5^)S$jOgP zn9@#`T^HfxKD<`z%=@+?U_Nu3yu?jdH7of>vP5~jl&qGC1sOk(R{DBBnQQ$v`pUk$ z(nYf0QZ8-wKlJX1Ev7 zdGmZ;)@HUrTb+RyPm&+9?Y-@~a6`?bD(`EwZ*O{pgZA$Fs-al-TJhPn$9V0tEyy<( zW)kuJAZ^Ih=rL>&6OeyX{Ep)j8O}EMRrg}n9B){om%Q+T|1oDvDd`*g7dw?7{ilJq z_1M!O#n;wvQW~T>;}0GSRg~Bht1>+JNr<)S&h4m^kJleQCNw%fhwC=GTk0}q&*9Q7 z$6ot9Nc?so>EOgk%@HFDMIFCln>w+=aj(P``A*g>9pi9Tw_SXH@x`ECpCl@^<8%>gv-lR42xpd!XI9^MiRo2; z-!(6{Six{rXo!BJ&G(OS{dW34;+9B>pGZA6=IpZn*E5-KKVIxG-}UPJ+GXQ`hib2X zPjFc4`uW9ZikI5>{Z%M;1Z&k4lym}NgkIK-Rig9s|)vjk*SIa#2(i%%HJ15FL&qW(p^lh%C zDHpr>Mimws4XW9UZrEvL0P~+FstAVy5&kUZm7%KEum)C2am&2`R zpjL%Xn!Lw_3hpS|sSn2U*xWxE<$vZZ_O=6a zh{d<^jn7}H{_dr5fVy)e{Yoy=GM7;;t#EUNm=+bEVvgb3R0FOY>Z`D{t<6OzZGtpU zI#~5R*^RxvH14vu_!L{T<+TV2g{1|XQ!K44A7m@v+HE`c%w?f6E9T?#UZ31%VD~I< z!ZpoJW#jE{(Fc6eD(YX`y53lTzLu3wv|*vNRL9*C0m6-qO1c!^sf(=_w?y1>i5@nU>RO9zH zJCRr5=b-Xj4{1I}eudK_dync|7Bn$`weC{Fh)p2>nsmLq10uO4XQbV}?B+T%*JN^i?u?ShQX9T^3S1JC47_Xe!DAM&W=mMK)d zHRK#`UDcqm>(@$R8m zL`+G`r%r5^-AlWWeImR#Vf}$&8dZhHTp{fH;Gl`bMvFJ0dvkU^Y<-j9ATgBn_(G}g zW4#nDg%Rd;Ix8AhYU+z?4XoKz8vgv+*7+0jmgzqn6%H+gybB~x7p%hQCxUOtU!Rn{Dfy>JcqaV zSCxKUths&5b60)++>AXdf7aL~6TTt#*d4Kq62?uv zvx{PG%jiI#ra_(*qgPoO9I*e9jmZugUUd3{I&;80nBV!`F zt_=p*x}MKDvh{nN?A^gEhqsH=AFb*SVmiKDeCnH54jsF8{E}hBO+jS zOMi{%#{#QD@gjMRWq!h(%;j8}Y~F#v``5QI=8BYB?~XXzn`-bNUgU|v4`*#ju^;nT z1N+mhRG80w+**2hGxM0IzDKcEuk3=-V%7um zopPPV)si|&4X!*^L}i zW7W6S{vC%RuRP0JwSV1#wY`JdB@!&=x^7GKj+R$0(B9^`zG$IY;=P2o{%aO5wiR4j z$FjiE(EpGI*N%?yFHSj+TV;Fhix0AJ$C{UR&-b6*5g@y_!*BlUpzwxuEHXaI z&lc?0O&c&NVS6gGQ&Y_}U1Y`8ipL{~ds$bcUpJI)wbb}ov2W|W{1Yp1@|9}( z7B_H!E-$ijn_^Vm;$u&aNGx};XPvj3JK=*CrTkOg=`;TiLqNR0kao8p*ut2MD;@Y! z2g9w5hnn-J9+}*bTMX1}u^f@b%=`G-dZo~gkKe>`r$31z@ncbCPCEELIN=q zK9uFNzQ`Y&lM(TlLfnVG=WHOVA>YC$lISoE_uyXAkfyVv)Iqz!ZjkwFzWKlZ4d49R zf8v{e`!D$h{*!N@Klui57#{x2(4;C~LiIvbRyg(kNz>igS+uE&H2;zTp&}%&kK$OD zZN>PeKEH>>k-y@7Xj|On8p}YaA(j$sd|oaEV`r;P4YLNy2)snt_~>0p9%fF= z?%V1L>eIGEWLqWGW1p%n*u^en5e?8|YdDRqGm)^tK5)vxw_2hCgI_5TFW|fedbvcx zys+V(p;d>3O)uxi#Y0$#MyR6`g<@3hIS&%_*GRpUA|9Ki=A}d zUQCj?4kP>Vf??!vI_Bh;Er_@AC@Aj%Kx?Z>f5Pc0>e;0frI>>OwzbSjRW#`lA}LXx z7^w6Z`9`8TX6zo8`31ihv5EK7IqZ62P4HPk&8Rn%1~UG~5l99K)7I@uUDc&wK1(;q zd*A2NM>sg(27alwG@G#jK0TLrKpd*oe#)-!IMO+_T>R!L*;D-3<1V=~@!4>2W*@5d z#$qPDvUXE0Hc`try-yYlhaQ-dq6-o}-Gy@4KmLeUkQ$}mJ1A0wB9EFvv;~ahL|LCj zhg`&g>p>$_y7I72b%-gvc|a~nJVyt80JgxA)C24`~_51wG!s5%D_@oNlkV$ zAa__5#j*hNTZ;AKUM|vF$aWKw2G~wY&}Dvxa_A+HPP^#fuO;I1MM1b@!ImkPtqYXH zS>&8Wy-tR*a>-e;J@8RI+50%MPoKotNbY>gphUs*V2F&^sB9{so-skBQ*c3Gm*)+r zPl%IYzUOW-L4jDKAhpxvL{ROtoqBZ70~&R=5;-xT7-|5Y3TC(<^1Fy{NJdgJB!d;) znNaZ3b+M&#!|0vn!HggD+6f@HB#|li)JMANDI;bWK)(vuKTvuh3`!?oxBmeYal!~de`NCwhn~ytl%R#6vEX5a!#R=7jeD~$`wUnz@U)X zi^gZ0VVS0@HHTuK3(B}Njz>t!!2!ZL0g0qh7tocd#MHJdWieCV`k_^e7>!kU>hc^( zVi02 z8mMubv6Tv?+{!flY>qj=Y@GJ=7}G3FdFn$WV8jrcGsoc^f5mewg`BX40`ThMqv#J) zQ7LZ=*j6aDdh3x2Vp;R%F{M{{paymH8N6)kqC8tu4v#CrrK! zm|i_=0WH#5LI#Iu4L-SF0O=|#f^b|p(93fJ9HD`!qJY*)j=mnfTc zH*l*ES^peT5*NbZ+wnH~XmOfCLcw{YkE4;EHP@HOyR-L^1iPaS=lvbD$N;=zPZeHb&($(! zXZ8s{Yl^E@_D%W`)CI%T+{KzUH^gVHqSKwx@C)`Wlo8wr5%EzsYzR*V^Qg#Gov4xd zoTV;Gi*^5a2+@M1-L)m7nnVANmip~Vw{iI6@t50m!Luvv0vWmyht7rSpaC>V%yF_K z4FGV*z^V9-3n}uQ2-f^)a?VwuFt10cYgmGy@GTs6lEzIKSd%}Pi9qx#N^QFzEhJDM z8iY|Et-heY6e$2cBW&xv7EU{|z~kC3a|myxwuo0AYSS&@a0h28HL+Moi5193zFY1@ zNQ_go{Mx#!Kg8)$a?(P_0imcBf1mfGK?+>iOeQ`&k&(R_vjML)Pe!j$LSikaT$&;f zHkzkA-ctGa9j(PhyvlV!BXgykgOMXxEOUH(wlCz8)9SIIP|HsE+zKS8{3*qnXbu>_ zfJCX|rIMHDSi!g?R{yyO`e}1QtO^>4D9Yo3g}Q8MoRk+#I6#Y9a|tQ$nswD0MA<^+ zdq9Kz^;SufiRL)zgzWnxg!_m@uy{4;dd6Cgkh4Z;uHY(YNVk*(6euV)@Xt6pOQ%oX z-U@UQP+{8{rCFr6P0j;!_!P%)GELp3d+ZZHH{}a2fVd2xypa`hKPcSlz|q|B_(-`w zs;(VPn#(_ zP;Ndd=GVCJMQ^;v2`1NgV5Oq@J@8U_^Y|2h^S(u2&d zGu#F6QMSe5@BgW87#vo$84)m?RI) z`~#zKgQ-aQ2AmiU_r>g)IxR-(;Vr!6Vc7| zKC%S1^d`zN=J2Z=Q^hwmvLBvWcC|}})fPruf3Fvie?t?Em~=17Sa3HIRljADZ~12u z-&z&X2>4or6}aQ+U~&KmRkTSDchupZAN6%25mj;h5R&9q>Kk5Gj7+(G!s);fAb$y2I2n!00960#M#FVwAz{; z;BCpax+j(|!RnDM2ISO|2ZSQ$3^OuCDvAtOQP^U+2MEZ{~UE6$&zIxgjSU* z!Q%a%ZB_OD!0Vj)|Ok?Nx0`twfMfmL@wQ&2$$BOsEMW^MY-hiqDgrMz$ zI>60!9d9QCly1zZYuxQMgcI;d!_)sHyc_KwUOX$v%hw>2D=otN_h9RU@n4~o^g{vjhRtY*th6G{ff?%=w8!L z#udS9EzA`2Q9w}=0nzb9I^5G}(zW7(0Y;N*r!DZWRj>!qTE&rmZZww>2um|{hw*sI zLl5m6OV+8&mB1hHwI$RTjN1vJ?szv5zeZ zKErrT>i_u<|Kpe6w*T_%|MGXg{PLfl<8%1sKmPvkFaPO}@qc*sfBL)MkH2pJ^^fs# z4WF$2$A7Hm&)}}}d#wNaKa|QHh~2u2P=Lkl)|C#!rA?6f{p&*;a`tM@)b~2fiw9Y} z-VV}P0i4HV(PZHUklXfw+S-;!hoR&~YYuFQ1%Lr_+tlPWqh8b%l0HWsQSn*0om3ar!foTM*dmoJzG_#q_r0yq8Sd zRanS!Qj*LOj5cm1zv;OjIYkWb5UPxd`Cuy1QLXp}&tf$97iy#YmS2tMzvSw>C+qiEu_;0k)Nq1J66A@{IJ|0%xPN<;qhi1f zjqe(wY8t|5QHpqhgRV0GS;ycu=rRr^RMy7&|+FDuSYLlID2MAU9GiN&$2-Kxt1*{7W* z7w?2o|6Dk5C?OH7$wMwaaE0SDlyH4(T+m%DGd?c;JcsMHTN6DY20|8fH02%++o!6g zR>~ZrOwVNJ@Uh=868?7K6aqsGyv82SA>HMUeAS3Te z46nUlJ^VmbERK0IZQW+sxUK=ltC&NJT5q`+EEAT{5A+3%m*`;^X66Ewc^;R2l&<79 z(R>2Rgttzg4pYOf0axb6KdskvCi_|&A?&_a0HZ5oc;yfoFf)bu#J6WbJ! zvhmF3Fd#888N$vQkV*h|xV==sgXhH$fgQdp;r3^Lg~!&t6UA#G`;z~Oin$cjQ6F59Ladt1z5j87KB#znekjt$QrFG zznAUIv})a36>BI*H>S1J{*&+!nOH*!rx54uX1rnzU4>SnkJjcA<{Be1xTM2}!H0$S z#56(!7WR-RGl44$t;}0R`e29VWr%o}V9c8?TwadOwQmc+t5)-R%K$Ia@Z9o&1kvVD zV$C$tW?9*3s1@oh<+^WHCq;WA8A8BBuGR1oFt5zRJb_z;H7ORzbpQ<4Gp0hmBDRgR zUIgu-{99Nzw?k77&D&!xow46P#4V&Xf(0;Npy_Xhy%uTnz2TvE`~66UYY}_W z?GaW(1j2-H8W5kt<>n&wA&zGKiZfhnQZsi(4WKD07DD3DCB2a6OD}bOr65#x220uB zLk$orEbr_SngKmy`2$`#wHon z^QQ=EyhV#aN8^Np8#w_5C@PIiI1EZ(bza22b*3)F`kXWHW05->4(1D~8tq#(TG#~1`$xoi5(aoD)vW4Mk*G{F@E+*Ukq{^?gb>9S z3N-ar$>zVtd2G8R8&L%z>_X^QRMp!DjKWqSfeIR6Rn;i|vTghhP5BiC7r8bs1T0vq zgsiS<)>mFoJ*Ep(8}203k1U0+#-{}%Hwv~FIg1h3fI1#IkU4hWw-OD20~oJ(t7;Gi zZ*(YmW0Qb#XQR~|_t}c;s^(DQ@(>f}r|DIV7~zaKkgjbO=27X6AucQBHcf|vw+uMy z8DnC|RW=CfS0V)tX@wKkUgt9xnz$9N9U#XuSyEu39BFJqj#J-y%u*^eGNw2gP*z9D zZqFX-d^vg|^z}?D?QUU7aQ4W6iygFSNcDZ-SNr_Ga?k7k!ae5SaF6=$x#!c_dN<04 z4=y`=rGuz|y}xt-9>o+mQbP(gI(hVH?ijC`N{*4QKqe}?0h^H>U)I9-7DY~r-vl^_ z;#~K{%@C-HlmQ*x_CTyA1H7i4B>Aazq#XMWCdB}w9>e>oMo}qjMmSwoSZL&)v)S## zZFSHXY`m6FS%NHk_OL>8hCsf_Dk)7O(epsW@Lu24??AzeF0D`1z)B0ckPBE=mWQy? zyKZkPZ)Srg+{4u2TpZP@8Z}20dIaN*+a*eSX7cO0ogH=?9f^{A7r_q0wxvp})8=n} zoY3}81>LrLdN#i3ZIg9hWl0Vjk(}qwn8|7n=;&J%jI-Noax4p#&kkOCprGf4aj=E9 z755A6W;uZ^N*8##wPGmI42M!bqsyjhd+o@0U>!vnM|3X0soBx%t2FBy%oKip5Aq84 z1K@WyQvMa9yRF%@ z8pK`dANsa12mIevBhHDMCjU*KGIo2KNSnZsQ8^cmqHs!{` zjz-ydA)45Bm60agO2B}3=538Be+6m`#1M|8_7`d@elX3%;TQsXZJwAy9cxe^M`x9Z%7v0 zpWH*B?hp4QKfCArlY6YcaL@Z+-P8Qxp6?j`m3!82|GRsp-`vyvt9x)0ntpYU1f>7R zJ=`De>ES=zll*WGr+ag+K+}AGUIgi$`ZlZJ{s)Z4liXf}P86@u_F{L!|2m3jufH&5Gi1 zztJGL5iV}WNJul)^?QTM`!F?em8KxMYI}Sp{7f)C);!&vA~QrWhn`!WI$C zIU^*hnd&yud3BLoxDg6^TX?R}Ao+S!dU``IQAsvU+r(*No08>VQ;{5cq zH*Ft4!ND9VZ>p*oJbW$1Rjryr+l`0PG`U%=#Gst1iqp-SEH~iJamXgRy)>7M36(Yu zZ?znFRXw~Y91Q!ePeVKl7mhyNDil&b-1Fc5{@-`cKmUb${`vpMdQU|$ZwFumF$JQq zl2Gb4XZ9gyx3uJ4TI3y7DUzZdQ%|o*I~Z`=d$k;p0EC&Y2a+nGj1eAks$MeqwJ%>w z&Z^P2JQir@@&g|@V)f&^t{ctA6|od6lqRjdC%hpAO@xIIO0jncLRosB?W}Vjs5^x4vH$17sE2;IQXHm4#Y z-h=_?_<B8pzU;>j3VhV8UPtYOxdT=TqA`7DE$Z zxzh%*TdHXwubY6qLkAs%(>H@YSu!G$GKQt9>yo%%l&lbl*<+}@s)Tw@#Fb6RGl~1c zdjtBkxhWRBJX$99=xWHU{5T?=9aZ_+zt#2N2OyKCg~qj=`=<;{eKaF-C75CqXqc3I z)6ojAQYa_@#SX_%VxU%(?b-cPHKnK6fSr6Jljm z1#sM9uQ;r{LJ+ z$8DEZ#^$6?_2HLSDT?%~JNHHt-_qz5%?UGjO=G#xT>gztSDfZpDO_nQHW7>DM`@ogW$hv!?qWBsEnM+j3Vf!4b*>$3Nh=B<7s|U~D>tnH zO?0pNpi)$+Xr191Vk}KM8zo!XQGkA_&y9^=If=yGh6D0`PXY3g(HMEyr>Foc>>NF+ zIky6RgfR>JMG=%(r&Whi5M}Do&4}zXl$u?n zeT3oV_BO}Zm+9kf0is|uLfLH-uWG1V?}*?rk(NH{N=`(Rl{ChDk+#WjwbOC%(0b>& zUG&#xJD^mq$tkP?B~V{6{B9re1L7vI0W0w8?Tf%n(Cts9h_nsCyrMucn6v>`6d~tC zuc$tv%Sgf94RhffAjGW*!XwsWsEsLCAO7?OFGExxI4K!k75r(1o8mtjXl)6mUxZH4 zC1<*Y1%~BQhZ(`3zvCx39{$J=f1uX7!GJW8B_4o&>n~d+fMH}MQRjjDTo|&ACqkMF zhstiCT#`FNKpM0~%#(3S?MtA&owmT*ceMg1O%Az`2vs+eSwLQzUWzYqBAb=t^%P{% zy?y1jO-|mnRaiA{bk&78h>@X3qRPULQA1RSMs%ArC)-d?@jesy_Fch4c&V^w|M`Eh z|MfSVbpQR&PWpBHZ#xP8)k)B=>qCIcykPFzO{!uOsvoJc!mHOuny${teM3{E?cqp? zRh4z_TSDLEJ#d`ZHs%c+kDj*Vb<%x~xv5gMEmXBQm`J?FhBRZ&9Cr{G4$;_EVI2H1 z$jk8XByIhKocy_fR5F2Oa2U7SB!eNs5!B0x?*ft`Hr|43vO3sO&U{*dVlnD=SONzt zV4LOrob%Y=Ru%f#q*p<2%}VBchp}l@RDey@- zSteM7jn9u5Np(}%fDg#xbD{d+tK9Yu(-jQE4;vv{`4xhXYI+kyy{A0MR?(33#|q~> z!6;HOs1@@?zpddV8GLWI2lATp9NIgXq|f$=i{egt>a@a?N!9+?&G!}OE#Mx}gC$5i z2xCefELqId2G=M==DF{3^1QER5%Wc)T9EP6`m}!qisJz#M{WD9t5m?f&s$0&-FkP& zbVtQOn=ik--vai(0RRC1|Ag4d4uslv9^exxiR=ubJcCDx7|?f?JfLq2D0-OD7Jc78 zVjjsObMC#C>C8;30Qmm-`d|yY`p4(ZYRZ4mJK?1+bg>o-D(&eezGskkH6$I zu@B~3pg|L>lO>)6)KOD56AWRrUZ7Pe*X$jxAEK~Hjdi21tpdKV?p{f-ed6W&U`BBcr(UhK4u(W5jtE_gV0OOn7I*f%t= zF243~MaO;y-<6e#EGGVp8e}8(MBbc*ski~DpkDwva8r8$POrriRg#)zC}y657vl!f z7MHTzp(mmsN(}2bT-G2m z7_O2hf|XT@$DKyk1N^N-`U}`Z)WyQw7*BdqvN`hxOGB%cP=<#w2ERhUx3rtxaHyc;z zTSbzawkzASqLj;{4b&X#%??g!2g6OvKLifqYvEVHyjjYNpxu_u-xQbpV?)*&;j!xi zD%B1A1+t%WjBS^2Xt{|iGeuIqo2rsu(xrT_DbcM_gve8o!Xf@W_yA5J` z{T?9#IL`YtG=7-3(b~aa+wqr90_$x zI$$s~q<5T;f|(U)M1?niR)qG9l!da%<;Uali=tf(Ep9b!dDu`A$~nky0XJ=9tV&RT}O2Q=H z?UxFc#{0`DJCJ7K?JG1_WV$a_7ub%xXy!nNwvD;t%pOQJ{vs3)*UcZq{YnR#r!;Cx zzL*mO!akcC4(b{u%abGzpeAt!oSXph?7u;8$7@QvX?;MKKCMRlbDhA&XC|@yl!v0? z&8b@D0cR-#)PGZku>)rIW)waoXVeVG(06>x-1~5_r;@)l@Jm~34>3_(R+{<&#tIPT zQfS2zJk|CSowx2|6~Zg4sG@1nL9gln?qD87FPK#U+qL`B(mwB)1-!TWG?tpj?rHZ2Uto3Wt5{N+m(Q~76;XkJ5L{+=PZigQ<_Y)m6 zwZQmu1d#<70`ydeDB{qrA4t37LO{3HFJ)GblrO_Hx%C_*Us11_qSE4Hszo>1)`YEa zML-%+f-AZM&(`cujat-wgQ>JiVJb!HYTjw=%h7QjnPCVaCZAvM)_H`Blu|0MPsM`B zS%0u=y@u8*D~3P8`@=l&7Br1ci1gX$1DqBrh%QoL8`#zh1d2(3Yt7y=fL;ef({S@B z?(0TA+{CW=;3=^>!4d!TfByK(@ju@a`X7J%@!#Lie|XRT`q!`j_-}u^{x9$OumAYh z&p(g<^|$Nw?#HzG=YKAjv3Itm9)AD(p9=NyrFJ_|!N!bboB9Ulz8cIq_o`JsPW&7N z+cZ^k;?ZeS`>Sjs568hXY*2JqX+Y0u>}Wj4b zha~xgjTH7k6W9I%M(}WKIrWgzQmM@K?Q!rf@deIC48T{~*`4ElYj!I0m7j*zr*D0D zdt@*QkvvpDFVfd?A^XuBWt!$>ePf0&gA?R6rj^g7Npkx&1280)F(6x$DH$!@+e8Qr z;c5A?#Z1|1Q+=X8+5-0HQx1_0&Y)FZNj~WcaxqlAN$Ys5B@xLijiMNtl!|M-_Ne*hwJJDJ zKGgYU)z5o7YGo}kO$F^dc?y57nUPKC_xXgxT!p9MJYfGJ1{}Z43!o-y8Yp^lB>lS3 zQ6>d3j67*vjLn9CBux4ST^SW{D?`z&By2wQ_(2fcDI42BM|*{8CG5-Jn%hp1?7Y3z zZpojY(k)2b3Lbf2RQB)=jf|a=-YxfcM(?|}=hto6>o!I0peyN16ac>7r)5HJ*b$rLVFtZe$0XL#NX` zTxz^HYNv>SP$<(e5)BcSem(z7V^pH&La5)r;uI+ixKxxj>Yib1a}i5WF1;z}3u^He zU6DjZRIyBt`9nob98*zBz^z+yEQY4WDyB}V*z5_l%AJv6R*}td`*8Fj!*FMvpvYM% z$4<=5L@KOl49%NyKFK&?2AB-Ua@O_}lzb$%6Ak*&T5)`+);A$d(GJ@)P|AAUh7Fi? z<8p+n3+}(k0#hGiD=rsPFeitOy8JxCO(rTKQkM5B5@_IMbppHyJ8;^*U<4qtUTfx9 z3EyLo=8Fu!Fx@Ux@VstQT8v!As%teYI>>~oKDij`#|WWm;@v$R!mBVTdGC@lKy(tK zUgCjbH}z$WBMZphDt+%O0aw?U6>=|TN0?$tu5;td@t895Rjn5;q&D|Vw)Ujo;#&@# zE<*$2qH-m1)APN*4RO;}Jt8L}m{?3d|G{nSQDWZfHleoI!s7z;(EG<;3G`C7o$gUl zq$55KB0kU42M+62EGGnnaQe4pIv`*Lz1P=elBr5}WU;uW2ICai$N(PEKZ*hrqk|XY zXBF-jUd^aEuW9ONn8_i$L!M*p;RZod`xt-uSn>9Jv)IplV0gs1!!0#krp?0f8$qPZ z4){$j7>Yv&bj4-4sHV^b1AcbF`ouq?c?uqY3%M69Y9&IvVhRDKIs6I@;8fAk;;REC zE>o4gGX|e$elE*`@DpQGw^a?G`Q$!57VOa<5rT-*8v^o2MDu>rSCF9{El^X)gbN6t zVS94OGuGgc*T9k6MtA#j4HBj45CGUd{EDQPCjBf|xd(GT}Y zWWzY2VVcyzd;WYqT0F{NR8(FE4i*`7HIemiPTQrN3iaSC zlW-4GKLx=3Fo`5i@C%b`Cr>8&g=YGBxkcZgWrPV666{*j6rcx$Wt8Lcd)^31(0NG2 ziM$wnNlfu*C#T@aQ?G)<;%_0OjNG9w{?HW_gxB`O$)2Df3n2St=}G3QZxY)%ZmjRR ze4Foq>Aw(-Fm!UnH{OWo1FBs}ZF$X7XSAY8;s)QuQXVwdakC)bM9N|F-n=Q}_f(zl z-*EDl#V6mJf{13uQ6a5Llvq)u*hosAN9}@D03iyT1q_^9-%LYo&nAAr7~n6zJ4BwDrY8TCX2%1gnK{!P)0L_lQ@cSDPhK)w6Jhh zj*)ISHk&~QM@2cY$G}`tWP?y+Q{~`8i@9*26G*b%O#qrK`Nsg9^Y>uH%nS~e2N+5K zvG7-dx~rCyzp;a|0z=xmI+++M?fKM%p#>Q14!=*o`Df&Has@Ay5Zoa>x(G1r;jv&# zAy9~}`K0Cwl*gE2r1a=BjWD)afMOZ}@1a(ZPlr7?q7eSESM6IGpiiVw%xt=NlQd7j zDV0F~@*my!$3OmkH~!y$_|Is^Z%*t33Z=?AMdAS- zVX;mMm&Ol?#)rco*+^BsKF1Ga3ld=s^Dd~tRDCC)GEl(qpr_f}-bTDxD9Y`|ZV-=M zxlp6a7Fmb81q6xa+o?r6J+&ntn?wh0H=8@5o&WR_FX3adkgP3rpO)J>bj;%c6gv}q zK+r5;?5pMLALqv_i37-m`I#=lgxCgdp&Dp#_v~aYlim6g>EqjF2+Z-c8~+g(=8uzp zYbZ>8t;4q(oINO4zOjuqm=9KYr}$t#(3c6twt!Dxfl75&aF+~M-Lys>Sl8H|tv_b% zf0cj&pr8xEGJ5@B0r#;3ah#@f8GFF6-RB9w!}`CgCE z;Z#i0ArC41gD_}b&LaWVzZ>_Vl$$m?aUU%g@mr=O6P^*^`_s)zs;A6)))kQju+7*# zZjh@er%ss-$;H-I+BJN}0}<$ymy9h-{3 zQWZL3)idY1L;0;I!=;QPKX$B0|N1C`t*Q*BZO`oAAWf8uXb37fIcfFZr>~)I zN!A(`J3JVc!qO@GB$t^q5d#lu{Uzl)e@u(ot`}F9319G?z;b`{EEQ48&K3GnQ0Z!W zd7OV}R)?2Ay?FoCi}>rs+a|m%iSh56!}IIKc$P?5q+K9$spHYOtY~Q}&JN7}cQ20T z4Nm0?l1I2mgg=+_q)kPq&0wdsRD%Np{Bxi0qE|B%oWJbztqULG1p39PfA^xGWx0rG zvCEbO31?{Lg2I-sK$_%(wudW>B@F#}RwpcW^9>T#l97{Un|`SEjQn8UP2IrsE6uJ{BpUy1#cH8E2b*o&u^q~sk>-nHy%Cv z6c>pOqmLu~Y7-|~M6|UNgeP%B&LZxl2VhZZ&7-^Z-J`HhMd9{UhL{?bt)a>;eST@UrG znEsKZI;FI3Lg~N=3G;>0+iqVkqHxAkWq)=tlIF`iU?4xV zN8fk_Z@e$?AJI6->yV7!jU=R5iZM#>pO(DtPxhfF3PPE>KVCe|nWff_OR@m6Vxt3M zKD`9=zT~l24)Ukl+mC?kf$oymQj79b7JKIAEjQ3LS{igF@oR_QgzQIVM58gUB9gsD zoK!w}CpTt2N}$x&Y!mrxhYaT8*XVIu*oL3bh4oLymL8|pn682HFAn7aD?V+Kz$y$6 z4XcD*+&D-nV*`Mazqn7u?E;fe45KIcvm}u3{gB6G>vpdg2tHUQh!s}!XN*28Z`AMf zPhasZ^VVmCYjiq0pwq3-y$HwTShOJ3LPDaz71Fdt!C! zU6R8alJVCCm)NYZr6&N$y2$+vYLeq@yR5@j8@jVF#E#3<1B(HivmKI3)gzF?og zPwG>cw!90l-LGfx^}+ZF5Z>x=PxOL4#pcp)FZhNXb;X-$l(|$4CPC~5xpi0teQ5-w+VUmu_ zTM=-%yb~L?Fa6t-kM>QPi?h#v`A-hI{yz>9|DXLc@$c@R!GAgkdL4uT&bw%ZF8!N> zbnzoqVjS=-?kJ`peCvptmnJRN)I8C_M_>rcIQxq!;lwB(M--lHKV|U8R;s)lQ0GW; zPr76A044EP139_zSjQ0#kJV>rbMcxIy3m`$2hL^v?SqrnPC!wr)F*`cjAs6vnTB7@$i!GmmKalaYoeaM~i;b2RDVM4|mic{Vg0N2&LGQE1y7oy{Q?rKGfmY z*kMvs08TqNzQ^Pt>Bf(Q2cLuvaSQU33!@pDVR7HEtc-%GPxI5m0kB6)u+qB~o=dRL zUkc9AGWotdU)4#E2kr7U(1y2MP0LvH{9WcAg~QB;bcRX(%{Cj!zZQ&aG#&2nMbHI+ zNGeg)dD!`){cOO+h!_hYvZ4r^Zb6QbKS&%Vym7WRBjkiTPfJDkKaUM9751V^d<&nb; z{$=)r`N1rHjmY5J31Q0nNey?V9E%Q3m~V9~L}Nma!F5cAosUZ_KHh9oGj8nzi2>GW zR4(rue{Z%!$`5s{>Ah4Nu?|*BL#6fjtm6`@kM|F%lFU0b2=K{;tYR@a&iv}DH+aGs z!qQfh*FhuuaZ5BTHsr!6VvZ2LwB?M>&k~EQAhB97Ts@kz=OqCSqr*tZgF&^w%4sAh z6K=}&T*g_29;Fmb1>sw<3Ji#h2H&Ds-c(0hYaUdo_7Zm!H1Z|^A?e5y1 zuq4Tu>p*N4u9#fOz4$6v7sn15{VoDL`acs))=ZfT1OANQ8A5bBDqy(m;7|R~4GnSt z+t5bM72C8GTC2Y!*BBS;OxjehUUET~wMVGCr_^se5W#|5~YM4!5X56=y5}R z8w5swXAD&7wz;ufYu?#Ar7OTgtvx6W-)hOX3%T7jkyj8GKE|0baB@DX>(UctH-c$S z7|`jjMpstRt$52)5)SI0lujz>;pvsX)#s9kWAd^Flq+hOS(jP%o3lOTy^}weN$!ED zZ`Q0KQ{1`lq4<0l!Rj2rgRgJ5g6QGe*5Lr%JD2D$1AjRgPQKEus@A^&00960teD3N z#oSsze?dhQ#Ak4%WRTu2D4d-1e$ta!dhb0?Z?5-F9O%dmo6Uv{LcX?EOzZi;b2N^0 z4sD28Q$LP!JEXcFDjys(Dj^UQdGmms?D*!xA$(bL1OpdYLtpgFOuc^iq0U4V!9$!9 zoQdgbf0zW^Gh%v8q({RMb(k%EV!*Pkm*+R#UQylgK_9e@;~MvuRH4e9+`Y@{5VNT7 zT{pS4(T3ih_Y>c*HjuHOM`-FH66v%cv}Q=eMRyH**rFh*dpqMtoJKxvj!WBtd>;_l z?Hr=IV)Z6tF6lOd`CTa@HLvA2zzwc#;ZlM`2Q2aX`aL3prUdka`_u{@X?nvM_!xE> zL0&WZRB{z{EQEnY(!h&Dv8U zz*fgO4@y{+1mLHviIRfAe8OBG(S`xi&jptNVWxh<(oHW?6!S<`;_9`Ds+7`rNDg4& zk+G2O(=Kgqhp&z|(p>2MlXVMx)XB(y08FC44ES&gk%nF z!LDOeR{3}XK;)~6SQ3*Uc@Ja{i)3Nmv7Q!fT~JzHei4j|MT2pkQ4~3xN}J0l#C|cd zcDlD#P9FePyN>hv#>hozugD4Iqc=%sh2M{ZR+~2+Q22lV79}7D$bnK;5APn#=hm?a z+GwLFUEqNFBFmWgEQrDqEG4(siUCh9^`PQ$Om(&~_gXy?L=yo022#kWDEj>zPO<`X zssP`2tKs*U@6U2Kr2tj7^)%b>+`dgGT@&)_I%C+v7=Lkt; zI5{;$vH2XQnAFUL>r-)hx~nutk?iWFKW0ISOE#+lL=EHv@Z@v&5mJx$^+}VxxJI6?2899&PNWIGA9b8T7n~iz`_$=bZ4df9c(v#!D&WMOn zG+GUb9)sLKZuw!&@Bj_51jYS?tLU$h#X$iZF8J`7O>?9h0FOB8&zb`8F>F{0*nF`V z%<&yZxZ_BYk_>K?#P$cV2RjgL;%v9c=Q)vvsBR&JEwc?#g8nIrL{`+tJY3H-?gMl8 zzc^JETiwibp}rTNxNZ-|7A`fXeMZLjcq_GV1Ma>UFltV;k>dnIp*^+$b6DwG>}t34)Z!y3t805a{) zXB5%=@^IO7y>(EW&C)(h@ZcKUU4q-7YPzv0{nQM zb57M;U)A@|&h*S~)x9-WwOn&|w~>foREx1FOX68`T}MsTgZ{c~9vZ&b^yY zHclcb*AjVE9+MXmBFGt*w&%r zf5Lf(SxTRz`;?`Fn#)Zuw4m+(%6pHS7f8&*t?u&|+;i}84zIAz{9RG22FWbp z`kx8eoMFL+>GHW?DJq6p7P|2Kh(fRqmvoCI`Ax2}S{*HUD40hYtW8Vj52w@j0Wzo7 zAVWP9F2)8ul81PcI391HFz?HXMp3G<(!1X0*bE#67>|t)vuSSKYAKiq6(zwcmks}+;Rm{Y=5Px%53$ST5QTA3aL&sPzkb0UBGAVR9BB;? z#OIIsoDxm4{w)uCgBS36EmxeEXq^A&B7yNDS&wW`+mb$`FC=Mk)M=h=yEdF({G_2_! zb6G)pgX@XI&(sj}rdwLW`ELQb%?=!LZ@IrD7u$Q+f!9D^h9XQYKI6CkUWm3(0YMl<9)yco1qkjhO0>GU%K!FKUXj{!t*=iOZ22@al2Qxp)VgNMA>P8`9#prJ-jGn{hZBn_I9JWC!!vy_YcNJViJj{rgu~($ z?b6S(5XvyX37z2XtE2_T(GW6V{V+psB*!?9caDYzCt{MjXKj*#JY1M96+gE8yqGt} zliC?wOS}%N@-7%OSLc{>gnIHBXK`I(&vtFT9qeT8Ee@1!=_SEBdv3sQ!3FQ>#b4F5levR{yU`?V(zHEHp$*?H|w5` zK~GV%=Nphb?T0}aFT(k?BFdYN7X1>GfWEcP6s_Q9rIhxO-jC_?tb{RKW~9*PYXNgg zJ-)&}@}5`ZQ1@_no>ZzwUl*z5bl1t@7Wef(FfXz#Ji{pLmOKWbaMXWc<}eUu+BfliHVLpP-6Kb>9=Q|^V=`$OO%2*|XL~BB--J)q z@T0$Ze-rEgAMQuh1JOEO zG9;aiUVb-#+L~z8J#+na1pi_iABAyKZqK?a5xtxXP<*M^X{As-J(Nse+wp;_c7~1d zGt0|)$eNy(%>oW zOAq0n5|05Qk1%`*fg*Ube_E(!%KYcm7%+_gYy*q0dNQ8h(;~7v@;CMYWKmD+GF9Tm z?MPcO-`YfSz;fTFBL1!@cXwlNHMRiDizCd_J=_Un6PV%p5~Di}Y|jWYk(V%V%b*y6 zs$a#96(9co-qO$%U{45!g1VLm`-C8`7!x+-c+fwJqY>x1ul&F|ED~+hx3m?a8p`?; zmnf!W(i=}aS#DVCbHo8LVA!Q4jgllnZL-r338fVEc$(h2AKtTp*TtWA{!42DlK;ZT zx-(9;PL>#@p3RxQJ8Khg-gDLU>FV=$zAV$->&zID<@$S9nDe|=hjBAzfcIi7p>1*5 zOCIHsRw`gm8?lslI%(+ZLg*Bcjw+97ht9<5LkM*|_oHz@qADpcv)My$C5WhYtd5Ws zpFY?T3BAl7N)=5HW%C0_Tt@;7)bA;=`T$J59 z@01Xk=Vuz*ZrCU150$x}5;Cf-%42t9>Vo6$s=vB%P+J<^|Il+LY>2N1Gao)Toh`vi zS4-HX4;*)!iVuC^*Lo4!=E?m!DeuXghUJ4PO!*tD$@vR!a1?G96IT!HB%Nq@*Z$wn zu&kSo-QRz9ZaP7qDa{EyYqVpNNKr>4ArMu}t$zzwB7P=8MMM_c^Ke>sa;+|$tZJZ8 zw}Z!-DIfjj^MGLKknY5DYhsSdOoO?>1gUu$6y7!?dgeG@ zQt;IR0o~3%-cQJ4?Rl-B1Q{%KKg!}WcSm(W$9Bi`=O^lP$y-scx#eT&p0vys@xIzS z7Ct2xG7(38B<=^DFv)mbi1NszKB0qm!dP1@AyP6Nqj*mhA`9790Wnix`HD!hfdM1x0RL|Z*8uo z(hwN7?>(*P!T!*zt@|w&o&8?nGp^BGc42ANZmP-B@+TgQQz23`1;I+kU&PNrdKsqy zS93NQCACX+lX40OKNl6Y3j7Q*LpiS%o=f>$g*Gkk&R&wF=VBXCKgWbK2HaWv*0eU|%`IvWT*|q1Tdf3U=#V7dt0>;_`1^$3-vh(9wa5&6djX# z*PwWkFTREdG*8mLCeWDh&W;MpHH~UbY*w;gE#NBbtCe56+5D~i0QM*GOki!p%N6dk zoe!3uPGyBJFFvCMkJqEan*LaFH{sA>5aKqU)b=qbfo>SC9>Zq-ZqYv^;H>y1F>}Ma zdZr-W3$KYDj%XxU9Wla#UPDoo!>@KI9j9eyXYp&{8+wOP}{A(LHGMh$^){h2ks=5pP?taa&| znf%M^E{yC=Zwg##Ori`14*->=NXUZ41PDTWP+X*ga|%idg~L(j=5Q-va?tdYu{&g~ zaf9eO^boVbYV$?sA)L5W6YRjzCUIJ=>#J5{gc8PX(Dk*TvhKC*nE5GbCMubO8;V>a zO=f^MwV^(q&cpGB?bvqd%M9|9L2{B0d7HCy(vZSfCb?!e+w;G!=lfg|Pz zSSUi~O!`*@#vou`+ zdGs=rp)6q6w<}W;eTDkc*YhC{*FAhzHD-33I$sU9lewpHV%r~O zws7f2Gpls~(C-YYJPy8WrR@H)f2-2)}bJ*4L;v8Ka1m|K6fJt^+j<+%-We(b_CE^nZZx?F+Y0Y zSN0&N3>y5XG>!%U9rRav+^A$A$}Hi)%bar%yx=}DZ5UDs$DVz0&;@{c&L2uTdJ7K| z;kSq1xUsVVLW5Ba^#{yIA%N^*T{AX{-ga>?sdZY^7H&XKRKACQbEnpKQahUdC)6~+ z27CL^&h#!I_I%yr<;SKe&-sC2FbwC-4{f63)NY+kqb8^Zlhc!58eh1I^EkBGW^lLA z=n?3LkMO)_Sx;;*g%>GSa}}(CkseFGGf~_)Tu5;e7Ujmht~OZy;^Q$V?^lKOna&2 zGyhL-;WyVO?CW|9vp96$em@5+u080F7%gJ@=goL!{xprCw(tE;9yraP>t(R6awvfP zMCc^qv32X`crWt0wf>U(_8`*sJazvT)A5ojtaJ`R!|A+tD*JlgYJomcp?%D^zO?%| znrZ#Dc7sED^=D1ELj-B?e4we7qq?5MtBQv7BxsRWzYAi7Cn6V z!j{j(K&Dn$&{ph%SD21w)U$6Vd7WPOZgRh)IeGEDMI z+PfGPoJCnVq<#UkOJV|VlGW(%^L=v#x7(owGs5<|uk3qG-O}g|$WsQC+WsB({+f)b z7A3Z{6McQ20qx;yG?%gEunFHw@u4J}CsmipB*!e_Vs(*=4}s@0j~!DQO_L(&nb2e! zvtz!nLJq6`xdB7f*L+tQl%jXza9iq@`o(VSA1Z&e9Nuv-wBjLZDC$hab~mr6e=o6W zi)8)8)PWFJm@@EfsIB3K%2vo@EUwy-;~DomZ5*5AY|J^@9SZqL1zjgoV1 zK&0N{czUVSYqVO){-WuqJ}1+s0>>*1-YVO}d1yZs+}$LKc?Z80#Up{kRMGm>)bH;F zT?U&8o@avxj-;H#Rgh43t@vx%$TPVqk_=TI8Kik2gTxeLQ*`|qH(ZgL@lI|UR+x#S zpDHjVH1OAOE-z7%Bo4lJeXN3W*-!h5Qn2Jp?~)&od&M;{`y!27f6rZdxzj?aj>xQ-UD6rG z(-r9WtD7gn2w&*$XSF>%JY+**0`npxC>dM?%@qEY z$i)Kke&h0XgZ*td#(n~G5Na5V&3?S$;@@Fg$-1};OI$_DVqF;`Y9ASJSp%|B!Tlwp z)_NYnbJO#0tKW6?(VD6+u3f3t<5ZO=c$UUlV$-}d3;whL)E3x@w#J@`u!-Hzd*a(!Z*;`Ji_oGp^_BTL!_y`qTJF!MFI^}2L=#uHVD`z z5$ssF$e|s6si9D%&(u=O{eO*DaKmgJrk5JN|Dhc;qE+>Io0lNJdYS2bO%kjOR4;&zDbB!vc* zLXVhQp-U*Be}iC9;7)d+)K$NWCz<@H8TW*XLD(Xm$y&x#w)PCgpUnMjS6rg*``~y~0p{%VX;2C|)0c8b z3YSlYAyzS6vEyeZ+w9Kjo)n~bH$QDtmDQ$FTc9GPomp=`B6U6dQ*~edfkERZLiG(&uToIA zP$&|jty8o@b=3#@!MR{ozEzX0_RN#|8paP&hS(xlysLO=vbJ37D6Lq{rZv)Ir_jv_Y?HoM@UYZ%nd zGE7Mmmme#EMG@_a`i169YezgTl!-f#!b^5DuzY{Pi=%O+3y!@C^#ax~3xKfKEp9JV zp&7Pp-e2x28Zo@Oz*_A3@+?Knt3p3`w0P6HGd}i{_jP7M%dF82m0HYWosvPsdAbZ7 zrPvio#Nkh+UosZ`FtJ>_2N^1xSSb^vy!bgLs62SEBz4i<@JWH!z6DrIUuzb+^?RuV zRoP-8QBS~Ptgjxp;S7}+2##v818L#B&SDYYcr;C#30V{f`_^&*%j~IwMP^Zs(dlVu zl%WB7V_Y0UN#rT+DHun=N2}M~z1_;}<42(mx#!+Rv{ui(j*RcEcWn^4yF!L@* zo>sE1B8nB!?f7Lsihj{JP)PG*beZgHg+>m3n(PJ~%107SyeRrT4fOav-Av^Q`#eou zzYJf$lwQ9)E9&L=Jv_a*LH;Rl?km{yevNiMDNytJFzoHld&ecXwyXCV&!C0Nqm3#1 z1(P9UK0<-K4OLCA8KFayX}mKBouUc$tCa`K?U31Sg!v-IPioC$Ed#^GLb+RXrM+BPY?6-8EZ} zFV7c#SzA3XudI(g-fu3xVQa!lD&5pOznC*fm1LBvSa(l!`R=4K0u4)iBk{AGYtQQ@ z$QtV%)po($o{_ZpUoB)Ln)3T&BI$8Vt_-8jp6qY34OPNZSZb|9nL`dKhp$MuXsMvb zye(zV2Ab^5zp%hI>49k{2I8mNb+Nl=t~CST@ZWRcFQs!mta{3&i*+Ls@d;q;Bv_l0as> zDMJG7`D|wi+o*zI!vJM(BVv6jJWZv>%!YE2l+XA}o*DC}1BjQA&+mvUE}y}I8ZC>d zi&oZR4Lg$JRG{RH7KpJ;?GUls)|8$hQk$qh!1pL0OJ9(`DZ8asO;u@?Iu4wk<&y&= z96vw}OV{Vk3uL#P1*cnzB7Z8A5Uo6f<>akifRR2;J;opD8pR#s86t^|l#gTXRy?YBtwT}~LQC|X*zHWQcJY3);(bNY!@=y{z@!hFr zHF4)6P2Op<@xm~?f$l`TNG%6y%-0ua#efcKh>>7Y{s9@N?bWfB{>K2A+i`T_qs4x^suRknb{q%Ki+Wuk0vNwt_)t z)VJ-O_095f*dkMw{~Col^$WSYPyC;}de`;q(!0Yul*LJSuU=g|DlbZ2frE&?XbeR1 zd{Kn?8fogHwB>@68Uba8&4#%J8Gd^4ldz1Y2_U3C)-%N?0g98~<&`{78>6@R+!c4~ zz0uJAQ5E_a8C9saS!2W|<|}^DbG&;)Oa5T!f@tFvLNu#>Oevy>jgu0fDx@RB)xHKf zd5;SPen0pIU5!>n`mWxY?1OEw2CJ}3ismGJR|c-K0{g*a~GHq^*1=bu{6SA z9)B-}MH0fMD&)j55-nG{=s-9PwPABEP7}5c+(4oLbDbQHKsv%NCMH zqm!t^4w9TDF2;zAW)Sn5xsP9oaC1h9R2)nX$Cq80ReBKq788_EBxAMnHiCx^!z1RNQ5X4q@<7|Lk7PmBilhbJ1va4oYs?+_#m>2QZ>>T=a9Gxa^`Q*mp;fwkWIIA zfJRD`%%7K9Zix9nFY+69^joYLE+O+G9D+0x9n>xN9zK?QGewad29=7=Z}N`=e*4X_ zNiGto{!#E;g&0YOPkkd-=h>X|*?;ckZPgAwquP%&c=(j0d6UpmEj?O`!VES(@b9(3p}Og`MIL0GPv1uk zxPB;Y$f4Cnx^v7y_*pk?FRUtFJBb?paon=jHr;e-$YeiIwQ;3%i2pZ!-Tf2E3C?IQ z2NzU0RlPVL`ps6ILeQpXm=8RpwesV7BfgsOL4#paQIo`O%M^1AX>1hMr50xNI>DO@ zygm~a8u`i&cOBwPYU@cd%sZ7)(}9K38wWAAU&3+Djmp^jR*}Ii&wi%_M5{J_}dSz z946S~J54HCDakhZpj#XT{ftFC&R}{{Lap5VHprOo+}r#)H@eK(XGpn2JpWnpXi_6>i==sm-BT1~5oUnLY87bAXnlm#dzi;C}hT$F6kdI@s#qKM= zt{+Ca);Qwp08Hmt>XHilf#Yi2$c+kK_slXAi}U_oFtTp?b;K42iXMAt@pN;$gYmet0RYr-VeVrZi7#ytiqlsm07@~GMFuk z(lna0!TF*!naO_2Q9JAK7M4t+{h!mE( zjfW)i*D9HwRAg-t7rq_$AezRf;Oj+v+6p_TOJs1GuWGKnDeT9#S}8L#eg$ILT!p_g zagxOocD)F=)KW4Wto~4}DB#rFagy2LYlo>TJ-ayCJ@H%uy6o zW;-IEr_KoNddRZxF#ZqJP@ftuOc4W{G0JZ-2L} z%&8ER09Jd4Th$rMTp8H#<1qgIP1*U2SAtz%U(Ws;IeM~0PT8>V7dcCha=^_G)gZ2h z%dfnt0~QE_Ih zQ_rTpJl8E5Zj+s_FSjdM1J9MFIcT|4Q;$17dS-2{9qp^1JWRK6>k&n?VNIL0%;u&S zChd(vpHPi!x+hA?4FLOO0Fq;7(Vyno-OfMAy_Q@Uk$$+rcna~%)ouI7_C~*H>o0mwz zjts)i$yRL&nW75ADDW--RV0akL|%8j1s#N6OMy(3m64j$pkjoNKJ1hN!zb>sFhQJd zfw%XTU(EV7Vi!G}oEd{TajTs^XA8HYHi7eJGC$Zh@$}M+JUH|1Q($&%! ztLZiNc}xh7zsn}VQ855$Cm`BZDq7k~lE1F9-PC$EsdUCb2V7aZLrM0bb@p6?8xzLn z@2U=JmiSaOHIU~TOQe_$P}FUo{M}d?@YGqHYS2x+t*C-5oHpX! zzG`S}okCtbRW96yxwPz9S$REDHJ=3y`_`QFSX*o>V8N2;KRnsm0_HQcOTQElw0N_j zU$MnnFL0~Q=~EqCV^PM5Zz)O{K({FNYRd%H-?o!=)sD*FB6L+JO#Jv}P3+a`#Ti)> z#7Z%EXX=cY@qkde#3#U5hhIIn3nWnw9nM$+A9pn(^0K8`YosFJVbQGO{-Cn}`GjFX z<{$T1!5uQ-j<

;Hw5URQfkDukdUHss^X|EGOdhWJL3xC8G0nW#o%4XQI+P<#Dl7 zoHovqAEApMV^osML+*WP*N*8YpI4Ff(KJg3vdR2C%(K0L$Mp1&a2J>n&mbjDoGW3Lp>D1M7np0d0@N@+3&h z1$X;H*z+Uuf50;St~GGrw>2#*YYGGf1I=HeOvh#Ghd$GSg{?v9~@u)L7Y$>dI?Ys9_*JfvSee0KK@To_Gh#L$*F zWo`w=e6$K*1bhQ)tAni|wSIiLZlEc<`B8C>&kFDhBH+qYvKNxgO$+fsjyO@*8P0zO?lGYd9?v!W zg`9@Hs@oP``e*soBO5a1yNsrpHPV9LoEC+xFR=|%MIBu>YyRH;3mO+T)vfW^um7RH zmnZ+R9tfA;Eh};=ge8FGo^?t7d(vYDFYNwIAZS`E?{^q@E!8LaUyA~6B0MJwljr9< zXu@(B->rxE_*v;f1LvFXg(*_K;ttn{suT=wU7zM)WX3~v?W+$DDXiJq;KZ+MTT9!u zIJY0fdSR`YMduBAlJZ?h-)!rK?PshsJUwpnOmzIZn!7A4{HPB7qeZ-W9}Z?pgY>4t zDsn14)fS#BHqV90h!;2N3~=|q5_SY-aM#H%zR3X9_+a#j-p`p&MITPHlnT_^yXp=)UH!-k z=Fse~JH-+Q3ui@AuEkJI;ak+Wngz!bRAf5Dsi`JdkZ83wfn2hIs}-S)W0( zl&kdNA63CH$-q7aD0cnggd_tfod;R~+hn*)xj;@k)-Wp5{N?tp{w_28L0yef{@CxP zj*oj=q6wT~pV^CA1=KnTv&Fdo=xCcoevZAr?i%t_G2UqnVbCWKw3d^1g6%t%>&e-= zu|2_gD{Wgz$agK@m9SR902WlS+ixMcVw{rP$7!<}E`5JOCtA>0r8c&daP?b)Vy7E<9>vFD-be zWT$o1#_5*d<1IYa2$SWyo%l459yt3tuxpL2>#?d}_K3u`A9#a!ca=Mc6x$u1KV2z% z#q)A3AomW!YuFUl5I3-|bg<3EE=2*J={_PxECObM9}Ghl3Ctmck^zeZmXJ@9sMT{zK!o6!MZgRYS(2nW=_31+Kec&w zf~zn5iukGV>ZoYDdA89Rao|lIe?~$W^}FJT7Ico|qhq5&U%-ICn(pUw4gvy>1&uMk z19r;&THxbeI9Ki!%?4jE3tl~rj8`@Gx+PDU@4=j7KG7Yc;FSe1?uF5+0$O&f7o=_c z+5G~dE`Zk=ckj#Zc|qm(JM$k*x*vK!C}!)5htk~UJze}3Z8^;u@s%-ZZT9d#)&(j+ z`fNMIS5%Vcju?oNg`@y6IfjM58OAJblCl3I&WbOn zss9xvlD$eC2|H|%5?>py@&3Q+ij|nxxwkd+FAE1I-&2OHRf?Hky-5jg$C#3rNr?W; zh7Y4F{oM1&-)}!2(P~JM(Ksn1RgM^~Nx49lg+bCAFyzAz!qyc1>#Sb`ZGiQ6q||cx zqI$x+J(t0$U^Dke8rI)RX5QO0E?792$(zA6fineYEKkj|fAul6 z&%4g>ll^RzvFUs{CIMmP^K8BnJ3=z~-Jh}1zzM+Y!q>mI=#cA#>qp6KQ%Y7#Lvcoy3~=>CLV8n7SW zc!YhsEW^OX6SWkk>uHW)VZ5`ZIBseBO8st2qxH} z#!_W_j>wD8mErwsRn0}m)}cqE*Vd-lBV+eZ^{xGtg)@c0{?^jIrpUAmLY7~1(^;W= zsK!x$1XWZvsJ~dGjIl+8w={8$8&ln`hK#sv8^xnO8Ik*qS~x)fb)PjMi2`B0V=$07 z5k4|F$X?HWGCy!~8r5e2M+&(mC5`+27>SDqoF+)(N0%CehZTM3y#==_k3g+p3LFaE z(hj#TRPUC*rq;y%njQ#%E3-_B~9d-a1!r_P>@`M;x9eSLoI>ZUUW7fr^CB+*AlvorcUr@+$dLHYI>_$nNvcsyEGZ-P~hK+Mlm65oJE zb~jmq&sJv~LB!*mNBkrybf_Fi6z0+r2BK6AYHHZNO9}~nbQ30f=@RCFbOSE3uJZwQ zWMpJrYg;`Q;ER`w^QWesp6<_M2T#APRa1tXRf@TU&n2Aq6%=d{1rTA{r&>&DhUswrOYbt5C6-e1=RQ@f7hY~4AUR}phWRrqvkoQ2rA7_;&etl6If*;kh5;5rAWWgby{(83ES19QI;NC6VK0$CbNh+pcli#ox(Ox@f^w z*qLV|Y%EHzaz@PCl*)S1CbZl5KML&Rt%audV57C$1fB?p{m#}tX~CV%87;OQPq>q3 zaaqGI5=#2Iaff3uwLjHSUC|>w<^5kg^Z`LiIPm&e^CgufQ`=)D$QA0ZMLK@Ha+~aw=7c4wn=hg`$A?Se~F(m7zJ+Nnk&Xn(qX$WYHMF0KJke)uu zYjS{-q%@vwb#T}}$-#Q?b>w)rOrv4PAyMs9haA;jFG=gL8c$PHef6W5fY1zyO0GGq z`nA!;9QfrnU%;>9x<=rl6-{g`lp=*v*mPAniyHq>$Mhc>=wFlIaAD52K`D)q> zd^LXIO7PTzv&fYz+H`#oxy^9Wss1|}`I{gEc@wob zVh1%%upi#fYKk)$ml-<8<3hy1``rbC;cTb$wt@H!J47e&y~bAn`vv@ct1C{ML0ib+ z3P??hqa7tto9ce&SiOPuE=>UDW-^2VqRS|d%cNQl+=6;}*g3lGi#wI_>0W?n_~a}> zES|6X4DSCH3CC@8wduM}@w#brM^1rxxTZ{7xhQuk3q`kveRqgZi#_`)?6TeZ23N2DG5&9ufLwYT9)^%iCLE{_VAOm zI*lh=4{d>q$4(G5$K=OG^J}`b=Wj(G#V%K!-zX=Us*@loB(t6G zPJk`}`6ScE{pi)0>;#kE+paeT2>q>6g_}!)DZHR8ph@RP4CaQH^PKKfn0rp$X3O!T z(p^T#^qQvZ^Mv@3jhU!T6Ij>oEBggP*Jew9C)thXn$g6wSZ%9MSjE)evu9(kcvu{h z^Bcc28xsIXq7-y#Giiiav+`!$zO&>N^9f&)BT2sG3Vr`W+yO-NK&W z$+m*Ro+^i`!PXsMMbvo5?`n=BsD$QGK>SS4jdUA&5U*0?8vkR2S2$zg?={)HWpmtt zhu(W#t!3dJrm4LrL+D(4^7#>u7f3RnNLtQ`XD;Ab;-=CD+Go35HHL+IcWHwiPt^nCO-qpu0v8-8i z(-id=yR3iI#q1hO!d-^sv5n$?2CcFu`5^|cwND{92d{F;o2ld*YT>hMq*NPfBer&x z%0S-)HAxFb8uDX(_y?qF|MmOuJX_fL}J#kUC zi}dvH^tr3>^i`g3J<-*@sDP|JM}JPLtmHOZx#=|`>=Hr0HEI}19w9nOc;f|CL8 z88&)#`%j%MOVPA{ojO}V@E=fh>B^rEQGSLFw^d~;@eAGaJyK>BJHc_uoKp8^K%Eu1 z!1uSoM3&VyfmC)n|1;^f_k|7pXXU+;Hy4*>gipg>8smkc}U?-Z@iZcmF#t+_vf>qa1X?wln-|@97a6vvf$1 zwC$3g?wzp!BkkigfR%STVT%+N2`nILvSC$?wb?$hX;n^D*}_FK!=q@~vq3u> z`)hCcEF9u(-&|vnAW)G?HObin{l^lRV<`=DtRM=Ud~HB`?s%6IniRcS?77*Fd_LmA z*vtzv2r1IO<{^YL4C#o!YiINE1EZk*EB}r+BOv!xt#qMY;4Yg@!D=x}(Nc@5c`MQ=iUzX_<BaBw>Y18q=TUT_vSg zl#&t$18B4@?ywS2$WEt;PdL!Xp5Bv7PJ!==Qk|V+U&y5g+H4UmUhR*^F93F89b#1M>Rsx?zyyQHwJ!roP2yh zfOKtlzNuxej^GoheOGQOQx0;p8oVRs#M8|w{Kzcv+-(YkfS}$Zn=Y`&2kV$6xpt4; z!d3K7*_a%Q;Z6!&u+EtSLd~-&+%}*OvO;Z%}0N4kBfC-e6+c;Maz_u5h{_h5@;N3A{pY3dLy6WVR z$W(I$=BNq2yDeS0FFEKl+8!<<&;OW-s}tYDt{n6~+B;n~Ax%^A!J93gp5?y-H`jav zPY^WCq@R5BLhEyZPcKdLuqYZL*@#`$aULQ^w=HSu_d&XLSp}=;?&lz+uCph*yNs#- zniw&~LQ$Mv2Zece4qtdh+q>zCpAEELc|&Rp`8t}V)0_0)@|@xG8C68$5kwMXL?XX4 zHD;6EHH{u7$P;=#7w2F6p?exxw29&-YGoPhhAI6Zq^2nvNV>eIUSHxnc|&GOBE(mz zSgkRvf^DVj*WSA4j$w*PZ9L0N>AH!UIIpj`^HaI8*5ke&wQIDw94qbK*DAHfh2>Lk zzn;uii*QZQRcDG>t>E*)%Hv;8E4TNOY&mHQkSl)ejVU}X5=B;4I*%{U_Z}1ddxd$E zrBthkVb!ij%>#=h(*{Q^&7qrpQO4kE98a<$JIHLJApb=cLI?%=&);Sp%m0V)=jDhYZnNk)2NE zbRk1DS7hg)a{7=Vnk%x?t(*~Lh~~=1^Evx+Qpga^m5t}Ka^{dBnkyU6XXPv)Lp)d9 z%6S60hSy03U(O$pU*UB+m9qx9f!3LbeQ1bzPe{Z*bSv)(uYYkqOU~#2)v23?Y1}bQ z(*q^)=1U{G-%;#A4D)`Fh&^bIYCjO~oqXvWivD$qv}bau+p0)=CSUKiY7=SC4{6WjQnw9J^-Rh6N4KSrqI~bNYZks?52H>P>tDdSpLr(3|%m} zCE%oxJWv$niF)j#6l%PSHiurTK^h_U_6fnv{J}u$*jMHFCxLQ(HB{0WDD=9})zKh_ zto!Zg%fa94V^zPadSBIts^0F758gG;hgH2a_xk$OJZ~S8bh$Y{U*~Buy~{%ud_M9? zxmhGyFgHlxk-)fxWNtW#7Mm7T3%gLiMj_P~wr*SOLi;g;aOFbJPfq&=P=5mUGVEKM zRcE-mk4L(H(%o3`$WtQgq5F7ehoKW>HxSYFMRCJU$9|NW>@kp?G~PQ4$ohDlE_WV7 zrr>ot+<6AMiq|>g&JN_4c%9T~oXRESCSIq@odj|Vtuvy$uY{0o@j6}ZWRMkjoepO*sA-ZE9yeP!a^*G6>jQOrR-RP(`-J4x-F&&tVn)vEuqDzFHx zlM1H+EJf>F38w`NQ9qHKQ{kKfL)1?srzf0qV2Jik$>|EG4-C=XDLH-NjDX?oD-+?& zAVsuyO3sCF7LcOcJIQYE$ZfRFR&Kk+JSVhr+YxRyD8K=hM$E-=XAt)12+k{{R30|NrA-U|_HSVm2V= z0AeNv2w;Ws8KHbexHt=#4de4sL4OC5eoid)s{8hM?(ens+H3vxwXd`HkFD8S8#8k`UCnuNwq|QJ zwtDaIP?uY|!!>ZL-%cMR;(xQS(p#V|XR*`6HPFLd&d=9KZcUJ{oSFYlIXN9U?fFK! zI!4-ta@zCe>&e0X3TJUpzc{UIg^7P#M*IoQ>2`B*ImfX@PwqX(7Bd>Zi@VF#bEe;H<`(zAdT?I381{HhoIdlsgB@rbH|@6juCkYvqqiD@|su z*W%Gx{BzpW_nVa!4TDt$InL+vZl46m0}T`+fET9n`b+}kf(F_FU^uVeBtRN8P!j;( z^D-s|HgZD)eF*q=pL4}Y+OJ8WNN1mufLc({aVz@rIq(bL3hZ?s-fLi#_Tw!4U^zRj73z)Z=Xt*U z-=)8Eyrs{Z&v|YE-vGec{a0-Kw>8t$et*+RTO%d4{{L*KajAm&oVNt{RVJa1AX2#r zY8d~ViK!P+$0|Tjd-&BRq~4#4O6AMvynTq@bP_7+3<&3Q-r?alo0xh5ajXR#1a&9B z1)z>=-c;2da>JQ7I}ySheRH8Lo`h%53(3QP*<#TQ0B^j#~?-dy4q*!^=!l6NZbf1y5=<7KE?|zo?C&@5K`wh5vFv*n z(X1w$%#grfguO|aOTjI)xQU@GI~%(~4*1GMcuS+jG!_Ju2Odh)P@_wXqM#m6 z;rl(wG-%Al?`vV!wu$i5AV^FDc7XrZWCNayqYaq2f6v*<$DVk=nserA+~X&}vG4=t zCI&1Q$^RXY$1O4ZR`(%qjG9FWUYj9p{=_3CR~Q&=4E#t12r>`Ge|-|N)q^=!Q_$vM zCP5aIV{_h*(N6G)UG584h;dERHz}Jie*CduOxgr2M z1sW|$pbe&DdXvluxr_lBey)WHvd|fR@~S&QoxrRgV2Ec?mLLmc@;8Dpk83(q2dy>u z;O?o)I0(}rBuOKe#rVJhc;I3JC{Rzk0!BEVi^*41{+WL$4%!?D5az(miErn`ObIp; zlQ0L{)cGbf@A(Imkj5#R^n}CvC!ftk<2-n<2Z_0cxFHB`;3JcW@#gd3!Gd2X$G(P` z&j2Gn@}nC2Kbz|RUKg5eZH5|&6Ayh|C?FhhmO5V@IQ$8*ArFwSMD@-n;47aTdk+aq z_YeCD>6T)i$W`O-bmU!w<(dTmU1O^Y zSL$+(pB#&VxXDla#=DZ3$TeGQ2>3ee6m2^0UAg5ef%33&VT=OoX1>$-hu?`NRenuYM@t@DP7j68mHE zJnjSkbDu5{_k<&P6R#7XjaN6f@CQSGuvX?z)Xj7Kyd@LP*3>H1DyEK>()Hb#syydg zZVt0jZt@0n-1(hqYG_*jpZ~>TO>XjxjCZ!3HD}$x)L840lx<5wNT9~n?A<=~Zy&bE79eXAcU522$*> z8i0StenP{+E`^0F6Y$_I7}M}7@uo$C?s5EE<+7Osslav=g9 zD2b8L8qBn4ql{b=z!Na?=>;e_$_|wQ@Ij2sf}r3iJJf`L2f1RS&~uKmLpcHbAa@ zz7&F+0ylN+3GA#R*_T2wKtF~(gQX+cm%=Fo-5tkXz|xWIOQAHNhhZ-v>1g()kPFa1 zVB}|O5NGu!+G?Lh&^;V6@*}p%ssPwaNcKe>l$bP}e9{*Rj#3SQU;8$=_ z=#iuB(3u20SOyn|hNJ9IV*pRbC86OcJCqN=f8kO9K3PG}K(;U7b0{|)dk0Gga}J%q z6oSv9+`_OPK%dMUWgwcPe@-soaQlFLgdI7WeE}awxjSN?Vd-f01$-jqewVsYhdHNc z_62+@<)KU6sl(9G>*cV8;J!HdbU73p!M-p90i21G51B*35$p?d3IPvYfs@agL%|X33)2R`OK}a@ z)q-MQnCb*POc~dLhNG6CNoDVi00_fVs8$Q-8c{ItRvYM-#K99U#S~)m{~`% zFTPR)eX9#~rw&6$vM;`dfc}uWRfnJ>+817e?rB2ZtHaRI?28hhUxvF`2kQ~ZzRU&n zs}nbXsRAS%rL1oQCB_~%f`+3M#~A=#fiHxHqZG%Dpnj?0CeUz{;%EfmM{x4>sL8H& z(6%@NDoo5NF@x>1Ljbu{}TON`tzjk;5Zp`+OsQ$YVk-Ks;-(dRdAJMo$WeA^7y;iUh;M<0qwG*#01wCA0erH8o`z~)`p7svjS7xn=t%aZ4?NAd z^%q=n1jdeJU;4n~jGo^30@#^BvM+t$c}CBdIQhyE%*-I=FMZ&FMlVb1R(&#al!j=I z3eCJZylzl;>M$cmvM+t$fktm7>Q)_sj%Z)N6OG;nsC#u7I+}d}k2G%MhPzn@>k-Mm zfQAxb`uH}ODnPXgJCa)dBGPco;MsWru=h7U2eXI5Zq(hYA4r zSv(TJCoAZg$o7Sd({E705eyy8zJRA0y_DdRBQSO}`vM+k^g4js!p;nueF4uidUNCU zuyi#00v>4e-bvl6!^}HU{?Z4YX!P!+?$swVN12G`sLjHgW7|sVRvlvGi1r0M(YURO zx>tvxquCemNaJ=*xSMsb9+B*e3MesK@Hm(%K*CXqqbGnr!V{q3D8*3{lo%5{2^x-4 z9327t5}pDLM=6f_1UzB}o(2s^u`eM2o{aB-hNIXQVE||0nb2?)`(jVPBi-?Ruy7>% zq6Oej@cqzmly&Y$z@rx92Vvnz_C=O}hfCoZ&~TKII|FzUz84yfvO`S){0E)|4M*9b z(F8og4L<-4hu@*a(hBj!I|nbZYyfv8{`|K#LjUt}^UY*b`;xIw#GISM8G8WU zO%(Hi#UrIK8OKTdZp;th$4g89cVVLS2QZjEn|Lt$E5?8vJK7sa8T-N5-CeK%fFI8# znNYnA$W4XfW27a)mJK+79fzhPlu2oQvLJ9_dC+u(Iw>to(*3cM&~$`CDXm4)+pyEn zbofe{B`pi+K{i-EG#$arNSl)Mf3N~*I)aHZdg2$t+6{q;vZu1uy`a}W0wK&?j~3wEFQ_$*yWP= z%UCib9xa}+iv@TOX)G1sCv#1xU6sV72-oD1hNT1eWVQxuDim9jGmR`}RoD$^I!dY3 zCd-WmRtil=DU~=$KZgASO-Ct}bID?cVYi^^D5Y`+Ne{s)q3H;=CdY`Rzr(7b=_s~_ z2IwJcuv%z3img#5=`~c-IGFX0WNRbgzn082-*H9~+M6g+VQ zs(){AKqWwVODRW_q`##aP{GVQ%7ZdFGJqbu8oL8MGbnr2grrwv_0V*by~+vbA)44d z2s%-H|Hs!r_Cv~<4d@KpiCd!m&snADC^b@qq?b?J674TK%Dm49^qq5{RwOlclzGQU zdN$OGr06I$at@#e@ItLfijGnvrAT@J)QY6&C^gcMq<6xvNYc>2u1H=$546V`Vb?nu z)WFh}NO}eKU?O_d|Fobab`wox>DR>!37WI#n9DNS*2J#+behSD8N!Mqw^ojjKRiSI zKYn;d$(Hy>9C7!k#%LP|$MoNl)&HOqb_p1o|F5O#cs)dObiwfB^{D1(Z~|bz!V3tJ z0;j14X>bBy%fbt20D*+5RFgC~0kCV~1!j=~kyN8JI03M6;RP0v0-tbBu!P_Qz}|%y z;06MTjyN~G0NB3p0t%$SZJZZcfOI+V0-``5X+F*eFMzfWbVz|*9D^1hy$<{l2mpcj zXzDFksFO_E9e4pXQlOW56&6kaZ70tJ0tp+aw_)J~&~~yhDR7s1Ar?*mZ71^qfkd5& z---R>9{x>qV6Ox!fW9+i;%;hx(NUZa8QAZ9H*q($zvw8=hYaik)=b<@?Jqit^C1KK zfEucs+9Y0_xPTFk6UF&ZfxQ;i2DUB~9mV;Ofqmd{tOJ^k;(VyUUI6QYrK30>IvLmp zg<)@@=?G~Eoeb=Qda(C^KIwM-6XifxG&-5t#}86%)y6xqQU6*iB8Wn=R@^iA&vGWX zP<_?lhL2P)>11r5@PO*A1}A`2FX?1*pJ+t&SA!Eks+V*!yiY8kdaS_-AUPj8ncpXg z;WOZu5R&tulM#MWEG`W%faHAWilFEx_2Dwm0%*>ME(QdWH{o*d0!Yq>zJL^Hz~!L@ z(3}r_3J^#*PrX13wTjT34_zGyBuY^4(839z?PT)#mc%&fMOrukw4J<=Jc0r0U0OH+ zw4KZa1d=vS{5tKQ>-)dWfgzm_T^`T_PEOp2?Jqil^Py9jzVO72*#4p;I3GHh=?6wm z+=%TjI)d||lbL?tXQ~m~c$cuh=m^e-PGn;uijLrX=wzlJR8K_%P;><6L#Hx* zT`CuVp(8mTGSd$}O@#tbbQI@9W%?qJiNK%s!0^t8jP(;|Q61SPtp}t4TG1zy{lrwN zE8BSU6ZNmPBHDQ)S*u1@BDG2!qS~^-4IiyulHq=mJJp&EP5`Z5lKFnpW2!wHoB*2h zAtU}|6I=)Cs!N_>H0ML6{K*$_U3dXB=R*elDbsO%XaPj$LuUOc3AiD=0NN%Xh)VV0W{}B=Ke{SsW))p1kiRe8T}{EpkBj; z6F}R^Wcr_+H1V6bf3Cp)_7#S8K2-YOIB^fRzvw8=M;!R7AVbK!3XC1a`H<0nP{G7K z-2NInit{0J|6p;dhue5pn7`;K&W8;BgX1QS2L7U>I3F_c5B^F;15jf}aXw_+AL2~q z0x)zW=R;=wArGif0E&*{e8`|b)EF`m_|sV!-uX~Lza`boZPI%1r@Jt`02TCKqZ+!w z380lsGU!j9O*M5J?*v5sYpsZ8;7HbLy9Z&dk~65TZg9g#tCwWTpUkE@yTJ*dIUh3R zPw~QSpsu>)8AfwHWXhlN9JhlPKyyB1(4T6KuY?vrbUtL(pIU^kh8I9{K4jdVCXKI! z7C>}9Wa6JRLcO*NwTcj(4;lI=Z=>Gag%d#A#$@iF+(Ny)3nzf)e8}iOWeN5EE}Q_; zPG<5f;}_&exjOMnynn8dpz9{Wm4LYf(1U(V-2Uw^I)d|IDgt`28)RMu#*W~8nC>L~ z@x<-l{u(=i^I?hsdWb32{%yPqz+ZF(=fhk}(l1ld02Cd;`7jp%dg#oFbAi9cj^KQl zfh0YJ$^~G?j^ccnQ%L#{6$(JnQP#T+poe)tCIVy+Tk!Mppp6Mr9S9^ds6KF$)&o)i zspvCzkOFN~FE}^>q>{;$1_CM8R6jU40i=@2q>}=rR8P3^&T!Pf){1B)j%2Nl)$^a^ zOjV+q!odw6$@wrN!0=PEa1W@fE_sHLoDY+W6d1$FS54uL0Ll3<&4EDL4xD`16iNWi z`7q^4fmWP+-4sp$Z4+z(0_n?e@`Y0<0W{~soCX9^RPe3PCmGH8FjtcT2XHTV0kmzb z4Fpm-sTN&uQ-rpScaj3WRGTh10W{}>lLD`)R$b%Oi9c5{&?OP&O0WXZi66*D_IQV) zqd1?rBz+HLUIoUE;(WG|boRuZ!pV10;f9aqe1yR8)92tZP!~mV386V3J5t~fPQH%{ zbp(jcM-vF_;l{}~QsD&9Hi0iG;E$8=d%jXcX3kD02Cd? z`OGKjepD_1MMrTy43hqa3I$;3NX`cX^lr1juWJ7jnPZy=DSO?9Ay6F@7OQlvm0)rAgD0Ig(h00QY#s7`cn0%#@EkQ4}` zy3xT2pv696q`-Te?2b0x4)|lOh&JX()~dXkuvUB4;76b?isTYPb3RMK@b^^X$Djoe zosSX_$k4#aR#Z?YfP9G^eiL|*0!MMO8x@oQqVo|40%_s+VdyDBbUqHGzz6&&ya3uZ z)&&CT4tNf{0NOSVA_Z#kTzCPrZ7c``_GsZJfWUaW?9Y|p-yX`a?!gw&!vd(t3W|>6 zd^AXUCuCmrZx3bIvHJk}E_hEzI*Rj&1oQ|#DinaBBRL;#k{(1Q0#J06jMIXocT;h|q$TrD7iIXGtN;Yk`th?+ z_25q@Wq1KMAdpVS$);&=M}Sr`MM;5sIN3K1P5`ZBt^opj^l-9u8k_)H$5S`CmPid=y9X_pod*dv8k!PEmv04?bEBLx!i z8h8P;k||3H4B~b00%#@E83<&!;AD5T$u3*e6rq(&Q&QjoPBvJB6F_r5(Lf;62q$~2 zttaa8M17m6BS3LJ#nPhSecnQ>3H}ryr9RRMKp=T0)(iy3+hqSbE8+mqoR!;_-NaMu z$=D<4;iDNJX&rL-Kd>jz0%*oZS^x+nyr7zjL9HM(<0GvG1QIQ%zG83!NV`~iCMj?Q zdk8;8NV{0t7ziZI!XCp5AnjslK2jhRdkO@`TciI*KGzW2`ADk(dO$N&4|{!*j$nMG zB>_EfAyf~0ijH7>r1eSq1*jhO6dl3%NDBjc&~&IC_7ok#_(*G!^hBs0_7ok#_(;o= z^zTqT>?t~e@sTzK^x!Q}J?u$3it)+eAnA{wde~ER1mlw<2k0RtR1f<}3l4fapPZ>c zAaMoO3RMqC0VLy-GmjLwiM@swKq{Fz{6HW{5qkqKfK)PbR7rt-SUbD`QpwDjP6~`- zo$vxk#wW)B2qbUEy5R*-j89e$4=L~xdj~IowL5kBcB|3Kxddj{WKGOl8)ef za;A~=%NQ9Mj<@{(8asmX$xLt4<~@;eDr`oyeeGLr;Y&4`3R8$2eB_O6^#-=E18-=Ac2c&AqF=^ zXeCpI6!4?Eh`|Y{&%}KHPvFv>mRgI9QQL&WB9-gIcMk;*(xdz*$9fKB8dw@$cZe z-jf>&@#j~NL4U$(xUTn<09whUg8nMFuJ@DxTFIn>es#F6_mluy$)tk*BUBeLxRZ?L ze5jzGMl}+H6F_r5RL~zl^%8> zPGCcUbV z=K#t1(5aw*9@R(;P5{aI(5ayRIMquGP5{aI(8;Vn1&8Z2PM!la=R+ss{*(}^qZrf? zpgA8pnfRx?g=;oW9s!#3p_8G1;vHNW>dFpQ5nAj+Cv*QKZCrJtEBha7h1!hW+KsSQ zNqP8O_~D~%V>0?ro`S2x3!rUdGW|~u!!;+GpFh_~&@mL@xd%Fx{#Q_u)udN3Ku2*t zWb_}T2ANj@I*RilbN`?t*eLYOpg12g^bh94IiTq%&WB9=gM+AO0BYV*oDUiI2X|As z02Cd?`H)$E$SNunfT1HfA2R3{Gl3`7pUGFIYw30~%{mC(KUGFIYw30~%{mEabE@G2jb;)yp z=6uMYKV>7;NDNK@&H0c)e@Z>oOAJl`&H0d7f9e9bPUGY`Ky*H2+@E?9uG2Urfb?k> zolN}Ggs7%sP*a5He8|v0sUJ6my0U{+gy?+8+&`I)o52g9?PN0gPrip+OmqqRW35n| zv0wBgtW}C0z7&4=Xxo@f|5HxmmJ<#CkMjW?Ls6U$mHziok=3MEF+fLgK4kPC>;Rcp z0XmBFA#?xWI$RQZW>B0D8TyCJ$EBd@D9(pW{6q4nXaH*7QJfDM_lF8nxd0R$#rcp~ ze`q)r3c%2joDUiFhkk@>Dy~he86@XJru<=!kZ}N5k%-QRO8MR3y557~qdFfd<$na% z^_~(ytCwWTpRx$9>pdla=6uMf`%^B!b-kwq&`Ks5^ruQvUBo86D3a#@&H0c)e`-9{ zNDNK@$@wsOl!oiWD12pHuR3rr&;W~{|0!Yq>=?(U zJ56+r{9~<ZBOv>dk@K}fgG%|?PGK4^b)ufdrzj15tb7%@?TYDWxJJd! z{?xJ+47aln4;y*24s0kn+nl@b$Y7&Hkx|vB!JSU)ue}er^s+t5%=LJC_|My>+v1?wO8B1_gUcfZA~M0dX> zth?@h=B%^se#=n^*5RpTye&N}HXyNuQ8E^Efx=PtXH_1N7x zv)8Sm(xkOMD^j{uUyhyV-k#jseXnwUtIFPrx2A6@=d|i8u$L73*|9VlDwSGQ_C=}{ z``NO58Y(qfZz`}^?(MO?`|njMv=;1*R4MMaVQp?OIoMmC6{%lrufPs0?zdwtYA}iG z)wx%x(mEv1Rxj?iWwpBJS+F7-Dz#dN6xgHgdDg5jchi_&zN|=-R>{31a>cSXEQ^LH z)mC8zcBi}P?q18R5!GT@Tb5fxlzMBX0{g4GX>6}b)`((po(*eFL)6?>LhPfvXo-He&Axg9Lp#s~yIM1FX&=57dRZE_I$Gs}PH#=)YyV%)|rPdIo)LJCZmM?a; zWo>VW(r7JGVE=HhitW|U8c{B8w_$B+h*E3yQ(%8_uZrsp$%>rcn!Pu2PHVqB`;B{5 zQtwdKh)Hp~J&UhlRIXK4o?Yi29p9UoH8Q{0)Q+XnFsj&^C(nNB9-Y|xFl)rH*wmgS z*)S^K>MYN0bdOHxEy^0vEv~X-={Jljx3CmV~M@(StG{9S_(saI|GXupV}R%(;eTU`r%a=H& zH#yDG4u99s>p*-#d`Ck&{6|Btu6#)g@f|ho@GlL$LBtotceJ#_M;dwsXhu-U*@R{z24 z@Y3!ahNrYX)9_0ZE}oi5OC^3_>SGzNQx$3TgO_{G_p=w~nMSqu=(}*tobFyd=C`uL z#K7NF)n9g6sjPG<@wc!b6Z{rn3JWtc`I$+)eU`L7OWwXZ?jey_c0+aK+71&Ve_7Ge zOhINn@lC$IdY-;+?jbCeeY-kxb%%+ee;&b_St=`8Dl1!>H?=fxdTE|msl6bxfVb}{ z_mEU9yQw;IU5AOWf1YURLqTQ_Z{HyI5N|BIwmNcEN2P(k^R&`D=~690W;SnM0Z(56 zt*?=L=qcBbcr5#4ESvc6kHoS!#Io;KM>=#w1$RW*bwv4gL^*X-8u^==`d7*MJByYU z2{K!F`#y6I32+Yy#^(N?TGT|7>%tSiHl_?aSdH0esd3P=Nb~`>yyQprZY;NXO=okmO9Ip zMyvaeg?2<)bVRvzjHXnN?2ly^a1Gh>_388W1KC$dCvFvQFAuYZ>XN*}jqqJS5G+M)dY*)wVp6Ze2>XE|gkz=v!n_NSFe0{`N zhj{viXnpM%vtNMOFU+hWz*_!eQ5~ak)gwu<>`bm9S-w6~j2S(nbWGhpTFyUuo`1Be z|5#YZXj=71b}YMyYsi_euL@(z3NdAgzXh4mGfT&a!9{kACRLAQ#IWzMKAbD)n1eYI@$k{g!|9&d$*TwUKGHBj*#? zhZ5N964);i*m?==y{SKx5n@juGlvZ8vj}Gdr^y?fwT03$*f&CdD8o`HJB>VhSne7DCxwPuM zzv&5o(<}bb0iC0VYDX?7uwUatHzoVH1%}KL*d4VaCu$>?cSiYlMlJ6&x#n+5{J!LG zdduJRl)vn{QrQiqvJR!fT1-o^J_UiHRSE15wUIWRCO79>Brl(k+j=<1{1a@z2q+O@U zP5(T{(uZ11NwGcwfuW@d?5^5KtInvMot4-8o!6D-tuD>mSgNJPv{z#~iuDnbO8obp z5`CWHeQE+j4hihm1h!!Uo0!e81oo%ek>9l=yK5tDJ1cMaJ3E#ZX)(3bnfhXVGX;jy z@FCj-_MJP?*<+n-ER&loDy?oUQ)wK$9c}Lp`Mkd2^O}BlBk}hQpMb{T%NuW84Qe(C z%oQHWW&ci`IaPJ#iI}m$Mtim;SGSyjs!(EF_f!K#p@ir=CmGYFC6eko89dS=mbLpB zV$$N4b&nZSq($p%uQH^iCF|?HGPrW4s??@1rsasK)ZJs?InxSi&ogG^NEFn4WYBU% zJZq0IByz+(>slE?IifwaWek}d$)38O3{Lt~$=U>l2whCF?hXT^Ps^^&XGqZ{vg_V4 zc0f?H-2c@0q@-$2#Aa^7^K1>U>cu z=$rPsvz-zCo3Ag%xXZ3or*C(8mv5lJm9J?#3)Kn&hugffSp3Lr~F4s^4 znOMuNRiO)H;_AB?p$l_kRJyD}wR3kDba{sw<;Hq;Z3xxNjqB+O3pH_yk?dL;I^St` zc9%z}p;N45mqVzoQ(Q||Q0Stz82v8WP@T5jH@kd7joV^Fx;BUEx5W*0MTVN1#0Ym; z49_#!o!R9!Y+w>=-(~vMd05P3&%=(AVQG_0t&X(eX_e_k9T$gZRA%^f92=IX+|%Dt zJ}fgjv%Ow;z~Z-XRJ?4r%J7`1#Jq0FVWp@9=WhLBji{vdZsB2t(RkBttzos%#Hw!D zA0^xaS_bokcE@$O7#Ik}T6C=(c9foxRO8Apke0Em7GWq#OIg;eVl0rJRbM@yp)NhM zzJ|eAC@rf}jWOhNrmNIgF|>1}3##WZ=H|>OsPSeP<;ZweOEHvlq&#ajF!XX}^;8=& zG;?P5)Pylia%3f|c^R|m(R4VSf=XJ-8(pjUkZq`S42$d@I z#T$2Pma6q7mUqjPs`MppIYZ@S;`zE~hpNgXCUuL1D#|2ScFzx0mr1Jc z#zN(D<5jxngwD-PEa;XBRnATD>^2P5%uVX)<_(?g6ffDW6gtN#F}qtlRLLp9v0FD( z!zrnyTQF3iEndG{BUG&|@n-j|P?ffXknTmHT5U-~-Q2@+Ch@}E3d5=>_O6iOMWZpMUG~E|qr0oR{DzH383SXzF=M~ANMF$V(lKD# zs_8MV)Amo_lwP5~BV|<_=YbQeywhR?e7mw@#2bp$uk4-5&l%od@nHDkZ>!yP>CNHq z^1E|F-X9Cd4H$ZptC@D^$@3$9eeFXm^|ufXPd|KS{WnuhU|{HI!c_F|%4>VAb&S z2x*xFp8+g%%8fdqmsnoBeT`IiaYgrE}(htpRUA=ahv4+x;b8bV~22 z4lCu5bQRUC@dy>lO;Q`+q9<%0kf$eQchH#eel<5cjR!Ul%S6aVahS%-)?{|746GTJ z`Yj#BSrzYGQ`D(HuxWVKZ<$e!=y=nbyiTnF$Kg$l^81!6PD@$xzyJ7Nq(4yq^R#Z{ z<&S>0_B|ChyIEB|L(Q$eSGp4tH`w*O>D!UN!_Gl%nU!quw$A*BC*MD%xU9EN_|cK$ zuDqM^bkmf37YYiWE$ZgA_@N?RC7&J9)+%+c!N%I{=*K`FC5K}N4qWTpJ9y;r^0VvG zf9aNMXi1))<7npl@~Fd|d0oFE?B<@^;JnCj=iO`OhHJe(1^X$UyclKQ)Pp~xi@xX_ z^U~^WaZ-p~`p~)mhbSoR%+{+rk1d|cvC>=l-kJMvXVR4pdc=vo*3s;XkmFodebOS) zZrvGU9{$Edk;`Sf%`iE$S$p+HQR6Q{cB0{rH#S!o2o2kOz-BtH zn7@dz%*t2My3j>UEL|>1?#rrjgW+5M^dxCV9r{|BKICz0L;Kj5UrZ*qWBbL;&bl9K zcK*En*=GNgLuoGxEo>7P)1{<@7NnoqbKvxvyadU;^i#pJW|}mbm3_E>C*thxo#JYe zL)_gVEt#gJxxsY%qI*jVa%-@vQxX?#!t)B`jyQy^zS>zo_sqil+zft|1P`BY*IHzX z*0dbA)8Je3X8z?u<9G9hmhzwLTUc?S{Obl+@91L%J+mGTs(lOG;koxrj-8V2RP)u6 zb^?3VUX>cXG~{}V>uFjT)W^`jZURA_* znce!HtQp(6Veay2k0ow!)vZx|sbGGZ#Vsa$Vd2Z%G2w?)A!5ELYwm3bqjk7d>nUqT z2&V3s*HMYBT&#C1VR$G~=#^q&Nl3j~q3+qp6T8(5jzr4%AQl0Prj8}|5QTWs4 zUrs;UzJ75SDtpjoaN~T$>|)+c{aO(c%N>60y>d$d+wd*GvUq>$qt9ZM`PSR{4KtqY z+J4*Sv}}XnYlk4M#MRp({9EtmE*MmP8+37Q$Ntyxr__Ufgp7@Td0iF3W_>YjXXmxE z3x-DP{h~LIeIFT> z9rj%P=L6SGMq1UeCw!$*hD94&M~_-$>Gwrn{G3^}bL49hL)SBQ@YZ%y-e$4&jL6Z> z#_!ihn;(8|d>7+s{3~QtM9;v>w)?^jonwKzrsXSIe$LAtd-p1=WrUqqpZM-q>CfEy z{HB?|EOVZ=u%kBL^>&MjYS(CcYg+xo`eEq3_MZ7oGduZ8o8`+w=X3>{wMHCo`E+m{ zG0@(s%^__UOx_;sCU0UMh6@ZDLdjQRVM0Mv7oGObJsT+_T^#sJ=^6Eh4+RF zb|$=WXruFOzhrzgF>sx7Chw{2cPY;jBEQVaC_A*VOk|C!nRL#pv%$wjm)*)YE}3_{ zENe51|3&ZF6n>q@Zp|H`esXoX!J0{$8?N0o`SsyB=WyZqb>a0fON+PZJB#jTn19~r zsGs9OF>WAdqwlXw5ws&#r-afcfPN8~d z$b+J(I~InW->G;vtnk<2gR_<-x<~=*eFa3891kVs!sfZ#~zslXSM`M**8pK@w7fS_VYjcjOUZCc;N8UC1>r- z8BW_S9%XVpZu{)8<0xN=X^n>Rhj_8!1lOM}dlyfC)pa}c@ws9l!50m75}gn3dfZD{ zbTGnTri0A;gYK*o8?C>@o=g$!jM>4T++Z~8$%VzT2i^n>J(aMwH1}RIaQT{`^wNK3 z9KCyFsr9B`F}rpQo0!>!bh`g2sq^|U_lSPhoH)y0cDk>5GB#}ASGH4U+O{2ui_7-4z8mA_z7LTzual||d^oi0ll1K-Q(3D+-QwP;Yd5S9Mng!0^Y<-DDX+t*ELzQByV zDq^^6^{e~J+9H{*W;<+KeO6_$o33{6u9&vU_G^iH_{&b=m~BaWbBJpSZWEWUdN|E1 zB7e51r45I8dDtwg!N`K+XWabV4m`Yg-6OZ4@03I7BlqRvM;|JmocsKn>TwUzcJGa8 z+zhGBCp(mS4{9Xp+)x{s-#252%L3Pr%jaq*U6m0$Hy{^$b;k=#&inp9C!RZcU4Q<% z^+j0FI#-RmDOU~7SGDsj;VDi}?W#QR7|^_N#}y1nEJvlX+mo}I}wylSuJ_9QU;eAYspOx*^* z^v3Y=t*fr-zWK`Kzi3bE*%QnYf%p_1;*Rm-uECm@k2X3#X}-wN{c?Hgv?E*BJJ}2K z&X?Bv$?Oi<`?Kirw6>wFYkRNvd^Qd_J^XE%Zp3wi+?cnoBl-iD^KTtoYqz}Psp|=! zC$5+GUnd~cZ6;{Ug@|Es3%w^eipiId361zv{(A;%CMOk`GsB4YT zys;&xqn4^4+RCBdVQo5HXODZt;xjW=-l2VQ^(~ueJj;*ow%XICe|kL9H5!a^%NDNu zvARyscGdfhfv45O7ux+Kc5d=_R}8CI{O#_2@ubd!VR7^>`IUY1%s==jU)!a3);C}E z*b)5&*33HRd#po8b60G8_^I*|kJrr=GiLK{JQ?xiu;ksCMO$xQJIQgzf;V$>5q4aP z_4AqW{N0OZzIYL4RAFU%yW49WR_Is%n3ezN6W9K}OUs{ISgWpkqx|8urm{+iu7=Cit1&nv9!cIm8MTp|AciqHq`uSv3(TMkz}-kw;M-*VV= zb&=UvrjyP{X~kC0@9m#-MFPJs-*HVaR`f=rlf=E&-A2i)M`#}&oiaLpDA!UlnfE&P zHOWVd_R2iJx@Bp?!Rf!hkvOSPhYj?f%sh)+GgG#j)v_Q znx6}b9bC`1>T|B;yt_YY-R-UL`okggYz#WS)e#Y@-Z(R{m=czi{AT+kZU??q1+saC%H zuKp_P@bE=HgWgV#`9G``H8h`f+NN*fTlcy)w_`1%i*;cG7R7X1~nLMi)ml3n*k$at}vj8Je;m6Ed2Ghwcy?5&u zebxCaGNvxp{H|d5tj+n0ACA5^Xj5{DG~Y*0(ca;bb?JI$YtIW2_3fr#)|{B?lD+Ck zm+eWdxeH`(e&hIDaPP*Hw!?y~tYXPkUI#*6sWiz9u#X;X`mXq(Hq@?Ujr@%TJ2@FX zZ%-L)JJTqc)X{%)cMtR6$9+*@MXragayfrLQpvq8CF7-f9Z$Yp6PsV!C-~=D?^PEs z_j8>7?Q*jF37;6->$a`q!SEY)Z?Jiz8@-;VP2;oK6({py3+9J$Z ze?&k3drnyW@5h!LXR_1J9_p<)@wQf@f7@OUe~-Ji-NcQA{q)Dx*R>5C-c4Vqx#eZu zjL7c8D^3P)oR@Ir)2fPVH}JUiUuJR6W-rR{`Y9eTS6TFH0k^TVNP6J@(@TAq%(f{r z2$YMsVE)7Gz{=GhXR8_RF*=Gb>=-FY2#r@j_39UFgE%&2T_s&w46;@L+I zrz6%f`SvAiy^hccs+wF@N3_Z z2jT0l?36sSC~oReqrsKWeekubH`-6pX=0meFEDp>-}X$e;&I>IrUmDo8jcQVpIPzf zh;8JpRol6Fj_Za;2p9hz&7Iz@)SAaQekAyg)5SgA1(^{S-zwhb*{t2V^j9cT)Z44( zf@#pHIo@{KYoBz=HQo`CRQEem(_ox`oj=?EmcgKKt&HFEYRMNBvqkFGbi~*PKUS)L z;+=o>O|4Ks@3C$5pN?(w5?oU|<)-&PsVX!@ufVHzs`07UG@_R2^G;e$236! z-fd@A_ua13cz46wRrTOY*|Qm=jecW4>ocQ=zjoJGjlHkWtQzZU|5D#RI^6xM-1PX^ zd-lj@ztPgM;?b}6JwJQfHw>1y*L-}#Zd@x|6#dKR{N|HSG>`30bZ1`j`S|tbHTL)T&w5%Om-id(luJxTbXpzF8SU3HEUY~c$>5|E{2s2)pWOpd#p7!tk>??$GpCW zopm)USGM;)i?!^>9i3PBo4qT8x1P;XO0F@l5C8PWZcXs?xNxC+1xd@jyzC^q9-TC} z>`a`JT~`DAwjGz-;Awe$v+^?AE2W9|1G%&{Q!cX3Y;AmX=SZySSsr^27Y*r}9=e5z znRT1D@OlxaUz@`Cl7C3NeYJl>f5nkCEc)%jdG?u%Z<`WNrI(&yZaR?jHq^gC>g(x3 zuEqsI=lOUnZ(UTZoSFP9{hQ|Fy}hm%E^_3&T-C~TcjZ#yQSE$*t1@LtcePI%8Fj2$ zc*$aHlQy?w&C43WsIE#~&xBmVV^UTFf-SQQ*Z9c3)>al5UYYW+=#18Ki6ZWlA(u~2 z1orISoVH`({$nZ^FRV5%xM}}FqrXsC=AV5WFOK+jalaEbdhaeSQ8H}vQLp~e!_ZGw zG3R!txpVr=>G|34(obsL<1e;$&pdDVJn!6iM4;DC(rRJ1L|y3VqEuzm>-!W}z2DWE zA-zg<>zzx@^x)L`Bt~(d?8nwEi|*@6Zro;NtDqcVuyFeKF8yP>Gc_K6Z>U@|_>WV& z>eFk_Q`uQ=hrcyvD>c^dP}?^WhQdif? z8sEr_qh;0_^%tKXV6>{Tl0RM6&NVnx78A49nydJOt;@50h8HY5WV6*Aa?|IZ8}|RE z`EBh_Un!bjmC@b#mg*f{{es`lX1c#VZE*R}`4W$UmveW$Z+CofeV?cPvMqkUci*Ks zp6Ix;Q=!r)^vt^86HiJv-IAJ`GflYa@~leP$n&%Bw*51ozhT$mY0BFgW_X;tIc@&0 zM1`fBck!E?>{)y-{JFB;j4RSM$IBi$>Iz8a9$WW&ztu)Nx`VD*LG7i7P0_h;wZ2Ur>=#fhaXvEwhhpV>%+^2ThMl|3jg_i(9f z(0iJm#EBUPhHEp@N=Nv`9Y-6{I?)g@8#gn~NwyDu@j^VPB#9bXuzg(Wp+0H)w zL^XEvS=u3^&jK~B1`E2IW`EuNySk%L@6u*gE=UcZL1N)-GEg;&;3xA3scK z6y4+XD#G5R=Icj`=TF|nn^%3fRYhBHqDd)tWBkYJ?{8mx{P~5IDpaLsogtqm{`*2F zxBkdMwdK3R*vtJF=Y39Dd-7D|)3j#Zv{!<9-5xhHh)=}iWfs_PHs;COko9Hmy2=yZ zC78?i-dy3wcOW>TcAdw}S*_R4D14E8`N~ygWp&b?i%h3Lrh~tS?Jv!{G*`ip=@*~t`Mg zR79k0z4nfCb@SEVT5g%OY`g0t^W+9*%+Y6CxND0}2F?2z#btI}vboB4%_okYi0u2z z^|!}en_~O=^~F3frK$YCu6iG_dv9;qbXZ)~xZv4ByJt6qBEBg<88zUvabA9U!=TbDE%bxf*PK}}~YiRddT}%xGG7lX5b||r$M~kznUFYl- z=4T()YAzQ^{pO&sINOJB2Y2X8d4C`5O;k%>TzX`G=BXq`o{Ce;5z3bdb=KO3On~=3Rh}L)KpJPyT?4uQF#JOzw+gK7l~{*;Bqr2ZpMPZsb7At zF)x*lq@v1E=aJ<|+qxIyE)=hiAJ6u@U#<3f)EfWziRiH>Q%<`sROMj? z|4^-Jm5KTOUOVmW{nf0OGKcDq%N+P-nee`7W+YALv;MxPf=d+Ngw%Z!$=sXl@_gN? zBf(|Mg?7Xru75M9B=qT}hoxG{on~97g+Kn3EFn29C`r`Ab&o~sQ1%_4ZM6=b=7IqV zyXu!1>A#zKEbob-VD#r6v7?I`BwSXCi1=kYU5nEQpVnx)9)3rD{{V)}dOLzk*h+Q=Q9 z>K>(Dy;HKA1H4B>K8DyndwBDg;U=w2$<1r(Ltb_7NSA!R&Uf%y)0wr7<>fzbg-1)x zuzRP)*SWO)rh@1EjZfz>x@u}4+}&FlwJgYtF7?pd@g9N{8q~1yq zkIho^65CEkTe|2HBHA|KwuIG-Nix@AWItXoj2uqKoU}g$5ns82@;(5xj+*o*oSved zT}n}kIT&DD%bZk2lRhDm66K45N{`XkNL1I1y~8qX(7uRGyr0hftQXb<>}Q+V;#FQo-V7}EjjuqujW0p_<9>&3lXq_vQpCL|58os^)M$9SJg%*Zv^id2+xiFb$RU8fl!_md?bfL zxcWfODOBPut=*tpQ4|IY3YoKLe6|^uX?j|7D9*W{j5p(WgrpoCARjj%ku>T8x-ylR z+Lom(X3DM~TD6GLScRu9&yhqKnuRG(eP{%X7-Dng zIGp2e@f=GbCm%xrcy;-r=nqp-KPOXFGB3AAcj4=x8}Y+r0+T{Kh7j0+@#gX-AI9`2 z4!8zXT$F3})LCy8=ifWbopdAGVZH&2*+4agmPHwzkJz?c4l6`7 zJ$DQO!-p*{?QOecaV?@G=#s!U^sB{vNos~*t`;^7f##*x(Fjs}1c%$$s$!Ak4tN-* zTk+y;ow=WMi*AEFYE!eE{takrO{vdQrBs~AqUi+u=o{`9XfY^TEjn_ZM5V?lz_!Jp zcpP>ct6~7inO*AzyJb>Tbh+<>&jF2*Jcxi9r$5=cTeRP*J0NAB3;o4jPrXWV^dtMw zpQoAGxf&rMzYse#^Q3W(&<%z%rTlsHewB%_P^Gl6N9g=gFby0MJ z*C|%kVerdbd@tz=7y7MS%SuQ1sme-jhg&WCblPCF5&#^;=K(}u1B5r%qT3eF7kXHK z;UWS%dSE5o>&L+S{onuX|M=rC+uywV|Ng5#{`jx&_zr*k=YRV6kN@(|^Z)ej|Ld>* zY5a5hZ~r`B@8OrWfA@Fg@*CW3X~ycm|81c>U$NT`5&B|LyLW}duu1(*{9gKDw4Czw zmH1wVxzQktr|XD4_l2|Qb%8Y40dn7eP+QsZ=rELAYxRk(kpM7YW}BM4r4+Ab7qw%f zgi?>WXz<<(RZuf^ceOzxR@|ikThdAF@ zWP`|A!g`Eo4y^Brb2T8Tip#yL+qW)yS6I2yDE+O6o&tvsh2%#H-_yJOog*&w3;_LD ztL`LsPfJ69Gan!sF_J3?^+Q^*12d2w?^3pY6}W8)Q~JYk^~i-)H@GbY{j?8?J??>@ z0EOxV)%FiFg5JB(Qn6{MixsaHL+#pwtUj(WWk&?>7Uv`hf+c&GF$tZX99LJU1a(I7 zVL@3eE^`Rb=yhV`f)St6vvN8=^B-^d35Zb;Ap`6+Ov!#&U+h8MzFGz}e1D2q@DAp6 zIjjTMv{c8}rGIh$r*`NQ=h4`p9LJR$R@WBAJTJn?0L06)bNsBL2TE(Wnespe#ld{x zRtjP;kf3qA#Co~Xjro9SDr9K!5wn*1Y>3C#$ib6=UQTIaKM<8KuoN#{;mVeTv=xOp z7_?6q8r3p@;6I8DNu-C4{>W>Pnjm+@zI@v&0O(P5nwGy>1+>?Ee)L@2P0G`$@6p|O z2>A_G;`yjA2N+F@gzs6TxrwEtIJ0lMT2J!BYDbdLLjMB23epIl(;rbvYuq_$~5tz9uDy><6p>$X+O`u6Wo;Nb^-6I zfamtS41iArI_FlPcdyCn4vrm8Wb9@u8rcgu#4DifuvPMwF!|QV#(1pQGKe1aEBgQZQ`LfF&avYzpbC0WYU#R|e!j9bCcz4+cu$8o+veK;YC8=VgO#8vs zUMA^YcA&3u|ElIE21bEycZhu}JbErH!lkxv75M3vjWGD>LE8tRqOg8+7uTR3k*Z_t zzL&uj4<0P~2xa@ekn^ZdP`-7j4!|8@5Y}wek4+|ZanCneAiXoz9qo0%QtoYm6{KBPU;?srNDUu|k}lggf()ssLs zPKf+fqhXF95%DM0lyN=xeg{$@oFH(Up}jWMC7FICOV{uL3K)+>rsgXxhdAb3NT?Qx zzMya+5%2_KDwn#O<$rT`4@d|2f#_zAd`M|8 z<`}kGz8sfk0oze=R+ovhlW#wYiG?}YFy>O6(?dy=12=D#^u~z^htrHRbs~+#wAZ!T z1h<}Paq9V0wm3|0T^yxZF@y}d%8NNF7~^eeoyN@v5EmVkYKap}zd{e97=LIJ+AK3I zoG>l8B<015Po3jouK}GyY2}h!Xs=X*vTtV)R`V+&Vm>ww+{u|x_Ot8w02ENdZd5HG z%K%K$Wk-dhG3v9v+kHQ6Y*2}2Z@@46BhysT*1aRu3_ol*i&-Gvrw?BQo`}uS5||{F z3DGM!vjrY(xu?IkY7ZdQ^>Az~OfM=H!5|MaaPRs_mV^h9gn|6^Y@4aBczC}z`&g9g zcBhu3B_?A43cB|R4*60j4%Dz#R6PXl`#)r+20CTfgO@e@gOxCF2k zm)jyz8w#E!{d+t2U-QlX`G4@uKm0qs`G@})-(dg3H~fz_{vF@Ic4H*$46pw|z9|8w z#27zb@caUdBOb~iY;#qU5sCt*f_mU_gDP2dJ~zNxq;>`4wDl$Ks7eWiNXg-NJRCA7 z(zQl(s6&Q!McrDIURo) z5{sw$g7WCZv)RSqVEJ(hTtvU=>#6ZNR`hiphP$exgjBi>kGzM1YR3G2B?g@b&!)&h zjuCU8Uj?aX5-xX6}5)L!+8+AwtzgL-gJ|F$*tob?jn1hvkQQUV!W}bIik__y=^>{Zvzh?dD3v<^M;oeFx~_ar@Hr; zx5Q47_N?n5Mj*Cwv?t{(wtH#gXL3v5*9EHQ#&@QTtGE=; z(V8;`b%+GBL(`vEo--g4z#(pmVdPlX+ppfo*y}z$cjcAyp(p7DjqE~jnLDiXAcIr4%5YckU5xLW4Ts-pDbBCpiRYEZguA+IfQT;O@`z$I|l=jUn2Ih8MFWNp$W*2RXc;e{A?;v6)+h4 zMkDSEPMjY4JKi8A#L6}S?u^)}1a|B40y_%rd||AJ27=Yd!_cUOrMhkTGW^6#w$9x1 zl#9127g&v{f{T48@mE8GI@nJhO!Kk2A(wi6%0nox#f-Pdjmb=!d7_7%v(ae)W_O+; z;w5hp1ijB`$pLt!Vhq!^CXJ}>u7oW8RxH3y5h3GVQY_b|8Of;+=i-y!CqXJ9SWZ;e zuPNrJ4)hWk;^>bZSaJ5JtsUW zD^A#L<42g3+weuP$LtqX;cK zl>DwXWmV5OHyZ?Gg{R*!Ntr|G7X)2z$;Mky&HxVnW{PCjECZ*tU3jZvnem;^%dZg> z>;teYzTAMGw@$UD1q5I#hRdQvK~#&}9t`jz~QUC3=TM`rAIV-kAB zu({cAJUpHfAeatEOMMmHR8%fpm)@op$NJ`QXcTwV(&aR%hkHip=lh7)k{iWnt=$BY zR+C2;Ee1}1hlPz#K}5dwP}+)J!$U>eI4?vy&>o^D#enft>H z3?|+P?0mrT4Vabrc&H1dal6ivvD53PkGV70Kb%GHZ0n9d_9>0DX0B5OiF=&C&6A?A z1a8=gQD7bK%r*lb0@PGmIwnaRp%UuSnO1OkY)w5>V$elG>y_n^tV+dTfD;rfb576v z9J%u2>06yCDAi$np&`0XF%V>VsZQe5M{+o_D6sXCNK2RK^RwFxQl&iDe=*ox){SUE z)Tyz&p!_^s5ApcTq1B{{Iu1Nd2+g=1Z6=113gBZGU_$PJ0rlnJRQS?ZNul2m97vY6 zosWa80xD(Z`LRV4z!0I9x&1-AMMmtNaT&nD+_GqcEWFk5? zKYgj(RRX*!A+L`p5T;Dj`St5*Z{B~1N`uGD;0u`nd&YsTjBhX4f;;9q36ukdknqyO z0`8#XiquId*^JpLXB;&oCi13EDfTnzLrofW86n~IX#b-l^ox)n2O_%tk^l0H=TH9m zpMU*-=O5><|1JOgIsgBAzVjFU(F9$rh3}V@8oxqz>t6#`c3=A?%X^AVM0c$0V)Adr1UZTk z5Cze2e54ye@(7lWu+V}m%7YQ&A*uC-74;2AcX_c|#a`#;lrIE*5>Nr0sy*_T%#~n+ zv;wX4tQ)!z0@a=QVO|yaUd!fKu)#kdj+O^ygEV{9n&fo4pO!yR~-k+;pR0iMB$CJCbh@W6STkSO7jI-_slP9x&vb zHCZ8IeaxHhp~v)CCsJ&a*tB*5TWrno3k5@fkm*Jscr(E(Agmp=Cdn_{qTn!pnU?H9zMS?NupM4e6Hmuw_3 z`P-l!AYv{&rE#j*$$M`iqU$g}3r3X}DY5cF=|S&uZ-vpGK8IndXmS_yuDK)tbeFtl z{i5lwWLy=Gh`b9-A^zvY@z)VDTG);uG&t$i3H5&lkFLo2aAo>>pZx|1=y!bpg zzXPcio#?zywlk11P*PuNpzjW82wa~Gy& zN2G?T0CM5B@dKP*izli@CCgCEJVigo4WuhBc~QeH7+b$|tyU_;{r#7+)aKpr7_$=7 z?}7=A>W(VV7SRJbv(1$$fuPQ85bfpEO9lbbdlkYpnFYeQ=3yp9EfDy$DYzG6WvizA zybG>OyTt)f#}FU{;~rmMKrxFL*WY+q&PN#gf~rh&c432K&uf&2YnId!taABxGoBq$isze7=NRV7B7F=lfV|$k5u{;l%m^H0|Dle*-cVf%5J=BG&Y)TX^TRo+(Nrl^x4aZ1R2^< z&GlJDE5`8XSTi`mOs-Iq*QUWzd?Fo{RvuTf>$MW+HLx;RU!}VhQq#71CnitYrP8sq za`F%^!Xp#C*Q=G^0iZX#`dTG&h zIp;u4L(@Yei^TTJvgkZ*f$&3Un@=PHCjb*I`%Kc~ZbUDm42-{ybL!j^U>|Bo#bUc% zBV`^+auQ9&VOG4D$~03ytj_DQ(? zZA(z+aQs#u?#}#YgM1KZRE>7+2P6nP%!qx?F%wAkg>15l4YeIm4`_DFK)9)WM}uTb zb)(v@v$valKYvuO0Mu3kncz>z;S%FK~~&{lpKy~ z+-dOCGG!dk7OZfFDzG;SkRU6ZTs|8K#fK}P`6{4Ir6dW-GrF{5sW4~FDnA=QCXDnu zoW&VX6(D}ZK%#0up!DF5XjB6#{(`d)fl2HDw`Ul@Wl>Dw?~iBuHN7*x2weiwh94Z! zvv}$E-VF+}dgELUU6=IBahfcK`0MXq{^cM4=`Vl1{?j|mfB4H^{^NW9yLbHiKVSaK zfB4({-@W6%{==X5Kd%4$xA}VaW77QdKNri`+uKqP<$wRjTz))}q7Oj`Fek{=I27!U zC$lxzC{?)CG{aefuq%xXje7ObL&waDWY?Y*TQ$;T+P?Xiy9FgB_=M5g z2x1Jt{c@Rgft>Dx7z8s6B`I|6zR|Aj9YxV3SsXNx5TSQ%#10r-T(Nk$boJ{<_l%PN;?$aMBmdDQ z#yzk~Et=vEc`7 zd&ZsY8PYCT1A}+=n{x)A5Pnm@`@`*6&!@vv0ErL0Oygk=3fOGCWrvl(!nKQdptB6krd70a?-XYCoU z7kW731L;>aD&|;emFi*C(!ES7V8JxiFT8LcF#~RLS+p7mSwPLP!QXDx zhLRZ>7V;b>6PrfzfGsix2ku<@CvEOUZtQQ}BGz8TTZ z90{OV*n?dzbZ)=^D-UPZps@AR!8Ai#&t0(`i1Jp7z~dmm_WN155$763td#Q*k|s4|vD$nE;mde%86oCA z&C|W|WI@0GWHfUJS6rqXSB(ia#NgQlvr~(%Uxc5z0Hq4BD$-GiHr=$cEI_sb#LrCa zo8?WIo~AzeNX>pHpy4*SbL%)x)?$d=tB$%P&J5;0Ttpn|ZFvY4GOr`xffx)vuOLiS zStu-mG{Op0ed9iTuu1N0I;ozI;;<@(ujUJX5?T>$&ISb?WX9Q(a{Gr=j8&5gJ7piQ zBq^uWRiJCi?15_(n_%EHxPzkQ6}t1z&)6)ZoC@&an=fwQgR+v+B|F{GSHt3N+D?PL z8K71`V9JN~&)g-fyNGRN10&N7RVPICGQn+O8a#j4qZEf3ORkhD@t91Qniq|jx-Nu7Zi-vLo59XxQe>Qn*$r5 zisTCJyC04fHJSynj(i%nL%tc%Ikk-&gV3D)NDh_?aa;azzZ5|-EU9_$P#Z$zEn&Ec8&7BoLyL<|sRbHqkK_BTDR^N}5R4Q{fHCPUOwTEo zplkMJLmWo-IRd;{V+6yjtxK@5b?;O) z=tXds!-hlN0JC~RJrwc=>u$jA_CP7!GECXhsW5 z*71(hitIe90yYHDx>pkzV;gGv4|#1^2{Hv|63Zx`Kd?gC0xy{C2eQSjVoWIW3_!f~ zY72ft*5R5@oM?o(3?CGsxs%lbwUO&M?@?86@o3h(J~~z8y9)LAs|7sNl9;6`&Zy#m z3~f=G7j-X*uYLbI-BTX~Ib-;nz1xAsJl{Fsa0h<`WGu*UAgGBW9#9QGQhcH9NZS2H zOo8Pb%7r6GmP{oelfFs|^pf_}p5-wum+VuaIw2&+mo&f`mH1@lQz}!hX%SiCqF-1L z4ULrr!?UqO@9(N*4Yb_e@L1Uh!SAR+tUx0ABdiSK7REwj!2W=7&&VP3uU+}y{{H{& z%K!0q|Js#*%>PYSw%Z{>9`>6 zjHwyX5S#kxzMByct+C`8zjEHQb&m@dtaZ|+{|i*gI=<^Su|7*F^_D5H)5Ip%L(PUJ zezn6ZL~KrOkHtG3qWA$93v0amun9BEV1;uw6fjQY=EAYKG?(b%0^XQHnE5#hmfI23mHWy74O)QIr1gh5`qT=Ew=PA81A#=b4>O&rKSdLgHCroHnx^Kavb#bKx=v&%wrPq%WRXc!I{N1>Nlh zYHX41+HXF#B-5U-gTGDU{jr4lek+mftxLW1SOzf5@K(DAsLg3$s_hAW1;O%kw)JNR zh^vK2nPW-zh3rVP@kPXc&kK258lG1vw9L&$Wu|ku8eKDtvbX6DdN9!>{Rt|&BA3A_ z7(4k~G`^Do>Y*;53@=szf?tr0^qk*yg3+1l&}~~ZY6toWs|N`-BQ;+Xkk{n|+eh2O zUtJG?0Q152y~S-3hr4N;-~A^vkQFLzXn(IHh{v~!w{h-*Bs!#xr#l- zf*>*m@Ig}MSeIq4yQ2X!W>8|z?L2SquRyQ|2w`+<2*>3$8i7pRnVj0J><4d@*5UuG0J)ZB@OP1UgD}slDPX_CGeNp2CCS1+OAYfHIdP*itV@F zfyL8gEK5!2=*UxFC?9Y(PF@0OXzGm*R|->gVPPsxiThM0$eU@x6SVISvFx*d4Kh9V zx4A_|laEY3TFt(%Y+c*V1EuGdylsyeYzEL?hRIVx1y}X}=F%cY3NONa|E528L~vGS=*r_iq&NTndw^Z@}Y?sK@?vaypSX`sQNCi90R^ z3wl=Atus^P?(WqeGm_1MY_S)EG7q*RyhwbpFo^cNGu?5miGtZ4o+e{UtecE%ni&E( z=r{bXNX9qFs~IoiD)dQbR96J_I*$lJ32g=>)Xo`$(9ChT2FWc`g6^;Umas(i72E`- zqK8*9ezyCt6>~Zy4Z9CN`GecLD9S;x6LDt9&NzZwPD-hS57?&YTLn0LKZIzw*c&#u zF@NA|`Z!|&$SW%VRVYawXJycQAE7xGH2I631`v9TBPQvaKx;;;UwhY%A2@v>nsA;* z7pZW!9b`BFz%l6qWylYtl04;6#B{LK4@)p(x)JGP9NoY@aCKVc&-W`LoQ7j4KN)5o z4Jr&Ln4WimG9s?23A;K#7L*XNU+C`u$xp$>X#JM4j(}*v$1V}DCwVsWt9aWn2xdAU zJwg(GG-KmT7<}F07A_4JP*Vhj4{*_r++PK-VY*+J>Ixry1r)J}TJuwN+c(WX;k2Yl z>;%}7k;6{~gu=l@M#w%|d(RlKL70o58=w%WhPMpWpqbe02RGh>#Vd~QMya&i@51eAW(F7L z!FeS47+_RMjj5~Ga8WFoK?;@K#V3agJ|_!lzkbEiEU4spE3#Gb4r<`!Wu5we{QoBX zKb-Vm{{CM(>5uvUhm+cW(@Bfll)vv_G1RwGs}oy80bs!NXQUhXF<$KwUAQGS`}%0hJ*TrvSk(LQsrL}?Qz(5QXog!8Z2FY9p-@BZ>mpq(w+jfe3rV)8hj*2-<*j-Oy(@{g! zxRDx)B#Qbq@?jq03-c1`WQ=IzgZ6eS3i63~l4Wt=9w5=|`ZqG$cw-I0K7%2ORxK(J z>`U|-*n_2YgcHPm!#muMJfl?EL-2Msn4zo1O0R+DS&cc zxYP?<=Aa(mf#}0-Nj%TZ1Fd;kqCZm-)mVu_-xexwUsr%{)$qA2e^O>N_%`@0 zx>?5uLA@A?b^RW*sK4)_Q3gF-!cx)xAvIlGlwTX~2oO9%t^l9yrC{ce`JNzG_B;B_ z5iW1{`S6&3*UX&bj%Bqv4nR1zP1vzQR}P^|GkcN9`<}j4UXsBEmV2c2Gc;IEA;sS2 zxqvKM#wlxz35)zO1%e;}kCxY<{-z~q=dan}193HUgMpj+^nKQY{TEFHMn*A$BWE)n*0H}#f4P9$L96Wo zZ{>D81gLxXN2)-(HtUgyT4ic`2k4jDDRIAXea^i*dU$plk&)VEy_F~F(&hQpAeHWFV6A>$^@h}GvccR z6xL`6U}mj~)KZ@5m)A=bHcXPx{V&C6nTME66d&nh&82`QwI!N-dOAX<9n=79V`IIY z4I926%o*`vu<1{+ZYS9WkC$D87TuThbsn&8Z)myORHn-hzFWE37m>I9(r({sR2GJ? zx&2%P2ozP?;j@Ac4^&UWrbMvH6uoNA1=Vl(-LIAW`hQvJx$$03@i(*lVI^G1oFBRZ znR3dssb+IcOr(-YNu)pKHvQE~{%a+Fi+GP|2XX`}1=T4nKH`j4`ZSlYNSe9M1gN5R zZwse@Id^jcU^DwoS6a&C7I92ZjATchk^^3e>*o(E)ql0pQEJbdD+pv)B^wIKcMBtI z2KfO>ls!4HSKXvb6PZM;NhhG(7vkH-MKx$ z0a$$CJzw{iHq;`CztL3{D`H=Dkm{N}gBgS-sohu?n9?Xf8IK94uA1;vFKGs_Up{P} zM%#)7oeKTn0u-C_>c(A$I7{_1dN&xNunE9l4Yxq-`n z$R42&C8U+GF^CF^%^7D!n7}58a8jj{m!;x z@LiKSgdeaRb559mb1cJBR3A8wG^v>Ezgh`NY-0rovB<{!%RBiOTX41fny;0DKdl68 z@HqczCBFNcmD1@XMC(7U?x#q!1G!OZU8elc&K;4Yk+>n$vR*(kz&eX zP-8Y!^mQ;$i=M49%Cf@k^VYhP>Jv!!i7fak_ zfgkFoBqC8vd3$IWJvra8yT0vn=b*ukyTP0hITHJx5vqVPzB~0vR}@cLmEleANq{UV zLzF59@0&QH_HB};QM`!|mv!$pl4Uk90mRY&2><~9|BTp43iQx+AMh7Qg0UfF4IU+E zpuRJBP?Ac0-%B&~y-Izz3a`xrugChHJqR8=QXoXtK*c?rd+zVALsft6w+lvBlz+2f z+g>)Z$gO(SO_2Hp`zC*sq1nR+-D9GZ{p0`r%U?hL>%IQv@Bi|b|M}kk?!Er|fBgKH z|M8#S|J!@TfBzr%KcD~opWoMe_@(VX{ZqO824`EEvHCy%Sjdkr(DcE7eQX&Ec$001 zvuws=xW2Yap7`kBY^$AAxR_Pyf2>??WKLZBl9Qx?GYi%UrK{c%=L$SdQxp`^BKo-3 zH!lHem)z5~VQzUIA3wQX-IgC-G)vth`^Wk;^inHWMCw9=8Qp(7immx}jxlGNIa?YeyPq?@ zR6*(DH`P6N*TRV@mrfr`1a4v%f7(7~{eZmBS4dQ|ROF2j90x93>p&#y=iIPQR<5;9kbE*MKkX-9Il zeN>tsVuz!r(W*@kZ9vHYjHKI!9_+ZLqk*b%xg%_8TcpVWQ~fhzQv*skO&OeB*Ii$Olz>R;EPH{vu1 z|4hJW*FUm#tuAz$=DR=jSUsG0{`R0GVQIx7Or|>gDaQ$gFj^I^CL4p)sRY*k_0 z%*uMu&N>UMi)fSft(lrwYz__*#PlIp(VnXwT&vp@$2=5H6`06y*_Go{BW*yA$d52P zC~ksrq2W@ap(&%TB1iyW4f!8co}>VwYSXhnq0TT}J{|5GphrK{q&MFZHZi|k; zW89(vNEv5V``L{Y7c=J=3OC=x)lrZk^(PD#p%%B%X}R>`!(9NP#0@eA7D(;2=XMiu z0PdrdxVcy|aD+LH6f!j42OBUgwKQ73qzUDIgE7}Eh(2c0rve!lBjSLSvd$l~+GREM1;7kNKj9SeNaNMBpt{Va zw_kbMG<{aKsTh`5SgjiY=1wD0#_taakBcAQ<7yKZx>|I( zU9g<_66T(j8_+QY#C{*p%sXvSHS0pZ(x&)#ENzj^UdGO}h619w^2?N;qYC$sVb*Dy znunOeBil?x`i>B&5KP+?%_g04=UJHtNQAz9<{;8HYB!c=9J?6!ohbMUlBgJlm%g{*;*sQF9(4g84PicNLyIWFBp%PB$^14WaO*|lpciSSzz|PGDyCix0g06}vya~jm1FfOkJknvP z5gAJ|1guCu?9IYL1H$Z*risi! zM@P)rwSJP(s6h?#CR`Xgz)(U3aRDe{Li0?j5iGH>eyfn;2|Z^Wbbx|!eo9Ty;R&{u zpDuJUc<@?l=8sJp#25ucxATCl%y&1|oTzbxc2QrV{Y|8p^6m=b;6c%k8z40JVF}lb z!DLb)4ohzdm&65VR&E{GJk-^$iFP6PRXXjrMYq~(;(vDTu@3p3t|Xdk1uFnv`ivjE zfX7pRK$<(-Lp;qbZ&LE{%Woze8;^E{5$7VsWHzpcVm)g_^TiaI~v+-SXld&+qHFoiH}oshsndr+ z3!v|R^OQhk`$^87SeB~z+gEv^zfDV{HYF78lXiB7Dv|quS@^#AO5yW z|LwoH^xyu5OM}0<^hGfM=kFi(?|g1}OHr($fS7w&@T6m`#97@ddlt4g6%$_%2E@XfP)z7>Ln$pn>>Dut7?W`G~hi zDZc$nzewG0$hNvj+RI+2)jZR>q&0Cb{vNafm8gMpPFB40sD;8PW$?Fcy66hs=_U9Ej}^Q>}nokA}svv zSzoL$sXB|u{PF4h$EPDf*NZf8{>bJicpjghg#Nsz{B}o1tXl{z+VqU-Rt0|Sd*gmQ z6*;0bINCtA*##2J&zwmw`PC+tybw1g`~;OOiHF_7L0^(rH#p$wFBvQeEKI?Bdw$6!Sprt) zHujv@iUt41E2G2d5@cG)Zq>ao^biC@$n-V;Ww zc{hO32d(^Mq66GEA=(^tmC?*&6}*^$q$uh5h-pfMDsdMo(tSVsDCQABas8HdxS`#! ztIyNA9Hv19ZeM(Vzavv(?NO?G$#=QZ&tqaQ0ZH~>&o;V}->1}F_{+yXZ~ zE!^SCeIW4&%o->4Mu>PEEGzQkU!#Z47uYrXBFr6- zv`+=vsRWiUNC7ezo4&R`JTS=U)6B?34ZEu{k> zbl&jCaQ4lqCITsD^ob7zZ|FGg7lL9-A4bG<%=Y7^`nU2pw=uAG-(SqVCexyRGI|)}4R@@i}p@eQ6i_7(U+3eNz$O`j~ zZwxoz+2F=hD2kl7qjE@^J52Jqy`xV|1@_~0p zF{Z}7#?c>|a+jYA&Sqo~c%6+g5({oFm5S@AgW=wpJyU**o_aA{Uy!!5nTK=2nxDrPzl1~n_!hMapp$PNtgNp8`?fV|CZCkz|tsRS%1dG z%^+>z>mhIn+GL#^F>8zT0}T9v*OoF6cvy;hg9cKZlpU&i+WFeS5|ft=ubJ8_^f15} zaB+lgxQsz}>q59wFj64#_zP5owY`4058@6*YzL=p9nVszrkXU|-{@Zi1s!u4Du0XA`bm;HvWwr}||>riF1S(K}| z94KK)%C!{~N6ey5<<>o4+g`>I9NCJVb5maCqzPqczq^XoVV}hJ^BZ{^p&k&CSAqPd zn!Q5PEz|cZpU$RwoqAP3z~VV6>SUcR`RmlRv=Q_fppTLuJjmrP^-f*A?dDnc?jxZW z*igf-2$LOX=;{w$V8S8f`T!O2^I3zBNZ{$4FATwZoto(GXk2R9RvUE_s4ArIR+{YA zW%i(^2)mebn?H(H5JHr=K`1WBcqy{-_uV?_4aj(n^CnA6*@5#DyJavEyTyRHlwpd8 z{CXLIDbG#L)I9=Elz8k7lwiAn|KwCfv) zYC260FZ0q0P=j#kFCIr7z2P$Wu185lKlA-Av~CG2(!v_OUjR%6-D?xau~p0Z(HQ`tiGw?JS6H0t2uv zx5Ncn1*HB!&F=iUHEIflCPvy3FZdt?F!^O8SO7E$)5Ogbmaip>{#FZ7KFx5aj~8lp zA2TKU+6b=DPf1GPhe&O;08t{DNk7}{14Kp%9Q-|Cq~`WEQL^_%?Uz(??YbOxM*Qp~>}&o;#xzsFE(6sv2dGe64B zMq~Jjk`#IzPju&O!*`9$EhrU(^X0dOiMzv{%FDaoNa#7R2k&|wuhqxpAfd+>ZhT6n zpwFI6Ll8f=ZQE%e+7N8dra=>(9GuDxdK#RY+@!_Ha12kV(JAoI`!h{qv8K!g({~~uLz$-jwRwe`uy$lsLme692C&@?( z!u3AzVVRsLM1M%&cz&QBVn6{mE|GFyV1{s}UBd{Y(TEwT09!l-6Q9h0cI`5)5CScT znr|ky_X@_)&3=cwLcfWzbQQqt=uVQ;Z%iLQKh4_@79xBszT-5CLy9!}dWb(Q8sPI= zYdy&2NrarhzMkAKP>br`Xq~|Zw1m0dZ`++%OSmKoZg;9WLrC6ys+t#@bR|t*M)>rDOM8hxXWg7gp_J*w@ z2r-;zu$r$DXW-`nM#vSmD+=%U6qbEmwWq6=eWU~JK(I-%t^U|UxIOChdb1N5pfE(3 zC^+ciUig>!#)0m)zUSn}(zHv*;f8~DAG2+Xb&yl8y9mD1-wzbWPLuF89O;LdZD`D& z;t;d$&wFcce7qtX5j74rzL%@gK;TeD1lOo{3Vx)<0>wF}rK3-8?=?`qT%@_iG9>0< zot_i5H&VHXX_kHm^3Pjp>P~CqZ5%9f8}ORi20mwbe8X0DKrDnDF)Ci_XX#L3d`GRs z(eV@EGKow^h&fk~7DXM3lH!!S<`os*Q{*DU{3eAuApqRA?4f|?A^-f+>$t&$otsFH zIFio{-H>tuRF7^~7AR1!3RNK@<+FOodeScg{`rv3eT<>H<;y%`M+~HKVu|%!*ycXl zS8u910DPaOkaVy?x(9_BqbMD;$hs8Se}f7KRe)U4yCs?PHs5msin=X+F`T_#@Rp&l zz_3?DNTtTII2~!MxgTqU(h3-DTW?Z++ki?=#S5tfxx|z!7tBjDzrRhU@Yn*4mf-RB z1`*^mANw^+g_9IDT)^;focFKUBmDw^X68Q?ZL7vgXMVoj;8ot)!o#@%J>l^U8w@e{ z2Vfr;Y5`+Pap@V7`}g23CkzI1m z_=;}#5Oo`C&zHm6S0g+B^36{LpphoJsPvJVU$bsm}R$ohaVL19?d)7P@TIZb6jak z3;7r1yXfy7E;_+lgBl)c zT~N3uCMRlcl5_Xxtqp1)2z?)$&}Su-_;lW37sYdZwHk&nzaek=eMJw4*Mu&I;8KhB zv(YbymCC1yB&#gy1Xas$)k9~OrmUSdQ$Zl)!GSISMwvfbo0M=7W%hv@PAO6akqx^- z&_k}D1Ev*b;dT$R9q93OUIEY;8)`W)vmyvt*TBj1+Exo~JqzK-!LiUsFO>v7XALSGW zR-{TvAw-SBQQ(FB?$(3C<6SY!<%f9D{|JkZN`N&Gzv;N4XY5 zzp*ZRM7b=UdCaF0dJSVi6yWb_nTx3k=&G=UTjepZG4cq^8vXA800960teHm+#7=hJ z$AE2&wJ>}Jt!!|?oCIjWOg3{4JH}=vo0&Y0j-vw@I*$1tX`?ah@xlZMq8cbP>eZ|7 z`@L7oB%8&FLdWSzfh^%|n)`X+_|a?x4JPm z0iec$$+?KGLt%3y${h{NA)m^wpgrX>P_UH{&0l-x>M_3UzFuO0b2t{DrN#)_X?K3Z zJ3B)(Ig+)br;C ziJqjd(d?lw&2x~0*bx=T67$fy&_DkD|M=5ip8xv3fBr9j`qO{@U%w|^V2_b_GcKm0?rOoO{E&G`NAe_wu{KGn!%#}C)hD*bBEW#TZEDJv zQNl03s2v++lzhS#Nal7t=M@?ZxDu$Y*RrKkxsvqP->BpQV3LX zcrFWR4sGhRg60* z2l}vcbxz&=*auEYPy&ytAd1N{m3T=NmJLh9)~8Gs$a20>o>MbscyXxoiiHdn@}WmC zUbzFMwEPZ)`*9A~t#u?4pIrhw4BOW#u^gL!_#r{tClz&@>FJsOp^Hs2eNHAhY(!_C zJL96L{jQ^pBpOb4eC5$CR6etLd1)abFN~8-w7qx)v|E&yCox-gg>a<%4f!xx29!96=sn1zgum+{Hx$O1Fu@^F;((E5CIQO0Me z{2cY(SI-RMri0?6Jg^5oyo=Lmq8j>y0sylsx&w21y44y!vYRJlKNvP+oT+ch+BeV6 zv{w|3n)kuzXH;M#0e3ntOyF+JZ-zXPjZ$*S@V#^Zm9chMye6jm%RIc&3v7u~c!!hA z+5lkBXo4*RSRcg*pFZslIbYw|T-t_Z^dkb!%nR2Wl;vZdAJxc#uqr6KWmY7k#?(Cw z?1%4i^;PkwU3742iR6s49EL=oWvXRck$1U^P}HaoeW1KrG8SnMeEgj3eSihmh6y%O z2j?&zZZ&F|7aRL&H18O`VzvFifD1mj45o*tR$atNUPpS?BZ6z)K|ie6LWoCJGVNEp zzbY$~Dq5Em;3}Q0T<##e`S_rMzC_qz?l1nD$EzZE0c#EnPf1+dmMw-$BxOJr-gH^W z0ahcg>>`ze5j3Fs`7W+&O@sfff}p$)YUnX2*hc!id5^US-Fw2pYhPcHKq$#={XmTy8Z2)(8l1>@V&A51yW+TXNk!TQzV5(tm6edwpq_S;Z*dHq^aN=B^(ttsxV9}GAv5KVYbYf4nSyB;zg!2VeDfikoJX(Uet6fqwx%H~K0IQkGA4!Zm4-VvyFpjf{w{_nhkk(=lAxl1{h7?ZDt3wMQhAb(6}*Zs zQyY915_P6lBncTf?rP1TY{S4WoMGTc0O^Eg*!A?O_Y6OyU7E@R(ef+779Zy1^wgQ^ zQW0QieQ#Kttfn#s)Z`3{?gHq9x@AiSCX;nw<&SgqH%B_U94bMN=p!pon|bbCSbfuL zGYsRhelQr{YroyqzKRfA{Zs=#TOLk%yq|Km`XgmTevuw_`H@SH(Ritnsb!6geioglh@hdxsB6q?$@B2qg z0^B<|pHQW7KGozDewrtmOi^#h5R)_!j4F0C3OMU1umT~i{re+>uV&3FXnj^{R&ZnN zj?G=WBp<1`#greV2$^*QcgoK{y?taCEa4U=&!7gdl={@tiamRE6=%RQR4aY+c&p$o z$R=O+MR0nS*U&$>((Trdr~NvwCK#wO+-f7wrp-^U+XQAjP?WNlgW>z|=(7kw?c`Wp zTgRA6RcGBMxu+eaLNC{_?bDf8`khzh^-ZJQjBEPTIM&e+rI7FZLV2W?@hudaYHn zDx^YzT$hIKpFIWMX9VlTA?1$n`_$j2g4P-iTOlHd-BsxH1O@Xqe26=2kVBz{v7wKL zTksRDWtf30yBli7dMgM-^*$4f=9X8Ba)W&V)#WbIrqa*HXtr+JhAOQlC{9`IggzoP zt+gg#2?d=rr7rzgY>RH%xd`|%e&8Dbt*|Ctdqv*G9jyvcUgU>uF(-!~H-~(>HVZ@9 z$L7l=a&zdWgnH-IW)sY~6@e-Ig`>gsYVfb539{8r<=w6Qq8F3LHYx5G0)Q5HT>EA3 zGm4JT{z}G|jTkC(Q&Y`UJCz<{^1iyN9hSq=9yJBNbGofdoF1j54dNtx6bltD%S3=eECtep*@`7#RLv^$p=fwJ(Ya{( z;1XoW#u;r!W{4)IyyP5G!zVavSSx(8PM?L{(kR-(%F2cbl59sK5vZQ5khJ@7$n!Ea zKr96*0Cq-GS`+|IhKgJAN?l$6xJQ=xnwdQ|oUk-#uV!}o{RLV1t`A4lv)HAlI))V+ z_yg8WsavS7Dk(=9>s(1K#lfetAdjk%SuF<36?A_)1UD}d0!@z(nUkY@|itf^$caik@#gR9uJ5g zm3K_{A6#bSH2jCW7H51!W~3^_Cv~)^>liskj?>izAxniK zrgT7`$0-sJNWPhS{>>`VTgA)*=&je#IABmy44iQzCPELse_)Hw4W4JlIKgY8-q%U0Z}3y075$xoOo*Lm1l>aNa4|`C)Nx0fQtK zw2AS{!SrMJ1$dh3K*?$^olcok=e;VoFr+3=#u4^>i0iXPdBB=VNLgbE=E)flLxMEk z)i&Ad@;|g0e{hXGCpV{m@KKsmTC^N6AXFwCd_op9KgCgoBR2Q{CMD_V3JZygpSS%E3YeNQ^chX$=427 z9t(qTTgMIPtY~dFF|M!Fi+VpY5J54mqbUnHEL8JnZ&LYvS=A0|Z(Jg8O?K|i$~7cI zfsa59kf#_Ol2)_@88_8V;eyi}e^FuC z!1W4Oe;pw4ER;-)XG8M4Rhmt*pVb$JML-kTPb~u?C0hAD%e5!~NuR9}olD;toI%dR z#kyV096mPaIK1fhC{^>mWslHO zF`B%an+20jVujOth>JGjl2Sr1vi7$7DeA9=;#3WulyxGEyoZ_ohcm*G`h2&kO1#gZ1i(K<~ z0L96L01#9Qn1*_>gX7fwia3Bm_&xJQm=N2-9n=6V?w!5N<+9i4u{LdJNnoz8-uRce zuwa_CTSZ~YwvNDRarU4*`NlTdV05hZPw~M5;6*r!?SO#3!VlG3;axFY{c0(7V14WO zj`o;MU@IX7Kw&A;8h{rV@GSK=Yb48C$8d&k){merB&%)tF#+9=FxC~VbIFA;5s@4o zu6;d1k5dUrM?9qP55k~D^_vK=`QCT{W!$_usrRUbh~F|LneYz*?5}3l(p!aE&$=SA z0CqXMCoOW7)!ZvTL-Me-lXeyV;i34ZdvqH2dscwR6N$*9#zw8~5IEAR<#N9YdD8t( zG;3!n`SRD;zp%11$$9g1?i{LC>+WhIgX2|vs-l&@r>}NCQK!kiKMqR+B}#`*6c<5A zd3jKNC6MH1Pgc`ZZ33e_Qx>n~kZZVbJ!-d>oZL%QpUPdRL52)!Xc}_hJ<%Pti!Dxk?F_36$_@MfBkFDwoXm)7yeQZ?|Zu<{zfgLS&tUN1e zMYU$+FsY8*s2-SeeSQ4a((zKJiJy8_q`yNP!&Y5|^S0;Cca&zzLsSHn+=8?QJH00v zF6e7)I+C@<#fc7vrLb(y_4G2+HfG@Q)7YeZ7msOC+ocqPWx^MHr?5QSJWIutvU8=j zlvK7le(~BH&1&%SCd2REPf!XF+)35jA^a^(aCViR}$AHk~iCR1By;!bKwdxtu3$DjIEuJN=S892(#u*Dw69W+b?U!wby1@DWa+ zHcq`<89wET3Tj@6h?;n8MUZfg<{l_)#R_C;F{*pC!dS}C`m?%G`A5$WVJ#UsX|{bU zA}uF%%)hA{n7@@78pL9LDASoK1P*3TpUl(2u#9qT2@qC7akpFGM*+V)ZtuX`!^xVd zOIZI-6fX4_ZS2OQ<@#IjpyL$a$gn!ZiIy>K?F8XV+*q)PH)|nSR%-ibUULs9tWj~a z*~*wuYMl@_^AYs!5Km1d}uk>T#(1i8aeS{8ZjVPxT&aJX_@aNzDl z0%R=KsIFXk-LLAQftAo-lKjjWt(j0ZGD6DOP-0=P zDANoFyEebv`ZTUbvH-GTlM7-2y@d3>6p3Grvfl5VE+BiTc`v~?qC8jSo_j^dy~c`G z#!C(1HWkit(EP?);B2e8|(XAHE__zDo-Y4AV{f-@)PGHmzek2~s# zH|4F$TZ#)9g>E8!0Lb36TBRMBogbV{1pfN%b)*7pYN|Y=%4<7 zaM0=gZ}*=2-?;Zw|G4+02J^s&B8-kg)dYxI$yeA>bTpu!k~-Y2ix#QT;h4-r1qRy3 z>I0;*aQZWBN@h|{Y$F z{8Sk*bnOxb0Hx8XPGUs^NKw19_00960?AS*R#7ue~;4xqu5-<>a2CZyx z!JGtWK{jJE=dfdJ=A2hPi%;d_nE#9{Kn7%Qy%+*Sp&GqtRu{kTd29J_9>iQkL<>@x zuUwE2Z3gSpd@HdFN~{H@E}@I}?WNSnW>xqZu?3%2!;nn66=>HeYbdtWPgF(+@l*sh z)oL7vsb!}pc!fTf=Bu>Q>CIgeX{O0J6RS?yxTS3b-(ue{x*)@4mu}CQmhDakPY^RT zCff7-?zH%RcRlJ0nj{OEDGG{-sFuh4GH6t+M-PiJ0%!5v%ad>mArK|2j8{`u|_G^YRpcPO@eRHAAko!0Y* zhFGI@Xnds~shFSkE6&@2Q&(6Yl^P&$Y5{18w-|usy#}atsLj&lI@e?Il`X&|#Cc}c zg|;Nfx~ek9uOm%uhFv^{d_nbWtq5?jdRSsIY_J+4@lgy(93r7cWy5 zQAtdN!0$5T1vi2nu+yGG^+kMS^UPiMd-3Ma0ajh8;bJqeuT<|rW$!2d?xy2+Lk^`$ z1h_|obS7X<_dj$=`WBffmD_uqh>dw^79IGx0KJ{2XI(l<>{KDe(I>< zlT_dB%)1m0;!9D4dH&ifVR1QkcG>I%rH)?+7yK^G#lgbmQT5=qcPT;yhDIbZ7)MY8 z^{zo(Z3I2qh!YG4?MQj#&%ALVg3<=}5IgZmX-V7us=hc&ZA()Y3gxiwrJ4k3u0HxJ znSn$sgOd~>TSMK*y27;k!3Zb|IGRt^yAAry1~US9s-5>~bm1}qqqf)v)Gu>yT1;*m zJKThhfo*(7A=pYGTDIP8mxGFP^M?Z9!p(T32jJLjo=FS0Y4gFG^-OZmT?SO_X4E-s zl>2f66;AWJCy{~L$q=vDO!DEHYz$~Rzvif^{b3St&r0?CRzBqZT*l$iCkBxD@A82r zD_v?%*kd>%=oXM2!UUYn!(yo$vn~&|qY_r~gVNBtF!{N8GlgHw@rjSx3$)>NBrr=Y zIA;QeVRuE>VmgzVxw%>zR1i#9pmHyC7Jt#E&CYmouc`MXT@hj&qDoi(4Umg#TeP$w z*#S#H?@K_cw5XJ7A;(vqts?T&rH5$FPUjd(jt=Nvr9<~kX{VnK zTVk_9J%YiXvjnD<7mO+rOP{tkM2*2wB95!%gDf@A4z?7K!{fB|Stv@%Yp`wLEm4D0 zXc1m^(xs$y-jzgput>a%JqONl6_)PKVC4CYJIwe2M?0J-1TcPMiJu=4byc}j8X2$sG_+TC5oatqlcmun$K# z^8&!ihN;b_ul+#~7PXylo;tU8;GL2g?iW|b+TRbX?9N(P00}sNVpXXLp~@?v_^c&L zKm&d(BFib6>((=BJs$&Q7d7Vd*n>f=Sa7$805-~fcSFT>8b@Up%@fVsky7qED@=o0 z!jXV9|K>&sk*`r|%>o}kfAgOo1ZC(x8|ep}>6mtqkRZM{XhTiPk;K)@AwXX`j3D8_)q`oU*`Yez5mDG{dN4~`Y-=7U+;cQn}7PJav6JP zTk7HWU;nZAKEBv)hY0yt)a-3xGoPgL6R+b(T9;G4x)RTAF*oXE@pNpYHGMdX$h=D5 zT1f8u2sJ-T9&Cn^E44bYH4*>@%q&Bdx0K?Q?4ow6Hx9hdgYd`|m4~R6TnY+B2OXN_ z#QxlxV7@y(7~-ifL0|ovosX0zPJjDNP7TVAOu4BQ6r;=&GEV`WzpPF-c&eZ!X<>+D zEK<7dU6iVbx5P*y0QyFwOhz|Y0JNA)*nl1)g>w`#0O}(v)V4s`>fZiDENxHJbxek?E)wEG zJd-_fpJNnKyF6o;iA8J#1f1W{KvJOzC`saDBKb^d_tw$g^%OM*D0BInZ~o?+zxn2G zzWJMP{^pzik9;$g1ye6Q8~3=WTP2dy0g)2jTB7hnXC!E){7v!y);ItC@Bi<<(f|J6 z`sR=MzwaCP58pt1vtxk6@Co0g|Hd~?*p86fG7#TF^D-y9mK*1>gkg@7nPXcr?~cEW zx4IL{3he_j`7TRRi*&$85YuAW&8xpDGM`NzS{oAI4O&OQ0te3E^AVeheSpg()GFpL zy2-&Va6o3*ft~{%BXF{faQvMgY9BI3vYNq5IGnll$l-?IWC?@0Ejd^LF;+oojBpLD9qS?CgheFkbWtv004xaA zq}K|=5C;CuIW9a7XQydLt*$geSBuPIN+}|u>`ewj7&I7AC6>VHBNw%pVe7e5M*Q{w zMKt}QKoILgK}|=d`#95^*n6;BWyh&#+4C)!A^YKxds#_g1ylws@3PjMx`)^L6)E9s zYBo9yeEEy$ehFjeExbHrt5s3lPn0}h+E%j+ZXu&2B&^hOriPrk6U$2++z;22eu>lO zzP_L%yl<>S&*dH9hw>KuvMoH0bVhX(tz02{svVy7LbK4V1gXcWf+yLL!c63ddL+1= zqTcnDKUe*eZTZKE74vZ#Ei4Dd0lEf!GGrl#&s#?TEj|#4Cd#@S-`8EOxL8HR_=p;W zZDu=O>b7h>sxq;p4Xi6EKQ^}9s!;V5bzW^Unk6x^+(jcxGYYguLpsQ!zqiRQU~}1% z!>eN2%{@hjjhQPUzo!I+4Z#H*>2`CO4{L+K;p6v*B-W|Oz*3A!MYc07L(?ycWdY{5 zi0{O`T%;9{?K&iNz}>!apZOWep|_CX4=k35o%4jYAv5touipVf(4xU(HybCZBs^j0 zus*(kq~JD^$*|lTTh%D{RdB_)v{`FKR&1X0L#=G#ML%Ncirl)dI^_?>)iy>Bo{vp z!=NatP4Cy^nQL8;xq4UZzQO^QM26CH6BSdgD8h(w_^_pF-=(ae;4q6HF=s)?2 z$7HowUya5KQZ&{38onb=JEe`Q-%HAy(BF!9Iq~UDLVHC_q>>M5q#si8&<1W&RY3I~6|%u1a?^in6LsFxHB{8t3=%K0C^tS2Le!z7>Nx z@Dq3#cOG4v%IB+8_Vqf0}*a*#L#?#Ff)8u(6e4IxyF zRW^{q3o=$*?E(OKvC<=n&hOwO&OZU*~|i>u-gW_Ql98HO@nz4NOzO31qXPKxC2AP zTxgrR9rRb@+$dFXsQA;G4}{}gX;K*>Gct#M2RW0s8*Er3{-_DNS^!@Dprn4#Tf*MP zX6Y&H>IyyuzP1 zQ`c|YpG<+w_a(|a^9>iijog@XxoBv~#iJL$y$1cygqO3;(xFp!yX`SeDp+72%_AYY zw*w0cmu~yhF{*@xFAs}#p<+QxU*n8L3zfk77vm_Uq_fd88sZl#B#k3VoA$_N9mWEN#VZ_u=6v3tH@|(v(l-MWLQy?1u?Hh4H!mgI+h{7BLqb}V$Q!Zvu$BA|EZ{>!HsOdW zYm`7Gaf})g2*;u^+WMw##YBgzEm+So$A(9sy>zS%L1loUa!R=f-~AF_3^A{YEb+CJ zQp$oOdQVhy!uVm(jgL3RXI>Bp^T4*()n(QIhXn0wUA(0kg@I^qZYPd@K!jtdy>2>S zmnjVbd2KW7N@1*&!) z**hM}w#VU7&+=24?V5M%%wLl+Ij=Wx4;P33Z8EUSp@OGs0kjB}d#+-zcMc-^?<_H6j zIwqfH-~KR}O-||ir!bOo6%d%gLcZ%(o7Bj@z;R*Ft^QIW8EW7$-4@Oci-gwijM;$0 zmBW(L9$N+UMO^z@;&shIwI!>|*R&>Na>+u6pPT0?K&6X|3(lt5?`>w6`?tp-tdx|q zdAFT@(^Jj*4;cC!)MVLO1mySg>+K8JvCy%>Zx%CBLggFsNQI4&6`J{=*nLc)Uj1uj zv2x5k>-BPXx9 zwrO=*f`4dMCCTEp~VHXEczoljZ@V!a0+TlIf|Czj8=HR!aCZ5qD$UB zcL?9T->5pf%NzTTOp8LLy6q1!U7? zE|HQ6Mf+z<^|N=78E}OKOMS{Cwy!bci2KZ=7udv@f4S}ukK^5IdY|erC$Dr9xoABS zy*BD185@@ylJuJAQyV5n`66&m zK6nUN74W8cz+8{cM>9lWUCtU)%G5pq$-zw=fw;p5GUNqW%5#Yp<;?~Q#UocZ(bFO} zoHdah4#(J#*4bHxOZTh%pqdVX;@2U3P%nvU4Dm7HVsj~4>PBBnknN&W-)lOe?(VHU z!x?MTQW@zPg_%mM(}U28Ux8FMy*4{5{KvilAT_X=aH4Q04trRj3cL>J1`Deqw&`=-deF zgHZ6Z;ikI(U}~KfWRe4Jko<}$br9lteny<7B<}I+1(%WwJPm)}=u^_zd|6sXEdc+e zXDCE2$_9VtSNoxqs+>aS-hniQfdx?uMy62_J2Q!@gP5V1oe~3VPy}Ry85oLHdM&wm z4znGkQmQ-w6}g=z)deWSqSRy^XEKo1pcecAR)&SkIMSXE9_{fy2Hwf+iwH9$3rHRj z7{y4ADmjK8=;^=ALpv<=n=m*ONg&NVO1}DmT2=9c`{NM`+8Nj~29WoNlKCAEodb4c z&YWzuWK9605a4_LqW8NsfE;tTM&sFa=QRNrC{4N%e+K9)AM;0hYzaR`QcZ!J@wDgz zuK3TCL#@4xkN-ttn!H$5!dxh!ww0u=DUc|C&dodN2eE+|AN_pn>=-D5%`YPz*h9i= zU)ieDTW%oe9`$OC{Ac~Jq8oi3Ds(ga`nZ%uZnj+Xd_&K%B*BhTq6sbTmQ`vI5WhRQ zrPGZHB0ZRiHnASeB9=Z$sOUugn>%akKBbJs4v_KGj&rBm-#-(~i{fMlF;s4{#3V#K z^m)5~oeo%?Mt|=$?eHjVaW7XwmbQnETCKUXVXs%O9~;B4`%|4}_6!Xcf}gs$bM$n$ z1m>Tq!##RxJ^HTsfq9-M?#P<*(GB=Kw8zzZKW12nmhwD%CKWI{vDiQRzh4-Au#K(#Iga|D{B z1EAMN+?Yl2 zEO`nho-~mLA#s-vX#DM|hKM+HvMNuaoUhF5hYY302mo*|SAhgvgtrgrn;;<6rGDQC zQ)1si3NQ~O@B{2(PK6v8*5uH&gI~(HWg?Sn-+uns<-b;yLb(lg;a5e%gs zA~96c9R>pkM;`bQX@T2LCt|`f=)K+5CDGv+UBTm9K;RUlS!0ZmLkCaH@O`1OWg6v! zI=gGo6r|yq5zUii3>xxbvmCR=j{eZR6YMj{rHg{@+o$q~nRcf+ooEl)ehJVxL*wW% zt?&m}Q%O4RgL++)DyZp020?9z8T+gs1UQe&=2{Jq6#xSb({PE}*H7KtE_!Jw7+|l0 z9Ueemvtj)eSZbtIfi$NP4Qw)qySmQDPN80!;m10r4w+`H=Ae2|=i5T5AWool4d6kx z*OOaEkbMRN1D2X?!XE0r1>muAB#qB@{hWtPN z}KmO(TukZM$zy0Hn|NNf+%RBz#zh3_1KmFVMKfI&)+kZX(dHlD3o3D32Ce1(m zL$Qp#vn};d{`bGnmB*8G_z-xHT86wklK4k;y!v4U!Ld%@BVldXey=HO!m^d!&rdSQ z49(YIMspg?7y?s1YZ%HWC5Gs8-ELOECdld#Owo!5TD-1Z{72)1tf$H8Iq*J1k|7HA zvg=7S8Zr>Ysb>#ttkPx9YGQy(Z?O>1%Yewu2DDZ}(Tqni4WH%GTmUE<`oc@3FHV41 zYc3aZ!X5A$pBJm{@FkMXhXXa!415O+JO~(}5H5t6f)dzFn+`uVQJ^*rpS(qB1NE!U zJP0I~E*?OsU~#HV-nKz~7aFKwGvZn*E$n(}c)&hYY{t-8OMJIdi{~*p^&{6v!=h{I zXO4^J5pARd`P}4a=3v2mxI`Wb-1>1#;a9=P5RcbM)szUEq6~2CNlWD+?stV3gtX%p ze^_80rv3?PTpd5)(XA)P-&oB-}r`=xH@x#8IE}CwFeUYOnr-xad0Mh_*yZSQeTC^qaQbeR{ z)tWe`>{vscd*&KWI}2h}+Z^aYZw|pEw_?6F<0GgVmpyC8huH3V2!qYGl6?RA?)zGmf8cMS>0% za-`&jxYyE}=&dq7H157Nii&Y40Vg+RnaB)YG%m)mm3A_!Y-@l{`3eepu=Q(T??nDk zglD!zr|6O)b+VpQ;j-{AofJDHkV#S>T+A`_(7dDMMAgx=+X z!AMWRmxR|J`LAMkf++<|hLOfA?9jls;)R7Omov*{?%aQ#VC~nz@&WZk{bQy4?`LR0 z7snrHuM>)u8-0>6@2VLZU1QbEl|J0&Ig7$P04}ab;h22QDDbYdR#N>AVhc{K6{tn$ zgB0I0pI{{JU-yMaWGSmWo5xnTMCcBJ=ce}4Slb0h)*gdLH}zN09$Ps^5)+hsF9dG$ zr7-}H79_f;53)W%XP5|(c%e2-J+jVjmp6`o1wK1PfFoTM#-Pf#)}s$R?wn^@MwHxyNWDsh6SNY{;d645L2{d;(xEoCrQ2Gkg>uaNc|6R@7h7ejRj^f`_jG z|6f;G99Os^X%qf&{h8wpUb+7Pmu=I5*35KU3v12G`jMzoXjbsHMtgk z`VC+E2Z-1SS^QhkuEi#D$SyjEW(%O|%m7(FC^SVGS<)9PN6NlzTq@FeC>{544ID*- z-<^N1lQ3kTpuhH>i-o-2a~f#)S7}Nx^2a~{=^DhV#2AFC2ErfS6LHh_ZYe zi+wNF9Tp4hM2!eTq~O?bhwvhgL!`_PVpD5_ACm=u@oUZjPq~9l9JwJo;|Ai@CxpE? z-9~~{2iE#0`n<}bzcx!gtpUsV0S8*^s9|xW(UIGNGN+IVAFNX(z^SwLCnpNS%y9A~ z8KVZdK6ANK3U2*U08+8wQ<2V0@NSSEMT!xKMb!r@1e5l7BM!tInRr{s+a*Ui(R8_< z#|Cjh#y_?#t?Jr`_PGNs<*Yzl4WsL>t4+4!u6V?=>)ADH1rR8jsC&7&OMu>aIF6i5 z*zS~SLbb=d7D{T!>wVjCBUTS#Rnw4xZRNL;@8qK|RXBM|thSkrx;UIDKcQ5SAn&be zQjBJh=j>PSF+IY@H#mzLHTN_@U2zQ%^X{jI^Z;2>*ljt@HV1R4%n^xA|E@+s!JNFSd;v@pR){yYM3ilSLu*kv1`-%AAZl1|_OqmK zfvDBlN%jtey;+-FNlnC;!*+NBP3RF9tz&H=6#eIC+xy(d*3Whp=R{CeQMu{HZ zTmuG~BUwk-+uuonnbaJx3jtmQb!#Ow05D?;@TKAcW-l)yiG-JNbCRm2@JNd^3oL0^ zYD9#tbzW`yH5*@hf$((9z}>7tYE60M0?XM)>fz!bYKJ@H=sssmg3+qlI1OR@6XApI zWO|=Ur-%-I%|puekEm68Y|M7GA$w^Zn86d0S*-5Ow)ifQUuVj#h^)Y6HJ_}6Q|N=$ zfEUn}p9ax^oNxNgO<0c?9RJP;7zq=~9vt;7j1L{7OhA-FR}qE3`C#qI%Wy_1&N!5K4b>2x;ogNgu}(2Fj9K)C^aX%l6q zxZ`xJOd$2k7#cSg+n}w*$rAwu3fB29X6Q`N!xF|5t#>;unKIzG<2uaHWMq5P4;CpK_E1JG@A>NOhpKGW#!}3K0^(a=-VoL9+R0QU!A# z5=$4*$eHg_UB>yWy?5A`(D9Rq&sgjN67gx68^yvOij8w**wrT)@aUIr7oQ1nYfuZz z1>Nxl^{*C$j9GM?Dt?C`6j-YaL9!(q^XM{)@Qw{5t+pjv0krIwT2+{X6&wo#?eG;vX`UffJ59`#$%3`ioR75m>A4Q>OMJ`ZaH;#3 zIpu%<&0o(c$KU*APWf~G@8uM+-A#e_v8XTn$dUpfiibp~SW08r^OtJ2`o(TQ6$6_K zZHC~ToYo$iA)p6_Xo@owc7fh1mbwTc-oW#yEP4>!s1RLr; z?^l{Qlg_-tqfy+;BHq$kReoY{Du^x=zaF@vn?ipM2OtJ)7_kZi&aW}@9?O$im8Kkt z=I0kEp(6`WoIdoZ&#!pds~@Vb<~5VsLnEO;D1n#L_VfdaTL9d$k4(EM1VF|?>GYa} z^&yk}(CQ;ELx0?P6T0RMPIL_?vJb3Xy=7EeTlYO&q_{(&P^35%3Z-~(_uyWnh2rim zh2q5>f~l^sGP38GYt6Ox-pdkWyqE38OPhkj zh1!qWN)%2+c~ooWqMw()=U~!|M?@dK1SU_Tk>b-)#~TV0V7lv)HNM6F3^F9ARhf%O zlIe%q{L-}g_}0GWo3j>Tho8zw-83)q1J3NOc_beGYqjQ!a#lUor$$p{WAFB?$@@sV zDdb+#ns81MkJd+$OFPY(?>>FdyGYf98l5kMkc8a5sby>`Kw|up&X1iR1@m~U$pi{Z z=w9!zKYfyhU6Z2J($B9x%M`$Xz`QE*h+a=0(Swl>gR7$v%$ok%wR_uwz%7}cM z*s8YE>V;Nlse6sHK=$rpIPGzM4s9Cs(`fq!CS3Kyd=|A6cc1)tqlfBM6#I^di9n*Q z!@JcW(Qn_G>jtG06n4n_&bQe!q|VF&JZ6Eg-ra$71_fChYM8j+x4}$q+z4Pb@kycI zFProa1TwQ<-z@e%mHsXJg5vJ+;%9E3jKI%EqVJVNGl(6O=w&eM9yxMcO$xHRyH8pU zg`Ub=*U^O7?kp!trqOwQH24%|?%Yo^-t;OQbx*bqUCvA-cSTTP1AYU|tPuOZwBx%aX;Q@;2q80(A}J&0@KX1V_&kH7q^XRgKan@C$*4-BPG39i z?YQIKX~F14dh=6^RNYQ@LnK1|f-e{sKCpHM=)HG--lr4YtPFoEF^9ZTEk(%DF=VSr zl(`{%tUx+c@Lq;C!s7vLo)6<I zI??hstWu%{Mv!M6D)lElw&t<8$6=z>H-x|KlyR_(2)~Q`db3|YDd927|7=mUFjTs; zRk-{HxSdXNHV;pQ#$2)d?cYGerSnRFiLB&aq9FAH zyO z@M9s@`&K}zg~by#V(~c#bzctmy}I4N=hj?*cro*v$f?z~duXZCZ=Q<6!B-V5wv#xY z>hi8+lDatvR3Cf_0a_K&wRtK!!7e}c(&M!9N{z`gPf$5a& zwa(I)RQvGsu!hy>1TZ(Hzf+qM_1``$ueWaVjg}4(v*&!5KD$RLXR9kuEX<_ysRc{C zP>D4DD?jnZmxS^AIV&ybN_TT=g*E?Qr8W@53rB}18$liAe8VW!ExM*uV>*KP`r;Y? zYa;z1#4!tz+f@484(3sU(JODbR-1p6Z*iSU67JvBQUAhp{hcv%O)}O4XyN1j)RBG9 zl|5_d@GXbf|74y-6Nw2V+c<^2PI8|Ad&66ufG%q^;J^cIb$n81n!?fVC@`8;__&y) zP+(U=$CY93)p83kmFGiH^pQgFQxtInM~q!lX;Aw~Y>bbS>GfGE5YRToNVZnbe!5-q zbn7yxdXbRyQJlO&d9LV9guP0jtzC$#(0r`L zyERTR$~oUj+5onI`Aof>3`pkA*Mun8rIM#tEgQasCqVTxoF;JiAQ1BW+#bNIK9QRLGr3kHDrqvjV7?Ai@t8gX zAaAV<{ABK&%ICMhPO$%nEWUk^OZ{f2(Ug(5gqQV3A3O-+- z51mRWN2(S^i@Jy~=?{{x@Ux11keTT%KM4GU^SZYF2Zq{spFVyz zLmNd|u!J}WS$;IL3`>v3{l*O{n`H9suC@jO^_UKztzmd%Lm~n17E(&2M zhtJDQp_+clFy|~S2T&ZJ83|%LID4-}FbcXwX;G}{jO4+(7SgP-@Inuj}kGV?5C5v9u4rY(YS$1PyHLn0I~}do=q%F z^bGGqk2(^#RN2zc&7)q+zTj6mW-$6$2ST4I7{LS9#ks|q;rSXa9$2~AxsPFw;~K_V zELvNxyqNrxm#o(1q7RJ?tqjlhLvlwISfO@)va7ckdb1*YEYil?j|ph}wJ{vKooo5@jJv>kC*k9b-RjG)F3^(YQl%8Eb-p4IMfMXt9GIRNJ*~LS=aMhFL$)*9G`#a*?*OL4rQn9M^)# zkEhaI?=JrcOa->Lp@u*(uJ!#%S%XOVxZEsAR-@M}@V4xlC*PARu<_j6g|o_O%Ot%D z?joxIy*TYTo)P}M_4-TeVe81Kovx|1?A#BbuVQa`eNXZeZgz=E0;bLcR2>a+%tY`b z54t~;z z8nIFjUBZt1Xd=9im<+>`?r)4o7C*irzo$cRsJ*ZXui0GPS$*m=6Te zv|MO-J&ukOmTqZsYo4Slx#WAf1n#t`V5rmJ{lL+W3%0CbFjJ<79@hN+VO3X$$Ei%- z>d>nxuC!=+&BM3V5H!+=G?~U8$cC>O9!+Iw+4iLjacWW$gnvw#;ed$H5hR^2PqLRq zpZofkpzbyS2Nl0ruxyxD9+!N;LFN&vT51dQS_->ay!_2TZjkxaQ9O5y%RnallheuY zhzW068(6d}p|WGbJ47RDNIhpHQaq0;F>arUhd)L&&E8>V810wX-P4XDmp~Zvi5$*) ztBeu40%&C~Vq;=OW9BOP{lOoP+vQqz`4vn8*U+gmQU*VW#~x4*#}|1twQfly7xVk5 z8;cYXuPi+?d;YdOXTGD+FY7BVUr)zL%bEncX>ZoHPHB6&NaSUo)S{u5?=)HsJQGj>n^-xLf4fz(Pinax2iX1 zZqTD+lb09g3;uPsT}9Z%Rqb`6ij<^=^_ft6^z)Q0O^IOd)k+R9LQ&vip>Ij*CB3+z zQk)A$pHE7h0j-rDaA9}(HQ)Fb{-;j@Q*^l_o;q$lTEE)>LSFz~IZn`t!||$G%egK* z*P=wH^jiMZaRq605x_IXSII~xyhI#EP?E3@=*w6ZK6^Dwcmgt9NIpA>8@91xiJ2Hk7<{p|KLQZc3Bkk>>H}wsA_awGhMte)3h#lXJVi4NxL#Vow zGIFxd^_BE0_BZ^@VJfC+|GU0y@~D$7XJ;4Ef{_SHjbo0RC$t+<9P4j&Tw>esSIau= zt`e2qE~&-M3!vm7?gVC4%5+Y23cboyqsG6DPP}6!EgLzOZH?p$UTEN+$r)kgm9JwkLqIq=Ed?m_H$%@Cq7n}CK2RrM7-z(H-;53f&sit(8a{7oTjZuvj4 zJ85YYH-0O&zfM7W{}nvsh>g8f=-Z%eIpVZ`{vl%Hi$Kp7U2_is7Gkw#M*NO5?g0|h zFD+Im*CR2svH9`{D~>?KH;i3$nr%TUEg zsqDYvpR9u(?hT0K6=z;9M>-PA?!4YNm^Nn)&7^2m;Z9Syk| zfyI^>*BXv}E-gPxty19q_+PODJ%tkRb%7_dGlUY9xtpH_A4))*p%(cyzdBV0ULH03 zZu?%QoB0Xy_w3ZUc_qKk@3`SyAy`^~ziz~rRAwlHYGRNT-H|F*sTFhx1EfGSi(fbI z_VXxu1ntl>kB6t?ThC4X8V=g?{NqZMY&-WpO>$PDQS2nqMiy7( zJ|=ifl&;wZ9t*VS3ZV@9+4aG~t&oXS z+ONEk$b| z7%a5;zN72kly1CdHfdTraqP-HIedSfvCoI`EIugI&B&QA_nuVL-~o8;o9fdQcfE=@ z`J4CK(|J%4_BDOthMV}6nG5kA9dDRZ(N1g!ZS$lM<`h0?I|fYr_sb1nlpOJut}20o+bbwA zX4EEVxTD!B>ahqHeat`C_KvBTT!z|uO%iIJd0pp7s5*r|^H-_5;nFaSVL6AEV7Bk_ zq^G(^1G&3gtQ3szBTqMh6L&DaK9UwMFShGEyEm z4P?HBBRDx0*Vitbo8mN?daa_AZsvKyodLfEG4LX*UY37fZ++A~UitPbNZI{%U3GrU&X^N%=OtfHql`+(u|JVQl$4>hPB{lqv08LV_kVDpaL&^iR?0NwB_{ zz-qGkNH=k(M8+ELAL|c{-5L8Z!J9V_M{jL<0il6yx({EHm52KB@2ofDgf)QIn>fg7 zpKaQ~GdQnLi%$KFpRSs^9$>kmV$ZR2frXdVR*!ECo*$qGVvnP7ut3R!t^mJ4zo&;S z?}bcVjmOLCzjS{D%$}`ApKp``49YPW6@TU^UNCDPB{OMt$X3J+sOWJ-{}!X+7i=9O zD@^HQSEDYij{iFVEFXE_^)78&;*B;IWKS#01-Ox-p2dam<$g4rapAh1CnInj`O%KA z6%V(7M&HHg^@7T|ig%xus^=vIo%kgPSR_w5FPe5*0?w2l56+1>*pY7-fdfx7Tc9_EV&?r2^nNvPpvX%;l_a|vAokP!Ky1dR6?-5TP zO@z7htxeWaEuZ?~MfJT+JGWy0>5zqPhb(adv~?|;@|-eJDPW~QAFp0dg5U3wko+D9 zM~|%^HwnrBd*l(x5X#OZ^L}ldMxq)gZMd<|Pc&=u4Ji0)@oiu$`(BF0!IE+-vT+PV z3?w3Ya&W6X0rgp(h2QO+)bWqsm-__pbm32g?>?%1ZRzT0Up|D72_6$u`wQb&y0nc9 zBv|TAEk(uH4hfqj{O~L}vU$l`|2ebyF6wXJZqiv3BLh-MKsqi7%5psN8FBwA8ktE5 zbVV6|XLW9Me9p#3x1)_-AyLMSSZd#aNoEWk{$X4tfb4b)`{R4q8m?N1|EuaySETmv zS%u+Y!Lgt=D^QLTb&#(WsLDy_H%dK3T;SC@p#hjao9L7z&UH;-qg#LA%}qgTX320a zCjH3Y3^>dr`&7`R_=X0K25X20%&mN8D&9Hy58sdfCg|Dz_LI@PHpX4eWd&kU~M zD$8@P3gtG9jhquC0Dc$rI$_SvjvA$GzjkHLe(CyQMYZdwVp9j$B9Wm+Fcg%LLEHupu}-6E1NQ{xd#sTsrT`gEkYJigfYgSY`c=k{BrF)k*IZ0a zA1Frix7o#Gd!;^K$+o5x!V}D+RgVZSRjbR!#MuALcN^84Br)*Hs?JvuGspAoqJk5+ z@kJ)f-QHeZz#T?uczJG)hmT>#`XM*srK?lb`?0nELq}|;I3?Pt{WPBluYZ_G!&#nD z{#X9R-n=J5ek*cwxn|av(xwZWjhmvA)K`%{hlR=S|77^=%|0kFp*nUE^j`a`>u*E+ zGfr9rJ$QAj|a$!LESRxqjfcM~c*{rTu^*{ju?HyG0cg~D z?ycySa_H2B?r1%NXgLM$fF8k@#(C}>-(B(iqUVM~XV5#P4sgD6Bd){~|el~RLRRFYAAx*KDcsx3kT=LV5?-&%Sg?kHJ zj}5RMH6l7xS!|KCRoZMVbH4%CLmixtGM)kb4)??6uFB67DTm3PP&|o6O#|>BO`K$r zVs}N6e#!ral>Zw_&1%MGPdmIRSmriFd_xJi-SP?TpAEaq3tbLbY9wf<2-*N@=hAAH z;dz+JTQT6LErc%|xnre&>P4KV^sIDPgaixzcoF$=S6z{4-#0oO&!{ZKE!6ZL6A5;2 zwdvV;C-!Uj?O%7|OqE>&MgEnxH{7wDJ=&mjvHq+=e>ZlVwU z-fJ$a&tM=$g8o;HpIs89MV!wh<`Yv;Q8`|7zSV1uSHK@CXPs#^?$j-I`vvY6J&Rv8 zm7mAIA1+I40B^%Sf_Z?fV7-3`B-v#I=PS@UTLai4{SSd8YZ7S*7Vl(Z!(N?o7%&q< z43qs!YGNvuh%{dhclq_%3#(;QG4wI=*}jXcjc8^1I_Zi*gz_MHAA5*I&NCYNPYRM99e<_DRPc3D+1 z+vuu4#Sgb*Yd>MA$Vt?#{#e$RRZ_Um^Znt&>0?~X`lL19|o%bnMxB(lL6 zZTWuE>E2sF0kEof+nQDxKM+z%G^JwO#`kR<;(JQ_3&x)@v17=u=-zpm3M$FpX;LL% zgM2g@%Lgxn#w!V$rMmgAun3wwZTg8iiz4Q3KS|v|?QMuEt@I)!;*fG@OR!Osk5YGn zFo8H0!YRV1JOwb@xL8n=+|Et`y;*y`v+F6@*1ux@`(Gdcerx`N9F%podZ3(u<~q3n zm@zxhIHSC1 zWmla97xER@mV{qfRkoin{~WOJ_{1tzB?(G0_jLXxE%na5z3R{GZx1(M}qEZQaN)1PZn4<9-atM+{GhLX&FarbCk z*81+*G(58X=qy~OyJ6xn(Bu6wC30>L3yhueV~!jPhVu@+e5M#3rtoryw33?u;>+S` z1?qGvQ!BFqB{*H>{h0)aoC!(i@tg|qFIxi*EkPXJJbscxrPLod1qS!szH5Fp{ywKq zlPxkLj9cl-kZs6UI|XpWgQ)Ult&8O5J5?>Bp4|Sy2Zq!r!2CoXyKg6*MIQ=*%#3xJ zfXOFMJla4=&QPZrM`z)HpEAsaRwzqrgw-%v@ViiP_H^DD>oV&O3GP?m27*$u|2HK5 zCkBD_ct`%4*ant16|>wcA1C`5hW$7Ep>~zA%zD{Ku0>L=d2E0EFNe(j%OT|m4k=pI zLF)7UwhT4SUm^~Gsg}<`uavX>OJ?`%eTM^QEua1$D3-(t(Eo8K|3#rLFJ290$_uim zBbhA@1B_$*QRZKVbd2go5C2~j%FkF~TUzF0J1~ur0aZPidayi-Y^=w-yr)u1RBzAe zO`K@GZ?RgDRCdB8S}zRGSbF{-E)szm;Jk1ILqBV zoNE`gcOE>_rf*ghc%YV}8qs7)`t6zhN$-=RBXw=QeAi-eBtv4!r-@!!-9Hr)U^^C7ath=e8vE^?NS`Aip(rL$+ z!dBwB<&1iWOpRw3;+QR*AcQ-i%bph}vjXKiS%?!Jy&4uIgS=Oh_LXs|3Wejb6m-xb zTF*XUkW3jTWG6Vq25+vgad^I?P?NsZbU{SBSR`Mcl<{tp*3Muq#2VGFB zb^1VRSsC^0aGA}IzfW=rnkDkCBi*bnQQvvMZYN*6U{dv}=HRuHTY{scwbhA&c{uGV zb3xOOgsY6mKTuNn`!VT#d-6lAdf*haQG}*onN{d9U?Th)`1i7rZ&xUP9tz=F!|Yh) z6L)8hSl(0Yus`R&A2a!XY=Y3V2sTkH&nZA?+VSC^wXeRgqEiAEN(7L?@$W5I243s^ zTHt*nriSNVKnZ8*j~t)Nl5$Z0C{JI%93WYqacc{lQ}7L|OtvV^X0EM_Rhi`(`U-18 zcV6#_`(Vqzg;*>wAJ_`?Y19+WwXMr?>EK*wL+~c3{)V zINaXXc=>CKm}3)ICI>f7M!Dc*@N@3?pguE&^`q5vT)p9t?9v+{l;cmxk&}S%)bk0MF5f-2Wd?b=Z%Y{Jxyv_nrP9)pYm^s( z5ZG?EU?jJ$YT@?HcCzg2liAXJkq%EK5*b`ZTS`mi1j}sh%iU6 z#$Qo96Xy3VmCJIOmLF-GI%NMf?rJ+3-{4)#bLih(p3Nm4Y-v|?)8nD7^4BSr%xk)S z&L+3=w-^7H=lCz|Fn!0Xt&0#WYGY z>5sd-&%slmjQ8@wy>Mn?&$~Sd;$^x6aO5O(ME+ix?xNAZ z$e)SO2P%ay-Uu-Qm=;ZHKem5`@(#Pw72IU>WfkAU2TBPKsF{K4{PzjoGEw;W^YHG- zS=S-v#Q(^m+a(jBWKBWV03-Kv9Q_71tMUYaq?cjTA*i?%1SddTx=+m*wO{=5*w3Z) zchx0jcjllnX$pAUmff+A#~)x_fejj^!las&cDY+C_bdL{$~_jYsf=f)88644JvQCv zXd?}uey*GiQgw9%dHwO&)G5kp%rtEAkwr12PqoN6EO0-N{6N*C%2_qPWa{f*!z3|| z15QK~Fx+`h(kL_4JuB4U#;fd=Z=D|8@c!f&ZM*86c=Jpx4&>G|9Js6)lGmggQH%^3 zT~}*sYPR8Gz7`R??R-40?iVJ5x1@9S`z?9LdYsJS@761Uk$)4_Ls&hHk=mpVD4i^6 z^kU}(cY$Q-F>`|35JOX5#Ci!KDN}?_%@rbx|7isZ71E7=7}&C-1Q5R=L3Fhq$0RI@ zxQhBqnF=A%KzIo^K(XsfR)m)TtW2{?MOjrpzyoD{Evcq^JI*g?U?J;%Ue&3CISQ)9Y>Vb zxeB4HskBGj2)J)B9-;H#khQCQV_&0G*2aCRIh=YudQ29lzXxfGjA$DxF=>|w-XOFg?cnT-KrBLzw14yC%7*z^=xLQ7 zDjt9_AECfBp|xJw{)3{$)lwoB-gaQP5H1V4YBqkL)2afbEpS#rxtFIZy(A$*`O(Ns z`kKn<2H(2s}~5*GoVM9rsxaazG)7=hA4U| z${1YY-ELm3FwMg}gwgZe57!L`unAAOvoUg;EFvwohg3cZK-q{1qTOdpbY;pW{~+xz z<8s%dk1X{^mjRJlF=QdQd^L>FO_(HJ_aj;Y_iC@LK-8XBm?SLMsyoilb}&DL2Rn3I z5~L~Uq!YUBEFdbnk2>dRvUd@c_TO3eJNN(k&BjDfAor*pU;Q7e&vsJxVRuGRD3^LK zfJ|SsQoiK~%Q~l2zQrDI2f4B?1?ur(0-df&8$BI{k^tosr0Kj}XZ{~kNW^7|lc4{X z48146`jb;{_@h|?zvhBfqvj|5Ull^a*A~eJ&X3~03#xz2#1w0_(Jb*rE~bSO$&i~& zOwU*E5#EBMtt8PaFJ8T>ym31G5Dw0|*6pfpl6hp`cUO0e^0|dw&X&)>qYH9?*IVxX zK2KNi=iYvvO=DhwWeY;=wH4G3e_@pdr|G@#b;b+&Qh>b}%^wt`>aNVXPzC9W(n2B9 zws}%&=}zn>i6uL?AXF5mUG?6m$IQJza3i%}#UN>erQ#QnKlp~sQ3D$mFERC3VQh1U z=$QNqw073K;I@+!2vBkYLTHXg4QqGnnG!s^3aKu0cjE}!u>wg8n3=lQ15E_xeu>}y*AQ&>eI2W{a#D=nQh}<*@0QXpAWjb{bWR zyqQv5pcII>!+5vRUOdxMgSF}L8_z_MhJ%oJilrh%(cu7z*(p^xPMOC8PqZCIig zHn`K23sCT^%~J-kjCugC`?Z=*^ySV@qVCQ`4vfdwGjl2HvYqFbm6c^J2-h(`Cai9n zg?)bBwtB8BewiPZv)AHgx*QtMjFb)DkqN{I03bOgT(7vh>@tW&C1eEbSFU^^vF-E! zE3)eAEjqe@712fchs}ozsPJ`aP?;CfUOs*UM(IBvnJRn1^W4gJnZWn5Dp16~`r&bv z@3O6QUZul&f40kPr}kLWV#aHIsmzi9sscK#hi6pWxp&sm4my31}@oEv$*0aGB!B;x~sCIHR6h;xa- z40&dxOhn{coP;z!2{7BM2u3(Kalk~d4kDs)vk^a;1TgoM;s(uGfn4|MgRV{mX44>w zV{Ex%FAyZt3goK($%LSt;sX+Rlnv7V-J&-|KyUSad7N#ZL|F@WHSLWyWju@OIn%+ERX%4*UH}I4q=h{8n4Di|^zT z9^h(R5#=H*Bm&aM_xTp|lvnEcs7}Aq1M9pi{#n%ZVZwTw$ z@jV=C$D@r#xk)5pe*flgmrEET_vIHnuK+W&L~S3~qQr)|9mVu8w(zt!aHEjsyKC&R z2lrcnYTZ_ml%@dp)1^qGQvkW?TU^BdT_Aw6@dp<%2T_~KMKfq&P1OW@7eUqt#@RbW zvE6WPyaqA8a?M4dR5wva{PiBe^!sdOn#XMZMfW3h2unNd|J7BjzmuqNN!NH;bt4;D z?$5s$>_PO$Z25?qpL;tHumG_AiPMg#{fSAr$IfNUth74@0&gD4U?H1+HzuIegJuXW zHxAoWDt#wk!F`+yUKGML2(=vX?%tX*H;t=}qr03iC_1zuNP-B#D+oG?OoTQfWQ_E% zy%=IN9Nqx>{#KwJht&T>HShx@=l zGkLo8ZNFzz*!5*?M(+3_FFZfPbE4XF)iKvI>$bDQu}T#RyF_8z9j&XA(XJV`PdVF$ z2iQgL#JDF}uK^{6_SRlxU5U&Y=_7WDH}Q4ulJiI)m|fs6&J% z0FaM1xCL#qlQD5iN|wAh3dh3rG>$9m@WhYbvpIa+N8;q1jrAV51dke*mAG1)KDReh z#(zW3*KM%IQDs)!^#XOep{bF2fpXkr)vC?_D0|BJ6=#6G{r=%RyDj&-X?=;s?t_b> zx-g=%79x2V8Dffn`yB$Rd9A+>E{f}3rhK2vC>Q4G&n9+B39q`$KHcJkFpu9}bOFYL zd21Y+Kc_o0 zu*&vF*kfez(Hypk%Wl+edS>CL5Ha17&U$ssS7sulV!j+HWUUp%b4i`#>s1z$jSqFP z$bTq8I^BfKJ8bZDnzHik{Ou}-Ev&GpTWnX>{#FUO_pqJ*T#2q;SR6V>PFWE$DlNVC zEIgq&JbV&AwRk%@sz(}bg!cJiXItvX#5?Pcn1X-GpLqolpTjCD%Of9+z^@ba?W0Rj zAu+wGiHW1M-E30G`_M`e*okE}{wr9olKTjXd!8}3dh+|vcB>__Zfgk+=O+tcYQN!u zMx?;^?vNiVH|6p~;J3(dgi`Q)_Zzt$^2(FQ)UY0c=?M&?jbeTU9tOFZzORRndm8)( z{FDCh`F%Q&!sQu85Mc$vK8~Sn{=Id0EQDf^ZR?Lg*q>6Cw5CZ{be$~6+y(BN^~HJz zRu@2&a!7RXt}GEbgwTCNLp?EUOJX`{=N;3)UEl^XU7vG5OE!h{J7Z?hE`(4Twc1rj zfRlE53Ls(tfp3T~C!aS8jln`SRvUlZX0M;Y)tY>O;)%I)inrE=$zuW&s?Y4V`>#ys z4@U22&Lpk)&ci$AB{irZ1FK5VI3$%DV_u0D})EDwkT(wH< OVtyZpgb9)L{Qm&-;8NxQ diff --git a/matlab/scripts/Inertial Nav EKF/SymbolicOutput24.mat b/matlab/scripts/Inertial Nav EKF/SymbolicOutput24.mat index 3cd17e14f3b11f6227528e4fb2838f18aaaebd32..17edcd19d9e7aef18dab96bfd37eea0f24e29b64 100644 GIT binary patch literal 184296 zcmb512|QI>|No8WINKb`l%YgL6d8($2Fci{LB8%%sY8z8zt`T+?f>-rF4nrwJ+CMCmG@`uwb%OY&;Ho^%i46Um8qGMuI5}NYtyxJ z+_&xAs-a}J(jp&u;4H?NKG&J^xt@@xHchBOsP;gqP{iT|qAI`c*!{X>XDqit zi%)0q?@3~xwy3Hs2%0I(b^bK}jtPK#&_EF!ctMPR*91TwXrK)MhVy$*0Hixs;y*h95dM(4abVeL5@`Krr+EHX736bWuViC!Dan?nZ=-a?k>NcuGKXYR z)cs`!cDpL97z{Z+xZ!w&-Z_~xJ6|y;p6WXf<5biHPIH@TQ{I75jtfmgf%4(dW0aN& zp(!X(q0`)EB9yiXptCL_9X`)#Zi_O?uL+?@hmW1+Ua3y$pAd?4_!JzPOZg3;W7f$P zv*4GLFW5m_$USa5#&QZ$ve8RNQ$Vh5Cz%^ofSOIE%TMKADo!+p#6aXRCp-$ zH20(sN-Thmbv5L#H7rdqh=slyK1+PcrMZssaKeH1iozeg2iIwC`3;mK06KR0o@v1i zS8f}{@N)Ytm9hx%##}@zEUX)0&-rxxoMTdy%<*UPHe(@YH}p*E;MZ%7_Y==#W`Gd< zDfhrF<k)0FvEl{v#18@LL}SfIqv93x{9^$bKpnG?%+#>ffGs59cp;JIr&IvonCo7^ z;sK;lZ3M>hT`y%O;I001;y?d&TW+Id zje#FCNH2w21*!qr_Rnnm_cq{j4N}s?p}m%KsL*$nop@2rZ>NrX_vI@fD(&?|!OOiG9?W<`SgTC|4CLNpM{g_VHTGuf=nD_x~qG>%(KT#6JF2 zfHu~p)Kwq|J~P+CYu>p;{xjpwmRQBi3Z{i+vX z7Hjg}1>Z5&*>+T7izYQC>!;aL+E0XBF%aBSbS--BbY7h${|rDq_~MRB^zY#MPngc*A>5?v9{b7_Q;fuX0P&^5Vmx~l-K z5O!u#k?7z?)-{-R1(u$PL>B<`Pc-5OZ4fh4l7vK;#_4YBXxAafUXq4H=L7V+w3~oF zcIEqLXJ+Wn2ZM*Kd=4}5%I7ygYlVh`vBScpak#%btsNQ;wkj;#0KlKqK0w34PKAZ@ z;qU-6+9zl@*r>2@6#&0N`wR^S`xF)~iNgaGXkVe>V4K3i=L2{etqU3sb}1}e2*3wv zELiw;ly$Cw!-G6&J`-kS9_T?MLZ*o>7b&(G`e+3mJSpT7Oe2z!iL6!% zqSacBTP>GQG~zxBX5>irMN=4DM%U45z!`<1BiR>Ca8uxVmsSf)N3$=y;4-R1tAnMZ z*%t{wKS8?>OGmRWf;gQnP9uI40Wt50_C*fRcheq0jvdjyPyxN0)&%GiZB($AknD>l zr~=bzL|z32M=6d90G>tTK#v@yI2r@^C~X)Tj#3=CLH*iA8-<3W6h~zMe~WQL!%^&u zI1Uf8z<8nIDE4I@fR|wW&~Oy{Lc`&~GcY2Shgph9_GK1;XJa(jkzYqy=Q21vgc}ot zg(KOQ1vot54aNrzM;SRk4i8*`5zp|#%(*to4xItuH!%U|k)!NTDI6Z8f??2blpU%I z;QKHk0H5e`k%4Mo3MqI&cRfLS4NC`e4xPUgf(+hGoc0FLCo)GFi00_)vH4tXyJ<|= zkt5lcLhvM&TQ`l!++b!M$-WeVAAivu$s2VTI+A@U1U~|!KO*ncVdzNqr4alWY^xD@ zs}4a&voD3>EZogH*h@(EMIDqF8*CC-kQ3D}0*+D~v2u`f&qP+~$cb(ktZz)^~$5rB7MbD-fU#W4bun01&IG#sTk z@&I@ZHV+z(QXI{2c*s0V2O5rGUzpPXya3aMh9lS)rYjB)6~^?T;RyDHISIhSu?4Vj z6#K$l4d7oeLufe4I@iYGVfGmD1ouRi5o{t9`@;0Y;lXn;;%yu#ILgQ|06&Tuz)lNF z`odg^!$X9yh0t)69XcDp!!Y7OKd5Oz*`eD3{4-_@Mm|wNPe-;d!gxWa50JqT3?0qB z%)#kfJ>ZffFm^QiG8NEYVj{3J17;oG94*4>?#nPSK%dAQr6Zany~W$O+^>^2>M*m8 zW?!b`Blnn2-l@aT(d>%^pzkAZ)gkDJ_C*J$dvcTa>M(RP`yvSFK5#edU_Bz)m-V22 zox+yFlo$ezQXKU_6_|uAhlZor7tnhlWH+_~8jeyNK_7+?7Pb-^j#3;!Pliwj%nBNg zVqZXihR_EX@r?CEWt}*oDE0;PY6vsH?4U=EVqZYthOjdj@kTSu$dT*|=;079iLHel zIm!=@n4q6Scr3Oa7LH_JKyQbT&6q7T9A$@sJ`W-HG2$^@m^nwXFQzy=R3BRdJ#v&C zstn+#v31aJlpX4V!^0#ndjOxPpr@kR7nT5C(A}q#!4V7{$-c0_(~R!>;F2RSb|m}4 z0*^C#aARt)GlOJbSm1d^4n zl;XGml$b@B6EqyfzJvn!Ma%^nj#3=?LH&}!+@Rqo#St{42usAaLc>w)3usIc_6zfX zhNIXQ(4->V4ci6{N3k!UVMX{8YzHhH$-aQ*6%i&F(HCr@>oi#BNcIIZvWU2hdBctz z$-aQ57NH54Co~*ohk^zdp+B+h&~TI;3YuMnxnet^;V3&4G`BfyQkZd8-aH?@0Lz3p~-dEtI@hpU50#BAO!w(`{VaK9jfV5Fx8H-iSqJM8$-b-s^=l9df~f)o9HltwfD+@0g+RkmilaY(zr@0z;V8vX z5Y(@wSOhd2r8rswcrg|Q4M(vr>Nq??3EK?~N3kzE06YVWg@&Wp7dZeQ!s1}zNcLqj z4v*Z9B|yVb*0~{ozs8ba;Yjucbnpnfip4;~QASS1;o*wd9%wkq4mAhxbSxekjvZs0R*@*oGwo_yh&LBnjER5OI1a863gT(d-L&n$hz!RB}X&9nHRg#~HWT zV;f;-2F<>J=NY%%!#2ax(d-L&pmDn{d8-aH?`ZY~JkhxQ6nU=>Lr2SBz$1-2B*>ff z3Ct0GR?!**MB&dI?T97s)geZX_T~`_Jkq$M7wTr6SdU2d#R*h_8CWJn6(Hd##nA-7 zv#~5_I7)Gh1|^0Y%Z7%-7sq1x>2dh$9znE&B)D3$ptfF2}Dy9!N5ur>LT z1U-^=4VsQ%Yx3t4^l!8q&~yY_lP?75!5hgwaWLy0#n$9&5cE1)DeTx$ezKHLSm6*| z+HF`mimk~v0%H#p8NcV$e^&x+l)cJB&?Cs6Q!w+6@@!20G=lz>#(_;ofK|Mlx^o^6eL%(cgb?1i>*j9ZZZqT_Z66v_Y7#dOTJp$cI5dm71p zXmA2xzrqU`1A#b0vL_mx0NAqd0^EeaIkGProB-Ih@B+#}AYO{>jRq$GHZHt?I3W;A z`w5m1oB-In@B;G)fo>WbUI1)gcmWy^NN}JHKnoBq2VP(nA#k5I2rq!P4`hHqq8@Ds zT7d96@JFx!2*gbxUwnl+$%Ng37vLuZ;>fpO;RMij@(e_JwYX za0wHJUqWckhlubKWiU~A0W{|$3W`r+0wxYEfarX*2!TFK0$u>k`6vQ`Bxg(tS^&}c zm;ixzQ}Ufzs8xjKd>pt4fkN`NSvUcto$R0l1QO)PcW2=Qkan_z7$J~EzCH^lfV7k4 zA1|IO%$4wK{5NR-T;Koc2Mpn{OKcJUP2cYN(&c}hs^aGv9XaI_i;Cvj2 zOh51unG3+sQJjwhnduvnp#T&e!TC54nSRiD$VA{zM__2@<3Pmv@i)jOY!lW4LIA1g zI}pi!!ZflG+gS4x^^di}J9r~mt5gr%S|wzXo!H=pk5(^Z(heVI=3{K&1RhOR$;n0!Yrsfe8AOu3)pF1<;(21CjM7 zPsKFg1<*DD5%(vjV4BbZXwJuhNcwL)c-);Q1ZGX{GoR22(RRK>R z^C~cQ6z4-k|A8jsw{81t>?qEM$o&H^lWp6^y2AWLM{zzx=pQ6Eel+kG9mV+&iGNTs z84W;<9mV+&aeq)hnG3+sk(>{a^#^YyLjfo{it{0Y{@`bjiNK#`!tl#OIkW(x^C1%d!~^7;x=^bK(fJUee-aP*vM!te+BPO~|0HkneO)*K zH0MJ^|4B^pm0dUiw4F?(|H&5PzqkA68VUL`qFf2c^gn(4j&Fa_QJfDE{ReU&^C~cQ z6z4-ct{=2*{ElybjUC1L5V?QQE3)I;SQmi5=qS#I2>pYXkL^YArk?jRWSG!dGN-B2>O#~Wb3yH z>j5EvR`kiBKZtDq1}A`4GKru+se^0*2Pc43GMRkK1%$bh?Z`H8W1Zosf2vFVreRb3RNVAdsv>4*=J^0hc7+ye|5I9D5j)N0GE17;kAVrw$9tS6YRx&X{AdKuF z2Pc45GFK7;on#lev6j#uYlZh7N3vF%YjJCpx)vkeMTHwan)BHXhM!u6`9odSi6w;Q zd}M(@nkE(qEr95JHW31O81Y6b)D#h~a=~wcg+L%(03+T>g%Ut?K4Cy0`3vR;Jw=Gl zhXMpr)?)$i0%+TKIU!I(HuQp zP>huMFdczF$`-QW+=TUj5J0=#H6{cekWJ^{1kg%m6c9+&CmYYf380lsZbIM`*?bO8 z0Ig)20)aGfvH=~O09x#$ObA3_Dd4g-)(-e%t?9Z->@{Oiz2av(43Dr z7=HQ&ECX5q(fO<*1ZuIp@B(O?U>*?2(8l&b3m`flUm%bwfu+I=pdA5?5ZH~S!waBo zV+%syJJ|~iY7=OqZR1%$AZ-)b4-8HKZ5wYR1nS71U}NpFKUac(+9pFj=fji%^iaX^ z8`S+pM{zzI33@1GUiDAgWZ1DUAn2Xrx2XGT>?qDB6wt%gkuB<=<{icP@DubJG8%xQ zqd1>sfF3@N%mtw6D9&dFK`$Uf0T?=x^VtgM5yE6507XY}`cecvoQwk|+^&BbC&S;3 zt^)$8iC8XFMf=k{8D2n_5cr7^P1E3x0Ig&O0)aFajOd#NCxBKmg$aR1jA)$(CxBKm zt${$gAx3mhgA+h=K640xa~RP;4Nd?p_SpplGNiE6U=@wE3I13syze=ZwYpt{TdRy% z>@4&eMRYz}h~al*M7Jua`9aKl76E}w2aIS~1toy!d?JBB+9K=}^b{dxKD>m$1?&vG z0NOTQ0tC{hVCUck(6;e(LLd&i055>Hjok==UhEPO7;6*!bA7*#*w2S40q9}6WMlMC5yowk*n0#30qXX#S;$$a!sIj9sAAf=#O}3(kqN6w;L4y9Bj0T|SD9*o7y4^t7)!=1>;3W|>6e4GgSBe=ZkIv6{O^DzPR2t(`u z^vs|*pJ;-99?Jpru^I&bahz!Ve2V2I@R!~K6`*?9r$P0wC+P^r zM_z)U4?^{@C+H}~M_vcegFK;n*pqYw<0CIf&|i{0>?gdUfO$tVKJw~7AikZ}096hM z0i=p4F9!q?Y-x?~0!S58-jEQuLwgJ_fK)N%sX!oc7VRm#08+)2S0e-t(w@T$AQ>O| zDL^2Jm-Z4~0Ll2s>k|S#wAb(gNXAEAln{7Fdjl$>t!XoVLz zG-uV}7W2eO^KRHWPhkf`A880N6AKFZ~|z~M;8br3X;9V-~`Z|k1!z+Lbelw5A~_!- z!gaj|!$Hj)1vYPNJ z2IvUR$AO6c18N}iDnLhYJ`UuwGV^G?&@+SJd>n|-Kd^w-2TezCJ`P0UA0$jh15oph z;Cvj2xIZYI%mtw62+qfW$ohl6kf8t!9mV-L5J7*iJzP_9ZG6q3I3EWhlfj=-jf1oC6fsHlceFg-jf1o zC6fsHlj6xPViR65`e~N~k@%;aA)AUpO%bB=AwvJeL`)m%$_`c$qVpkg|HPlze0Tx0 zolHdkNiLY)c$ct0)(W*5ySgiGt&$os1Nh;iZDS(+Pd3CBjyL>2&Ifc1MR7i4`X5b3 zRuf*u03F5o5Yd0&cgVa7&{3QZk^2X2#xUraL2*7r=pS?+6N09rI3FVM57sB60jPOL zaXv)cAAFk31)%6C&WFhQLnO#h0EUj_e2AbwBnGajxHi6Kkem;Z@`rRo#sOeOB03*3 z<>$b4y$8cbbv|Uu?+MrSo)kcr!l}uWYb$$bDEzmF!!*x=C#+}Bgb(`QX;xygTtyWA z-(Y}a69u@SiOGO?Ihvmhh!%gQ^S{qG-Pv70M1bold4`mte79=yD%v&jS}f99yGVV1 z6Xm5~m5|+k=Fp3XXdabPh#hS62k80N`B|^TP7?JMqV#Q)jyN*BM@Ht5Op3a{%)ny5 z6@wwi2R9s#&^srSX6GyB#8Z9eVVsJ7E;utX(v%-ynAZPFjZ5JVznf@4*)#AjODXb> zT_jja&xMwsGf4W+;>@e&JI=k}29@}2JhuM|<#WY{n(=Q#-R-I{##j%4vC2AA`o|w@ z9oks$;bUDmNVNh`tA8D9TuSI&!_owU*#DgXr3EVge*BF%b51r@9WYn@E0fPPNJ)g9 z6znJL%lG4dPS$R}v1VWom;vh{>hAGoAhhmZ2Mad-zmN7lK3dJU)VULlHUn|AsbI9W zrqp-<9&g3=2L@1~S8N`jiod5253P=~VmS+MA*|RMd=9iTs77F@W9@&Jo{aum z4NjA?D^+5`f$~5OG#(7}hXJJ&5GNQY5Bxxrh=IPOP6pU<3cx}`^WCroU~>b$oV56; zM9eXM0SE}n;DRmyC2_=-+D^>`gB@$};|1W~20LZ}*!%z=?OZFW34o3_+Kgbd(WZgX z+7(fW%l`ON3td|`gW9Ty-{3~`2~q)uA@)6aZtdEt&Fwnq!+jS*34mnf5et8Tf26yxRez4 zvMY11UcG&L-W9{Ew*_zCuJkJFxvYLAZrEr?V^?r@EZ7aCteh|{T|`(6WlTUKD)E1 zyh1>|Ju-8j-kJN;S30_X2>Wtq^C3g;^)8Q2dd?~Tnxxy{ChRz9#MY*3sfKSX&Y2z_ zT5Lb_(g-IfBZXeHl>LBSWX8TgFIvw2N-r{HAEp;AW51ynEn(lH7n!pM>E4Uk33TtJ z?0a-?Gxiy}_j2|py0_U3?ayEe>N&W;oumP0 zP;r3;`&xaJUUQQ&r<87z+0~gn%v0>Nf}L6)HLqDqnRA+6k=B)yJ&YAQS+FnGm+$Se z&mNX7cCuuDt1nOLdX+s)DQ;Q8&a02oY4%p;T&7o~ca>xhixjt5uy5B#={I*PbIRxy znO*(a!`#JMs+>La=%g;u>|ya@la=hc`VoWX0wqp1Jvyb!HhWm6*u;|ESwCXb?4-m= zrAH@sX=M*f6<4fezp5Wu*qpO>Sh%>tf?ZNSqSxG_%(+dE&g|;W9_B5MUct_+ADP!| zqRcr~Y_sl}r!*ah_?I?d6_oFe*Y zdRImEuxRn91-qhtM8A1dnS&*bhV$J|opvoJxxrCBw`?b!?U&X3(A>R9EVs;+&R&_- ztd4&%DYtApoxMG)`6B*>cy5_HoxLfmc?bT5L~fZEogJ3d{LS3m8~+{`I(vCmvmE{f z{yp31Z1=3@Jp2p%d$!Wq>$93S<6q$4vy09S%4&XV?%s`mj~ktBlhtg9e}R9`4m#T_ ztNAwm1^zuAbhcwwb2$D5{ypAwc2rg~$J|{}EH~1b&Nj_zrs7{r%8m4-vt6>96Y(#^ zb0g_=_NuIAbNma5jps)NxwuA09UiRvDb2?n-#c1%%=u(eObSMsIeGPD*DG;V_dai! zWVxY|B6#qM^Znh*(n`B5U%N`o#%9mndQ3Xb;L1UD9SQK1(}Id7Kh5B^0B7#^z-ue@8Rjsis78A9B!?Q3}}s7(HiC18nvM{Dx@`P zX=@a{HEL~Z6#n0>TBCNh8msy!$}utpnRQf_1W$i*497Qy(;LH~#c=RHpQ?=XYc-zX zQy|N*6=a^JvefulYE+gEPk(L<=Tc>4P;1o6)~M~R#%ewVa*Tq>i~f<72tncj^QN1 zz$KlgFq{+_(V9M^5v?QfmBXnqoE)BhEh@{2#;lNKw1_dH=lG0ix*q_RwC%x(c@ zv@By3A4+Izlt*ineQQ*3Ym{wkly~b$YUOZF45x^v--*iV=Vw*Wn9*{K7DdJ=KBmal zk;Ka3%oq-D3W`>>tMZP2)MO)sZXOjIaABu4jm9G5fWcqBEK1k}T?E7FCKhU9f*u zJf|w2^SOF>Z}srw>ftNZ!#&l*N!7#k)x+nihw=Y@sCxKyb);3B@l78^dq$=fQ%#a3 zA=ux6^>+yNOJM!@pDp4!AF3l)wi(~>DOk_2)neMtX4+~p@j25G?B5vA>8c*yUpPi8@hW+9bJxxr_@8&ZW$g^#GNSRN(fVj!ez2*SYC~*Eyl~&> zX6ZOTCrSJxkAEiNA6fh}8UHBYA94I6gMXy(&s6*)fq&%i&lLQl80Xg_7B|>kU7mfD zE3u}{mrq{YygJKQQeMiu=83P6yhL5~RbP4eDRniyzC8J2YSqcUlkz3iYVP}D`IF98 zpZAr`pM19Fi!UW#+@m_zcXGazM@_S@NWMg8b*ZmH{*=y|-@e=qVpFQ)eZ?Ilr_|K; zhBNpylP%kxGK4f!AGZBq@DwJgw>@BBg((-?zA`9<$vfKKFhrshqj!I64`Ud6?Urj_ z&Y0&Fo7e8nSl|`2xqUrD*K5z)_8`V0)^5Xg8-@-m_IA4$!;lpd-tNfIXYJv%M=?wk zc2nC;L*^>PCbqkT7%0S;x33ylG9<2$Ue|gxL|!3Ntu;Ah($TcDt>;5zk7jtZ=7vl@ zn%>!38lrGCb4qJ`h`3`~PV4Cq8OIF!)&n6@j_I#jZ-h*B%+zm950QAER?>PoMDBe? zaO;tfDeu$!TgyTe-)D-p?imm>PRndPIUsGEVcVKLAZeW5)Ou||-Z)dMHFaQ8d0J8H z#R1v!4DZ&wfyw3R-L1C=6v{IdTN4MwqtXgm&ko2$WjM9w3`j+#x3p&Vstv3ek{OYY zj;Xlo)K=81Kd^ad>WISV?&!NFZ3Vqr1NK95BU49XM(;+qRrFSLZ%M4>7D=q>5HOgQ z5jVYKrorrtgp(c82C5nHZXE^&ni+{59ef7LHgOUiDh9J`60$oa4QANHuj!a?FvlkG zS%;9p^u{=y4h;kK#)NAf@&;;+@%|k~23n1YeH}auCCxa&j%kdUnhB{L{XR5@NjcT0 zePtXb=hS@k<#!ObuRh=_YJd4eGP(5cru(=t`Sfca z`S>$=O733v*}uiR*@KPvXFIBiYOcRkpo4L-G}sTD|H+vK6765pJ-lyXxX?q`0IL+WhTy z*0L&Dth-+PauU3TS2yGTyJ}e2U{=dwGV`0JGKRa^yIQiXR3_aw3Ew}&iSC{k6wI+`roO7w^_}A&_o^z;caejlexEJft{l6#2(}<`e-^PO=+tQp*g1Hw0#WWcTBc#dl4es zSTpu1>g-q)qV+zpzk_!`$v955WBR~M*Jyrb$X~7?%vKV$W_2E6#sw+pV=A%EM#y)x1k36C~@XB_7}2v4#Sts+Byuc=7(Umcxsh#YR;-fLIyIg@9KG2N4z>)bdzVo89XWBP4ZYfx|t;TOb>BYj8A`ff*>@5x`h}l~$Um`Vq+ljBs9<@30?t9p@ zMe0!-ZRV7>w-_~2c7-oq&XBj~y!$mQT3E;Xs$*X1>xP$n;;$N7bH9Axd`RfKWQ)Db zUmWxNZ2g%efnx2n$O4-;ZY6!pRqh*<{OVp91;1F`KA>=n**yQ@yHn-b&pX*)zEt)F zEIoR2n{dsFE4g%KvlXjbX7l<9vkUcZYI2n_%PjjYW0F%c?@UYdfBAyDG(}!>{TAN6 z7wg;h1s1t5Hz${ul`OY8HvDdMP`qC~Tr|3UQRG~K8Uc&zPkM!U_SU3-cB>KGV!Qdw zES3GMF3qoGv{%14%b?UrNfjEtS?cVts66<_l9g5lg^q29*SOaBmd0DIt}gh#@I6Pp zAYA00m2&;+R~IyRbM?PF*z7C4+cq@3wk2DE734i|E06N{l`pkmP~NS(DmO9ku$|G0 zQwkMJoI~{1sU)}jc=WZRXNV8f0A|kp#&7kZ3AVe19QjM*DlhUm_()QDH~J{t4OI=6 z?A+LH<+x(9<3QM*pMf7{pQzx-zxH~4^;w2^ztdvVbLq#Zzg}_{rG%eJTYB1R|LO=V zQe|+_v-^k5yI= zEL^0#`FmVp?S&l`5$nvpNp(32>reNdesBJk?!_{x7eh90jvncDDj(|0(Q=9!em^?! z-Xy%cV)V!GU}8~cMR@n<(BSW@BOkwo8gqJ|47E?GozHI6ezD}Yw@K51lgXosA)iGR zmT!(4G&;O7r*&Dk!^U-oe=G<&_w7hY@fF>{Ydwz@jnc3v5e1*o`pu5pn4PW1*_n4v z-%N>~d=&rxv@p)SzC4qvzKe=ILtnk)Jobm%JiWfuxpLE~%!6mXe7q3Q_smD8HSSqS zH$!{*bQA7Z>k`s#%o<#KP1d~o=hvwTJv2u7JNxP1TRMC0eI6-z`0Jsf&+rfLgo|Y> z_q)jN_~5zcOwlu$zn-y7-vt;wALud4dUC^dZ$)>@fjc&RHc|bBR`;BZxnGq; zMW;B0i_w36mhjo~aZliydREPaVMfuT%MF9ie3UCb{*bx$TV;{wTVeK-Ju@pFRlM3` z(#9FoD_P!t(PY*O@6o!^>!l5^#9nP%A*kr^_O|H5rrH;gbzA2x|CRpDDVlBKKm5vM z*!Wf5Z&Cj(<*%#r1b&Ov3uO5HFls12*16@zt)OQ4WSQ?q8iF_d><+%~Ub+68VALgn z5}9Xuy>4e*%TJ$s7e$?SwDJ?5>VX$;I=^K}^*-uqY1tCKrq4jnzsiEAA&kM^XfA$v zfbS&rNod)*m@A7)O7$N(&ux2kc*9Q7H-`g?Y~5;G6k-%zisZpyfpFBU3x~jEszVIkMZml(Wuwev>{a)pIxfdB4<3W!+h7yQv5BmYN4{ z_!N|%Fhi4e+sZpBMt4lh>zI{lzk~a15ja@2pA2$sYmv*-wFOVr9Nqf9<~Gd=-hAkT zP2Jr^>lur5`0kblPXDxI%ZIx>t3+((?bzs6;l6>VJD@7zTlU(_c)q3YRn{b{oa%hG z+2Pm6RfhvgZy(i6jDFqrb&;ULF8wy{^x9^0_mQ1vkIo)#3j3 zBgFrTY`~^K!_Xmz85|Y+M>(C>`(i`f&Sv{Q3vP7W@?_KE8>ZXj48kY9usOQQaf|C( z$1rcrsZXu$TW#K+#-&;D_(Q_eeOn4E-P}Zf>bA(=E@%(AeYiaX6Fg4M>?!7w{I0C2 z-(z}iXWZr{{`D=^N{goZB5UGFfN`uX zqYc*AV~x*8J-4`>_il-9^kJ>Sxk3$YRToz9`Aol(y#0p!JWaJO$GDEcGK^WG+wx*q z?^<5m>^SD+%i`Q!{4qJF-R{opp1ST*=Q6t*oyGH~{J3wv#D(>qC)0PDopSvHN^@=T z0=|#hVNrX}3h1lkd{}9+VDGHVn`c+%9>03vXAo76o9mXIQ(XLupJqZClP+Y0yqta8 z?dI;-*elmA3l|$YDr?VJc64w~eNawEl5vR{rK3#PwpZdu?lUFx=(aVVk63-r(%t2y zA)+AqEAmOgTz7K6R$ayt0-d4R>z;8jAJvUu4OnQ2M(r%{J;vJRCc8F{U zTCnlxYCs(Dxd1gW_YA@3~SBCfCz* zJSrAia`kg-SnX$h*)TAhK1U;F$yR|6AFXRt$`^iF^=*p$VUcrJEWfL&Eo^;UD_mK5 z^(`my0eb~CZ<>Jns+JFLmzc!3oxE-><(RouW+*D^^0~H2b?;ZmspVNlJa`bW{B;<6 zYrbUnQ=Vmgldh?GWq+Ky#drSOl*Iwv^nh3+t}L4`=HJ#QU68-`vu5G)XJ2>Us+v`O z-Rg^UPs18T&F0i=)|aLDE{5CPests8P=ss!OCOz%<=kt&E*nf5Vr-zjQ4!ZDfA`*2 zTMGY4Zqxd@y)%XHX3XdKyzCZRw!7(!+=EW>+gzgNk&Er#z2Gu*e{V2Hx#x_+VEcx& zxw{XyS;X{Jmo73t8UNZoGNv z)h?!A&u+^#(~{Sn2QI%BxUxy}%DH)O!~8M5*=G;T(%q3HIm3EZZ+ZOv=~<@O*Vg?T zKMPbZ+S{10NHQ8Httz=E{^y>X6>6~YO;CDbu-mNU2 zg+Kcf&Ur~FNkpuY)>oOaTdnk?;HEf1hTv@H%G&P1uTCuzl7i1ZQk|wIciub{mwvQ7 z=gn{IgsO&n;Q8bowLLXr@=F9Zu-9MVuav!bS4%1H`r-4_mn41AykXo`dix<)k7uDP zuYgM9iI+dNm((tipxHE3%sF7ud{uibcJ-Z)bNOIUxBIzO?5v&3m9n{~@_$~&oOE;P ziv78djb8jGxSa7!LuC{KB)n4we;fKt-mCGmxa%1kK6}%#cSCAFk^S?VDRCv8sMXm9NB+)s8FL ze|$;!+N*od&QmFZG3{3T@g>a>7jqn_=m$X|}H3mJ1k3X7l zQah`#`9kS5Mp^h5_Zi|mhZK+64ShViJGzf=#L!kc>XpRWUzuS%zoR>7)dg*Mb1Wm} zQQxDFhh1zJk4&?zXPLZ|aNONj(HqxM7gGJpp3OIN=-JW5L%y~H-o%Z}on~{<>t6$@ zJ#w>Zo0t9;$g)q~@OZO|mh{3Ui82o|76v4+?Toh@FFm+1@s-WhqKK(#scCUyIf3zT%q~)Ndqru`8V4JmYk7X51FL!l4sAWS zyqm%FY;>PHP1WK=f=+T&@7z@nbGhLS*@gpoCEGzRvsw_xGf0 z%Uz()^2n^IsLT-VlP{f8Q)#*?GV*(NY;*92;dk7p53IHkONliQ=FIQtj~ChMd(>uy z$$InsZFScV@2dH|R=mum;GM4`N7M8eRhh0c`{R+>8!9~lU&pj^<=Uyd|J;0C{qb5O z^?mOzw6C)%w*8v5%I0)Q$_;_+onaK##`f#+&t@$-88?HnUOCE9L-hiW#k0@4Vv4nb z+EZ)8&Ru<2a=4>^*LTGrYKQCQ#q08J?7git(@kgpTSu$KpM|by+`3#mpGU*R*KoG;#|b^pj0r@WL`LJ?2> z5=7?C&Tv~-?Wv7hi4P%Ba4*_7wm6p}~Tv!S9{j ztnZ3Zznv3TT^Tgui?*)eTYJZnpw!dI+_nP2aLHtL5NWYslv_Ilwn^B3$jdrVFC-2Lg zuCJN@Tz)q5>`TF4O@bqb29BT5Y4cbo)o;MR<<-_Bl&KW!At8r@RRYyumSmy79{mM@xy@!%H<>AZTExr1%b*^H~ z9UhS!S(Pf42IZRGh>~^fwW2>HCf7dwl%6`Lj7QySqy9tvXGOn^)13Xp4_W@+-v8D5 z+mzb^x4Vyh3}fWTvAeYzj_;zq=v>?QTPWwj4)=3Esu{ya%)k9|UVhr+{FIB^obOfF zST1rXK3Q+xlQ=x@TFI=l`#KIE+oDuzEqpM`-S;Y{<=0)2CUNya_V%ZG9{W^{ZA-%~ zjtE(HpYim+v}K=&OS+%2!D>a^VSmpQ>k3@7LRLOf=Kb;wfnT;a>B_1u>NI~bPosZV z_9|+Nb$#&^!)1Hz99Nn>yU`wjX>hBhS}$jnmK~MkDtf4mwmDOGe_hoJ zCBd-IA+c4*vkc!h{k*)`CPjQw?UXbT!}x7yUGHmT9@`@!x}*CcmUDsrSkvgR8FPSH z<0`j4G%hQ__Q}oKLTQ%+Y^(QG)U8tn`%Mp^s>D2 zPVBnGt0$q|r}XX(p4>4gs#AUJlmFsxYfLtLJyvU~Ia7yI-|%v#@i|4Ov{NRz`_BZa zhB`YYSkyIno=X0;&VY9Av8@u*w@3Jq^P_cw`cGZn6c_fKTFdNdy!pht=+Gr)^;-2z z`Ia`T`f%B0YV)X}!P^(cw(PdPnf6wfRPkT)jm1{(h!whY=FE+yta2gQ zCtU(^^Ry!lWakMUw(-4b;p%2Ad!%>UXo%nEMAuy3FF)8<1%6Q5BEN2H8mKldUaeVi z?ph&xf$F(f@s%SynM<$j%v-|z_D-?kP)XPWC(fQz-}X~&gX$H0GW&wIr790|)1*^g z^-8tmWvjM{)Ykqw94WuJOiFS{DNwJi;@eFA*IO2?yHT@Wy3E%hYp39+Jw_`QU6l6u zwA4ynCobP&Qd{2K$ytW)s%2Cy^uLN+^ptvI+PL~wP(Q!S$2ZpC1oV8xxm)YR(7`F!78Jm;-Sah6XTto!D*YDLNmjl=_qn!1;`%Iem4 zxyVUcL=KAOcPLqR&dFilx|MOz`{r;f_EvNEx|a@xwT6W%+b&i8v_B-E+%`8o*Cp1o zXU#KRj?|`^b{i}k<}fZU7&wt=tz$-e{p9I&2A@RmhS^Jhy~dV)D8W`TwXlAZJI-gG z4a(=s%)tWB6w+k^o7bJ0CEM>i`^OUZYVO(o6;95cOBEwzZuI0*?3Wg2&0N(jaMju> zN42WFa^W45H6fM!_w-amcq8`QR9rtW>Kpq>?9Abm7g=|P4%#L4Ze=NUBln<;CjWQ<8pDd|lM9(m7jCulHBP z`syl2-pkQC2NKUI+sAw`my^F4lCbWa<&PDsX05t2HLmQ%=|eoao(XL>anpVuqi(qT z;+gNFmnI?C9v!ckIv8?BprIkvx=r91-FCVDnUgPqwT^B0@*}LKN$O;kW3=ak*zC!ev1r1*?YUo$e!RQ*Vv`7VWnt1BC%)rb0(}?s z9&m8@@!Gxmrnkq;YVDSrI^7p{&s$OOJ#WUmp7k@ntXAS-U!EU)@+;eN&nw$z^Gm70bPQacWF%Q`sB$9ev@SjM9aiq);sc38jem&w1Ie zq5gL5?nvRomo?~xdwCktzkEqy9~=yAIn*R5C7d~!aLO}t){H3rn&e#5_+*O(M2lwpDPD#am;J#IS?f_Da`qHtrv#vu)#ynoSbYLX#;H_P2bhvMcoLDBPV3eA^&Qf)5kd&tI)R=qP zOP7=!);$~gJpR=ox6@&wj@eu$kHR(F)Nk)?eR44Im)jI>lkkBHPaFqXfeqYteqTA< zEW7Kco=ZPqXDuH3zNYCat?X4lYo=bxj160bujnm{sOf9IdS}zag1q0WM@~u1-#OG_ zvtr~e?O9X) z_EF35_^gVG&wNtHT397E0;Bdeb4P4#juo1;@%?NYen|`dFxo(S6K&|?IC@UvXhk<) zjp^6UvJC5(mFaVjJkD6^>{J}{>7|16b+v7|1E(9SqbALLASYq1rz`zn<&{r2R(E}K zbzRB2^#0v3j!M1k%x3ngtC=&je?M8?GwHj|q06yT-!$zOxPLA;UPkr0rXSDR<=zG! z-REUFQKxpZ&FYu0O*tFjEcED>6K@;W?BgPLa*wzuHeNlZ+Rn43mnW}l^GesswXEFb za}H|c=~Z#!T(&RiH5|!k-WhsQEJt5m&Ne2_Vy$OVQ)^lAfn{Nr>W|%5*3a19aO=6t z!`02FgKZ1;7a1|zzNvHASy7eu#eROWNQ`zpZQp5jB111wu|-mkDhvw z@FRt?dSTi5s>v;$cPLutOQ|&_y(=Bh?Gm>>?sTO*qUczhljD|{T6GKm@+Ace*G3ln zKLA8PyT1-3NtWbyPMH6|35*zQ@cN%l_{aaj3IFypC;Z!==LGL(PS7PouB12+7)nyJ z$mZO%=dkdeW5y>-LFeY7`&PY;Zd15>{4BTn0m8j!dA>0L$_@jRdTbJVi)lY0C~R*0 zKxq(Xs``5KLvu6$dVA4b1n(zw!=OJ{27E1Y6`u1U?M$ty6Wlm(89|S*7<&;|c7;W( zFbiRxQA=K6lvx=dPs|}-!nnsPL(2VWaAT5C4hJAdaznRDOa=joFkq6XJ#VU9-m z4R|4D4h`g9W&zLoywZH|!UlfaOyFTYTa4@mEK;y9`}ug3L~zjEtm%_{v=C+kQ+U87 zU@m!Lmbh=^YtnMc%EvWs9#pI&0MAnQHiu7IUck_0Pg-!MH(R_Q#Vkr!{ z&y0Te);xr8q#qjav)f&!By>5AJ;q0f%=UcTCDE`V6uZIpU9-MwT1|iB1Cw%b#U;re zPzkFDpInrK1nMF+Ksu+0BzzbQWi;|R|1t*$Q*FwJ`~uHr#afVJGR6Z+!+Au=x1Ml} z9SY%zUXXl=Wo%Bf$j5xee=fY)? zH1-pDgq`h7>L!>g(GCP!=NR~`MAcnLsM}x7kQC{AxEhE@8GIo&^C>G@2%nfvAGuZE z)(B9Ji!Iba%fvp!riDu}(aQ);r=+rVpkWo;C8*U`S{HG)8lV{;S@U|#Q2I#ugekOp767#yJ~>mH*K*&cT7odg)%U7>8e-bFm!IBrXPUUVipRT`K zH$&9CLxB7h)9uLHZGL!DqQcYsEMiPoo=lc0h@i-C%J2DHu;P+x7}w2*iI?S%Pk96^ zMDhad+N|iGgrQ`1MKpNoPkWV+3WzWob2}P&@L7E4;Oj%uB$+sY=EB;GE<`n{ZoP<2 zl#mM(O$#2cgK9D~)u8wia+d){T5dV~iRhaR>B*tE*YBl)3Bu^+p&;GyCDaGA%J7lr z2vc8`&C0#+v+|(SY4=FjlD$2=cJo@tZ!}0?C4E?Lw)JM4uwTvzY1Ke|k!$(}*r=qC zbfJKE?p3qZAU->LN3Z$A4EGfLlqdBu^6%1BMBr}}k(Y)CU4Y!DCz`}-J}1L+wir|r z$A0nPdKsIR7*G9~k(=B%B<2g)9UvgJviRw-`^JIM3mNAE z(n$P6{qg1j)KqtwdummixeS`(Kog#Dw5d|{V@Jbk4J z%)<{LLe!5@nlInt%sgP%kZJi7hw>M-Wq-Akg(Bd1?88@k-Er%73wWm_IC35$V9By> zCR8;%mlbNhFaivuwl8esbl1Kcy8mX=MSH28-~8r3z3}&c`=`C|FTeUjFZ?+EWiPBh zygcla#TB+Uyr(Whq;r;gggZdOzexa5B@&ZOz89(LE%#u8agEP@D zw#r{#BF|NLtMM?$w~JuW*FZz${Dw4fT$=PMZJh=^#IOswG?naVTlgAa10IaZu0mKe z>X0HCyKCXcWvNaWz)uoDDV=9Zh2!w&i-Kc2SrjU$!B2)TOjbvu^{)wnX6plY!|9Q^ zYd(u>d?`D5Z`ANS7x?ppD>%qI zyTeXwL;E*dmsby!E#M_$r(OcaZUMzrm~`pU*LpJhu-V_!srE$;zrsGLlklAp&E6Je zjRWg-zT|#2WNXw6?e@b}JwP=o_OY;rPh*j>+t~XqVmj|M@mt=*J3%{{M^ti%spgp8 z6#49RhA5?D;XlK)Pst0+uq1w2|9H;uDvxm8 z3W4p79KKg7wZHN^IA<^H>)$R~@n#^hR+J zzII#p^XZvfMRoKSNh@Lt5&CY7TG)^+yEwLYh+9EtF3A~G?hIy3`}B-F)+%v*d|^buR#;VjSVS7E{6aDJ z5^b`7z-Sg`RV!O0LB+$+WkMM)4DR_?!?y7Bd>W|Z@AL;6H*?32Z@Qexc@jip9b1~K z`7LCawXEJeU}*Aabdqe?N2R3W!gJjp6D`kUR6XP}$JWk%jW%w zd*!4;>P%oTAd4Y6v)1~*9}Cp{rAID3i{r?VD>%AFEP?t)Aa4G9O*H8=R4gV9Nlc{B zoEGr-ftUIf?`|bK!zoP=!iLCuJ^x@o9@L~VTN?6ji?IRy831_bjO$<$V$&2atTU(s#ZIiBx0i91r@z8Z+B!Bp^8K zLwitlcHp6r^$&m^dk=e zjY=qWntSvFijHO;AW;L0pU*f)8(05f1j~O}tkYJV)96l8avFc&IUOb7^mk4vh;hq? zg)^|MoXH&wqn-3yUQVM#o&jcL`02+d z9O~>k9X|T$T3g*)PZkMw+bvGZ6r0PkoJmz6+%$yWz+n7Eq8U;Axc^ePSMsYdueXdSGL6U`4aAv~(;WQUZv{ zrFDWzvoI^zwB=qWAlUXbLx_1Gc12)81=43!$^64V{M~>5<1g2LeaHX&n?L^e&+q(B zfBeV4KK|oB{mcD-c*pvc%gv=RVS^5G&3COFx0JY<1i@d*fMIthfHYIu{Jm_0$ecQ#fn%;wOsVL2_&O<@=0nr&Aay%`tD#_+3xX@?z*?^_T@ zpy6TN9ftss{=lh*s16n`)ToBU4LVzeLMjVts(2KFXXJ1Q-LlM4;#6_nb8XDkQ7zp%zR|(K*)e+C}tr^ zqrS9AY&h6$mmh=J3dYwjkYmL>tN$LOOjq=B?`)zY$+bt<~~QB31#6u+LCT%bhZh)iNYX z0qRn}DTE#!${uJRG|sL^Y(=X3dc~R{?do?BZ5_+aT-qTJIqrK+)(L~jxIi7?treiH z%4y;k(JRZ`rNKK-`>`NeeM$j#N1z2#qh&p z908nU4$i!8Dx-$Ab_ly`FeUIngF*RSZ}I@%@x?j_zth6Y>a1(BP}br+Y_BcXSL{q5 z*7D%QcIJm|W!LI^K`Am|fevFsyx}!4f?qnt9G0LJ{1ZSwex?aN6fl>9jE3Es`V48k zS@@hpoh<(e9LP#vx7(2Ji9589fIA$m^f_HRE*%bxo<(!M;)lFTbK)=_995zP4 z+O|^bGAVS^)kL3SU}O<>-58-jSz%FoG8VS*(nm%(rF?*fh_OQ%iSHDtWD^QERC1FsD^YrqeYr6d^m)${uZ>0>P{8M{Rmi6g1a{ z#Q1n&z|YU&o$`?M4O-Cv7e@`$VS>i=vVNDTlE|xGd2*03rd;g%-z(PzOUEpNtj7C3_H$Jqb{`Ls}@jgZ) z_Ofnm;(wF@L>c|nVXM+@?1+4})C+xxx~!EJkhA7G@vJU+6uYj7Ldoy|d24qh{ z)GoRT7gKs7(Q$7@po|wTNurUCdKtCOlp%=yNRxdD0zTn%@u2BSW_;G9 zJIq+flqyA#4+5QX5)9yr$kV=o|LVW-t z!8FWZYOIhrdQ^O{2VvxgD^h}S<*-4Znt#th$n#<*BZQdR1PcgRue-U1mhkfo6Sc^- zqEPbkb8-a-O~ArQb{B=c(!lR98B`Z7Ib}f2#$z#AtY5%R1Ngv%9*7XOi8S=*t_dcq zvP(boZM7jKqr7pTT0EYCBd<7{ziFtY?uO8@qlA03pIMTF6dyaSG@k!oIAi)hoFR@k z@kJHBhQ>iX+q-g6j`^rcelHr_WQar)z`d6jv{yg9+ht|~nPRWmBRET%0ol6MU+sGa zBA);l9x2bgt;4|3!=Ujc(p*WX%aSg>MXi#nkB?o;?|-W3hdUKSZX#R(xMCieyS)uZra}MJ3uw@nQ|Yr;#di zfVLT5&bpJtD2&eSL<-e5vtk;8Cm1z(G|maIIU>SsnD`Bz&ksIZ*h4;?{YkX*RQm=Lbqe1Id)n!wwXDvcCI*u>;#F~jbgW7GP>wZpxe!b{F5_Eh(=`qIn&?I zT!dzovnKh%-yFAkmSWdCzs9yOC#X*|F!EF|;X(g&Kx-Ar@Pwj9yEhBAwwhXC{1OrW zi>%wX{-O*5r~_Y2;387tv#-IZKz>12AqE~1+LbqDWt$v&@p|nJOFxK{3)@p+IIcy) z1C?5Ey8A%H>>D|XkL^na2Sssist-4Xn$&5r^ZBQhU}e!Cy1eY19?Fh_m|Fxq)c0#lwb4#m%crLfV5*ZfFE4lx5`~TeE+A!1gmk=7ykK>8W4x= z%z%WBv~o#B=6C2Ye*?}XB2wH;@bny_NzufyriYIYJpLdc0Mtw~zt#V`E*# z7z^ktO#J~7`q4P^niRhxeX;$?7rfgwmPSdXj5k@!vP;XOrCqx1m0l;Ny@=06YPfmv zvBIvUNJ)-{$(+TY2$SI6^NzGdlIhTnG$9<2%q*7$Ak1PLzD|MVkFlwf=}FW0=#?Tu z=`j-HOz(Gkwvov94vPx0U;V{r$(M6c5IZDAGwq~iqbIrCK=H=ZAtfK>7(HHf$X)(^ zx#)JKJeD+Prxf2Zv|hv0(7r&_7Qwn9VA41>=^F00+9u8&n}?J2HL7SIA1a!I$=OJB z_98~gOFDP{s3{x)RRWBBzQB7snn>&h2+bcwu+gosF7>9NfWA=>V#~9vpiWoA{16&8 z?(V&2ryh|#lk|WFDaxq}D6Zq2`#C9^hdL>#D6#%wkU~Nm0&3Vjus=yDbNPOrFCu=! zjzovUuZS`s*?9aAIqk(HFUUL+movJ9<8LETo7ZAXE}XL(?1IhN8K=#Uk)9&`SYMO+ z*(4CS5&r}~iN+SrMDOqQA)V}=#1bM$fJ9)2D^L;ui6nbH5FmWb{8P2tEi>Nr;t%~$ zj9h7^gppq44&W}BOJmp)Y>FD#xKcf4vSPK10jCXUwvi6vCIddtu)q9{TUt~8l00Gk$eaur&v^=h(rug7CQLKgO(ELyW7~WAh znM-NR(EZ56HsmBV+@lMmXyRic^b?^VlO+jz3;z#i{NumF8Op!n4CUYC4ERsZfIwDs zm0J*CZiXgRv%8l+T$vr6{8uWl)b4^R=1fgZ(FGVV6})_} z9E!1bb@+Vz2nhlt_wbjE*RE@m+_>liJu*@!*RB#7XLJkemI3@HmSsWz7S-y1w`Fy- zGU&Dw#A7eE4lXCu@7-;y{2{Ya8Bas48+l}7PVz_8Yyev8N=ItZiyAYoBZS4IPy;TB zTL_{`_Z}8N&F?(INvi7OE~jSEXwm1%`P+^rZKa_uh$hQcaWZLS<2hzU z*vlcC?Sg_MbL;`Y^?JSrMukS^-dCjF=YVv~qc$sql0|XA zyA)B8ybF#>4y~$Q6CVLl1C6`}afKR(L=*UhDZUZN&@hvMcns2y`3E+?c zz=x2u=Gkm(K1ItHtTT@ZV}idyN}mlN35M~CB?Bo2UhslxHs%dx?XxHhNI6qLX;6U-0 z(TA^4kVWJ4s$0^}>#xruqM<}vKe@N3v)~qLSmTJd=g8>f1Nc$JU4y?;E}n+ZTS;!x zDF02wNc-A-1cMMnkr&^vt2mT|RyLl%8odTrV-iTG^^Lp`wrb}wo)c#HuQ5F4Kh zj=H{0&BdfGCJ%hW8_Fy&_Q49P5KVwn z(+%ZxDPI18KfOfLowi{QX5pe<<77h(Lvb1A&qw(I2SAlVY`gA7Mb-F85*^D8v_<;0|EnL&A;Btg*EPHex_Sf%p-kM)DO=LcO6W-GD* zV-74P@S)ZU^-MrDS8M#)tNa_(a)WE3UQFiX*ESa*;D#q3+$6K$^^ZW0Q3I#QsF1tB z!!ayH(us`$ALZ<1t;n4Huf3h^`d_`BN0I9}LKV49ShV0#tHrGp2dwmInhg&DYn8wX4CGX>sbI z)RZm!|C>Yp_P_kw9P&^9ibMYC-{BBca3H!i+a9y+uX@<+IC157J-&=9|2jJ{DnRWd z$YvE=({!B3`r|~ZBk@VC`Zm?CEcf6Xz_MAYOM6A!8eL)Th&eb)(UruW{GcyPgbzK8 ziQ?`C+*1I$JO_;=E7z*yn_5{8xS(HmMw@^H>v({=dw60wfA(17q#$hreF~zPSMw2p zrinmAHc$(GbxmG)-qFc2^RJaHUYh5vR|FPlNVM&Xx*)WCy|bPIjL2PDh>HP=8~Y9t za%Bk>w6|SDR2F(v3!|Oi;c@)6473z(eJWZOsA6%+<;=2D_O;F6M)Q}&?kN#huWg~*;~`wr6ftmTH) zDxY|=sD9OFo5kg)#lIhr)@!7G7Y{YLFS6}n~&C@qs4)pwCx21zi!8h%Lav_j6 zP`H~P7ZEIZAx6yH-H0Q;zsHvsNCxglEt0CCj|TbzqJ@+G>h3+CVtK&#+ZxanyDoiU zyG0;Ma>^+X$cr{}xPGPAm`7`yh5PqF```+okkFGt&`M12ELb{8oFMBXJX#2e}wDQE0>}=_$on|7XJx8}p zV!P-w8c-VJ-mru_)6b(frNY=~COujJ1LVygH`k{TXFKW**$-xODZV%3X51AK+YX-y zrv4q3G^Ar`=a0yku{B7vGO>5!U!zB?saDb2mS_i_itNviQIVZ zdly=i)J?dfP9Q!APn42diN0rvg#xx_vAZzimhHUqtPz2J<+9fAQeBV>Fll7XGYdn3 z0Qvo#lg@veDJ@g7vQ62n!96a@5-2$}cMqZyI9^K&oo2`1zK#uME#K=FW@w{5$L zQQXS-;o^JgmRChY9^3*wNQQYn^bIj@Nx99KLPGv2iHACNtWwWXliC1_6zB)Gwg&AnIQaw-s!NSyUhU6Y z8k#s5QsOf}-ar12zyA7%zyA8`fB*eofBo0@{CDs1pa1&T@n8Nn|4;7`|NXz7|BV0k zxA}SxQ`-L1Kb6ZgxZBc<)qnrTLVbLx+YSlxF;J*I^%ew}`$4m&elSzfMMJ8^IN&Lm z>t;dte3g$7?`FQA2eK>{>FwsJ#pmygd>!-X)1hxn95Du4qcrG9X8BYzY1}(T_s21h zSFu6U>Unp0*jRX2bUa3StumD21W#;P`N(k4-`mulOk~>AEk)BkB-@0%6FM_N)~gi7Ni#hV!PXSwAK}I zBEOG6B?*}Arh*ej*iZwASdsp0b&|Y$c2O@+Z3xE&O1s7K^L_uufo=Zu&mnuS1N*D` zF+D0L+V9Nh*n#7alY8-d zvmy1y4F$CA$^9Pn3TH}r#J($0=8XXO`eI}Hojw&9w_^Edg0+jbf29F{ges`gP&pQw zrR+B`_(5OwDLI-V-ye|uiena?L5d0x64C>*FRKc^=oJibG%qG0OQ}6VMr_hl$uyN( z*n@{U46R2$oZK#XV8&-<@l8+4{CB03+ou7O|M+??(X$Z7Cl{sRU)d;fDIw8j>w_Ga zW9D*k#@=c+2N(a)@u57xgP$g0=1atjaJokahb2I-&FhO8Qe!>R2yu2Okznq?e`BLY zxQ+@)zuX>=q}o(;YqL5TXG%!Ct#RN>S00*_;8y;Eo+qJGF1J8nA%EDYK8|%oKhGf3 z71(IHfk#cf$aJHSeB%X3)WKbUL9%rn3tf?fI(xKbL1_b0Fbt}{Z+Vupp8RH;gM|Tw zlD&2XA*SFT`px4wx%h3^hwK7FM0ehnKIEaXx8fWoFaWqCH1{SVh4bML?)S7Fbughg zt_*EyXtW@RDMQc#iZJ4x`uIudVgGf6zZ%L<5Oo+u7>ZAg&=Zp$_J1@Vv4;zCRCR;n zOJ|e0BP$QtKR8*=fNTvqe5wV*0!&A;xdmVY!O(g=NrHhdCgRO<uXU_4!O_F3Z3hQD5~8*CCJ>H*xq&x!~Ok3yd@!yB-+UKhQsOilu$YwY*^eCZ`T zA2kMU`~j6oqF-LH?5Gfc7?i(woPKQkx#$@%yU5@RYAWPe&R~po+K6H3anFtl3;%pk zljzSHL>fZ_0Xa{W@XclAF%zl@Z7EWs4aQAoBo4*O$T`K`D{hcomJ_Q*pg4vY#}Dbt zl-Q_#Uot`$q@ft1babhuaaap~h6jxJp>Dd0XY1l^FhXivs&sj#W;HD-g*<|X&&d~K z344?;u!UP0Fnx&KfVo(pUMJ&}#F*jCku}8K3Df|*u0MH-c4c`?&hwE>57_PufasQ` z&M}oin_3+rVI3Uk2+5XVc}=rEmH-i$Z_kC}v>na1Qz^G)1+ioa_*-HW2)iYYnJ>!B zSqNMq=In;-8MOeqWFjLA1i3(r@FuS~K;Fh%VMG@9!1oaXhh*=T zVp090LbU7=ERC{e?jDU?B&R%MSFNXn?WgJCi1fm>zX)9M>J2_0V5ywT1F5?PhTw?_ zAJrTNl!1??ec`0!C1IqkUEW>^{gH;(>WLO#pIOA?vqZCW=P!tgLhw=(xA{o7j z2>6)LX_xoNnqtEJneEQMys9@Rz{wI)G;|HkrTs!@g#&VVrtgObl=Drvu$}M>2+|Rc ze3Ovebi%y~8i0&eK0&~O%oK3rfppAWC+k2)vI5$UY^f}2z?@5cF`BG^mGq&8^^wfe zMs&&5QgRN`l5DG%KgT$K4&MuBTYY({@6)jdDVfF}Wo7>PpZ_q~pYeyw{@36A`&{-v z|L)&%*`N7;$Yo43cNfDYwV!-@Valw|+O$7)`{daddo_c!7gEn2lp>?B%{5&?DD=4j7`=}nhcqQ|jN7tCQl}Fw zL#_jyOyQt@q}~6h^%**LJ}{4i&W)dopF$caVQwfNy;&DT>J}Zok<|*iJx-DsA>CL!)J3q{xXt{DX2>iCc1>_K{%rN;}J1|9=;8kU2&jm`Y z<@Hu*@a#{Y^D*zIU%~*SDu^(~8sg|2^Lx^CVE@xRng#4ElnK9#3mL+l*kx3%c$W$H@6vU2%mPBs_LNK=n0PgltAiG0hUXD&he@S`Lu~PM)n56T97}y~JJbVrUo`N?>ez6@ zpj7H}O_#_1RYe;o%R`YLHG4tUd0cRz*-xtBBlR6&*l|#{DLX8}gyj|}eD&E5xwQvN zoWl!GWObN~78!>YRAJ5o-WCVxsE2pI(Zq3{eqyODZp$u4x~v!>T3;7Of%SF8i+=cc zW-W`m>HsPWXkd*yxh_pjES_i|@cf38d^^Es0F0P%T`jV;=K{oJx>!@e@JQ=};p^co z5g3>5!N7Su_RByK0mi`Kffx?S2%=E>T?T@@%JdOo`Uz^Fz++-|7v7)%c{;7w0z{7i zrY#ztHEgXun4Cy{nKy1zr6=QP^EAua%&nI!T}9J5re!8T0!{cnQlb{s=!hUBK0bhj zMZkM=igbBz{vMH3Xh~g@n0IXj zGl81zhFEef>K#Zc5RMW8ZL$)ik}lPgohu6GObc5BPM;B1!4ZBYLC|me{*14IFX&`e zUj00um%|84XGci0R+Bt(@#QdAr-WD)=mUE>jD0x_n_mulY*9aPS`BeKS0f#a`0|_F zoRw-IF{nFC@N$6X>j?Q-T&~%hg`aVJIc!$Kn5c$&8ea|r`N0dUxP#aJG;HhIQ@SG& z&mWPSbPnYp(9-!q7+8Vcfck^Mhsp9>KSD&6E4`dF4`9gubp_`VJ}J-|HMcMk7sV!& z#7m$Ka8O}Zknf!j-Zl@#3G>$psV9PpTR%=OG|L)_L8*>0fX3HtsV9Zm$V zoKQI|mE|%sxG>-$FwKQFKNg^`{K>=E7Ks%~isttCOXx03W9qPHYv9CfjhEi&NI)cC z0RwLwiX8~{%9)m{8`dmR4veD9^I9EQtd^H-#<0UJN3Oe#%D0hGNL3{LTDL*yTyJsk zE(In=48V3{65ie7jKAmbP8PsHY72eqN)D-0&;HK11iqZNL(a}i6~ytkXp`iAIiAtl z5Ht_i*niEpb|dbGp-RxCG5VlP2IFg~{c1HhSBlAsY)SmQ+;!HbD0PJz$}cmK^l1{W zq_2D2t@p+-k41;}eIP(zwZccVpl zO^<~f2Nz2dvx6|HPJejISuy+b{wERo^lzLYHaq`m)`j(cs***s_F)9|G5#ND ztYMI&WR}+7w)U%P56=;-+NHkq@*HNKfASu&W12Jo&N78=ZAo-}C?KItfL`J@mpP+z zsl8GG3LK5mUKiB$Rh@c;fr#wIxMrhHVFk!ETTAR8D+3L9iAR{8CH~q9L83W*{~Vg+ zBS5O?O^e1_hZ(#Di~GgKkBJrDW=R1iC3bdRPA)Z4zFsZPgBkg@dq-)CI%pufC9r^! z(EG`yPpFBk=P<}ql4J0O8QorLgKXHF&r2m*;w4m+=;B;z!-=}&AccPr1~tRwll#Bw zrUOXFEo9WZhZnM9#X+|1!=XqZ->< znn{3=D=1pTL?>YMn;^8=bs`$!{_MJcG>_+C!JM1H*>> zg{lhEi_%GSEsQ4XQbGl=@||k>92thAWcejFCkB)ZMr@gU@P^>c53;wB2paUZ73IOy zNE?Fk0JtF%7`^V9J8%pZ?F6$=!udSzV1edsQipivHCRJ)V2ZeECdVNz0BmTC73SF; zLX3tF8u3tW7m#8CFbo>_=WQopyO&MdTSL88+35S{OKq^{4pGUB?g*<*zllL{k*e#!PIv!gR%*@%ErbBLx+UW( zKL8s$VvK1-a_ma4PQ(~);}Kg_D{31Bh-Y!9;RUK*n92OgkSV4f15@Xg_H0Q9znqF* zR*ol1h0EDjqm&5oY12sa87gczBUAfLud&?~pL9(hp1R6hmLzFVB2vh2nI&TE8V6NQ zV>*?dH9(Kp1irCH+rXJ#$3=ctl@#72`1^s1aP(={`jm-Ab9^xc^v#P0=JeXi4f?XZ zLyPD_0qmf$`;2+M9a$i~oxt+KZ~^o{>ds%FCn1A1T<;Do%JZ5;lc9V$ zYlgLMn#Eq&9tX_BqoadK5ww@?&ykUBf{+Bd{fLbeBKieHaZJX}Z z0@@<3pCsF*czMy@Hp@yx(4s_`A16r7j+XOR?z&LIsR*u=l*6pO#jh>S(HE#BuuaE7 zw}p_Lj$f4nZRFoNbMJP07si+*_zc6K#~Mc;w{DT~T5Rp)V<@Mh(*PSSH)QZL|>9q>^A%*A=!m^jM^jx{EkxXW}&I{yFbP({PgEs{0 z#2!5doJl>1rm>bw#boMg%+>b57K)0i;GT=8`ZMo6qRJ$fvXyh53hl|CIfuN9{-Ngq z$*Y>Nn1)8~gT?eV6?4EA#K4lsaEdkz1ff+ZX@#FVl)+!V8)cZbX`nh*>VjljH(10| zm#;ZfqRVHbOu3LTM1-!e&liNx9suz6yc`R9@8o1g1U&K$GARs@rl_yS{N*qI z{6GKrD-+fonZ|M=%zeST649}@I~WPXDoJcMlFh@o-fO4|^{#O8i6GJ4b9*3%c_80FKY z?0QHWdS*DBZP_k!gy`KqmU08d0)!&b1=j%F!<1OM3&J#+Hx*?0qa$>mE$|MDRh(xu zb$n<%cy!Y7G)3a%AQ@e7^3}?+?!@%Ib?}H3dgWk+SPCnn)X;<2vBBra56*#8Krw^e zvS1*B^l)D8J#IS)n#5FW-qo2k!ojNavQ&nST%g%wmK3$PxKIJs3~RymR;h2tUdll* zyVhdtbzz=$NmC|JpHb=O2ZK>}-v&GQTO|kU`Ri%p9B7}7CXq#Cuca{#A9g(burP)N z?V|rM4Xqqi0X^-hLtJ!uQzIvp9Q$;S2@kA=zuM(oyphjg;{c9nNHo&}Ty7@sF6w<1 zut0SW0hGv}RizJFmr?yOvP~U`@%LG46kb?(r)~Do6{3ftQjs-?i0m^EebTL*M(K$7 zYU6_##?P>d`@BW*h18r@f^rcC*e6g3jpn5t5UtQFT(hDtR7)%<)lS*q@s#@(Sjgjq z5qEL=`*MvF0!qa#v!(bVUQG54T{!8yPL9A5Ku zq-3?dGLU4}e3UO*9L4f=YgtlZdf*4?Dg{UqzDOlgwFGTgUDh=6k@Vg~h{8F&1GVFn z0MwQ>Wi5?;NC){HLgSd`hWpG~w8$QBRiQIl{eFS*!l3VZN4!mg-P{jg0LvMfh}`aC z77@KRV!sQed`?QUFfD@6MVO#D$cr;*!43dO;ZqF00;Ec;)zHSTqYEUC20))X?L=i*n?-SS&hPd`%tS^Xj{t^ecy%4vLS-BSRF)XDZK_T|z}Zwv9IR4S8wlG~Q{<+&{ON>%(gI z8TrLG`-AuS>Hc`K&zWE*F#C9{?M?1rL{bl;&JgYBpPu9ulv_@cB&Hx1d{%@N8oLiq zT}33zlDFEYuh653-(h$ky(1@4nsD^$lUr_pZIsa_aVFORL~&3f9}wy085*Sk-%I|1 zVzcT6!2#kfSxgVxFa&x~!O+1~YM}3Uk}mC%(%j&&f`F+kMf5r#hUA$GGQBE6B)|An zk24{~e21q)YQCWl-W09^vh)@WW1mOzr!(pd87eN{ABqnQzcHe&b4J?rc&jEE>ZAzS zXA=miVg&EyU)%)cn^uAK1;?5cIcaemTs%B@a@ig-CC8U~!T)L@hB#T&?iE5UJJ z$G>-`@#^9O`nc5FDejr{lp{HC*5l+hWt@UrM0W@GuxCat9MjktEBhLL3)0k^H--0C zy1vM%r{MNZ^ zl0l)b+h8O$=vebb;uQsMMb#M|0$L; z;skehDAoeO9g16VD-MA|(cl)`UBBFW-~Vsso5{?6_Bkgr$viu2t+Vr-y-&oPI@A@^ z#Cg3{>gBd2kW>jVxT+8X>yus+dMK?4-H>*x>DPE_*~lOFPbhvkM@NVZJRy$HcOdJb z?G;NiA-2i@ywS)_@yGz2Nt-$avr44&T1vRdaqJ}EeCk!-sVXEOKENYzN2nG_2Df7= zTB@F+R{V^yIhHNtM}k%t+HQ@a0xo^PhHTQpUP&iZHnq-o=_p_8rG?WGeG@ya6-v~u zFa&SxUYyTI1t)!QX>hWdxL2-~U%yisZsYSN^FXU<+5Wsl==M1 z_B&xyK!T6Jr~BUEKxB}lYX*BBo`H)EqIfat4HHJKMD!_(;NtR@nOc{YM1kt)u^|7a zLYmQ!!r=?-@~8^6uQwmA=9Q6qM(7OTwN#H0(6)o-g@`np5xsImgRKm$A6hycD+kY$ zaR;^vp7_-&=kq?BRgiNPjKy2uf7Avxt~<8c@jaRJ;lwe}&x#{9%|_HGLcNA_!^Rq^ z+xVvTM-AAEX@YZNO4*de{yuo6h#>t^$m8H>yoEO?QKWP-#}6tCNiNlpp`*Lj< zaE_%$YyDMma4(i^&6j}qh|scdt&3VMpIQRwn%*wK_=>dT+1&VHb^dzdntHf7WJg(o zF`$iOQ4EI$mABxOmj`9v_^!!P>clD_`vcpxizM-Rh+WU>#gR2$sP#&$8t;ti<=^Q6 z#TDp1vnR`|BC6z+Osso>f!A{(oH&6pbbm!F&kY4AJIOGW5+Al=v76 zS02$#)aIzCV&iPbU8&~y5V7jmS;8qK@ZRiQ`_lwe_!l5_HA~j>()FNx&VD9iexJ>~ zQ|&@lW1-5~(~ex@z&#$ zvj$ip{f7gWH7?J=#ouIIYS0UZfDIF09fia%;NNT~+3OitW^9+P%!0{oMdPBd%Uok8 z$+e;U4@;WJQT(Qft?z2nx{KH!4uKPGXTwEkr&PGh&`;yQuq79^b_3X;oGvcjS1y+3}XgVX?i?oY=G{j57IYR`M5`Q(!g81mV}v zl2Jnqf49>FVgNc(E%r`3t04j#g53fN!)p3?!OA|eWcvy412@c}3L+S1>bhl4mr9|Y_c$=EnlPID_^2n zvLnda2LUZR(Bp8Gw&*v9@~ReH34w}5Ml!GN|W?UceUKI5;|;+{m;0ETJPHt?giTPD?78zgpWze5Wiu13lQcW zx`VOeE3;VensxyS-A7m_{$uT^O&KY9nggbo!Fu;i$jo@JIoTLu{$~cUkz8!sJ650@ za-yMl@amH2uW*uH)!T1pYD7BKt>|{jSGeE!jXa->g|*W3h~J0Rl>z&Vl1KAOhRQ@#zGQos zR*#{eXp{X^$0L17%3%MQ@|BR&rizWBZzdiYha;1?TOO3Oj`+v6z z_AHj}R<`4cnhhhd`VFMZe(~-AP(@Ud+|T;L50!5fXBqH4Fj*nHRKarEk_@|Grf)`U zVZ;qcAnbH0mT&u{cj2sbtF|dEJ87;T1=bc#O&r*gDHz4nYW9L;U$ACq3U&9po4!z+ z-_f8lrMkvPv()?`q-Wcowu$Zk=8-kWclSvYm=ZO%QxI)+g+PB-o;#zBx*%~5sflQ6 zzTZX}`P&B8VkoMii>Vv1Kia?H4mqwzXkT2f_LR&S9ptU~N=;OxFrO;pUnS3VaD=W< zX>J$ypiufHF3un?bT^IELueS?g(KXjQZbd!y)a+S{Vl@a_XVa-3pFCs-gK=|_L8%r zUBAscVx6z3OBy7)Cx%SBwiCX8kvBKZt0s@a=MMBJ@#=A~EE**pT+iR(G4q4LE;f^ zex)Q>CnDO}D>rGt{Pi8b)W^+6)e8d`Hr17nY0#0aH_V@48dNE+yw+j)91KH~2aR&~ zX`Q!H^3wkCZa=Vc$6bYkHI&T7tlvw2!>|#|HDUoGX`*eeyldp0x>Z!N&$)gIx}W1> zCS3{PO<>lm8*qAUJp3v%Bx@&XkV%l+$KsXDcln37SKe<0LPY7=c(Z(QtP&UFG6~#m zxL#g~+wa3}+ia2phJSb&K<(jjJIQgIuQSU9^4TaU z>rC+^VS-*|iPcysXcE)(tca=l2z#8FM8r01ef4JuzDQ+^fkH9$4Nu>@HlZ&UxGw>n zPsT5&H@*+B+ttm_iElNph(ZM>I*piO%NC-qAW%?8O?QHwhh*S@>fO=XP)NBc_T!=9 zxQ3U?72BwQ7D~<6wEd}QcyALQ{TiIbX_$aJ~yBpf!_qkn|MXMPF-j zSOe^6a~x5?t3xETy+4~UuX9US3mU=bc;seVBir~Cf3@Bq))V4|<&-^))L#?6=)t5o zt`OBh^23Ha=}iqkU4MzsA4*EMdqydP0MRbLqPmSzK1{MnDlvSsWD29o;KHH_HbU93 zQBj?Y_mHrLix-GvM11_l&w~NI?m_Vh$JY-~d|KtZFKF_(*Cb~QdESmhed7#nmWUyO zVeeKYQVIgjY@P6VO~*n_WB(eJ>V#|6h}h*5d#$r2+fYbZPD=D9au!8$Y_ntPEPZBF z6h@PbKr0%J!vA>}+#GpusZBvGDHl{aXP6=LdX-&P&GX&$#r&XTB~s{Wc<7j2`OX8z zXw2-c0fEUfi{a;*6+@bJo18OAQBdjR$A*gA?UswYMoSh3X8DTUXz_3{*n*g$R@isW zKWm38ToE^*>freriv_(?F$;F36wal-uV#F>QwJXsM=jh24o*wWhpzjS9Pa$YaHkDw zD0=%Wul!AEmSxr|u12d0Bqj_<9P}4bYFzOk_h+0YLo2y5=wTgtqM-xvp-aJ1PUr7a z6h}`r`1VFwA%0^QRKP@i(p6t`m3|258w$c-&`=Yb4eq5dObh*;@& zSzF&Tr^W;?G)SG0yKF6{f1CqnRnY>L?ei3pE=t8GV5|8zyXKsYQ|JunK5jel+#{BaG)~9cGtiR5R34~W( z5_3cki2$a1#cJYWg>K-tvf{YExAJ%LBppiLra_o$M(SIqZA~$EaOjgPa_nF#QVcxD3JndK&Zq7}N5y@Pj`7AEXJE5AUF!bXa zkA^cWndCy!L$bQQ*?u#4PA>Q`gmsH@W~sPEe4B}`=g#T#C)R~;TctPD(m{MaL~LQM zUc&!Zc$JF)9HuTY^omtMtbblxZWSpUfubIFnKn*l$D= zGy+xS^29`ABRTt6@9chOjwuBZ>ZeYll7pq;PYP1UNwvgvUA;;`2PJw$vk`Z91uWey ztPKvob`|WJLpxq*&Ll^OliZY&Te@}oST`=8LI`4LPa3GWi*cQKoiq{iy-D4sYvO}P zw$G~{Du-hR`=Dn@bxAHU)|95HRfyx91|tG`@~ct4+9r(9_L60URSGp*9ZOG^)sahT z$w(ZBYlfThkBKPUMlWd-4@)#gkevt1=d>u{Iq9bgVqzB`X4xRFT)Dvp+v)01Umi-+))iMnnr_#rU zh$l5DZ^D( zfi>^O7_6^%+#}bO`OPVmkmyZFYQG|LaBWHZ;ldlR8hdDYar^SikK=6*s{JaOT=<@! z`^f4uqInXJ)zS^YxJ`W(=;iUaW0UiwnqLE?@=3f*mW-qF)s*>i1FlAs;ZWBc^&iQ}%T!csx?H8W+NznVZ|9s&) z0qed$#}w@ucpo9!8r+X}vNe8@Du@FT-OuG9cTu(;2_HPPcapy;x&YoSo}Ba@42dKe z>Y5ESND#{GE0_0nu)nr=lb+T(Al&XW$o_ia7ni1GvPQ|mXY1d8Et8`kL~wn7(B)7F ztsg4{+)q08_zw!U#qhZIpTgT@cu#<;*~c6eouaF{`dEf83%G2&u0mx zK7UI(+dlLMJkrjUoNG8n%g@Ao;{2;qMn6+6FtZ}0wD~1v?a4ij6ZOvI15|~GwV6-t zNBhnvZ2(MeJ8|h#g|Y%YCF^Ghg0_AtWsHYiaoV#}+g<-f`O<{7un{?A_$0xvo^Ux_ z#5y@dTehJ}Ly+>lY+YW}(#`7K^W(Jmjg%j#?Hg8<3g~eM8IJo2Y}MYIe=U5>6C&`fr*jl10qN2 zD?0Pv4mr35V!-+E9cIMyG4h_tyK9T;sBYznxGoND z^M=Q_>(5ti=Zs4x92<%6jO&jgW@6k_aJ|jz88{sFUdzVG54lAZv!KU?&=gapdd$;g zzL|ZKXYmT}bl^Qcb0jjE$orrBtQn%Sz8cds0Or3mhNu;0OrXdQjfja=pCi3vgMah} z650~+8p;kX^HLFiS4|s49%{FF;}~U3k-l^v>D7&ao;T|>!3S>k{ggy&>nuaO{(eb` zYPV&$?v=I(k@vTDJ`AOKfjEJ>I_LDIw^ZjT4r$Ci{DZF|M$o{am}yz^+1WUw6rmZ2 zlrMo}W?LdXy~uVgjCww2Y>a4uzznV^{;xl}!3Zv)%F2b)Mfg54<)bpvGu#Kn_Kja# zMJ`w3C6fnZz3G1z{_U133Rd7Jui|;?oN|2=s%Tr)tB+!nv(61!E-Fh;OXvxw@OWP@_ZkE|!E(Z)Qtu%tBmhV!vE+jM@dSe_O8gtHOJwy|mMn)Fy{>>&h}? zMA_IlOGV~AOuwhnh4ip^jG9OHQMKqg)JYHIc(NZOZeS^Z%(KZj%I0hd3N&hY!{vVd zRS~p2ey2N(O8Dr7?h}kQ#Jk^}X`89}%Kw$o%)u7eKXz)9jFqd7QZcDfcR{156lH~zS)LMgq zBna(+iX)EEfChx;N zV$S*s!(oj^E0thZ;aQJCYH03S5W zmb*gp8nq7OpgiN=87oG0Ax|_K5>f<73ey;EgE!4>#7R2Oa@D-KS@W~#6h&Jm=9gfdl_0$c{ zuNfoLFZKqTcvVuq5%Ua(-Q#Z#WGT^RxyTt!;0XR*kL7L%k=i*ok@R-Q;y#IqTSM2Tgos&;Q>!_QVoxXX3#J$$9g4k@zDs?brgt!l0K&%rFWxT|U1XnH-Cj+OuXeD?x)jjpVLHZv0 z8PLbsN@uQi&hp1uC@3hFYkV$v6DDGu^PiJ_u&Wd%4E-+f?m+0>rRasu6VTnKR zoq{owrhUJvbG>n*WyM}LoykYD|3Igr=kS{yIVJ54*`ClnN3(kA!>Ls0Ho*p|vHaIGbou zrkKTXiF}$9n=m|Ou(i`-rIj~T)ihzIACBerio=?7GejmN7H9aTb&}`PjKq$7#4|mo*kHTYnF$LjL&! zDd&)@JxR}S=e6#=MXh>t`@uWmcN}(W^{m^oJBdrY#YyGCEJQiX6?Mb5VHwBEsa#Hr`h#k#(-t36>gDOzi| z*4Iu&(TAiTKicCe#(6YvTuK4R*Av+gJd& zmj}~_8)~WE%N{DpiuYYK33SeAInRM_Tnl%@-c_IPt$Ge_^ztz~%G_iP8(D+3SX- zWkr?6kvGVL)A}#Hhr9~>F9=lv7?TNMU zzrB2Y+tw)Tg?;%U+qt-f~r@!aN`*ls$h4E6SL3q^%FiXCXnzRdY@?+6l|X( zZu~I1@>1vF_c%3i|5@GG?x?t4PQXw#dSR$nP(dDJdCL4R?#Ze#{3x|=z}@J}?eqEf zmy%WEDF-1s3#M#F1;hqIih0gh$2rtZ@Csmh?bk~U_+FTaoT31Cbip5H4(T~N`vTxR z0h>8J{(9c(bVXzn^fL%xJpm`IT{=JM`N7ORdiLn=c<+25ciw0v1#EhC=F)|H5xAqI z9j-cxuFo}Km3188`u}*&I`+@!modh7>Pu#a*8T z{yhr3w9pfup+<;e^3Eo+D#I&WuhE%Xhr36?Aor4nZ`T0L$eD={;oE4e(CeKb%Rfx} zbqN}l;oc{^`JY{tAyV$f90Gusi6RDtuKfjVz2j;}2OX%0>oqh~Hm6#u-hi|2%hsM{ z10Vep4v%V%MPJ;P7F$V-#+-LmO*CY+^VYX!I0_PZ1eT(Dr~(Z^w^3g!Lk>=Q`YiLq zmai8VmD3b$wT}ix6_WJasHOL-KFW@HPjii9Uz6PR+3|3ch=bIE?cYXROm%9rt7J7O zo3!=J5btf@lx2%w`If@WL{E&Ul}<8Wh~p0Oz5Km)fSJOML2s?IFpt3qc4nZ(t+hj| zZi5D3g0M%oNCWV@Fq;X2zEyV?PYqh-^g4v7hA_buD!9I&H^6pV{Hwg&z3YwQRu4J6 zDUx7LJXqCgzrhq_^agXk{*soF^P@TJ6BVS^ObtqI;%BUKtX!5=09v608>TMu=);1A zk@iWfvqXg{`UBY3oPlWp-w+t%38g}1Z-1T0ByihKo+%~lmV8l6r2(8 zlwcS*KX;5JE*X|Gi>3_(xNx*gze+0rX&i&|4|&%Mn?dT==}uEnj{nTZZu6hO+GckA z6LeEYsBAk^WQRTVSvJjO6Fc_5W?~fy{|No%9CrJwS-Ui@R=^9i*nV;W^j0B!y1Z2p z?}+#-T;YGu`Cn+vOC}^s!2272P~RNBCA}`(%L8GKIMhYt9l@VD5|UnES<){|LF`l1 zRk}es>QUYLlR(Gz)ye?ZNaTmyxzyS*hZq&}#zT=2fC4S0}Pb;&-#Y*%b zoDL{?27~Sy47+f}yJi*5kEke&-C=X;aLW0^gAfY+`-)+*kKuA?dp9gri`(0KnaRd; zqu&01FWR$-uSD#PazyNMa{gXacB~p#FT$2-Idz~hF(AFIW0myC+bbKsvL;D~fzA(6 z-;?KC!(Gwh?NBKz$_=?le@7(-Yr*Um}`*`E_rL|yxa!X@Z}>r8g=FLcgPKmR0Hs2 z_wWaeX#+$}Xplyu0jMifLW9u&DRP5I9!?6ixS`NoTW5W9tCGB&6iRoqq~U9TNC+w6 zq3AGaUeh9-Wp{6h{UxPYA^1^;yAXMUTzn|a``ZT*K8HJ#eVQmPx8V1@L~#Mr>meOj zDRkyp2#FKyo6qEfC<<+gdyk(4IIoDhtUQ$ft)z+Gf^wfd+-dEfS%x|b4(&fsTjeYW zrmi$a)K7c`*EP?uK*Z{uSv!t!baU?7G_RXZzKRXHiRqSW9@z^c!y_r~d&kZ-1a95Idbd*_bG zV!{)irNVVX>&~$zqDJJE&+)*_h<&AemY?}PKg2E6-K%6}1aKzn0be|O4RkUZiN z!{xitmOlR!rA7whUG@N^n-{ehlF&HH@>?t9;^6&*<4bG#IjH(Ci*&3F;$RA;Q^;J{!OTOREe~ko}<|iB$CGb#AwQS3?%f+ODmEM7T{2==68sq`~ znWV)5y)~5hGx2t%z~AAhBYCPRX4FL-ML*+kJBrP0LdTAn>eX-lS)1ed(*C zo6d_kAH6w$Tq61*?8$ejKwXnt8R~h?KSV7-=J!9P7&o7U<9T6;J(QL2uHEy0nwHP2 zox9x;9ebdB$tRum3dm=4n_jA_WNyVimX=>y01>%d4XB0=H}}*n*Tg>V;O}HKk6n&7g+R_637)QVCD89%dInmT%&VY?NFGoql%N{qf?B6Y5sdRd-cu}rR@PbZ zZep(-^FhGEdUONH1M{f`#Hu{dJ*rhmAdPialiNN`t96#yULlS0PheY0#4#QW8E#B} z19~{N^ImU&O}?K`(*I`w<>1qsXFm5ED`ub0x30=EH&!z?qtBzi7p%zSIw~{P4te7W zR+?mO{oc`)9NK@TB41mcsC8p)G$N1{x7WJgbCoAFcxrH7f?EE%A1jAr2bl#&aR)dp zD|Llm#;b&+aV4#wT{BkSvF+o(p8JFN5=+|3fTU+@6ToQuGJMY%dGZQimJ+E+``~+5$88SdbOeHw@p;glG+y6 z*;b&(4=?0C6tdmVUpaOl2m>}M5gEqe>>oIW^hVFB?5oe$(qTMF*!x!nVe*U&53{<%C-4`YuazjYFqIZuB^i%&hI`cZDzQ>vJ=Y3ke52G9WT@NeAQ*ZSmtguILHT#nrKZ(UhKm5v!lssN>9o$-uVJ&6Pdb#>dnp=-hE;YMHon=9w z759@@$_h0_a&|!)CTb0w1;|)YyT$y}%y&gzq&tZH13)-R1hwvJ<-XRliiBWW=af&g zZ{=b30($yIv>fmu=nk~F3!$#TpNFJ_oq$f5Uh+v}==^+x%}qg1!>ze!*=(px*Gv}@ z_#(PEz(ZA{V2mN5TJZ%EEt%P<3yjPV#UUYQqc3b~ymdgZ?k60@WY9)?Z+Y&ld6r;x z&A?vAPDN*qZ{tP2(X&n37ixu7@4?Z~YX2UsnPPPZFHXUe7wr<;-SE!5 zx}P6GZ?r1$mrsUH2(kCFlF<qb`98p)0eJppr;n_38!fB9rQKj%+ndx?R=Nk(~aB zmmsg1J@Gm{Y7)vbKVqHL-fZt9CgV}EdwDNPy#k&*uxB3w_Ve}txu(85q>aKm5q=0 zB`(>*s8?fXc)w1;=7bee!M*(MNpg_%tU?%bYG!E4RbzL{)r@S~|JBbsr~BirIj`l} zgeIe=tMW=%mv~P5e3!W00ra^=*zx+L`NraH6(@%dNE^Zr`k35Yau!-myiJpi%QWng zgyonE#_e!Xi?ui91Db(hq};^ud-Inrr;LH`&)5A7u3M#PYB7O7Ku4gzwfWWke`6;a z8V!}ddpoS!LC15zc}}guFp;(6#xEyemPvp<(>EXnpVUEYp(_%fY z2{UcEP(^c1prf|fN817ueVBAzpky}L!>LPY^y9oONziQC{|wx_b9Si6l)q5+2SfJ> z3ccRJm)iYnKI3XqkW`>&CI!XLE; zSwm_EHoLAM=$;8ZLCPe`)QYYQvX6$4A%_!~Ie$p}IEuP%cX0~pi9^I=3;P`4ZJC@0C47EDUWe4|j^=BOs@uMz2qsT3~hNM=~QVQHqM8|RHm zfo9W;^A3M;s33#KiOUaY`MVT;eJjppL$hpL?-u)bFR|V2rtQ@s-hlt{hotMjX$_%* zc&5RL$>eN#d(#?TD*3abz(PjnphI>A^q?@tNs=kwT&hPIswd_*D(=%)YvX^Kc^yf9 zJy}M0ojk=YR>a-Br+s&&JhA<~1B#cV_sX%Lefk(FDtt{PxhWIEXLZd;{^O4qyfRad zjMcH9UE6um?}X9UTs&PriQ8Q%YkN1Kzo66Y72{Wn2tNMXyYG>+e5+K|lCmrI7EW zf3uTP_3&3$sPEFvg^^{;?_2l*8cML0+P)`Pa~*#8aMOvmoqH)u6A3aY6y>!4s$JqA z%wSscu+F02qd=_wBg8aCis+aJLYeZyq)<0j2Y+)b?moLt&2!_( z1E=tSch_-t+u=ckrrQY<2%4UySqM;t{qgHwb;Oy1Hw9 zvagzhK0sB{ICY4Lzoc7DxA9p1$xJqBFltFB8%He|B9{#zAKD4gD=uzTNF6CpF?ypp z-pDs<{(avH)pRxdM)G4TQf?3OPuZmpy8eTwU4>@sg2_6TLf2crm*jChbSNhBP0`V@ zIV%|HyIdD5HG`#k55SE;L|NkMX`8GPwIRgGd(Z%v5{$A3%APph5ddli5mdi! zFz%b|5TPFzl2bc0EeZb)#{Kp^H5MkWOy+~M)Mxu@j172U9}-n2yOdyJ{aIlV^gG51 zqRn6nb{)xL;gWHcb@E=)LzL#zMJ^f7vKzu5f7?Uq1S8$@gpGs>`y?J%XE_`k+9Vb% ziNnRho5BYSd~c{G+$@~fTVU^XN?rRvi(&A$<8)5A8l83woBoE*_A4d*Z-J7Ol8(`l-CWGvF$YLTwD80R72~H?UO}HB(6rW75V@Ro{v5Z|featXZ`USty z38OJtMkWW)YE~<3zbCoX=0sUoX-O>4g=~fYp>n=D^I6sQphtzisZ><=%|V{?JV2cf zz1dEFXus-H{Va_VXO%}F6x?;R76y_ zCeAFFZ(c*GxX?NMM3`8B-QNwET` zH|}VhD*)6hcezQ>c z6vj7EsNwKgF2ibSbg2mm&MK_iO{@Q)$B2CdC+)-|=D+%4;r}q>fBM2ZGE*o_W*MB6csn9ByVw?3<LU>QZ&s^E)&sftL`aI2#Bjc@)uH*1$q~z&y(N+J z3Ee(p9Ksk^xt#EdKdOC=SSNg;(Z1r3Zl|6dj{A<9j+x$be-BFLP#yUvsx$68TB@sY zGhqj9bs3x!5Tbn6K><3ey}>^78hxM=Z`^%|8^8R6uG+_^Ts}-F}USLLg4&K4UArWa8>qSEBgYJiHmL#*LKgL__=$lUDwQ*YE zz)?CPiNE730e61?>j3_BOiRyu+>a>&Tiido9RH;=i9DAaRY>7Q2xq2l0N1)`m~g|> zr~p6>VWn#^_ybq;EI=J%X7X0wDjzIVV+RjYw|!BQ5BepG(0%?I9IBG011%q@V@?qL zKAU|BSeFk|Fu!xkeZ)(){{Mz>;X`#EV$B!P{3!9I)rVQCdszQW`oJ`W%+?|wqL-ky zq^BH4C2-3)@{)b-t5{-v@`3xXm!R-jodBO7a@40|^_oeN9NnGgDl*#*ll72{8h5ALw1L`lZvtA%!pHzM@+e`gFMvhC)?%>N*F{_eM#c=g6-4N{j~ z9|=6%bpT9mR-gCk;Ycxh%%1mEW?F0(D$+7tT)ZnP=@aBsxlg=oB)F-gT=D2s`aH~( zn^^Ht7u655{87&85Jw310}!E>>X{|xY9!g%d%!SiW%WusWDsBmX>djHKX}s0f}|s0 zPYR)Xq)E^>Kq7@t0^h+^$Z<*#9h?Gqw;+xZ{~$i#3sClTv~?94;2+H5v4*I6|d&n)xD!>_qIXF^P4cclB64G{3*jbDUM@3is1Zn8?bWgv*NS^nc8^f6euOp1;(hm3Kr( zrAtu5#3g*k`w{L+IUYR6h+W|RKg9v;mB0)9qVm_1M=XR%G$>j_MTBtQg!VNi2m6vD zyFE)=W98xu>iHUh*QNUVXhTC>qv6D_@-2R}B#*@_wY{d7hARI}HM z{s+Fsicj6P#6GC-KjE@A+KH_y1fl&4xA$K5u6ON5;JNLajrulUh|XUC5s>&t@Sxty zQ7k(1);mt{6#@gkQHi#Yy}W5V(C7DHYk5YyvuN+~pD1UZ^;Pc=)ca z99UW4aVcC}o}r5g{`y7cMm!o2373v^+^80%J4m%2=V7i|$5~hOCSv+b_`ugB`5l@r zt@-qPLA0%^3@`~nkV)h&yRqGN?wOXtL5Wziex@QyFxp^g31i1eO4asQ+g!o9-yxV87`t ze96mk)5tdK_1OOlg_ih(p|>b&q}^1WNkKVZ^0^6}h=&mNQ(v~c3rEhNbUhkb zO5kl30or)SXCg0U$&(}}P4)Q{r6?(13@Kz^O1{=)I7uH7<&77O1`m|xiauY#x_oa= zU?t!0VMFOPTkk9QZXnK2laUC(5V+FwK$8)5_Q09qwu zoVT}hWoO!PMP!7;dj_X1E^fch_*@P}K{784+3`i)t0IXg9Nm4vbc}0{31AOYU-u~% z>((owWdSSn4CfBWMP@w`_I>IF^-KR96cy(9QVn#jK1^-h667`?vwN{MSoU!{=RCnj z#jekOVe@q@uZF}3q@#HFidq5GR&)>CvVrI+Gqzbh(_YBi(f7lsC0B0xxd!UucWdop zS;T7j6`)pCD>OxyM#$-2dx%SiU%#&qxtenY=w21xM{U^~d^rc%2b2)9Woe25a$FVL zrU2W?7l4vjYFLUkphJKOCFAW?s^c{b+FoZk(|$hw?CVOGYp8B~XBpt{%p*Km^{d+R zt_`fJS3T`D%6pZ%lfECZG>dX%(+Kfsv2Wh->1|tb*S`>5H*|=pzRPwBSc%w8xCu?& zn%-~o723ExxMj?Fh9M>FtW0 zh|$BZm0lyXAprH+XOHR|Qk&#oO&^kID-v%-ur~H|v@Hx`>fa4#v(bG)bIZfAh$TY> zx2H=DT~d75CqJPZ8%X7>o6UM^YPs6O1E$8x&utGV-fZbKE`|z>>tuPQ|1iO(bv7{v zL5cjTuci2N-{%}s#}zZ&973qxd!v#6>>(KD3JRXMQU$j zF49CtIk29ya>3ijkdp=xMgzmX@gMfp2x2l}OD_M4^-YWSb+cwx?_?@o>`I zGx-!$&*HJk;pA!q z5iNj`8P+4&u@znPl_8vhZ8b4uXjMQ8z~TGW_P&uTzE4WRdWUPX6hm6M+!kXOlxiB% zc~kmT-sI5q!f8cydD2wN6TML(qOCmHk=r0YMIkKMijaO;`KqB~!FCQLFH}gLP~0}% zfX+du<6@pE?ZKBarIel~|3=~$&RzFzEqaKYCMvpxZ1$Mej|2L6*;0HI?p+i*m$k`b z?jNB@7kYi7pA0SK2a&A$y-JDczPKFb)me+Lj|w;cB_Uqh?qiM&e>c_Mfg|0@pwi&< z@l{!(RIpNZu509JYH)^S;GCe4Qrz>d3|s^}U4(&$PrheN`px&3 zgF1vxFbn!EiF{ik8ehx`OE3J_pV%mU(9kja0lrbZzt%G;u=%`nSL- zFW9;7^iAsB5v#1Tmy@B`dQi&{R=qZlS;(0dy+rA5Qg3Mi7SMG!=s|3BY} zEa;2oVnPPvRh@@*@iU}nYlI|wh)p9q6PoTVHMDWL{c;d=>0?yjqQHRWeHNyrn!QYpT-V0|;O``j}&nWe*?#NuWEcp@!ki zclsQqX^!ql6U#D;q7G9_cZ+M9c|fJmu27Whu;Wqf%unQ_RhEY#=&Wyd@EZHN44Cxj zak;5gOIwFj1b}fK4YCBq2SL$fUbSGL246*}QDj7aGsvdYq78mrWJ- zp@pU7RKj|!WVk2ayi0)Wvq{wn%8-!Xkw7A0g>)NFF(GB<#(Rr9M@d;DZ?klU!1?GX zucG8e$iQeUn!|+%Xacs58=Ck{&3aJM)Wd~VuVuD$TZRG3LY@>mlM40N#i_IFSB5j$ zysPPrMk>EwKput1@=68qH6Ww_r^9KPvNBngi|1+^+fVv81Bl|Ph{(TNE6>q^AjBHC zI#MciNRIlWx%50cKRCu6$6jB2gg1pUVXjJC$vlq99H&qmYLtl*Ey$I`q+xdaHic_A`yP7vJ|{cL+?lLwHk69HGKo*_*!9WUfUmSE zrP9o|wx~H~?Apf4iA5>HiL>P>5fPJtHe<-u!k~?AbtUSvsv&$5oZ~vguQ5}f$~t&U z{#5|?oFH=>{XhzT{mcLSEZl)jZh3V>*V_F~SF8dtHPIS2?%H1xL zvwUyhE1npi^zZpnxU%=N~`I<=^X>^bqK60ZHMVjG#1i@^In~8izBd4q)QnZE43~05L z4KJu?3oJ?6V<3pRkq?o{KV_O*f15X|&KgubFDP3I7`=!oY44|`CU#egpA5s*$1_7K zv0sBkY~P!kA$)4ADUFeVk#Dy)&xutYpq^HFqYr_N9!aJoH&XqHLj2SnmZh=ueKm(SZjUC=j;I4 z3z^YIG?z%tQM|^7y4TkmIC0M zzd%r+29!)X<0FqPQGrienB3|42M59=>>{`f>Wn+@2(-`U;tQk@f<`P-&B@7Zfc#G4 zS5HZi@Q`i$Hpg3ITn^Me(@#>Ofz+kY^YfPV0~!uBp9irN_Y=yILL26!Y`K^Dd!scP zWbriux{(}o@q~^b=9ek*s+6d6I@px$5|3k)3WsF#esrZ1X#|BcJrMe#ks<6|<*a>6 z@dvWScSpmA{PKC8910}_Fu^;YjCi0g`&iWUog92yfg~D8UD--KhF)6`i+F5I<>zxa z3qZo920L;Ol;E!$J(g>2@39*Un*KBXKfbd=#_56U8 zVXHtxDqT1NrB=nPpF!R#J|1tVs0ZQ0yY(_~asb#`>+wuZt9vZ3hv}J0$dKC)r9iv9 zj*UbZwe$G(_WcTAY98mJi}T7OHG0$>koJF_oGJ|qsmzaKJ6!`b2WyNu{SZYo(snrV z)B2qU7}=vS?bU+<*|r`a|NUf~mQa$WZTBVxD+aeRJW}kL7N1n*==U(k9D$K(IYVU= z!6H_fWDn%Gw?Fn#?N&>OU_*nZYurp?2Dw8YuyUA&k|Xn;$OKf{@MaV6X%+5jYSj$ z5B)_4l7Vz`2Ar(8=y`s@)UV+^f~oQ(C8wkJ*Ss$T()}1uZ=fD7#+9vX&gyHX(|eWC zQ_D?#QBOxeE`Fk=frQp8%6;#3T^^g4P{X$U!S#<%E zdi9|O#;QI4fI*SXOMvjshb;{6cpNs?M!^xvN9VhLsCDx|Yg2C=**5i+#RI{uvM6td zWK{B<>Z z1Y`8_DZhMy{U`=&b{(E)0YN5|a>^yoHPC>c?~?Mu`+#c6x{f3TDm1LD8(^UJ1$r!h zt|7IMJq0ft6x_o7zg!aj6E6A7KXA!k{(rbcl{&vultuhb-Y58#Vp((+?=;)W`iuJG z5~KR+-Dd+O3w6FEO!qna?ish_T4sqJz<`SHfvGC z*8Qkzd0G^lyiN|zOhhjQTa37ViSj4X$C-x<96??b{LBLWj%ho5HfYt-r^F(QMuqYI z$wozOtEo+6twy9oIP(ONeK4@TAxTK8RGFEFG4TkFXMIP@@12yv#Jh81{ebAd?@#VV`zY~M@^(Y{WVkqNA`(b zj~ODY0(Rnf-SYNGtFNk#WAUqY02#N$Ks$vXLq73ngTK!qyfAE|pDVnLVi^5F*n9q# zfTfUEu~oyq&u^v&d?2G+yGQP0M-j&oZJaDm1@+bJQ+)W>I~U-o5%HC=+18S4Jbv5I z@MYE&EK(aDWDR5Om;5h7CrE)joMgwD0X)^?6uP%Ga^W*}*{T3OPSG91W3}GCYmuI> zazs9kI9Mn3?Zs&<-Rc>!W?c*C?1D;7%Y~v$TmQ4s4-P}{WAXg=VSNF;P$r{tnye7^ zB+XPWcbQT0sYhR&`ULrR)EWU!SD3m{!orsEfPteVM*yObDZO{~j-2DpH$5Mduy^LJ z5KzkB78i7v*zCm<6bqUBmdnH2c;B3f&Ibd8Y9G*}1N}KmOF3}X*Dg3vU78@B{z2Ct zlAw2se3`Q;cMgQa{R%PWwK{MvDU)u(szNNaY!{qSa4Ok_G=@~sa# z)ZfKH02nRq!EddQZ+I=;l!KCmVHyTDMXLP9 zs|9)A3dOA4O4jAjUFUHjDkWJaA3dpp8q!ZPj{tsYBnbLjIBQ;2eyLM@lPY|Tw;Bi= zHmGRleQYcR9POD69P`^;9vywHzfHc>ByM6S=a;%eD-A2q~w?Kh(;lK z1=+GUUKM@Zj=YT!;zJ^SJfcCaq_+)7E(lAa4a!RbEy7O;jh_Q%>9P-}0J*gHWAX{8 zAUEim_fJBgiU~E4hbOWN{gnDEq38g;RO!8~qYFKm51%Ca(&6NqDQiXu&{j9FYx+%- zE-8#dL7G`Lkh31Zslxj+jE0$#=5{6~CLAOo`&*O)Jj(WB?W)9ySUsee8^rS67Y+ey zgHEqTr=%d358RWfBo^PZ#d{QD=SGHD{;XQguiHFJO0xmplVo6h>5!C^rhI!gvN);x z)+GjCBuUIUMTC(I&3%Vj%z@+z6UAH0faU^|6Le1xbW1=_qw*(ez(VsfOd>(WnXQdcGXjk`WG1bj|02Bp4o}gZ)rWn9;ijg%(^KO`iw1x8`P&1; zCV;O#jQ!Z?^c9-^iw^c&+ofliJW(2Qy1+dSfxc*-qT6_9Hfy+LlCKiVb$x+YVnhIS z?8-nCLygH+6#(w!EjuY_Qdiy5F&Ac7D6N5! zz);B!xL1Ir>w(;J$1+Io3(AC)u~CQ`ho021eW_)=&O_#=@W7Q+jxBtPP$KRYQEpFr zb%O%dr#PdQB!EiW*nuaM@4$fhZ4)U%MyW3neGUg6|DSoX@j$VmweK0rkuL! zD+7w~IXUAj<#zxjD5-tNs{LN2`QBE zy#)#Nmj_Pi%N+;blKj5wyDR5P={>JU0FDu4C7jAQS`;!-E7<8;2rMVttG!-%r;ALd z5BcNBXIPaHU%r$W$-D5l;;9-vY@@D!Vvr0TW_|#?=PaE&T1dANIKjv=EY5l%nwzZ? z>98E}!n6Peu$z0h`T2j~vE2TQ&ou9gfr@}c7Z`IXyavyFjATHwCA4P_WiKE*v< z!?(rj;DJQ4Df#VN4%ds*gK?TJkpwjh-%kPYSf_ZWf@ydl5~8RR65vt}5V~qYeiAvt zz#*pqHDUDoh9;R#HgV157&XoILnI?p-!95>(uB2u#xeI=VT+}i6ge1a5_OrYSQ3CbRcfaZYkW)Y7OaaT7YDh|H{EDN`Z?QF$+0GT;ep`tKx9)% zAN!qbC^p4y?IIqYbfa(Ej7Lj22UN;`JzRe}V6bs_Ii8{#j|W^r{Kzkx+IZ+fXeoD( zP(kC|s$2CuIEweU7lGb_P~_PV^nDPd!r?9X6Te9T0r4@1Xa2LsJQrpC1OA``3kmQk zKwszQjxKb^ot6qW)AJC-Po7Hq5C#S04r@^rTzQ)r>0MPJfQ(LKhfjPHRB`IE+iM1@ zpZN33gwKU81##-lbc7glc`EsfAnB*0S`+bAo|K9#eC{YbVJpXfLYv3zBOre^l01Gj zXvO8a8-O9czhC>kaNVTFpOBn03q`4?oNKN?&|>d6g4zI()7b33V}ystCeaPL7Czdy z)CxC5Sjs<6(vxNOIT%|YC^_nmz(VRfpkFhNlUgJPYAEi~LvwbamD9F_bHMBUOYKHd z+9|EvfNq(Bp{&4dFhFj4p~vMZD^CmctzE$M%8MpvOn501cmvlr&w#*tjc3I35r-1pWoBWWCF5bY3kzkz_945cZUdCzo48=_NBFXeA2c*OY$Xn~&Yq^&L z!PtzRbM^Z{iE>6!S$<1>xSA$3pa&#a38 zS_g$6nIH1QtN}TsgScVaFIqRjg`(cAF>0Lvlw$O`&X>utABZ1ez%k$9G{J7-7PwUg5)oJ8T#O|VcD8=?}7yG(R} z&L@lBNW)2#bw-;4{dDkhZdmt+02cWQhllL#hlHr(+}x?9nM*Vk=ccW&Fi=b0qYvPR z*k~oC_We1_$e~&chAE#3D4bpPH-O>Kk;s`;&l1(m8pQxm=RDWm0F7)Nh?-b)6;R=E z_ha}4!N!H@Q}go3rqStp`9L=VN78TvMmAZkXVfrFfsR0>?g1ZTZ{9B&@Yjf>CO=|k zzi)XHyoYku#jqkW9PTa1Qw^XOA7Co4^=bh(V)SdLYQPXB!k5^V2wm=%Gts;6Xc>}< zoYp6PQ$Q@NQgG`^yxSmpDSZ}O&fu5Zc0uo#P|HV&{;7mJf0JYvSzYKYHB|P zu4@%_^_vY7eW|AYfpQoM>K5}VG@XT>-xe>!qqmmcs5x8S*ek$LfDem>ICy~#$!N5# zyPM|(_t-FnYpS*NeLn^@-Qxy~xO89%Cex50gV?JkG?mJSRLvp|s83oSWzE}|P8GMk z6&ZUtUPw+=dYuFp4Z@W zSDw%3DcjCrKbW`^w~3Rg>{Msh;jBG?3Nw{t(=i5zOL={jhbIl~^R=2b5muWm;#}I| zt9jv81U3r`J+(b2J(Sv~GENef9k@is{Y0UqKf-&z9DvSuWZtw-qa;ueCXjAf&Q^$l z)o~;p9Q%e@5yzo|8QFDihIh>hOkP$mNmFFLV^C`eZlzbO}V=ai|)S2v33=M zknH99p?Dlo&3bN`UU;)`$G5-9&TKE8W5q8O!}&gIM=iTmkK)I%?;o(^Utwf1K6Bmm z{gKAkK^JYD{Z1}Zg0lpQ`pA{%OuNR*G>al%Fvk4kpTiX#CJi8EzIc2%s}F^4;FuqX z_Gmj)I-fI-jvjp=9eQ>(-M#fT)uxR{I~e_o2J%EqY;MZm-y&^MAJ>Pg;8fldo|~%VV*vGCEo^Hf^9tqY`55}gr_b^-S0qky?BxD zdvliA-ljA$-V9@J^x#G}Pi_vuoMoD8_2p0HxveJnXG&2XwCWAnj~h?C@^P59penaV zHJ7A}`>zFs&wK<~R1rFI*6(e40tU2&b9QTb>2!Kj`BzmPy#%jN__zT&C58F$1MBTr zP7-=ETe-LH#sh0UZi|5YrG3MO=zBd47xMv3M9n z6A%^d8VY=IWUWhAWbD{xZ{d*_u5h2WZTfxpVJu?b@j{tFSy!gl<7`4I8;?^{3C(bl zFXqV<xA-H91*Hp7cELi6}4bS8S5v{#}^0nBT&M zxqF$=7Wk&2S$sZ zdfw|L(`G*M4DM8}%IX?iqF~0q3C+xLNv%h*t|DJ?Z`!jjNiy0Pn6rHpytBBt6kn($m5}f&&VwYRu|6f% zaP7I#J!HhW+L_j8TDgSNkhnq{0Fw^Q;o;6mvUAO5`)d^Y7bn>0XwCNUi{>M`WkYPurpx&F9J3p4lzS9eoh+u;}H#K8A4sA?Yvm11$j zDago0cH|SUeS$NP`$SPw8L!g?S7|h|pae&%j;5tHFfN|Dod-f1eh+qd;#|y{XKxI% zCgI`zSBIgxwdl~BvBTyutxrdqqZcj8JqR<1d_GQn8&w$o3azmNZ33#IFieqP?BnQQ z-L~c$9E!7R7g)p6DtQlhv)Q+8S#t69V(Bca=>;F3C;&ghOgw zL$w}4+0LzPQ6`;tux5R|p`bYXq*O6jeGqlfSY3KQrHIu0m&vFke@184J^E|2*InbA zmwVV=ufT?@rRtN(swm)@Qs2me!=rMGx@{$g?5i2hUR0HA9BA?0V>;2?+ zR`%c69$vAGI)JH1f)VVHby)>c6qe{>+)xAltOLR;m z{&jLFwz^+hyNiC8NZQH$fDJI>5A-jf9LG7RcHsbHx`I zTDh88LFT$G+V4tQOTiw~XBBcEnwXfPx0s|jvqikTn=s%T@c5YP>OD04aMxUftZCE^ zNknHETlffDgv&a7@K8o~^nHMa%VZSn_}BxXFGkE~ zd>O9;mn+$639kHTYQ>3rLC@sA%xNGcV0ZgxcYN}*a%xZ~DJT%QWFmb=VLKj$wXDxK zvhf|4HC~pfPy=!P$bO_F3b(ihG zxAt*7Hy<`1#^JyV@N&ngm7ns7sLAUEo9UA3sy^4wL#P>~Ov%lwpvOqUHs;jVsV%*> zWeC3yfxsigmte8}@4x-WUw{3dzyA8`U!Q;d^}qJ#|K9Ka`PVZsM8EEcCe?mDS>M|;+OPiI?=GBSx> zSBMExjO%53ye@~AveeI}KG&}}jYXrmNBQGWzM_vYM4z&LS(!g({5uMl!!z?0Zz4u3 zcjnoy`_fz)>*AAIM71=GNJ2d!1>87v=F_H*3c&|BN0h<_(jo)AAmFI``W@@{jjW|E z4B03R6iK4<-VPcUvOx;TRLO`dNasC7f?_f?bdyHb(|~k=ebel?_MhKT12S383dl)u zQ4Gy^Ou4EaZxfp4o`nw(G^T$h)td4hXtf;>w?a_HST(Haf^a z|6SLySs`(0ft##{Ps>P;QY(AAosl(8{6yN4<L6nK-83QkZ zwQgLuHn?K<@~^fJz0?3b7ATNki(pZmHPsfe8^5mUgQv3Aqb(Z7B_JO|C4R1`vLxjX zP4d4m)YtXPnfaEAt--A^dIW?bCzUP6Tpn8v)X(Gyp~ zT;>)jhjI?qw0xQZQ02GfT8hAGiT90}#g*a;D$|4LS+b!NN#dLHHbKg{NsOVx_!wR& zT-Y_%xt?RPPOoFRKC)?Bm~qC51#OOKNi(+@cZbTRkzQw9V5x(y+(VK{f_Rmu>4;^B z*c!W%^CPPe+E?eOh}C_Yx0BnL5kw^9rpEQxmUo$2BDWO$jC*(ux?A(z6Zo=_kJON7 z%1lpgFT@j9md>iMO7URRY=z9`xXEGOnpETRCHx}Xe~b?=mqk&d?Xw2`S&j9^?J^bQ zU3?KUY0D z8`0^wW&`n>k;l*bJ>3$gAt3YR^u>qd_u$gK{5sU9vD1u?^;u3PZN`o1KTAhk#|D}? zVaKH*vj}jk+Pp7Pp2RmsoJ*^(RwU$gNS3KF+;D30t*S&Er{hx@K*7)h$O96=2P|G1 zBTQ(=@co#Z5)$n#0wS_|v23rvim)YN!2g&tBaFCsL90KwCF)ZyqFirmi)7U;%q_`o zTD@?d{Mg3NrfBgZFQOQ1?X-%Co}@dzFm-)pTEHQVE=7Kk3`qiX3kB&6de?*}OW4~> zD%+kLSmFjGidt9LKznpLGY33v?NUgE=JqH?#U| z6IkTwq!+IFajyXQyx1b?{5->_scKag_9iTRiBwF3kW}A$YYvHj~|U29*@y;Bt`CAmb1)m77Od* zm$Jbv9QM$@p9DqVueeU|ihgXB4r{$fXv8mAc{jqP?i`2@MBTwF`yyd~O3hl~O zRJgp|E!yVAl@n`U*WA}#mOnPht2_MNCTdlZ{>SDN% ziHk?0iOASmsj`cGLhQGjdctH#ySVIPJ8FRYEQ8B2_1MasibuERn_Wb^XxE?p2Q?Gj z>+T-REcp41V88HTqkbtW?9mqPUeo0BHk546RT#h7HNU0B^|xT7k%sMEOE!(~GOo+^-xG`l`f4=d#?{C7~Ofc3USN!hzugX{9R5N4Y0Hr z0;!j)2NI@Vv8)&imChRM##teeoCwSYD{)Si?^Ai&heN?jeMpxupb@(vj*@a3v!!q7 zSRg$Ych!_6cya``a>fF%LWZ~goF{TVI(+_AP6ae=S{6p%p_AQTO_1J0UOb5eA}}en z^#e2$&STz?M0cU?q6+nNcT5#HJF`b6*^&bwe81vCm-Y1Zq4v%pQ8}+tAuYK*ZGZlI zB>)~zIU$Vv6zZZ{FF8OUDT)6C-Wj;x4xS{Wu%B}kUjvEC=lkmC8>s8b(WE^5mQz5~ zqm{dU^zx_6En$iTC|@V2`uUbl+pWp~$bWyD>~G$(E64A6w%8xA2^&p1QNo>f0DJSz zsfnjs0c$)&SfUel3E-d7&$7{JoXiEGa-3X&6_#S|k$TLgtN`WP-b*!3Rhljn58UF- z2f_wx4`aJB9DW=XlI#uH#7mllxIiR&N|Wc9bYfa$j}340n~F>--fH2CbDQLQMN~Fa z();ZMcXJtfp_$1k`P`=}e4~a}uyE3u?1qK&XUQ^*@)l9dx(hl@>xC`(Cw>>ViGPkY ze1-L&Jr;j_QdB=Lc^EFb_YSC`z3g6<1H+a9i)9P4@mNDJV>0J%d@xcAUlQO^YCNZVwGO;`Z7B_->{yOP`U$88?5G}NTNNzr0zSv(6zq!DQo&8x++t@+ainF zKK?w?6~9Is9jeDiu~(kU4mNtVC4YOOXrI?Duip+8p7Sgc34R|@4m$9jN4ATcN%c;Z z)QlIX%#zc;OTa4faf$6^;W8+}gD*b`f2K>e(v~W6XkA@rPXlM_$jJentc}7QOGzdn zeCgC7$4qjx@qKZ*{Osc)BV* z?fJXVW@4Y69cA~cUp!FubA-{k<8V^d{0Y=E#&VFpUgF*cXR!VLTiv8%|5NvS*L_l2 zIzA*zTqDJn-}t@jmLFTjD@(ey*)#nr`ZKMLSju;w9)*qz1PL+!MfYooi^F**``UTm zqZSB*+E;HT{A|R#Qf2!rB3II{koI(Gt1+jcADnQlpgy8f3NMubX!39 zG=gbWuoLn-BmD+Smw-KQ-ZMQHpTJ%>lg;Ragc825_Z5Q$&TaQ-grbB;DmWn*SuXTb z!N(>IQ#8L>o$XgrNmeK>tbS zygSmm5d-HL#(ETMfSGVAWRB^KdxlQyI}^U20H1ZeY+pB>z09$+r*a?h(n`m#binAM z>;dyN_k9%mKH~W%Qg+P15ou|0$MILIGWpBgm>ji1& zaT%@p#4(W)7q=jKXTJ|V9t~pzH`T_WVckO}D(bgh*KX&%3Q;{Gez1Wlsjm}eueS-X zbHxMtcz-G@xi9hqA4qqTf3mZQZrKU4p^HQt?-=ISh^L&)#M3L>+mJ4wMv(PpmyoRf^Zkg>Jm;6MOfQhBa4eZ?!|l{mdF=kKxoh zh2X2+DQ%i?4H)={jsu1Zub+JDD9iPtJ3B6bCr#g`~tqGE@|K$M>U_b>^S}Bay$HIE(jMHXwggMPu<5JRcGJh zJSHa1-MWs}_xM_2dehfRsy;Q(k?nibV09wIe&#&(d`0beQl~?;jy-!O886zS&GQ)} zb&7A3r{G)rd%Y$kwk0GE~H66(*rV0@1QT)F*iYL^EeY`ud@2> z(W}^-HhT*TgvsW96T1rZv$ZC6RwifdeEsNIZ1&VL*%g*fDofx!5r$lQxo&C-tyBel z+|o22^y4dju2!+tc9>aZGZsd(-n*WEsz z+vBhoCjCFf{$Ugbt$I~FUd+{vZ-oP|jF}>?qF=HlQ zB7w%v+po3e-yBc(bJ&k8rcu-CHFVn56PviMp4zxO?t8-xukTrksXp&y^N=sCb-YZO z)q8F1Lu-~9V=>S4;x=Ad=ksE*)WoU0Vwzn@X2xo)4&2Y6*lXD83H`aB@s{zdoB<(e zd7DB7a34!YT+{X%wH$qNc>JDj%(f;lX>%9?(h^pDzJMDWO)xq#u6C^YlHY32Q3%6U|X?1ah| zJSokT8Hl*i=l;+Dp9l%bcZYmgZdnQXMr>#Jb<5f@wxhIBFxAA?rO0V=5vkw)qUg0t zWo$MtP}b7oJeiKF)a}U)5Gj6!ug06d1+x4y_Y_L^qGI#D7m*(zxOA?|%#pA852s`{dSqbj-AW#Wd=16SRgF$B@ z_jf#V@{NtkX$YqV9+{AT$zVs1;^I)?$lF`6id}g#m4o&TF5!BDTEyFE3%aFFtRy9( zomvt5P<~D+rg^0(+BOG68D9$G*Y85i7b4+iw&JByEH0vqO5sFN*kf)G;m7G zcuJt0r~8-*ARza;`$CSMwx`qOx=)B7;%l9$xB)5R@6Qn&BTW; zI&x#GQ24l^Nmu8mCtO$~5mWE>8FBNqTCyPbtSgy-JPfTquGAsCy(aCt@kW`&cH?@# zhCR(A*rnRz;Qb$PGb-0|x`HkdUaAY1qxV!KVjwoN;pKk#p)K~0h#jSnuNR%j<{JM&%Dj{ji|JsDFu}#)nqa8mX%7oO)TVY zEv#p&mmgcuUumXEY=%Vvf=hQ>njyyKSd^^Kj>thIW15ls?{);(celuHzo z%!5dO-2ca7F}$aw!@*zD-fkuN;b!`NhlD;WsRyMd?)f7mySNs%6;t@gAFw)>0*g|}C?2in)Nz!Slbc86*Jo3%<2=~xM?t5_cQUtbO-8n}M$nkA zi7{sdgPC_pP@f>FfM^Q!!srdJTq^&G)f##3+Cvsh8jJb%6XEI}m;_bHVkjKErbakn zJnN7Oivj3cGZ>=|9(0iZK0idoezSr4M9BC_N~lK;RE1Mk?9`Osj1uh~AfeA$??MGF z6m@k!q}dPEEk~}j=}kc0xsx$2*%2;)+b^Qn8470JR?UG_q%yV7os@ocgd3l&kO{j! zxe5L>6{D|=eSwD*5l-hO2*QyaC*h$SWe1tN(gaiCQ(&^!p0aD*e7W+W(VG8rJfGVdtR1sjo(heEwqdypv<90M_5Md83Opv&t^mstn`$G}OyqsI(j zbqY|e+HL?$o&_Z3m7(vG{}}|u_dZf$+iT^4*D3AG<#LQVO}09}X$|a{(&J1+=mkpfTSIosbGa{{wb(I#n>1Oyy7u9uscd2f{m!T*Yg?_+<&|%9ukIl? zWLt|VtW!>PdLIj>NC2CbDrvn><3*t#2z?8OhvTGnedFJY8aJvR z1nY1r&r}4aVm)(c;fFJk@$4_wi$^wBFjbm~o2NLm+0_H=?6-fOshEl=f2l-(e`#>s z&o0SsVKefI!!aB6J z0!LL3&iuUN=^ZvzP0j@Iv0xk)-+Wj*7I6@HycdUdYcP1IY=XpWaC4l3t48AgFs_{%eBg28p(Hl#l!naJMf_f@s9mz8mkKbV>9p89q1fp27LUz zFTCEB_4yNFc=Pn)5p9y)Je!Zvj%;onv^>P`Sm4=(=3jwV)dcR3Wp8!_o@k9%A)E_q zo6H>|f$SGWnLp+;r|aIoj~m%%8XfV4+2D{phm$^9w%qh0r4fm(f@Kqp0cBv1$s|P{ z&YXF%dbL}|U&_)2C=TNMy{_&G?$l^Ur(Kbs#@2gtT}5o7_~{VgQUY$`s$Ckg zi1Qsz%399PzL~dUbYj|1vUVduImR84fL~%bd)siC!1-`syZSSNY>nM13)+{#lphp{ zezj_rDT&Fz(Cu9(rO`!jE|umEp9D&F#-pZ8b3qm7Y7F*~oh;$lf-qBhg_g zy=*x|RxfXM0g@Dn-px?l8bqUW=$+1RAn@h3x(^0RDw0CS*~in?2WD>;WW};+d+%0P zi+DZBHtHidFsfV+JAaHXnzh3=G4}uaFUK)WeOmg|FDGfta@%rBKl&}rg;6PT-!Dk= zBW>|9POts=qIG-k2+Bu#X|#fQw^BdF7*!`ydZGHReCf%=51D&A{gt1&Pwk^Bm5emO z@ruib=8>;LQS@@aiSQVJ>pZ2EemGCGBkPP5v9M5*qa(Df%D}aIagS&@@K+HzVfc}^ zyL(DEV{=b(YF=hqvCh1-QI-crD{uCon|2t$StpY$ws~W2j??B9$P1smc-w*+9Up?- z*0gy!Dtn>_Cy1}0Xj3aEg8XoFmrNysYx zkRtRI%iCRwDB!zK|LVZA%9cxFE5mv>kZt9HQKqUkQkLhDa?S;E0jQ zebH1A^a5D^Y)v9Y7)uI)=#-i2BPS;z-i+ZXEXJZWFbboCI0!`^^%#9+Bg&Ho~Uys zZ;XC|+}4N;Ik*kFCHfbrM)XK43{v<+?9Ye%(1RJ#R70QT-KqoHK1#wx7@qThsux6a zUyQizF1&7#aUaMTA=J$p3^hhto^fvoBDm2<d0>$pVn-{b z_U_g-5QqxBCT$}sve82a;36V_2J*wePxQb$A<%{Eg@ z(z^RT_g2_cp8aVN`Tqe9<{_MIE zi|v6k0B5Zwjf8NkVy)7Qv0~-6IJPo*RYN9(q-UeOT zEdGypuE&lS{Z)=P<;EI~JK3|%DXWGuo?_Mt=5pH+s=j~Q*nD?^GQQ3pkEo(=j4Rx`2N54x4mKnXI_r(j)&-YteO;YU(B2LmTW6Fz$khB$^fG+?`&`>6Gl*8O>Yuqx@k8tl3ePbV)f*;QwY4CV?U)NY zee~}c9q(t8mUrn}29Fe=h+DiFw-cfyP^z z$rK>Y3YpZq@MfY=X(fW?Tet-gEi$YlOoRO9&K7Q(jP^=bHGf~7vgyb?C|jOOSAn5wXqdbw-4pZCY|oNFSy1OvPa_A1|QhXo*D8U z+=+?y~aPO&yeE<-)G%$hePr-wdBR0qD|WzH1vJ=qlh5Z_sM7KM1j2lzhZ zv~C;SUd;%75p-#bxXpo!RxP;Eemd|-jt+$VXrXi$_$q27OcvZIzEb1UWCN-9Fi_Smx!oA+vdkR&H?om6r#BnXvdZ5!#Tg0js*w- zPA7OJ6OlVlF!b+Vy_Na9BeAo98|iKM4^7F}1LRSbqType9wbF{35I;`?yqMDZ;x3yq0~)?IQ_&& z1SV{-!7d9nqjQ#3u#j|;jBTtDhkOtTMxZAy*dQtxVyhw8=JFZRtD6P1l44u+rUwrr zj_3OemD?6Rp4-JprC#t5sQ~HCwxLB^VFDc8N{eAWlgrHCnPT49FIc(_|KLpMWhYEW zy8MZm%1AL$sP~HODTZVnqbsR+p2OqI-2EedBb@g{aYc)Y?Cq>v;%D~3Y^y3-U6S3tJD;-ObP*~595>(+0_PE>NW@Ki;Hk) z{sP6=zCeJl-3Gz2?cWI3s+C#qmZh6O$yv;z90f!r-c;!vQ<5n}mlG`T@>?~yqmles+=@p;uyV52*p zZQnBcF4TmuEoT`zJmZ-xPTo+dD(5-~m|Qi8xwVo#B>j zKM&Z}zLwu*@`&yo!#8=PwPkp@H*RKk*)<|w$>&q$qWfOE_ve5@^@6K>@1MaUyoHD6nAiAQ z{k|y22C-Ot&z4d~(RfOw2*&fmrS@h#+}bjwgAwMNBXeknKq?ONHdZyHY!a?leF&?q z8JH;0zNyQLTZr3rS$%CxnR~YMk>)AUAh^JOku}PnK;LGuApGO=Osi2XuXFiltDY^9 zJ;6$t8B@h-$($+AJl>~y?$JNnm@l(~I8?^#;Qj>*=a0aV(+LR5<`>WQr6XHSRSY#t zWG1K`-YNYm;E*|{kMb4PU%ggN@zT z-lgo4++2>^mIdr8vDj=WHpj&Ks1#!Hu3blwg@(16M<)zI@xa+?MJ=7IgbfK)VmDSw zV&Q(Z{C&BG%T&2-LiozRdo)GJh=H#}+T`#ByYouG)7K{>47B8{!uIHf%Un~jl}zWD zpRp6lA>Y1`2K(po1wa`%OC^Eb|LFI(Z)$~9Brp5G9P zp>QXR;H8!O67jKiV9&NuUY%>Wp9I|!KQ1VXhKj1S^;z`VvF${vOQ^7CKqLY=tLRa~ zVQ_{{RVPSvugngZ!2PY8>=^0~m{AagQ2+44>XEtPW^F5Cc2Ta{9w_)ydp+Y;%7BOY9aE`c8>7ytRHEL#GNa5`oALDcm{)V%6gNos{ z^I0oLWl)9_Kn7W=cZD-skE@U~`U_WOD$l}XuXBuU0_B)D4(eI-wy0oJkL458i;0cb zU!mQ6j~85s`U{CQ7CXE2KJ}L&2f}(maWH-rDrZz(k!V2p-uJPfd^mK*Ql9!y@>28i zk(W0Q!Y|ts8&7oCM+UfgJ9(!oMv@T4W9clPUKDN^kxZ5FO&caxib^ud4I>eB+wE=@ z9`#LJZW<=Mv+1=)*{k|Q$cNdDzdNV5=?g-eWc`9DSRb4=$~Gv0%Fjj?7djv~M9;w&uj>6~k>xziI@*bkD&3cJDxwtR{FniQU*j)=%>Fs< z+BrD>assK0o_kk_Pz5g|w^E2GrMy6R*_fkBprii-00960tarz@gi3Ja2eE+0v&4Jb z_+8_D(|Gv$sr&TiXhu5PX+=S~Br_u-le#a;drQ^qScMoHioMa{8zPcrkfYcf^lsGm zz)dMH{d9H_eA0Yu&L`B-sCc@3hV|#ZhTeiDhICZQ;vaqORz!sa`j?77^V!%P=CKiO zCf5F}6J^D2`I;C=AUwRFe}(pjhQ6lX`CJWiatHf;R%!bq66E&1lHAR;DXJMB`sb*o zBpmWzr3$-ex4zSDFJ0^Isv5!*@7D8^?~>chjy}D^ctnkCX3n|5C7Wm==_^%)`+I!Q;ZDAp|43yvN z1oZOwz1n%Vr0x_yp}pFu^C=9pWUl3Dx?VVjh#roi;e9G^Q&Dra+t}YCF5PK9&EL|0 zf2F6$G=5?3Pw>0wegHN+gxiH!)hI6P+Rl7g$>(F1gDwbRhr3bMbGEP$gh#B0$;BK3 z32h!Jov^2fFW*q^`O5{%;nch8`J zGfaatQO8x^UvCm$VJ%WdPDDua_=>*&!`a%iUXKn*B0{Z)qAT|9Fd`CuGf)XXqyfWi|;~Cx{e!_k0j#v5I*f?wc=DtWRt7<#c-*e zbEmEmwWG4gv@Q)jdbXK|Ier!m*?=*b6=%IDFTTx_2!)$V5oP~i3vrTLk+wDbMDs+y znX{f`NLukTZV0e%{Xn9aKy>JLT;=kb-I?H=PC5V1DM{vU3`;$JGPv;Pk1~2XE>dnu zyz^CPD`0oSO(!ae*J@2djj8W4X-}bIa#^nVt)sm#A3d`cKh!2mXDX6#eGd)Ih1JL! zLcOm+P2x|s(cl5M7egL!cHO&Kfz-Iu@=T)(Vt@O?O7-9P1;)WCGu6b zCo(DeCOG?%8itFikq2i#LbHLfOb$msV3+@z{82_av3=K>8aZDn0PY*$hEq&A5;_i* zci{i0*f5@7E8uUsTRiPn*G9bOfdW1aWWVE;S`Bkf{r(D7f?0m<=3m!|-%tx#{_naAA^Qp~vl#=| zHhYDMEUeX z2nyc76Del=npBWa}KVG(5)}5*qo!j_qC+I z1jQrqVN?k!U42fSgE{!#bZNCj zji7E9`z6dD)*B>e>W`cb_Bd&TKQHfaDMYpN_Qme2%%v?Y4BZR`~vrmDz=PI$W4fY|22x1Z2@-OkWQTp zR`r1<4!178DY`j+o|^d;zU;1;%RZpiA7^SrEQqwD;Ca{l-tjS;za}~CUf~x)c(+RS z2r6Ez?|YXhK{4=ds)@mVb0snj(fK7pMU`wt``%n!R~#)x=Qh~CK6loG{V+R;&$HuEEUz|W&0B4toD5)0(Mbzv6tydMxwVvaNwoO@*; zI1?9hW8g=#FcMXd5PLop5Zfuq(Lju@_Pg+#6407VPdy6Lk;PW)p~uZ zZ`nc<^^PVoTPviBKc8cCqOJOkmVzmZe7rI+*9}X|{NmY0=VB-IKEue$smR%lF^oar zEpkxuaO|i;VSL?+%2+OJp_%@I>SxdV19s`}@l3zNKV$~Q4=CPX&W^HtiVT=59->tI zFGF6hk_NyghO0ye`bL&)VysX(tYb$s0-ppQ;fgaWR@oum(gxj0{&{5VG0LgSXoroq zBOx>P^&+@vsZMOjNYJ?-%FO`=ydG_m+_Bz@fuK0=jJ%rCXNZEtMtchxC%G4 zT{$wtRQ#x;I5qH4tgHvF!_8^?X9x@5a^fc1ZnGS#hf0Nf5pO!o#0=_lr3+#L zfvi^MGJ0*Oir2qKp0JVX@^DK@)6IT5Kq$++vhVDnq$a1q=*D3yE6ns zL`cA1crQp1qUO#^a3toV7Nx^tTH2~9KL0Sp7CzOyUzNw?+7B8ZiNPMm!fq3Mg0k6$ zS6>2=hNKzVDUmUd-7nzIj1k!Cu_^)Ur$4-4sfi(sjbN3zuOCY1UsF376+!-sg@?1S zm$INg@_nqqbA5OSBItP;VBI7?&HE+pG)=G0%gVFo@?&eku4cLsb?>lc>na;Y`vt~g zlFyIZ@lxDDi7cKgGEE?rlubGY8mAY!_rVkl8YAm2lg)-e5{4!X3WN_e_?(Oqzkm#` zher$3&DY#gKUIb(!S^_+;YHdeCZ$4l`8~eTqGB+WTHDYL`UNO$59mcpYoqH>mK!B^ z7z%78`7c%DcAMJWztkC-g;kC#yW4crgsZ(Rz*DLA4m=&FdN(jbew+?2BguU2(qnlMEm6_#XE_8`3bT zfOR4j2Bk)5-rDJBhLG%JZz6G>3bTLc5q3y#v|uR8c0G#pgmn(=b2uq3?!ICPO|ErD zdsS4dl>`T_&AmhCA3a45HgaZP6X`8I=XxoOtBZ60S;f-p`MJ089`nD=-F1_Eeka-~ zE-E}O%(Bk;soW^EII9G9g!dEc3Z zn#;*7p-Q`Md`BYIHYeUeP}3Rn?pP1-x6eVn!(Pytx zs<>22i`s~aK4J+)rp8}>l)^0-FX3=_VbB+QHa*3^29;oFmNWOfbS}L7AnFbBv+LoS zqBh>oHVGtn=r?|BD%6_=IBnNtp)3*XwI(&dawmJA(qOREWXL-s$UemjRjpdEMv%(u zR&$S90=8s9K=L3?t8|3+wb7ROoR?9cn^H27KRpN@56{AL-n+BZ6kF0p_(}x0p{U*?@jG` zdDzMmzUxd@jppd%*91c*ZZ%}O!zhqd-~Q^~;lfuob%xKkQ>{F(cStk;xLp5`tU*45 zuPD;t`Ob;mtdKsLrLYlF)z{rI9Q4V*1ccJgk0?@`|C~($@FiC{{tBMCR9BGKq$32m zo~l@jr!Rj*jqMbp)J%3fe<5OExu>g4B>Aus% zkM9jRWUFc&p|tY!>Rt^k$4U82%}~~p$$-w@{^SxQtWPpyj|OpQZpM-mc{%}bH@4@E zHNK@Z5D)m!*CyuR8o)!5Ii2F&mu)At7w$)H8y}P}h_D0$hiuuG&7Xp`)3z4+DNifs zWIur%LZXf2@@d&z^=@IH>f%|$EQa-L^>qc5-{SM*{B|&>j8RT9)d_b|zA`?<@3Dh@ zOM>N~ieD&&ebo;~3sjwy_2bkGDbYeo3Z~3IW0`nN0&)7FDOkb^D4Iylmwon-R$gT5 z>pKh8?ee;WOnzJGMZHQ^38>@cte_Z?cFD{ub4}J)w)2h7oAE>Qn(kO@!8yA95=N*< zjljTV!Y>u1zVR8}3%k62it@6REL4kq*wAjc>CQkIRC@7H zrvyN7*CvK3u1aeIaiG}6%O$y(vUxGy6qil1qU(7>Lsc9440MS?kz&of*JLU&*g$+{ zzo}`IdMVRkl}x9&Z>;>}9}3G_#kXk^R|%+O{Mf0}dv1-gwgyT+76I{z{#|#bKFT40xk^g%p7+sBxuws zp^t~^exO^vRew#3qG?bdkn(=La|xrG_jI|{^x*R$Fi4V*F@COXcZ?*>%5Ei$r}Tg(w&CFRrWNQT z;CUm!2M;L%1UtNgxEUQN^#N!@WZev39ZnghKCUDVH*mef-OH#PPQsO~Z_z5dCUDCmpWt6@%QHnMMqM z_;v~#ihW1;d}l2!%4h3$IRAkC?ozc`QHz)|#u=~KN}XlAYE$=f8(SkP$|;R_D=f4) z_UjAO-z0zRacz{{c!`~7y|UJkpuao&r;;0c+gtYaHuKhn_R0dG;{*>7D$y(mR>i$30lz791v-@iIBkNcZXj?MtxMp3Z zq^@d@$HM4lys@z8*-m5eVRIT`2|T5J`bn>UVy2aHLgU(a)pGSWFFuO-BpPVvDkrD3 zX^OO6T_{S?78P29mw0SBZ_ToZLp`7v)0V%CGsB9Mr&;2u3%LQ`@Y`m5I1^xrssG~S zGqNX2W{n2E?Y&R~$i;&$23YUodm7;z65VZihI#(PRh)1aVoZETsoK1%bXFyvSu58& z`de4=AfKWbmxn+6fEiS7PuTAGWsW+iGZdc>!F1nsYB zLVPM#^fLyS$ROv0YtvsGWOgQI?m2x>_FJ_w?A&@iD_WK+inQ3V48Z@<#Fa0M&)(+# znS6gNyGf*}k8nZC`y(LP3oDlxv>juxU8Oy5YF-@|xW8o@x8Qx5>_HCY)ftUv*IEeh zm$yp{QrKeNkNJ036N=i?^NUN}98dSd+E`Y$84UcQLb{N6_zzAzf!I%JzuH(RrSvaW z*HZP3_kUq`|V zZ4Q5=LuN<3pr{J?>O8&y+OG;K_@DRb1dIboAy0Dt zy410J9Y8wf3l9pHlC?!N%0%4&)|D#ZtPA2nP`HQYQgF^H?|8{?FFT_72Yf~$!O#6> z3gVJWceN&&KVCbn;_t5McvGiT!lv~vw!u}JBFk?*`Wm6=hA3$H8@Hhplm$J*?Y5UZGq*?P+9*n&c0?k-Q zC@7-)qc0uMm#l4^k$KWAgBbC2{5Em4SGv5M5V+gh_YH9Bzp_l$B;yk!eELQWiqi&A z2mI7W z{&A(S14Y`m)n-TEI8O0-Z#Uod0|j@gMhL`f!bjlm^o~WrY`8f}-m#-F!R-YRJEFl` z9dmH!GWbB#e82~pwYLAC*6T6=O47UPpKU)pe*;ZLTs~|6Yi(u?qGK`$JL9QA|TS`PVbVa29hK)bl~jMdpF-M%bbKTY|PVTk65q z0e)VLJQ{$HxWD=>uj(3*M-H<<+wGqqD769nF=2I-wW^K%Q`(OHdF%fG00960gxJ>##N2uw;2lW9HXA~&!AA)?P;Ul9 zMrG8yM(s?!_pYn(Rrs2GIni$$6C2_!7zSxZ!$?}|`<{2Lx2CVNvi`iMh{`)uTv_q$ z?<$qJP_`(K{bt+sEsREwAX>x~|7rzDxgbX*UKK%q|F{49Pyf9AkN5R|{^n1A`tR@i zpWoMi{g=ak`fvZb|6l(2&fomY`ybo?{MY^U?#HD0yT2=zv3Itm9?Jjqx4HayLc1LT z4 z08B#glzpgAT_{c~Glcyqd8@6e2u(7uc=VVq7JEdxw#btU%wzKLAOB`~{L|y9b71Nf z-8}UzaNCj#EGTmaC%8Sfv>wjUN24BOd2h`&7BYq`G<{_oosq+j01ID;i_M1~HA@X* z$_>)mYkBi<7?FSqH1^RHls;`D{DJHl3)ZkX0Us7^5dI=nk~Q+QziTWbDo z*Sw0flJh$kaptI0=5`VHhZ57zP$o}NE0E({ReD3MtVaK1WpqdfG{8KDp?!%V4lZR2R1A z0?h22H+U2AVv|Wi4&pfM*Wa; zWat!pXvzE_q}y1~^w^LgLlU+rtGp4~X9A32ZvoC%4P9mr(Uizl)-bh#(n72?O5|k% zII(s_qly7*>=?g5#KGBF5B1%B8_9j}#v*c)2Z*mFnwPI8FSh=u<|jl*oSHm=D8YtFgJm z)BO)CGG=EfW>o~JjwMu!O<$qU0tO&4_+G#5WF~P^{mxjzg=!ecg+)>TQhz_G;P8YL ze^7A}(;wSQChghY<6k2^G+hl)PaQ9uDYh$m7Z-=Kz-w9o^z zm#{7X@~lztV#JMJkOb~Sgxnl%$1ph@wZhYFKKU8)5*@z94o{#^30Mx?`6W>txWW*G z>Uy^e?g_{Hj&UC!Xi(;-5~Ms28P>A~pxR<9EPZ}G293IzkTbBqAijc9(J<#fyg23f zJnXwS!QZnCsf$-|#U-L{@d!Yfw;|H_bp!F29*TntkKZ(S$mZ1d3?&%Y8=vuZH46pDE0R6=4>|48#YUEAtopbatu>vw&f zfa@_gJECVAOn`VZC1QVf&4esln5D%?*{V86&~irIdPG^Y_ce2*K{<$a4&5n;{;(+d z>1IQN(_4uQ<>lbwU?EZ_yvj88ebbwtCyd$){q4 zM#%=oY!f+16C{vshpGT$?NmY8CZd*nCn8nJe-s;>n$M; z%2H$MYYE`t+?SF-$*hBplRtov@*rACreF|p&n!2MOfdJsaUWIGhs26#`u62U=}Z%EG7|I5R(rkd>sxM~9Po z5uj}WPyMV>c>cpue>mzN{`{XiD*E%kchn#If89~lE{@K}f7}1;l)v3{1V+ky??W0T zR9z)jPf~520(z|KR+G<;5trdP#@AX94d*1NQ_#aM&?2F)Qa`^4sRJ$XsQbx@H6ayz#)&}JHC#BrBC9=cA>WE%0TUA z;9JYl1Adl_+_}Yx;LoykzZ*#N$A9^x?6N>p9;sntvw=0D(^N0$5yKP1tnNY1?g z10kN=iW+nqK&sY5rIMsE9yw2!#Laj!O{s;R`}-&ryVxXxWvLVREG2zX=Q~B9POO)m zCqJ-;qJ@jj0itfdU&+P(1ZAUu8vT!@_MUNiiYyZ0n2fytdZl8H5mwJLO$@Ob8!^9$ z&dOj0K_K0G1(7?Q89m>6yW5J6$Fgs6s!64ILvLmXC8}&+H;UhSI=@|}M^6mb=({re zkk*xok5Y##s{#TUIB@ykCRVJP=?Xlwc_8rc@bKZCKm$eZ=r?ey{bP0#z9cQmNcxt; zfa2ci@}Rd&Sk<&jK_^;0V~K8Z$>zR_Ply1}{SgLJ6HHmwzT$VfZRU_i;jmLWbtxlU zPY&x(bP}^k7UdVGBtTn+gH=L+XuGTKcU%@SQ{#5f#qEX710fFgzkev%$}I|95qx?$PrTL=ykKjUxJBLf7nSmbmW&#h%cTM7ABz;zIIY$@Zh~qMs}Og zms@Q2OWQc3-jeoT!TFsFLPR+-?3D42kb<2j5)f z9zmW;`6Hs`Vi6DL_>zliq$K*9s+Xci6M=c$@g&sJ1p=a>_0lL<5IdP<{G#Rp>J<&P z+!M2ab2rbMnUeL6p_?QcquP^9%4i~ol&XD^(BpRQ)~at)*fNa$p;X2jW( zdc`{tt-ZBZS~x7)CKPi)*NbTjp=i$uK}8(W<3>&CSrHq(rNtuoG0(5Rs72$uM7tgU zBkM%kI^Z$b0-9wFI^J}feYq^fr!Q`C@YysWC^RxcY<`v%(CMgzA41Dv-o4xG)Z-+n znICr}csX^Y1%{GQ_d@{gq0m&w`*BJsZD6MH%^6QHQ6E8)pYDYd8(e>!L*oy=rK12y zeb4BoFl}_jG4^GaaDo<)g3#f}c)Q7=d?rV{dIzO{9Io~WsMmH6%Dw)OL9h5)Yjkiq z6ilLv$stvo2JTaqlTcuWJBq9)8yTnFj)tetYN9BJia~NGho9u6yVU2+3%UULH{uiq z;SxLRf7BoTD+oiP99x!+q@L~#1NVpH2HdnUIArJVUd_KkDG&hH0TXTrp8|ws!+*L=Qs@-2lGY)<^&-N@Q2(w zbYLRi-hpZ7PfJ7f==irD;CPcYzzV|=$^=jYGC@t-T(LglbtWDt6^+Y@N0T!~o+by~ z>=Masym2CQ0Bwp8Qm+^b>n4j2wvWsLLcxiijXL}V@DF2^ZN)XGgmdg;oP+@${S9pJNV(2!Zm&}a ziUhMhDpzTAFP6K2*Mm}}LjiD4nFX-Bg@dN8T|MV4F8-mxyGV|0HAwy~W)Kh>`wkwH zvw(@{pU`TXp=xg=mQ^a1HT=QK8%@JT3)(LnMp?@J1q!siUrp1aMJYAgOg}lA$tE9V zi7q^o?*U}v49`q-QMb@}%Xj6T=eiAPWQUU(4@iv&#MDkcdX`1+!*yJgg>o@OpO5Qk zMxYJuqdAKa8p?@#I?_oNoX+zuXQy_-SbiW`lOb~Hz0u7^7rU5#Ep3GoI|$gYCX|c} z#sm9874g*-wzvCYh?T98>Q6yZ1GH`4kbi!(PN1Lm_*{XKjwkG+K2$#P>~!G+h42?P zt;cx!XUPe8&E$3Oh%dCq<*%f!XERv|Y;0)jhlfvt74Z38z!Bf&u!8a}>=AMOg+NpP zx|*wQdI8k27ObQ5eoqzS+{=@DP~iB0uT}z$mnSVG2QIf$rd&Na^rqMnf#1s*O}TEk zooR`pGDbF#IcLUZR@SNS0LCm14{3a>T)zl>W;wC5t9Ds)MRUq|6A|+ergwyaVxz zY+GSj(Qbnq{_4Sm&~8KB$dxuw*flN9zyD9FbaAAgBF zxa$_)K#cp1(zFKMjfbeIwy8%9H@b}+RFkbR&=T;3w?Zy@r0}Y;Zo}dCNdw(nV(pz7 zhn5sxp0+9TK=B6T{6fk>0mFXG_C_~B5m}FDyLF>IE zvp`=oC+enS>dsj(&pnR&Ghb7DYzhUyOQRDB-N>I{){!mou?>c7B6OYshFZ70-oSh) zyFBCRPPaU7ZUj#bLsCb<%tTS^hr*u@bxs;Z!D*y*jtxN^5{nvy1@a# zA?Mjh$rMS+6EP!YaSZB-LNK3boJ~csx$u;V15AH^D$+=!f;-JrClMDt;z(1;YhUHA zsv3AsP^&mGyIF`GLo-o3gr1B1gCkjiKW-gWDN#R~ln-#?HSy3>k;Q?MVN_w0i#WEh zuTPZ!$0tzHQ&p$+x^QjAjV5a-e`=e)*!Iv)uB1SEO=Uo0&kkwg#f}^j+<9YZzLo$R zUlnXvJ+toIA!MOg029M3=)Df=0}cU~-qymITr@l@f`jLUoZ`dM6_BDx9RSORV18&5x#=e5E^pt@6TcMWFELMrW|Y+L<{oRgen^h;OOY` zH_6Z)aKLzi_DLi0(0rWFML!d5Vr}t;`+x}f zmmjDFW1^%IG9a9Bu#e0D<+#{YapG`tfI}E4#SuGx5xfXPGahpd=>eQ8Hdu1%plP0F zDG2l!>7Fo6fD4JPcy$xs!ynL0re(!*30?hkS3RJ`UXZC5vL`oi0ENRH=)bMI{N=B# zyZq%pth@Z>|L>cgf?uXuzf(rnxA76Y_4%T^7-7poVRnr8a z2=*sfk?u%*Qtf_C1v53CvIoUwZ{&k1srZOisCG};AZ+ie3aUW+y)m>?2Zg{>yFV3q zUJR3&57FJvi5_n=%>ZIi2xM=W)d0K_1_QMM!T~dtyLnQRd&gE!((A^+uz_-v{2nOM zAO-#WJ#Zj;wg32RGmt}R_TCq>OVsgPzitFWPvB(;?Xeba9T)I>D9*&Ge!NFD0XJrK zVUfFh)FOTu`9VMi;V(Rlax=`^M%bR~x?Vr~_Job%%@O%0%wu%Ro^#akmpfbOd2kdJ zq8f|9fKLcRuI2^i0gQ$Eq>nr>Lh(~rS@Ikbb|Kp;FGh$GzZ9(SSg!!r>B$=m5Bsd{ z>!jitb1O~L5fs9Y0i#R<7q!0BpQ+5sF{>&oxtDBT)9l#CAf8g62+MS^LYgs$&G$n$ zh2063x+TIl1i-{L>n{ne(42@8-&I#op!?#T25wxGc3M;qW!TtW8@Yl75jfU#U?>@% zHiz|yp<~A1C-&yEgRLw#*TN>AyHWf80GaA(G8^m~e|T|#A^`3JhuD+(s_nlTEa_Dg zeIg)6y9Wn>LBCvJq`S zh264Re_y%$!6Lr-UpwFSMjMkpqpBUD@o%~_=?R*gny#`1#hO0Q6csdPB5ZI@?buqF z`?dHBA>y$sUjrqPS5{LS_x?Z32nL^fHak%7gd22F2&P3GbBdY{xA;(c_}+T_;PBr- z>{8PYY4wgRl;H3-4J(Wl z0$10B7y|A1sH6DxPY;obwMZ>YA`j(3TS3xidzY(L6e0liH-TOQdjs?%FePlSm_+hT z%-P@p`q*-J^cxgE(2haz582l|j1jiDaC=46AS!MYF*iJTg7WDVJ3bA=qj7UdyVWr9 zMuHw{J}SdpM^riy6K)VwaXdCWgSkIH#{mUOptb1wBGCl z3L6qRtiA+x%FTB&Wym<(VyusxzPS1#zj`|t18x49nU;KF&)0J?n%ri zQterhH4PH7M$J9e5t;|CcGg;MhnpPr(P+%Qu4s<*X-Ya4^xOYF{l!wg_?#0lw5Gz~ z6#1>so*bZO>`@8+8Kl(1L^L54LEHf-pkl<6Ph(M7;YgyX6@zZZ$Rr}5Of5yTHN)4$ zLi~5k%V0`WDL1L?-Dm~68K~w(wk!=aP)hE*`%(2j=wt3HjW_Kf6tI}Y z$e5%iN=>bp4cE6hhnDS|(?uKWJWC}X?jS7jA0^Q6aO6dvgawP2*^i%r+Pi@>89=s zqb0BKY<&7^jZ%MG@ZgACzJs6!zh9Sb4!2udEbFYaM+!g)*$+Ot8%laq-axGkVc@_j zh6y-2>0V8u4zLkNA+k+3w`|hgd`)1iTvD1XFFZkznylz3wC9+&%Y={2@4fZSbSoq5ru?)``>EgYud|p7rQ^zygN=BgX!;o`H8;igX$hEhW75na zf~0bY63W&c@5YC=0imf!XOGKys=2whjCmaKS&aD-n_8}(RU@usd}ixj{;KaiM+b<@ z<-P3sYVTL8iaB56O3Ssc)~S?N+rC=oPwgIkQWtXs)_+E>8CZFYFps&-iXWdkW$&Wn zN3JedPIcVVaVV_&LvK4eHhk6)w-wedSk)SMimwktu_PJboyJfwRmT~F!KJhIl*?ok z?WsNHGAn5%(6cU-4CM4)nJ#_65qA9IxY6ku<89dO(fDPsT&u;=^>tdw3ERb$22?mR z|F$nr2)|aBUX1VZZ+*E=Pmy%X^DgEJ6-ltX6y_B6lXbU!|5dwQOz>*)KegJcZ7=42 zwaTAb_04HaiDIcKBGjn|8q^=O5)C{^wu*JpS$-|NC$M@|XYi&j0-# z|Mjmw|K)G~<@~?Abgu*T{+7*m#m2nl_JUXhUWVX2M-o2F2yf3l<4=_YD&lV>K5FuDg6KpCf!D+GC! z9cUbs&MRLd8e*-f*iy8}=-tpP0tyL5(7+@;av(4eDA>?%zk7VPA;_U|N0(H`ue+I! z&-N8d78E1r)!_t@79OoyxMnI8M;dU~O+R$lIsOI(ZJ?`HLO+w@eosv|=ihxBg;@e_ zF50JLVF+vZP!$=-MG9|^C5R^xx;H@<%%+I%TQi172K6wNw(Hx+F2)bRS4_f~gGicm zKJGQV!7rg06<_q{?zP8U-cmK)=QmQ?a@sxOv*E{CIQu+MW*0amH`fC~a_3Zyo{tL$ zISyz-b}WE$WccVGZ&7vBg(UtaxyAYNL#O(axwr8$=T@I<;%dJ5F`08(3-b+m9f!Wn z9rq%SKojXUmW5L;^cer(zC{HRm{uM5Jos2B#`=ZVTn7K$c z7iIc(Y|)e@12ygF70OHj8S_QQDEC7dEXTXHC4@X{(6Y~$&xw8#sB8tPXHb8^kSE}f zWs%}s{YqaW29hdcwbMcMxOjBEaD75K4v%`;=P}3LLOars2O8QW8wOIF#Pjm$Fd-(4 zAImFw`1V(6(+FW#AU#IUHn_q18Z(q3UQP-j;}IhxrvcqdHW4w}(<9?sLTQ29bbKC5khBb6Qpz-XX#5uzc2v;<~u?b9M z#C`gcag9+RtMKG+^0+`kjtNU?2edWu+^Z{K(cANOC1XQDq^9&>g+fFdrXnD52mZN$ z`3bh~Y$t8fAqG;I>W}TH^{|q$aSc&Hm5(@pCE~pmm#%>~WR5$72Pt1Kw}&_aZUm>e zuk=?xv^|10{KF=x`K-0r-fs6@0KN%ra_v2m8yC4xH{v1~P@!-*vvf*@*S8?k<`k!? z<)FZN@+_#k>Hs;WCz3}o!EiWeboQZP*k>?k0+;c6 z*jtYD!?*MRKS030uCeK3D-9df^06!o#j*KjJexHyIqH0Ibc`M!hlZS%2!wV@k!7re109Sq-J;Jbs zR=o~C^5+vY%dTR=deW!Qg2wGlVXBnPQA74sRj^t3gO&JuZKhc?(?Pj`;zSLd5uSG- z3%CJI1fixGS){-0XW{l3TYY#`jCwZ5E{3#qoY{eh_OF|z`Sk3iUn&55aqR3WNuA@P z3U)j92l#UCLfu9H!mBU2JRFmTtU(4F8HMU{Q;?EB)cMpU@PoHQ1>_;I5u=K%GkUjZ-kqkC;a0-)C57tBBItHvc6f5SAKHic}u;Y zpoJ$R^r8wvN=b)I){ks{^LIbU1gl`Zh+|?Jy5N2GhmhgUxMC6}>>SHYYXj}~9d@p& zyVQUm+U6>QyC?1jBc%EvE&0Z(m;Zm(S!_FXh*|l`@OVTDk7y^5+_@Wb+pcpB2gJ^1 zXpNzrYNns*gpPmn@A$am8?8T*aJrv;Cs10v4u^^*flXEu8oIR@EO_7vJDsq@(yk0Q z*dq>Z3W&0_yWi5&bLq(8V8xd_ibxVgcSrb(h7nL^&Bw7m<1kdcOTrf@Vkz3f%_=~W z0A+dxaEt1kr~o&Xj=1ku%BT9*B(~x$(e5PCEQ_hIC*p@3*XqdGMKLWdzV*#!w{JnkLz@)KuWj!Fi(D3AN7L09KNc+GCB0@Drp zNLZ46)av@=u(Z|QQy_uRse!T9X5XFq;?x>n;|i7et4jc%!UB;6yTM=2S$J*QpY$id z8qJ;9@n+ir38$q|O*2T=4=*FGYJmFDfH?eE1oDmMlCrrnj*`m-J~>nC!8c|9xKA3^ zwZvE0L{-}85;r4fm zyj$ba#>Gs@A1w9mBjp@hy7XCVJaC`$mOWoaUh#H03VX=c-ti6k-APu=`CrI^Yje6aSGr}C}B!JyBYa5>VZmSVw))asCHzLg*g zF%-q+2_-$GDtFIKJ5w^{d)(&=^}YI>CNR?c5S@~65wl=#4@et3gKPu=&ht?2EXL=B z&D{}7dnFYD-Iyeu3cD#@azaS=fYKjonzbX-tR4b-|hJY zA24Z=nw&-DP3Jy*v&w<<-Ps7ZFQ+ktQDQ~=5{7G<+53x%5j|^2omjt*7eLZ+9l=lg z75Q|?2g_2gV+mxyHZxg9z}Vh;?^Bd0-$EUj>^hMEZC1qlF$48+&>a1%v@Kdp8Lj|F zdKipCt;(V&9PM-#bu>R>2M9aI^uenT9=lxgm&;V(B$o!;dk63(b{6a*L-G zsOiSWDaM~=UnK((fwClP`s)I-FM9FDMbfRWqfYEw^lZXC zvZ)gTH>L|}rI?SX)`V8O;k|*tE-&Qpz9Ix=fugVX{cvl~dd%I@yBUnA1kvH9V4T}I z1c=(#1Q)OmeD47>aFA*lqy~qA-pLW z-VZB7BNsF)YBI3o{|!=xdOn`smBvSJ10p0Y+*guX%kW z=~PYhF?1lTxdcVC#keoaYXrK)=$j;ShJ1P{R+3of2~i(OHftw}YHr{QvPv$S*YH_D zf~7>0;lh43oXg4$nWpD43b~1U@zIEl9U8KQUv;;S;O(2P8kT^Kz93;?F zNPgp?6v$;!_L2;sT$~s%3ZMs$Z71{8u-(>~bWkytH&*17&nCMhGF=f$uz3jxf?@yb zU%Bl6{wG}a&;O3g{`vp&eN1e(Lxg-x;x-t9(s362(eZ-nRJ~A@6;37Q_8Gsj^V>#C z;9H&9NYWvHJ4Noso4ixV&J2_8RRMmaP-=psWG36;<<6Q4jFlL^s-hus8xq9nX@|de zuS`*h_Be{8GZ3MFe1DhgD?kgZxWz&QB9JGtAFUq`0GO83RIfv%^1Bet#f^CzV}Rr4GpaYum@ifDF) z+Ffn!B$r4HSKv%cs3%n#S$?rM6%Cbq)4~XtXZY5se1I%R#rn%-1nIHX=in&PnyT8w zH6bUOH@!G_54_o^&N)?HE-O<)1lR$6xy%Mx`Iy?xpTF)L7lNA}qkA%iVayec=MM6% z_LtbbP4BB_dAW?43+3ciu3=?b$+J(}U-4u4brvV9AI%Jo@QehVz0+Y>M6FOs83Pt> z)nou^>g85a7fnV_-#y%x7}%{60(A%e_O8Vx6OV|zb8Qka^J(%ZUjfS%NgWIWA+0lb z3$LKNpeTo^B&Bf(>sRw`=r4Zcqq9JNNhM-Qw3>?6;Be_KT+H9J5c|Xe*;2pw5=MLY zOv;FrM@?cqfVTTs;(RU)lt#raTDP>)bw?vaUve|lq`XgKg^?RuIj%@Nz##)wJt9=z zN%b{iGv&bKB@U=}XfD!%p*XJ-;Kbf?;c0;HBDQ=?mrK@&M)0_yTm2HD9)z_jwm6e) zz93)i?dv+qmm0{;XA9AsBZ;$vY+Pqj7GM7q?z zGCCMC#~ubr+AS_ck%9?4xP%XE$~Luj&WGc?QRo%kE}*PU%fbD9mRjM4)Q2WjEL)$ z4yJyl=)5_w%44SFkegr;26GGFQ|pe@0P=N{m|Lx`Lm~QoUpD!XRlxPF z|<98>~oR~IaGv0ZmA7tQU`n8li3ETm8TEOvHq|Cu~tNdw0rX}v1Rj);9

  • ph0Hbd=Gb{MU(WHH`L~y zl+aO4Zh@pwmo&YPd6UQnfl@oM3_pH8P486HenMxu4VPw`by8krkVAXTQAwWw#O~Bj z4eGcvXT|WEGFAxCnwdM|{vH*A{67Ey0RR7ddCAVK%$D7?WLqwk%kneS$QA>Vp14vC zNJzS*OOk#@-}gNa;%D;6&t$%H{@-=4r7EP*B6h|Oh+ypC)L0gx$e`04}uFB^WlK&uhvO&cFMA-9LH7;ej`&a^{& zu_$CoH;CwY#lR?~ld1rnQZ{B_=FxuWc8CUg3Rie{gAcV#z!EH_H;QfvZoWgzjJV^2-(FRUZhYkgO zg(NdTn5|hq2s9~ds&8k+~!a2b``-pp>0i=ZAb0|>s*`Stj%|gj~qG<+I%>`+c7|l z{1epT^$u(g8Xr$rI@?2bD^NXltfSub{XH&Xr2=8aBe?81g1}DTM}oU+;8QGCS|9h0 z(jpaP!CXObdl28?n8G$zR9LrWn0}(z%pjkC`ImqGpMUvv{kOXf|MZu?{O240%iaFt zZ}VUN(;xl+aJRqy({KE_{`(*Oo0EN1{q?We)VJSdD!crD{BtT_PN#wmQ+?+++ePGC z6sLy8F4G|=0}ZX`RYxu;>?I*Ctw0qf{u8Q#+4JZM$fgkxY_()eqrC4I3|4MLH%@S$ z#pQyW7R-o%Nk5-niqm+`3uI^3;88TiWpH?)P@=8H`I8k1WyfeJ0N8wfE|dtG$ywbL zf;#w0!Z(_HVPZB=z1fi9gliM+s-ub$zDg@)vBHe&@glhv1g`JYQo~}6wE!g`<2Xa) zDX6GW(CTgt00bL9PYW&>2^m&QBm*-&$w$L218iJNdg|Q;`pQ4u#4rOkh$FyP$@Olj zsK^zMG#;)FYxpX1NFJ5g7cC6k(9JsfY;D}@Y6P@`il3)grmyzlBgI!)#>fMhqp)0&)afGK9i7qQk zXs4pLpG=_Qeg}((VA3^rH43w(t&nXfXr{i}tL>4COd^+mf5$O)eq=psmT?=!9Mv zhE=$bV&1gLRFP?=Gruz^qp1WfQ|CEz2n;pzn2DpcAX;c zJb}bs+#eEUEa@J*!J(O5_YRh|SvBsk7qeq(MD-B2mDiqOjvA=8;Y|`<_4L5KLji;% zo{1utuvf{cof1V=4caC#E1HIDZGQB4{95foX+MAebT4e3r z?=bU7YG64VG$<=u+<{)&)JnOOw4A}IJU4P}sU|zY6@AHfb%#{Ky|VJmuCF3syo*s9DbmR4 zAX6d3XttJcX_7jAbXd~Xi-c{CeysYkvIF7=&0C30FD^SXls40Z_XJmKkU){laj@e{tb=KZOEMTsk5Q zH;=PK2E}fSW(+UXN;yV(azni1JnBOTdW< zjALC7?Z5@Euv-xmgNyrQc0mrUZa+XB_~JcbLI$zubS8>1+}6Xkb#WR!C~_I}1<(x^ z<J(K>d` zxW3SC1Eo`-V6KH_q`|2rq_Vg&aq)@j_Tw&B1DC#_O`#F*+{R+F9&tlGX4O0%yGfuz zEPOdVQl6sL3cs<*t9IW_Dky#-7H~Q%=T%<%68iR~U1>{+A*7boOF{Vc)1zQ@wEd&? zJ`winzqVp)M+R$0?V(n8ikr>-NNrYcxsww)k@!fYZ?I3%dXgXMj11|O4Un$l-_=I) zx5`}niy_K<{{xx$_%iyZSO36pA6^DA=VE+Ig5P+rC%e~S-0S&;wT8zzciW$OCaJ$s zVMOs>XLWJEa5{xp|FXJwk5_KLUwGS_d;R2{-hL1zI92{%ia+P!;--`IKgY8Iebmz5jW?@5=Q)S_nWO@VX>cO- z19YPbOm85U#z=yvwY5alywh;m8#&wFspH|_e49w!c5t`axFdUq^xMQ5qH2`%UF?gl zdzO$6m#h|6+(D?$OpM4lH+K~7H%j+@34TvAzma4L(YW`q`{CQY&p&wG`+2}>?LxmX zp+8l1+mD}prhnsp+do-*a>j2IX30E%{Ic6`{f&2Fd@{~OJg48tg)eFUu^YFa_!}Ai zB5p3n`SBZziM2nO`m4qFH~oo`|JSgaE8fi;`-gMd%{3uLe{t@{|38Lq&iN&yfA8Sv zi{e-8{24cQeEh`Dmv!~@+08IG=&hTv@!P=}L1R$^!H@@M;q*oSR(Jj7zyABW>;L@Y z-|McQ{=cQWT>92sua6Dd(2|F>?!%|shqhCE-kw*Nrxlv6^XjhtVZPh3*T&bIJ(32o zXMNqGTdPJv%#O)B*7+~=gm4KZVirrn;`wBGTV}tnlEE4IOG_u9(@SlSE>e*-Y{Cmi zEhF2+?%K92MPHPuN;|Yu1<>Ft^3Gi?M9@}8XHG|%ia2HLS0Jz^0-;v|Zq<9zy1PP; z?1M*fM9n_Ml8De#NIVl4gH4}BK?h0^x(EsH6rN;BTB0;u%e3K`HE2xQ>no}@5JGRI zd4q5PG3-(=qWHPU75XZmCt!~-57W)p5JEzNK_y|S;>fqxGQz6L347gD-(%9`Yf`k@ zz4zyU9w%GS38c+Dhr_7|&`f*{`D$_B?yl*CiO_BeGx!JzNI#2oE0VSGoZcqh5qC`= zzmYe|z2yq)TsBr}lj@8E*hUe5v+o|}GScpnXxjHPpIc-b)3QYDs_rC0U(8dFOd*W3 zeVqIj5A*xmDOhwl(^RG(A)B?snO4+u=Pzm;aQvnnp^kWh;jxVCXx2E|o9W5fTKI#< zt$o2U=3xNiNtIgEQ2iY^Qjim-!Ri6>Y76DA9$^M#J(MNSPR6m8M#z?Evr>sS#+%I8 zPaoVx#d4(zIHqc^%MC>v+SltTi#B1=9nY8u9ycng;o+Vkau8aJ`>D9P6#VpHP1fV; zuC(riV2Y=XjI|X%LKzC|GP4$_p1%#2VA!2{QDu3dDe(>kIFuz-E~nfeUOd)&0+Jd2}wGzn&Rw>`&d4qK*7b?j9jO@ zWg$t=9yLl7tet+|?Fp@9(Po^|`(eB-nuiiiAKsbNloMT~Q5+tmLfi=+sCl+TvO0g;d2SoGTJ~z9~`G86ZI@f_{mWp zvW$GYxD}ug(K!-`=^0!@$R{Z}rrB0*dkAAwBb=_mWNLS$TmUc;l^UM*pu08{`Syd# z0xD2lT2brLiiJ$Qcs!}s$cEygTlpm)ijHGx)MEoE0FwfRq}Vlr`a+R@`zg|g=ye~9 z7-~(``W)98hb_w*ppSSJhuJ7E)!5V8x_1eOmhov2a=bi2ADtl7iP8rEMjugCK@Nf` z<0CqZ2eN1Z^bAku(Z3R|e!P4-P^4s0oYe$|j4>BGoy&<70t2GaUn>qh22VS|3|Q$VL=Zx>1Pb#*NR;Y8z98Iv9r&@t4~mV>J>4txe0v1(6Oh%T>#{piCn_ueO=n-j3@oCKyus*! z9MxHCXAr{-<8>*L?qYJ57Jxd97D1$FWka74GPc9eXX$Okv+#gOaEOuirW6VN1R1^& zvWGYa^9mE9ahJ#M;bEbRmkO;|5o&SM+kk5TBJ#BDa;Rr_6VtLI{rj@i3E=}HL8o8iDM9{Y_IJ2`DA@~)JfIXRzj^`^+JE%T40?n{ z+Vwun5~M!&E}ml}PzK_1&eRtX2V65*o)(0R?y;i5h2>(6wcY{Y7AM@qBP@ut7i z!-$D&fIV(2V84*lC5ur0|S+5{YTo}Dbk#wQ=(?f>xO}rNt`w9kr z?jOWA_A}%@PELTEx?9B~eA!O38TpTIBi14w(uYt_j~-&SmrWOfG!U%u;Z6NO8b^Z7eC48{PbZuNl=<8Ne(o=X>yo5-i#Xk; zG+KS52c2(@gFl77yYMv6`a5}6!b#JWz|wGqGIVC0EFBqpDc@qUAT$sRBBsY7Vue56T@Z6XYFmPra>|%Pk6YpL}q`P;!f4quJ zRi|R$qud&SMyy8IdbG=GC=r^5T4k8?qF2QH{txCy2mJ4U`1f_d|N4i&*8xBMe@h1l zHFE0!^8rdt)AG9L`C#~-{rmYP!RPsk-R9Lq94R%z!{ol@_>|U*1dlLTQH}ayL0q=+ zdlqgH@Pgx47O&4}EqSRh%6^PL_VZOpeX2$&WOQ1p25Cep^LI3m7N;=^UV#uT46EMt z-KL`ep=Ux3=?!Duf4WC3VJE3)g~W@{p@}V^~Tqi04_F zISSFXToxW&612V-9=+Vo-C(lKu~VyY``SBZb9cizG)|7Kc{yzldM>3qS!wIby122z z!?_|?6YZeFWSj@aj_f@DqMucWqhi=}F}bX`d{wf?$>{kl{FH@-V>4-kPDD@w3g7Ef zlKZWeC?8)CCQcG}E&DfSHUKg6=UoQDiO#J{c2hrKH5#W=V>(4% zi17heXO-@mW=ws^+@l&L#-Y{Tt`Yg&RomlSkNQqB=WmR1IAl=K_ zx1M{g{}%uN|NnfKSq{WZca}dSKoJ4N8gd2lh36?!Bs|Ykd-k2j_S~MQg|QG;!7}il z?~hP|5=*D6%aUEE%2n@qUVff141L19T$d;_B~jiit;*_z(-fDqw30WJikq-$T;>bE zrc(sfi7XBk5p!fi=~&Uv+!=L}l?913RG6wn+Bt5e+ztW4LLXORuFQ)dZ@+bfII}YW z*4LHWcAr{L2I=8OlkmK(nJploQl|kYG}kz@tOw!@i?DtsBCRixsNTpznI#O=8#iPR z$0YY_h}cJ<1sV4ffgS&&o2 z(&_0QD0|++A5b^pxq$ucjOY{$gHZYUnBnMV@pq z%5uY?zFcl$;{a_FeQjPvK~omcl$RGC5VK@c>8M3M!fGKNf|;V!X!-zK_u#-Ec-4@^ zOVE!r_c%ofV3X3QSqqc`FcDejBSe|IbFqMfD7+h)o!5x6&X+%uGIs68%WrEcqj|gd z=H9mf#)dEN34T?X*yo^t!~JNi1C4(kMZgh}?v1RRI?JAf!gv~DFUJ}Qvq{Hms;;nI zGxT3ydn^d#UUOd)w^Ai?r`Td$%~He#C>#plqJ2v(@IXYB-B!4s&eOxe&$Hz=sKe+6oLI23a9(#VZRC1&bsIz9@=kZ!jdk*iEdtI2|ul%_^ zLfSIS&mUm~?ES7-iexK;?tL#qroC{#F6CDNVS+NbTW{W8#P zL%MrV!bArn5)Mq`UUh7EstC2QKyMrv`Xl24`@l7m@uJspRI%+KRuuF}p&*H%3ojsx zr!9LT7JY=GCmNL~9xFRsQ4@T}K?xV`~(t;@$-y zm3Vig)G$)@L4S8_R**Y#7orS5kpG>e%e!>VY@iAnXDAL=m`Q0|IN*ZeJ^9MBtXq({ zE&33?+_xvLHe{dEIie4%f=C2^9#1<6@_nxh_3it6b!3A4tld6SwTCZ*2%hI2ynd&i zi#wNmJP+wpQdeH#5f0PL)ts^yZdywJcSRqHkregm^{>rk_g|i&aUS3D zp9Gx4z^S%BZFDFAS-v)dwqKM3WQ?)%FjaSx z{dM5>$Z#&0Y&Sj1K@~Mg%cJmE+^8X~MWF`Zb>bycup`T3dY;cd0rk+nbL@&rn~u$r?t(5;?lC2?>eyd3hd6e3Y% z@fnu>2B7*}brj8gC>}k!1$l4Fh>S_}N8V+-PTn&_mx7VBN{^L zu?Al%bvH9992+?@oUSRdh6753!Wt-yA~T4uLY#6%2$)5ETHD^y&xbfk`EZ+&^jw_q%pc1t2k#idbEBY2y9q))u z*kfrvub>J`zbPK&z71QDAAN7fa@j0yRc1^1oz#!*E0MR2y~1Igd_~%`_&erBI`{q3 z)1+t-zYS+ln~D>!hJeni0NkUh&b)v4hrjzDfBf-Z|M=sN|MNG0{P7>(_HF+7_ka9( z{fEEy|J@t^>u>&S|8o7ezxLOA_+{fl3y0tjTqT)hPW z=4NQpR0lH^T{NUxOhTR_L?w@v?~nPaj}e#qc_7PTk=btET5`^39O#%wpC9_h#1Uf@ zmgQWIzZ9J39&>~3Y8#3*TZ+^cptU9O-8KOfKa! zSf@=T1R5^$==f`+256j=NvbM$Y(E0n4KCr^8Zwoz^Ei9_g|aUG$BWZ*ssz}}jPH9V zZ!RrYkRd;=WfH5;7=>BhCn}zFAA4&_SC?{PM2KB%l5x@g zd4T@bHX|+7uGFaYjFZETl|-7k=(<^-%IW2Yu+?K{WYLn2QvBd|3vJztO|8;EbhZT4 zgS!3w?&yfH$nD4w{5a*>^_p`bMdaMbO)WpXr%K4XPLV?Mm972Helo3zsT>y?c;Wud&8UrXfQhg$kAoZt(%x2pdaB?nLCI!%PaBDNm zn4S<_SP~ji4K03wSG|}tv*l;N;QiCv`XI}On#NA6VT!pLJP*E#ctsq8zLUc z`U^p-^OvRu%>wj5?xlzUE}d`Ji%m?;t7gXGg8M7Oe3FzkAasZ7(vtBTd zS<`ZK8~92u)uGVxIABcxu|Gg*VitOOtaCj8;MF!7H$J{$-)Y|H`bz9+*y2uWBU7Fn zo|Pw>OP@P@R7gK2eL0G2@Z>548DXnqcfF@56XH;6vM6eFz|jyFRD3h*UX0g-^j~_j zi{)OFl!KpJ1qnvi0iF3<3%DtWxZDF{;WCMzB8Swzih?_nIgkhT8T> z+{-5`WPdTvEwx@0O~QnSB$Mw~C8zzgkuB~YSg!4{x@>DQf6|Ckph@@Cl@UJAs6|SyR8pP25CrWV1(~9CimRDy?GAeL_-r;w^tCFQRvDbLhjAdr)s-gY@?>QU!1DptJeA=O( zE7UTV#U)*pO;NX%V(#g^>Ihv-4@AG|hx5T>d}bTuo(mwNw@y`Cae0*%b4QV)h_t`@ zc`)sUzEEBe%Fz#2D!I@qq!0tuvZj+4gCX8rQ-AyP-iAb1#PZ`bE-P z9K(bFy%r!O2>9_R712YW%gS--T#v-LjSQVKLS)U-I#yiZ1UCl?3@*Qi44zHLHFlJk zYp)`l8L6|TeUHCl6b|YKsM!ugCa?%lxUCBTuZI9iI{sSj|HnIj^I!gL-ud7E`JeO7 zU;6(V?~LybL3!tONS3`0SLTjG=+tswmi=o(hea{D5X}<55H~@Do!UuSD^W{!$WNrh zggs(@qpH^@Q(-ds`(^>a*cd0V0n>FVgXI=y1&Gl@ww|;Pc7m^+`22p52aq-mR0Um) z&qwc@&G-69h^@pwL-8i9{}AI;6{uMBX$r%KnMVkZQ#$cM5*dHek58D z!A9p2T9Vct#Qp@JW-)nP`Jr2@l%T zhcedzaaoE;AnAT@Q3S=p0qERnP1Dd!M&~fVs`OjIAC4H9FbJo{j6g=;O|WsfhA0(w zWZrDvbw9uaB%EWzBoH3~g`2GMsI`rzZ`D;+aN56=f@|0KT=7b-W$>d7c?Cb8d7(hx zqQXIcwLIKmk*JbfvheoGY#yni3+=K+O}a-S<>0D&ZlB};irQin8C=#|RGK^97hYlV z*Jf}<(ueh~DGryYF0dnG_x`*!^%kHaV1JMamFb0)Z#kZ0bSGEJhCL)j zy>m>j>Q{s<*bxK#6cKL}pB00s`O}r>yKYYAwfq!g3eq1v8x#~a0LZv_7Qai~M6~yJ zRw}Q_nL`dTY=B3Xzbdp;Z^_>CFPwq>p~Jk_B>+)oCXWDUse=NspZhcbLgTs7#Yulnl`5>(Vw)nD-+s#>)8GvKo;fv`;gv2^ ze~y3;ku`!TQ zhb5>m5ac>D$#ypin!T9hk4gz*X=~7Z=XM_sLL@h#Ey}ZYh=W}HD8dCX+CZ5$U_{;# z)>?|v$0htu-9`ibM^)caLaHVp&5NAuDQR_5FnfJS09EA)qZLX({$LA)r~aLF`K4*} z8ZK*SZXG}p(e*Qt2n?p16ttE8jDVMU!YxRX^P`f#z{|_gbbS*`rXeeV@-CX1V1}ldoxf@+vh8 z(UgQDYd;Pj1~9Ob2EPA{I4nngH#6sbz1``zJN-CkS`wp>+1&dPPi%C>%PxWe>OzN@sb$q=s`9hHv7&G}L)LonVJO}Gm3v1hS zR$8*Dg;YT6n%rOoy6hnXNkQiWGR&L)k}HuPXgz-s>L93ND(CES{M_FTZA~n!$q~by zVxz;iS-xrLa(@I3AQy-FWX1zMQSjzuG66kil~hr*ley&6CbUj8nxSSetD9}ME(_gt zJ!phdVI4#?vN>FW66q(Jl=@(D{eY2Hk$YWs8k|}&LKPsX_AOI~wUzwcPAvyaqVM50 z)}51}HuZgaZ3qb7FTg{YKw;)`w<)b;O_hCRN#i|h$dkgJ%q!YHqh8GAEN)-oRN=MR zdb3A|%7vwJ4lb|gl9-yIStAgOde0^F6_c{Q9}IO!>Q~YsF#+LjSi|v&;5f@l3CE_K zH$km>Nyfqhy!P?4vgmV}tZ{s>C?m7BSbop-d9IQ3F`lqHNFG2YW7w<#Kj}d4;U1Cp zfE9-@xKKNMKn!aa!Zg%77jiOPQG#Bcm*G1QM|u#kvS}`^lbCTJ#jDHD1$Fz;G++xO zMzg$VS44h!C^bsO)}KXv6R0&uNU+>@^n%Y`CPgCK9Bio88Fn^ZTJ_DS>C_qTP$~xH@!q;$%b1?vCHR{Nf-F&zk`op6Z+6iE zAi@17TKNi%5v3L-Z{`OMj&b!Rb=^7o49%s>>qaofDFv;rDPuh3txLQGr-R~#iFAP* z^SP9CdPVWRO!9!7r3RWGeL*Pv1!Jp0m-!bh3$;KGVZKXcOI9`d<17yr>>91rUmsZM z!@_>#2_-5=&kcd9yCIOHiBQwc!kaJI$_3dRKzev6u76`RquWouaTSz67V;& z+|!q1ks+Im1vHc21|#+Rzb(F`23yFr75EQKa98>qJUwDWVZHEO;0+ZIMC+NI6am5B z9&RpD2bok!@*;b(#cHyh_miF6pHcS%@(l(=qnsBsorK9OgV!zNEB4aKo$Yy_?fcB9 z4w^R~HD{0%Po}n)T3$CpE=;i`S-#Q}y|R77-Lr|UbyL>mSx%Cuqr$#OeluogCB@k8 zL2lQNzGt_#ve$2Y(QUoX_|+!nuW>%I!aTC-C`m%U`O@#$uTOZ$H`jlRx*y+s$2VX1 zo~Yqwsrydwy668I&%^8Tn_Kh?;-U?b;wL7>7kNlV`!m>SK%95NDdgPva(Si0tiYSY z*0Fz$>(Led(N#}LVi-d)#j*&QH!50?`J6vx8BF+kXDO~d_L^HGx|6bhaeu8b{aYFJ zgE|y@*|7WG2i?~G7xzymry)!Fr!lnJLmhnj|L%V+6S)6r?1Bg7BhOmLFX(B@P4Jtc z&nDsV(X6CF=`*$Wud|QuN5;L40}AW3In3tDz$g+O4%@q&3DbYzef75xtMIjCK$V=uB&CdZJfkKto|AA9(=$3 zNs6I{FKd6xN!#y(6cX?FFeWBTy$!oV8uHlkfC|uzK6&#;NV$>@v+ZVY7GBwTliMmcf@+9?QpRuYt zyWL#O%-qeVr5_f&uuFzq$8aOjId^WPe|_*fb`nENI!0KRoAf2=*#iXQNsmTr%vD1P zcFBT%@JwP2oF@_!P;ftbZyIlf`5b!YV0dqU{OWm=3?;RQA7}Ix#ReC|p;arz$X@cF zFDFllClxUfp)8@{rT2kLeckaI+n&~~pG|Mcf#CxH zCwA*kwmUZJoCtiyD3_=B+(G&E`)&x&mBl$slC7YIfBABNv`t0FcIs^VB>jFDeIF7Q zx!k1%d^0xQ{{;X5|NnetTb9PQX6@yyY_TAxk!I1|~? zp4MM^Rhz};s1_wxaUuZQR;7ZSs81POCS{+=9tfHbOo^Vd231*(Zjx1ZM)MN43(V|p z_|mujw%c~W8hbT9u1y!2FLRfAssMGY>k_F2N&}K2se2U>1u?|=s#4sdJj%@&%)QfAf0zl%fQ{=gp%_S{W{`qEL zFVhmJ5?|6te`)Hc!LEEXv0@X@^Vyg6m0DDc7lW{fuzc=3WI-nwgnk7Ajasyk!RW;q zUpM=Rtd~Xi7g<=Tx;nOx&Mo-e4XNuePQIZ4UqGP05R6UL*uETYZjMMfJ%tFMEcILs zw#j|brO~E{ww&pARw4r2-Iiyy&(wLwT#nYLb*);62d&5Vq zS~FE-%SS3u_7gX(L)2vEUk+{!eJmeQu*Lp|Ho{K#-)s78=JJCCNj?==xRD{u_OobF z)WyYhuiD?Q1auJ&nwsu+xcv4nS}4fjAh{*_5%z|kQ6FaopX5#Yix+3+hzIkYlEshT z*We@vK)XnO12*b#@BXZ+qhfMGb7&OOKJmD+9JAUeo~FE>hIc_#q0>YOO*rB{K_S40Bl?i?hwm`mX(tMaU~m({o-NhaI&W|w$P2DT&(n3e=> zfH!rpydc>9j{Mo)(FF$6-wJkt5u)L-vFW=F+hwu3vj4Jd$4zJunvjfZMIO>B84&I? z_jm{wW>ABEWv4bVJ5{4RQ-ITPCte>ni^%S0w)Yv}tC>UUR28F0|N8!G4DL$jk>Ti^ zVSe!*mZ6IDF1-qAGqrGm_yHw<7dG4a@8a+%^sYI;T^w7*SCecxd0RP=fl3mZoy5PT z_8lS)&xy1iqJ!R`dc_DL%LKKpU#rM8hel{0jK$64y zhDrR^oh-M7-CSeR!J(MB>TC0Ec>0^l9uOX>sd(f&BI}P*)F8;kt;{#SQ6V z2uElprg+O%o#cQ3)o1EPM-eJ{h3%xewq%2TH0>v0``do@Bje7b`oR-s!N^R$>ju8k z3SPNzs4)?uefcD^+bVL^<1V1CtVFXFy@Eo3KMo8>#i}tl>SnWY?&9EMeughP4Lv2! z)s6Qh(PmCi^ar>2r*X6C+$g8faNnedl7oHerdcUTdVCz&Ze#aT&rWWtV0IgvE}cC~ zbXaGOWH?xZS7EZ>4y7+WP=R0T>r2OAkW&L8Fc;d|{Tfrl_HiM$cZ#RDLgP$qNZ9I) z=BJn|LJ}Lkx+{^I->78E3l)x9#=^g4o_g zHCRP$t_+I%qk}saO-Ys+(?nN;{Y=+EA^j0nk-NLaG*H`g4M7zL6P}0HSwq~Ep5T3v zjlO`|jnitNN}@?hWp}Zj%G~&pfOrr+E>m;_Wmwsy)v23RHp=ifRm{^z%j@b#Kwkt` zaAplSCw+s`3Bi%6bw){<7OTwgEnXpxM2lGBg#{#g>0q9XY)Gf*A%`>)Iw_+gVK5dY z1)3Z>o@Ed{Af#~)1_-X$c5~z#SMS|bOq(=G?d+rv1FN%17~Pd)BEOGt83%mw^cd|* z8b}xCLDK7{(>~opydl$U69h=YNR7Tl#0>~D`3fY2YsuDKkzpeEI|@QzP(I#0 zpJ8r8DzW=S#{|b##FvXSY;R<_u$lpuZgtKLd*nT>Jj9ngk-{GN#G@h;|IHZHd z)S#(kA5e6C9{-p9M?WZO>}gkJOB=pq*W5y2q8owhoNTx|=c%+g%@!Y_fb`M$Lk zzD{%QC8izX6&VrF^D<*`j}JO+VbkW}g*T&_2jF5RXb-!R?`owRMWQs8;oU@d92UW- z@`af#D$=2b*R`R&@4`sX$hBc6MGZSNHEeejS41=%Z6GO08WhMv+m&J5d-m0a+iV8I zK!v^cC>+{Qj0F$z6}r|I-V<{d#_}vcJ4s3peso-Xn9HM*C!Qz6910qo$EQutjP~h* zlP?5AJ8-aJXN~Wc1;0PvTCs8c%~RM@T{};oUq?vVFyHmeHYc`$Vaw ziyKks>i+N{+w|Ffaqfl166pFFnDz^wbm8H!o#li{@fz)J69gT?&q3`z;8TLBqR3ujAFm zn<2;NK7Jz}3z?1?ad&nXp3BC*0;fydh`2NZOHIk&Ltm1QZo$dS78OV~_J#x;i!KUD zr$^@%^k0=85C`d5HGVr$qQVlo?kT>_)c0mvCRO=_4QJHHdL6UC&%X=^GA%(4aI!Q7 zUPo#vXb~!Pc$1M@^Mel)22esW5!7er9tpL5*llwlvhTJLJ9z1$YV4zhdg;2U?Oo%}ga6`l65J68?jiJ@nzmq-Q*4O4@~ z5xYwb!`*X`ZiSu;`EJv%v=)-QF`5%O^H*#7;6Q6kXJdWv>m=M(6Isd=X5raF+J%K- zXZa#nw0ux6Sgi5l>DxJ=oVwSTG*DYoU(iI8teV!;g7i#>9jLj++a5PDd@Kw0I3Lub z`^tMS{bU|ck$Cc@7_WE`4E@Q2E}dt91%qeEd+5;7f;v_u?F{C=Iy9nt#(vr<`6c81 zx}%uotasiKZI2ZMvtGeeY;^12+KPJ1rfmj6;66hI55tsp9`qr*Sit9~=%Gq$sYT59 zQL z=X+$0LeF9D#k^j_9g-KsIRz^+9pjM_?LEF69}5 zUbCmz0s9qnkfeg<$>Ckmda?{;OsG`Ic1hNZ8($3d?1o?p=w=h}@3_b2ES93NACUgPoSoqU-(x5&vd(cSs z1FpVVtq)Z_UDp&X_S)jTcWBL`4wsJ2h0eWC){9M-#32o{)Pa%bJxA$*!f=r^=y_iS zrjgd}`4g<-`^q%~sY7Q1**mZ%?8mN(PYL=_+lU~V^knDPVbC`n-xa@JE#$i6qvrY$tJb}MWau>Kb9;zMl%FJ) zo8ctMMLh#E=wKgs-huLhiLBaIDfysq?;{)uS_jJR52NFcV0F}jp!HRxmG$+U{|5O_ zK$-H=d^>unx>gEpe|!!nQbI*rSHAZ>TV}SUsxR%#`bLi8qiFjp-&< z6$?*XB<(7VYcN*syuZ%-iQ5u|{P0JSf9`<+LU`{%a7s#fN%HId1K&SE`N_-<$>|Dd z+Mlrg4I9+hCtcMieSH3o>rc=VbrlzNeJ$o6kpBd9t*;(u zsRkZ?{dLaY)H=l0K^vk{*;$DiZLe~y<{Tm$d=NrWbZV8DQJk!5R+na!G^HRk(} z)ivz`>2@R+_l)n=d1quY8TE(BwYf|>mH$p!=vGOkK2&Ccf-B7i!+E#H@7@0a_fLpx zE6Si>WI^Gd5dDFK6}txI9+ZDV`v(>z_JdIOgZTX?Sbs;fM0$HZct_jc(ESPh)aJhU z)Pf!=Ve-@^UJBhVt7iHWW3o)oYkVG&xQ3tjpFhF=1GF_o${4OZ_VGUsr@ob{E7#-t z`Eeva_1=B%JIWfE30e#&Qm2}XIl5b*qBq3nqhA`#zw<@rKm7lF(f{~|fA5R_dj0?M zMgEEcod3Bj_L#IJEyibi#@O|$-!}->x<|f0&vRwSo~_lT-M8mfixV{#G9{iyo;_xu&QCQz1zW)9K+mMOQdT0~quk&LA4o*Y5Uo zkrk1i&N-O$uGn!19pCs54tIokmf4#|ka!uHSDX_;=VQ!cW#QBuQ!U999KFwi!gI3R z{UHY1BO|$D%`a!~&noz(nK!YTwk(Vl{20D>5Nn9?TFWhB7?1FRR>B;7wvh>8B0!6M zO#z_zIKOu&#?V>}y1Sc)M|0HLXLIu@kBFCrsr`)y+}jy2e)sDrp6`UP2}mRZ0zVP+ z@(A-Wj<3r(cxw?CF^0I2WKrTZon-pOfYv+~eFLdLrzW2dOh-@ddsOice2T%$D{8g>6nKr_2d(G7!0Inf>MPn6e!@S^@Sfj zgy&B8^TvDyh<$zw-Q_9kd3{DempcRdIh!cd08!&|fObjA5ZNY>!zP>pmb%cB=*Va2 z;dhbhg|Mqho_$m2W1k8r1iKwnEs(~ndU@`sw4IwB20tkK0#QvqtW6gh-SF&K-WG)< z!TNnczoN)~g(q!hPbDZ}+GvyG-jg?KiP!8&N}>6(wxd0|dux`Uh~Y-2@Ie#F@Z z__dB^e3C}M#2}-{9~}rK$SuZH5QsjH8ao-qP+pithHXAOsI@)PCrds4f)w*tnF-e2 zRCBixUMI2{-e(Q_k{v-2yQq0csY54dyo8R$83?!<@ePyVy@H;>3twqNKw5@?WeKiM zt8;kGILuVtQt_)PR_QQ{0)F_`^f@}>loNo-T&rD&k6X&Ds(}&K@|m+^mT)v!u^t~% zwj`ACsc!Cshpc*oJRKAMSUSHTK5Ot0yQCT>#o+Ef7#O9VH8muuY7iok$_S;4j^cUP zn7DC7TQsi$9!xv0AXb2yz;7@tNtm}-?YRNHMMq_*BV07li%>PaK+Sx#@g}7*y&heD z6V@tq_7+tu+<5s+o*m13R}B^N3j2L&=%n5U#Y^mEUB3eI00v!vTI<;qJi^`=&v2hG zpE1hioU0y!&#G=@ft*Ewh?dfKqcan<=4x^--;OWb=ICQwu2-(+$lA>KxlZbdE7wpT zXUwbh7h;sODvTzkC-$-X?GMtQ+~Pc(LpC)ei?RODS=&&oe8nejwF`7t+Qnc}m1ysx z?+t(?{u|g3z~0ot7U@WOxeSVqc2nbArX4JxHax~lMC{YX5OpujeV^^vP9Waiy?wF| zqhj8uvNHZE@{v_YoQaef!p5R70|d0byGPLZhmb+mZLjHs-QZ0yt1j*wbv9KA15z080 zj+jKn&ffgSNg>PNhcT0dHO!&HFVL@F2oGo}=jeBEu0X>`bL^jn2S{Ie-}I=3`j5uC z_b1u*M;<0;`;goW`-P}K`)*PV_F|Vl<|KDR5k#q5dgmbqmW6ycK(SrU20sTKzAzdBtWU20zwJe)lq~Bs*@9(k1;3Td}ZaEnUmJ}lor+W z-IaYfh&Y~~@0O+6tr8w~4VORI&Tfaw@r5o?b!AEhLy@+F(lS!o+s#>UMB1J(WMfA7 zG<%Gq%c1Pl1l~4acVV*{aNp)|tt%?uE01L33bK0RT@6okgXQHd_lO4#{Tb~J)|@*Q zl}oD=b$5u2;t(Lw^g&CG`gy?lfnH1Y&Jihfs(p~KqSRJCv$V*`B+90KF&nToeC9#L zm}lAmVGh(|4P^S9hKlHuN`njnnPaHl`MVsTq?++hbSQ8|_(he@cj2NZ9fgA<21vF@ z{Fjy7A58HN4;O5s(lRP9Q6Y&}C_p?@JU7OAAjap-p-Yt|>J7@KCgDuL1gZufwbA-v zX@qP4KL7v#|Nne>M-IeFmRt*v1Px{&2s%QqByd6R2GF8d^uFlH9liIS2h^Fg6n}Rw z^aacm5FnFPnas@h@tp#RbL3;ga{28x^f(w?!<^3`LGL1z;kAj_ulBn&gA?e*@* zr1{r>Etavjx1}D+|MAyce!M|LOqBh(r>YfEa?oS@tyIgh6p@{x2tH$E?9mjS(d-QmaR@qy4-!9a9VI<5&{VjX{(q zwA(N)8Z4Tb1T)fu!59sGq>mSg5;NZ7R2~)ofK({GxK688GK0G{Jv@ zbz|@|;~d18PzX2L(N;dBpO-w$=QgAfi9p=ZEq0VL2B)8~&Te8?7f!0asKFI zdMMd~GEc8mcsnL7uqFJ0f5>3^2WRn=XPEZ4(DQT%engmdpfgUlcFZwJa7!Z6!xcm{ zH#IS_KTqMA(UO_pZQ+3mj!nRslYoa)?Sh4;ai~qONLGk4W-~OPb;>660hjmCr%p&a z-zdx&W4oDA1sE&Zkk2obc}JbZnPlQ%h7D2(;3w-Hl)oOXZde03(K}?)*GvV73}+?i z=#+t6L(f>e&iqS8De8H;?Y(P54%wU4ilRY4ueq8rJQ%Ko>i-shb@2%)K0U(k^ zRMnje#l|*V6j5}!A{;Q)O=nb~U47HJWB@9@TKp%c+~lI%C)C#*XrRMZ@}y6;&gkq5 z#rYy8B)X@YNZ;K&FkA)1f?AFJv!(M{VGh~QG#54DG>sI$p2Kd6%z?v)>62=Y>J zOzn}#>fK<22oPc~t)S}%XX;j%{pKAaj9&HVyQ&{EA2U?0$E?;S7MxHN*%ugE(<$!B z11v#2KpeG_!4p&&2QpU@FXL}oR~8-}nb-tDmZb$@BctXLK583*$45fe_V*XnC~RMj z6a!&+R_Wrnidw_!+N($}=uSP}tp0HNakp4eVH)*s^T)^N6+Io_H@hM8C& zPB%I7&RpEMAXmI!A%ZyMF&#ovG+5>Z2{@x|XMEfMs6}oKAnJnY!0eXR%DtDJ9V={} zy~_avt%^Ac{yxwTc#gH9NVb#xhp-NFbHgT|!QY9h2)jQWKonw}B{#U-Ku6q1U5@9J zIZB zyOiG%1?7>~#y2EEVr%&s-d^TZ4%P{`+zEJ&iJU(l6(*0x{qB zp5IF3mb9rp$iDFoxo0L@<)7C#4*pAGf6#_WnsdL+(glgY@5(+ zyg}aU%L^RpCNf%qHTNtdyzY6{%Uq;Ud*HjTiIBP=u$@0LkzoLFmcc@OKMXSiq?}Lz z(H#d=#Ggha-Z;db3OsX`WJQ`}qz;Ph^?>i;Ad_2gnzEtJ9on#vhwq^xlY8)GA^bDE zv`FQsRp@#Lb^}hgu%5MW`9eXGfD!(Tg%LD>V(Z)H`1HWz>$$ zO!gV1yQfz%^dV|{Wj5s>#Dl)kkWc1*_wgpz9sUy|Hd`DtSh=JBkc^C%#?=F()#$h; zUI^ANcd`Q0vH~l+0@Yg)PUFvbDJ^gTC-?zj5Yu(myi@;wu|V;fZ}YmZ-xb*WN5RxT z15YG0%$y+1!ndx}TL-`E_!HvQ-lOCEAt}2e?;PUyy???Vb4U?PC>3KS1O-Dz$xsNP zH1zq))_XOwO*~gZ>iDhTW$Y<(uqW~<`x8ajV$R?LF&FLrQvTFo`~7|6G;vvC%NWkh zyjGZ6#-EW`r2PAjcX08Q`M;<;^-o%OuI63(@0WUz`AHp@6ZyZtgH}Nic4K0q^tlCA zp#XJ);z(Rd7H56d{ka?kLU=S#v903)0S$P(>zG^!l6UV7i9DQDJ0z-2&YNV_yO0HH z@QVOOoPc?AW5KIT{Qq!3$(q0M%HMe9e~Xv!XVAVBc)1f;c^D*FoxNN9Cv1O<*Z9Wk z^Tx}4W5oU$xFey_<^<6eipf@Q{oCo!h$(xY(tc;sd-oiHGIzN(iP=5@~VpbocO(0 zYOaty)%FDV!&}n&ifr^f7O+mn=o3XM=KW-~I~DNMQJ6V`bAo(E8Gop_^kw_=-oko- z?DIr@Ok;4O+bv0v@=!eLgXS0A?8qm)7N$bg(E)49uiE5WkfzueRq)j)^8&I;Aassh zz@;bgL%%M<2m^?_VFaj#|w&wOLF99o%(-hxf%A6Le@J?wl zhS#c8`v+WAe0=Sfk|ZmWsyNe}K4Rth`Lr9Ar}G_`{+oJEuUz$c;t$0%U#V#xrZKtP zxMBo}FkeY=sC!ve)%~cj4|YVp)Q}4f6%G}c)i-1Ng0271L=VQSS)k(dT79`(ja&=3 z1Qo_*Uy?Z1XXmpLZ)BwzhT!YU4@X}Cw(sJ(>xllz8+j3i>^wZMC%I##h|>XSd@Bp;>DBMkXODy?sI|K{_YS&RC{cKg&hR|?ILeqL)#PsA zoK76RckWwx)RAzazQD5^PJEilyJKnycQOP6MFWOHLgSeJ6V(rOkP&Z_!%4R&F-&YJaSK?Tjx$7lZf8bl9LMriPG( z->fYN$%snlg;($L&<=$U(r{Q?F5Yt|a;8%Z^^JD;&E7EzhezbxKFBIs{s8=nhck*r z4+!lLD+#bz<8eN&9v71yT&(xY$Z0c9g1;O+r%zC)e(tLugoF zURV6pDtU9`H*jefGK~=q^gT#YA5aV2=)PoD(2&}U*|{JPSpqowmF`Q3dRuSME{u@L zAt#LkcrdEYP;wnO7{?94E_fjQEKKi0?Zh@ybvtx{ziO^-8r|f5;oBB5Ws5EpGR?+s zZIuwP5QPk7%q@1qDA4(9t4>}f3ouANcoYgWd#m2@;2+AT+1!7)YE#() zr<#-*I=|7Qj)H?*|L}A$I-QW!#kD9ULWXCLW!_Btr2`l+F?2?NF{;V~`P9&`UTkEM zhuJ1Y;Y3Jv09K5G)p;5ou~j@to@zC&+KNY|SFrgteNlA7a}W!AI*Kj6H11E0D|qqs zaheRc1b%&+jUAkhZA<*Z1)2Ll(>6!bCl>~eJvcFfCSWa+9Z zqp%Eyxiu>9z(+R07r9^7K(iMSjxqbbww|*T|S;CJIcwMiT=$ zR7L8)jw?wQ;QX>J^QK`dbS!P5T9H!^zT~3-{QUjP1mle77i?`<9P&>DoN$B^nj%=c z3Od9WIrlI9C?^TF3|t13m#-N$ecX$1d3(fFWHKJK?NtuSl?f zZP~~qsNXCF;7Q#mq>hu)htN-uo`4TS|Ayp1I=o;J*TM;4!i9l^y48nX140Kw$Rjl} zNG>XvgNw+`^=a~E__*Yr6;2*$F`#1oEfNwcU0rX0+%cJ(@Fx3nTq|T+83bE991nGH zgFgw>^)vY6jtI0}Y^Ue>Xnx2EjA<`?l+$?7e2y--Ug?fqOKHkSW1eD+8n<91iCTru zQ=yp*{D--auo13b(}D|ygd7KR zj+A18-QskBez|n3_QgK}elY%qS@0)d|uf4ht}eAktGh-|hqDJ#QDW zhHq6U$cDVG|^9D2`Pa)v((`1h{6l@uja$ zEPq8;5udFGQ+JSCjKe5e_|gQL=`>iOA>A}NMn7x4OJ?M?U`W2T-uJKJ#~#h6Il^B= zf0k?FGQ8OH>T&z}c)dBk4qDWyhm&u2_Dnsg@PvVC!MP$I^|L8aRg#i8@S6UtuD34O6DVTn<9g7muK-~w-+8&cYMmt|1v?YZV3kCwHc69;t ziF+18!1@6b#`%2=R`fdA)N|&8dZb7FOEPN3)2k3~3?LO1Gyc)$A>gyuQ(9ywPsZ7g zQoOCjO~nr?%Kq?Ea;$%Nlv|I$;>z^ zP}3YyF@HErA^zpC-jU%@5;;U^DwWeRG9Rkx5yA{;cnPh`V49#yd&~50{!*dG`{yn*ZD8!xrsBw|TF;D?%# z;UThyZjlQ+lK7#ESB%l6`S|O%rE=EkU?w>T}C)hY>%HXI-i6HYmRh77u zVD09{jjXsijmN5r?Z&i)dpm@gM#5DvS&SD?&)H9@;2^`+%9p`e{k7yF+M^ggxoJqy z;nZm!FB8T)K1UK;k45;fmM&js>$wz-3?_ z^raeAx3c~&`st_&Cr$^#Y_j#k&i1zID=)zDPodUp>oa7}oGw3896q14O%G?{1s|Kc zm{s(UJ5*ciNo2@A*e#ujM;b>-xOM3 zk0H}l3KkX;dtKE@ivDFNuNDI%?cznD>$+=LYR}$9Lx?fKzJoI+pQMLd+EH0Ni0HBzS$3A_e)KJTHuxdnZsq!^|A2!ewYGTM6a6&6%h3%I46aDo% z+hO!aMrVvk>(sC@26QiR1KkWhUTK`NK;x4`KgW6vMWeqj2+}t^HD|2eI~f# zGZ+%r5dvwyYx1sZq-3Hg9jsT?*KMQoVx&0PtU~HizGOCDyxtJ%lE_)Qq$@zo4-REmFFm!f1-?5 zh|>fSl>D^7;uy;nwMFNe=m0`#c&P-;>XdeU_|DG*FFC0>sL?K0c3sFK%zpb`dsLt? zHYSq#O2L*RVv)699~lIE;;S%}1hl&EYQc(h1LbAHlfem$2x;Ald016{xU#DDc5$J? zTMs(sI256}MAXQZ8p07o&5H3TlQV96I{@E0!0Ty|YaRj;%@&J2Fg$;dSy*Jnc{?xT zrO?tb2;yuz^<4M0q$o7(H;p&1;yzCNm4g8LP*)lkO(-lM^oWOsa76>m%ZvJGay0bb z=l=o#0RR8Qct;MzYN&>FY2%|wA8}bAvZ^cVsbzSkx#})5;Ahc$#(!gu3J>EWC5}7ek}}51(t$V6 zxFKYoELLPWsWQ7n>V&X8WDn>f$V97pr&Dtv7GeA#FuP%+Cz)+CoZ(z(BmXS3TV(Z< zo#0goV}3nt<&(u;;`D%O6wRBOe$+=A$|F+p@?#?#65#C0l{>Zl;7CO;VaY-}2|YUd zA|WmmXd8ihk9^4t1w$BtCoOp9}Sa4tNDG}I{t>CEAO|jcI+S7o-Uh0f%W{fN7J$p@ zkE|BLx{(U7o4>NHb|OCi;UE6)zy0a|UjO-x|M@q6`qO`W@r6JA`+xlUPygYc_`iGO zzyHlY;-9bo@=tudhhN(M{oj|%Z*aDy8LR*LcZK};Lbn|PYS!gjIJJW^-_wgME*=aMjY4=?4AR}@TZzy4jC>Vy>C>ifj32SjHxqIbyP1 z_;K?`>LBOxp~JT!4gr`r?2wgK>=pwAd(8dZ&kz z#y{m0VO?6{~i?hFEh2OsUt8 z+Ih)bSDt#rt-iPHJlD{f#*tc*K_jIBi_$_-^dk^b zZ@}V=bB}RehP{xZ&uL^%6MlLu$dp#8h$Q~%lwP$daT;iColtzj&{u{fY*QF1C$tX? z$Rp4JZJ-(=qnC0aqcM}qA^RhMMh_dJXrMLWRnKPoPacXIBUkPZI zdg_dAB|sN;faODb3?}`7-g7oEY&JT8Kcn)+X^m_;e_(gu*rztti}oVgF^#ciiDim) z*fIt=b5MyNRz2Runo(<1#0YOqqQ`vB_D_uD4V07DK`lx-p$H4;;JxaAf{j3c%yV$k z*}Un(^0U{vDO+pFLs(V=sibg-eMH)U?$$?^g4vWZA=u&fgaAH4g6JE0l0^8S{vOud z4nNgK@QY{A{)FQyn0Olk%kmqsqP)rqA(C{)5-jw7a=09mdg?2luc@`qWcW)X6*{^m zi0KyQw1bIkP^G8KThdD1K+c6rgE{It#dfsUO?Wa4o-h%!=<>*7t&a{kl2jl(bP-6x z(_=~5YcP38N(xgP_vJ>IsK{sqq<;W-`FzE7ZyQpcg&v{ch^8k{i=nX=@6QsDbb@Yu zluGIas)0M<(Z)2VUltHx?Y9I0Y*hdX_!Z#?Nh@Wz$j6-ZnaYrHhA?=2Gk@{DN#@a5 z2Uix0LO)dziJ=+ej{!`eCaRw7)lY6MgIG%Z@N^`R50L(XvZDggK$Jc$=mma7z~%j_ z2@LnnWfS1WZy?TCxq;4s&M9gZ!xl5-{m@=I>N-vxp?oaI$_>Hjj zbE55f6jTgB$0E=lH~lCrJf~<;R_7!Bhz&moJ=%rf6RRajG6uKa>K#UTS%{ssUp+Mz zLwfn`h{brP>FG-EedeLN&?;i09lbUQqs^cIwb|^97oqvi*k%_k{K2I*bwsJW_HT`Y z`2A_IYGlGBp9>Z?{;aFW{e2s~dFPY(<@DYob_Z1ucgIbcYGv}x*Ft1jekVNOo=8lQ zdR7va}$;t#w5NYevpNo$;uloIFYJx_abwt_mo8n|P*PVHV1+JV!+2PT|dUIxym4@v@33>{+iwIMYy}a)`hUHTDnB0asog9J`v5^}#)&P66LO9@npzvEtCcT-0J{*0Ff!zd*&sC?i)R@?a zW$lSG`O=>t%o7(^xI_V$WOfc6VJ_$W)$C($C2cOsKm}5TFW&Aw+^l42b26!YpQPL6FF}Him7sw~^h+3XD+c0-1J$J>Kw8Su zYJJnsNAX@cbrO49iK&m6q#b_o1t138)F;3o5wLt^)YLF8J@m9LxFL|Hrn0;1wB<>C zI4*IB{X1CjEFr)WDEG~>bA2D}F^XklyF9WraoRd2$`^*}5xrI)SlX!gIT9O8!e>+< z|7@hDQ7Y+40e=_Dk!c*P=+KrBd%J|I?j_240~94=JeIU1kt;|*v1}Vupl(|O40Ece5C}8T z1f2l9`AE>+wK;;)fT=!*uLjSG=IFGMDSUyX{cg7>8q;Q^#?nAp>KH7aE05!%dl$@~ z(tWp-WE{i~uux-FNSdmS#Ssj0N2ls=sYRTknf9~y+~*wm0^JOhF?487wgD}+mcw8o z?jomno*!sHR_J9+tGN7b)=6=sqm!t^n*u(h;}|bq;VCjMaZZP-bb*RilPM7pN|SlD z^;RCZX4d+?*m||oT4-8eSrbn11(h^;6c+EmN&Us|YE9OQ$}cYUjkcZZGy6hhaN<2` zg4fa$IGkF?K>Ze)D&BH9a++=!5VUrUZ79M{E+63yRA|AHPMdWKN15zcg;d>n%=;i) z1B4k{LvHBJRYL5Y0);wVJZ+InYf#!e086|oT5B8dmX{g8oJBzGio_Ca(jaUx z)u2DZAlkTzdJt7fL1Sj^8Dz8AGr$Gm-!Z)i2S_I30*BjN#=POqbn8;tvnQG@iWo2I zg^o;^(NOhK-1O}>*{y~To6s8D{$%#n_UO=CU$7oUwxAyv6i8jD`a>3+n5x@qlHmlIz|Z7GIM=Zm;8%_~{Jjg0uR1$fF0H#WJR3 zfp>zX6NhTQQIF2wTL(h^6@p&w;SV??POtKv~QB_DL45iIYk1e5Z7USOmwcxr>(O*zP878U@l`5+I1;Y-z|72xC}Q)rwU z5Ca(RnT&^iZNKsgeH(Z?TD%GYST_pnhIwk<+YR2%0(je z=feZf*I*BDMd9>QsZJ!Zun>yNTwM16$@`;6*hjw_eOvjsTXnQ-!<6O z7fMViUldnH=Ql+!lwu-Ztu-XG>gs|e;AT9C^=cn_2;z0S>{fXt=^hgP;y~yg?v2@R zO)J(KXg{y>#6S=*@TYY`ysclm4gUt0B(2+2=R_kw>RX|hKDk16)kWe#0afQ8`kP(2 zGmr|L5I?iIgtREZU$N}(8)31U!SsE^U`KaYNzuXfi^qbt&=7!ga*PilngDUj$RBQl zhD`Ey*)X;7&%?S}IwKBgw};^L1QMh$f`T((}{~y)l5$u#_IdH7=yo-G2>ok?RW-8p5F(B#Nnt+t+a|5 zII)wy;EHUI4=NVcUQkel9=8U!`w(6n+4p3npAQhV*$PIVJp+X=hLds)Sj8QcU3q9> zg}$G1K)W~oh}9qXKuPrV=ikEae}U&;IE=HqSbX=eu;2J2e*c+g>AAcXRYl(TBSL@R zsLL7n78!(1oq)`~6R&-P{X?|bMO&Z>Ga>_sooK+f`2oToXZV2mG0KH2zLaSx*}E?- z3iPG_|M!N{oV}*`?M$E%1NOo56b-Y7DtMPJSd1hikx*CnLiYxgwyC`Qtf$upP7og} z$=`UnN=g|t6yi%S17bm_REzW=@82reJX%GR>W5V_) z=MP+uY?8<8H~N2p^Zz51t~iVE!Qsbu6$2YB3w9t$#e zoKgi}Uk_iqzkp{(!C1roKY#YW|I@$i&;Hkc`fGpoXa2AKuN*-9fpV6YFH#E4_NFMc zp9nqw%b1?W<&`5k-_N8$v3c1ey|3*xr=cFj5{MzXwT0fVd+lreE`BEPQ|>cc?6nPi zf{uZdT4qGHg}l$e`RvuE4@6Q(JRC6|>&_Na(KVvu@!%s`4p&DSnReC{+5#(jrVobd zUlkZ!y0KL{D@5u%DlioU^G9tvK$IKuWTGEtl=;iHL#OYpz4Em6VsZ*3yz&uPb?CXc z?Fpg1qa{f76{rrpPzj6`!XpC`iIt5x*x>ksqrRun&%0r30_QhOTm`mp(8v4*t;Rky z`PB~@!snJ0&nhmGA7$-5#`mylK&Z*o=xD4vQb+Ops6cdU1`$F_CzU8pnImO0%HZ5l z0+HYREQ5|*kk6L`SE$g+y8Y(5eCWlr#^c$b%c&z!da*#2m+55MXJ%(7TD>;wTs#+}h-3N5n0$E_wybB=u&OXdb_(DbnQqA#-*q;Vy) zSUsWL6h{EM0-k8fGRkx}$~cJY8ln@aM%dG<(Nr)}3|U@tm~ARpOG@Uq9C+mQ*|FkuEg&J}1kr$rvlwo?@vf33+M>^BLPk6%a+zxUs&q)YGNHB=66B zDya57gAYY|HqwlD{7pe?5W_a$ZD7X0SBBmDl0d_KnZThn=Y+{<=3!gE>OM8asf&wG zF+t!cfEv?dM;A^PSfq*4BPKib0h@$085tZmgSQXO;^Nm8l}&bM`7=2{cF zNb;uz5|9nwRp%9!6sg2u;Y+b1rATuZj`b4)ZGvOMJ!7gM0+v;;M3JJ$=Zi(5sNu=y z1izH6AN4C{kRL~R{SApoeW>`46yz2~P}e>N6I7Qy@FkEu;sEwtNr1J`segnxNrFv< z3<~9O0yk=@mJ)@7wx+Ir9`2{lzC!++JOp(06nck9+2_aRp-|*E5w!&n5 z*wSj&sqPZu%AA8Y!h3vGV#gD{*`fRT{b+DZRtfcj%EmR|FWU!0V0 z-4RO`f8IqG;GU((;?iawn{s8zRK15ja^hi+N*E-TzeD`2sKg3g;R)98$^loupKOp* z9`?E4(kwQB0Y=MnCyV5QNEM8OlVcwQ{k8CX?;xM^K3++veY zNU=Btp_HsHjW)*ojlIRy0$~KFydB4BIMELXdo|OS*oq;F1!F&<5+W_S)i5eaKRtw9 z?TzBrmkj7v`oe6#pocd^K1hYVjfBA-@VLeF_td(%lg-7CB-l^{(NoT}>B){->qkNz zO{nEuWTUOV|NnfL$quu?nx0RjBs#t5DA&-dL`W&-p`~7c z0b|T$GqVa)nR%YCB+FcC_)m8hXVHyR;wzxaxQ6$8UO*W43@)qBOqJmQ1cvuj?ow-l zF}Uir@i84S?n<&AB+X}SeW%Vb<)|SLDUpUhnt%`CoePsgIoUYd8uqh5?8IJ%|lB)bD?{nF}J5ty1ix(Qpm2I z&f;F(91tfVUTAlIO#KnffSQ^)p9?wY=&TP}=*|0rTRb6ZQ;MtUrUlL0dg@D?>r`KS zR{?*!!3zL%D0Pmxj*Qha_$_cwh|Mnu4p5cTxEp2;9#BBI*CF^EAI`@(ayd=ohe&nHP+Z2F#Mis zA|ykdwdoN-bTh;Xy8__nvEFqY4XpIKUP})wo?+h+W5DTyxHV(WAS;pzeU0ke(<`j_ z<=6}MS*gA4f z)=6dGVo>q@ziq zbjglUU-y;Tnp5TB1dyCPg7gW~0tY(m1or%iFqgKUYIW$8s(?;NFj#6%I?yvx=ry|o z`1WsY9`KBq>h$s#f_m^rcdM&^$!87OK`D!#`pKWI?(;W)hQcXu&#vYX zLby#7$G;Ej;EmzhjTeDz)z9t>ix)MI{fX{wwY>L$RzdS1&Mo0j`|ig#BVr1;NFjHO z4X{yE5iJ}hb@1(J*#~^(bSIDpmUC0{O9=Z|5l&Rwoj^m z{%1J#t-VZT_xm6Jl&e?vtg-EhdMFTNTRkNSdklu{`o(^$$or*=@3U7Z(tNFwg!VG8 zUV4@Px2-$NqDR(3vps!Ek>J9uEHm){V#34u<5l3F2)3InT z1WBsRfm@D;#CNY$snfb{%i)E)?WTd!%r%fM%thy7)S~)(5u5Bw=xL8XPiC&jXEvtE zyv0aRQYb!P7{1c#F z8}>L6#f^jvbw%dniO*{i9~D#SA=Qc%0UnB2OU^08;vwMdfZ$xn?OxZ8qvA}FR-&hb ze77}{1f=Nze3pz}w7s{|WWuMxt7THGwLNJ|vJ>OgsgkexKmXQ*kU~N5`w%V;ox;ZF18#F^a z<&2!JKC55zFlt*iecBrFN?i?A|Hr77q%$Ie!{f!Yoiz?_>E6jL1Z#f3--05H1 z4~Bx7>rod-Xxh+2KbIbyX9;&Bxxl2CosEqQksl{QSrik_kF68aA5@FWA1*^IlNfJM zx08@VAcRNIl7%VAe8?TC_rMI6>XanM@#;B!CHeB}r&5#kPn*$!oY5a^b-y+r2bnP1 z-6G%C#B%1|Rp_b|6rH{lD&H@al5$+fNjQ?LLJ3yua9XOVVbj|$rEhN zr1L`+g@|!W-!39azCBa%T#tb-HIC0DnERI_uWLY6TalE$!LHsD+qOyOV2BupnMl7` z$$kj|OSTkSfmN+CKL!HH9Ce;iP;N0xD9rphkdPFyj%PF~#CPk}1tmKXMIjTuODSHY!zY&l@h54H2z$S?HjmBa~gP{_2D@&zm0$Y7WlkWrsw^x zOtN|ZT{};qbg?F1yt@L-VF(*reCsQmm_?O}DI*)}*v}}0x>8;FLsr~QowD>*j^Y$z zGc8>~sbk5NkSb8HtBN1d9xw%T%1D{)L z&KT|ddncjakGm{WBf?qh$j+Q+s;PWp2&)HHRbNEAUWes51D0$Ox8c+jsyDiO0p}8+Jmacq>Yp z3FdD{cxp7zjm(Ho#|pQhLw;yp2d(y1s5MMHs5#GoL6C0>%d4`T#~aKJZ*`ixpuf)B zzvFugLKj}{#9BF>3px;Q7OLG#!HPAqeD zZq9pJV%ccC8+8Dh>c=}hL@y=2AR%7lEd<4leX4Ij8y?RrVhZ;6##YWZuGn3=hE31& zrd(0(gH@U)bU9^qHI|ja6V<9Jnqn;eQ-v5H-q~6sl<4<_myG*_w`K4puz*joW8NNl zarl?MRAWm%Pc4G;@|(a=<8h4W+gj42zs4|0W*=+BD|fy>Ch`|02-tglAXIC-5h@DQ zv&*9zOTATNotv}s5YgC)eMKI({aBy}kB-KXc{iAIAd!YYf}$3mq_DTstlxB0KZTs5 zE^J8qC$jtFBZ6VSWHl$4to4y04r>$7YDp;Zs$fo&oKJz&b}I;q{vE$h~5KC z)uwh=LO|;D(hu<_HcRKRZQu43K^j!cLXgQ^n<)*lL6X6+_0<)EY^AF=h10`F1$M8B z;QU??#d+#{J^(82AOB4SarBD}3f|A~`@|NA$s!RCiZ8DJ*vmN)H!rr+CP8r)lcKOz zNkt)8)E7R_-DRIgH;H$u4{QHA2=T5%Rek-yEMY%HIIT0rJY@?VDrJjF58(@HM+j?l>2Wb6DatisQX74AwXB_<6C3Y)u{aMJ7FS6L9 zzB%jTzP{3xhD=sKe`T4~>^p4;9-| z&#nb|aBhf4UhCmYuFw`L3to`%?6y<^=g&Q8f)|Sf_3f+#Bby$fU&?)EVZM^JfFBkz z5j*Bab$zX{qL^{6e0LR|R}{=YU<__U16YE5z?d z3k^u_aN*#w4GA4eu31@)?4B{!t&3Ckk*i}pk?*==Y_mYp7gT+RJGpgwXuDox$qv$T zUQm}g78UI3;NW^*zlmr@S9EcNuluTQ6G$Y_>cOHFlX&e%Nc*ez9&)P1xo9Xx88p|# zCSoHTW8P*s${Gxx4)xkl@55bQ<8P+4#WG(&{Nl^AI;9kB#r|3zIx?yE>ZcN&jVii@ zfqcA1Px_Jh4X`%Nr@O~_Znkrogrw`ox$+qFJ=lZUL^@1~&AvW$i!4zl ztDK(t*`9V+DzALA^SKu&A64Dz8JFv6$62G&KAjkR>frM@-md&%&PdSc+%gRAIs2*U z(uhA_+bJ>js(ew-KpRz08`n>_2lF~^YAXZz1#YJo!JSjrq4Ex?K#0~C#f1bygx{Md zvswLnP>g#}3y`t~>l&a4_~mik+LRS->xbrG2)lLpAqHm?UtHed>M>i`(vt5I`nq1N zcNv$FXW9@D_!@mAa=5X{}%7$o9C$R!HQa7renSyBS)q9 zAf}ati?YDrxg8)E?QVNcpL>A(o;SQ!HPu(h*soL&>Un~lJM^QY$&c$aRKwbCe<8VE z#PIDcu3UMq%GUACI}y*#u3P3!j$F;4j;G)y^W8LyCgAr(Nl?OpiN?y5r&|+xEPG_7 z^kuP;@UlpbRjv4~w_t$pqTe@LqSEXRU&71HCh$TPocQWl97pmdj#uTdn-CaXUoffU zUjZ>cEo!=vZyUSXPF2ujC`xEMhEDx2UIHs!c4MwH*82rn)T7)iu^Rb0D~rvGMC)4# zeu%{!n8!TMhpTw}k;eqvYPL z6U3Nc+*F$Y@HC&Huo)kG9}ev`uh&S8xz*h07gtBi>C{mV8unm(ZcF`z_K~kwnJ(9L zLW#!K!xJx`Dv{vHOS!nK7TF_9?&yk+ODvT+>#7(7y$D8_xT3Gm6T);7JK|cU@8}Y> zreJ{wKht=RW2}Ujd1|~iDIg+g53)AGRnaxHlIt=n)TlAH^h`d+VO2( z(>tH@z@B$;A{5y&!6VMcrBJMkWA8!f%=SAYH_D=@DCX;r$9LV3nMx&*d*Pdwopa1J z6fiZs;wE<~U#^_gSW}WRCD;t&J59&%E7gRA;TM%xCqIEOF(~_!k$fv6irN%c06*OB zb0zGFMW(+fQnr>ti>o)+QpZ_D{uxhaC2j$GF_oFgdnFu)vMWUR-E+7yn~Lxv+H{Ys z>a#(-&CJbK1*yc{<7TTvaa^;jjp1=+feL(^@8Bu&kU9?HQNK%~nXlnYY`{i;V=F;N zj$Teh3X{5y%3l%-FyvUotVl+O=_pzAn#D?6y|A2c|H{EHUpxh|EUrB_>oE4-n@Vt~ zba2ykj&0TQVt!|nTq2&jVVf)1M)DfeuSd@PKnTJ-R4|(c#a8c;L6Qb!dCv5%31tbp z<)@9wJc9+L$nlNUCHbDKi$?D3dybIZ>tQ|b)&PtQz3in2D&qr;goLitOhNW3!3&v0RyCqoj>!|J(3-@Q zx^=)fs@!N^NVsp^>%?7y{NP=wD+^o|GD5%hj2`}g+Y=&TZj}h}@E%A&L*E(=QJ1bOLbu&3Q{Nm}xC~es8O#k85 zK%Ug=hRG}_oVRy;Xn78Vd7{)yN)FoU*{9GqNkmSuo1dlqS_Au3jWZoA%FIwgqN}Rw zR!A)a>~n;zOYL4?x28oOlG6Ga&1En>;X^eew+m#b7wbi0s=THs`+b3_?(FvX@mz^c zw~Brf8OPI&ewsSNW`v4780QDFDeoA3=MnpD8&?7elHE+sT@sVY2&5%uaHAp65QC1Y?y4;)i><&dt_fI7pdQgA(2D`Rc%9Si0E3ZZaxW%4bUiffCvi zSJ8m_L)gNy6{h}ccSuGo`@Xn0hL8adF#lX$1UI30%3U0y3~H#b&4QV}atW+We9kJ; zQR>07WsmQf!qX3)0z=zu*VJa9$~EjN@B&K8H(+S)HOvSjGEzezB^%23<}NX*THo1f zDG2@~n(t>@9qd(SxZimO^PZW|s1>VC9hrz~cf(+OqW)EDbhYXq?gids$<&G(L@YPh zhEA^2=@d$$4N>)DJq`7aV}X(`hB+OCq=)D87+Eys93LjUg|((?7rB`D+Y|DJDEh^w z!zP0^@w{XY{ADeKV8^5Ms~x!SFH^kE-&A#?ZuU_E40mSpa)ciH3nZesLNfC2SW~5D`YJX{4g83=?QPRsp<}xavmDtYM z;GKERcB5wdHrQay!)U8$ErQCokJ*^T9gi-MeF0Ao+e~|N?qS|gxu)}~+yYU}(~SBK zWp#KO)z5u5CxeO5C534K0lj9^vekgjlOqpSnYJlxdKyD;-P`wr_zlby1#jy(AnrJmH5&ta*@l2TYeZpS8v&Ik@IWt8cFq-3yFt<*XT)%w`0xhch$^7g_)yXSj z3)jK%D4O=;-P)Nan@R7K{Y=HGa?eMuKoD7m!~YoDdy)X-dZL0Vjf))Ce9aTS^Y1Y{ zQ5VlW>4=bx20<*FS^Ygb?palfcOtL*Z74Qr7$zWVs6Ub?8Z5~BjVSa`b{3894uOo% zY+jD6c+-Tr2B>I^iD ziU@_t@!hj9{Q&j%D*JGcv|#NvG4Ytzjq-RVzQx?Wr_E0t4Yia4Hpn>Cn!9{H{DsWw zoJ)xSX)@zqGiU3<9C5J_oAEj;Mw)6Nsk%XJb27koY@zdWh;wDWr}Xp z8{39aHaD)u#f^`6Rw3L1yiiarCQZPOB)!p4-%1S}G#JWyA4ove%4sLy1~RH)r1g|~ z#n}T50|qLjmJ+T?prFvhJBaN;;xPl#=gf6hwuLYk0-8|IoCNH@ubU zWwRQq`!I>i)rzG$7==Sbd9ow27-gPogDSN(n(u4L+lF3^4KMX(;S>vU=@ZGAjqSE3 zE;qo%BPcmsw@AU*54IJ_3w?2rTRPcLwH{Y%SMdIQ>v4ymSf-3t{fXcUf7kP(Ci^?y z5A0v~Q;VsRa%uD(_80!tPrJa4Li`E+3;)nbX%Z75kl#Um;h#D}Ux<<^CbnA~610-( zAr@!CK}sFQvbA_XQ;q?5H6DocdH?^nHIsl$7Z*Mbpdq8&P;8(;k3#x~19LbtP#U`h zrDq1guqwqo!X*|Qi?o5XXsFEQIG{al!fHkb(u;Dq@pmM!5i_MEmUOpc9tu3uo9`&U z@TZnXjTM;vJ6>P-Q=c|*R{T%6U-*Y^!p9n|#_=8d7yi^oDy8cj{>0-8|IpN!<4VfU zDI>%zdnN}$KNK{m;W%HdBneIGomU$!Gw*fB`**y)@TWdG;w-o#&R=pm8&~#y9#T~? zemPU*<&u(Q?PHW>AfQBFH-IBIicV*I$v~5)rk(xuuYdaUx9{zr-}u*m`u6Sb-u(A( z{Ncy&w?F>u|Mtdz{^Jk+X#euFKkjuK6@U2)9NPLe4X-Bqw?Czq!}A$zkz9JnSWji%mssTa&g1dMS*0tCxg%^tyK1BOKN+#_0tnbwZk(E-&`j(@?Ys z^I<>b>_Cp3!q;kTOc8aP)yap7Kd{Gu*#jBlO3;%8Ao+N@MP2~e7F6<-bg?$oX225d z2_p!$;h3qmQb{c5ne=Y4g;$i)XS;c9l(J^^XqjiEQq$x<3>h*%m~5l5=S8UvA1Je? z2;&*wr{%t3=WAhQfJ^0V6SAC;uN_lw@2dxW<+oul!l|u0Y(9>w%k&80hYBfyv#~?m zNe?RJFA?946_R7#@|g20tHlCV#4bB4<+2EAE*3fpu1mbzm)MDCC*D@XuK~|qqaLx2 ze9px#yu|gBzFibNBVtca@lo-j$P*A;>;s`8`0;t29&1rlH+Jza>ek*UZymfEU+$$j znZ%w@~|xkxy9cEWVhA5EDfj%6rPchN{i7Q>26} zkyz(4aWjz;G_BA$q>s$&>Vrgot*7QGR3%+SDiQ1gsRit-Ia~opQS$`{>`IX7R?tpq zuqRx)k(8$t2c10NnH1nK%03qrb_vL(G@EAyhdaL{cjqey*qhvt5Tg6Awh6 z<~}p+1`Cm@9Gl@GTE36CssRraZ3^8pyh?{Pg8WTr`U(g82IXn_m_&22C*&~Uhf`NuQ$5#ijw={@%VUt zux33s5xS_B6QD~>W2?Z5v=mg&bk`Cq&GwBI=bLQ4PEJO&fGgOor|}XY2EAhTbQ2t$ z?x)@@uMhkdsn__C6BAZ33w*)Ho+NQ`?1fyrl0DE`JX6g|&{8su1UjtI5NNRKiiru8 z%psjBDo3kLTQ?#?f_%hvd=-dD975dd(PR^zD184q$P5mg1fE{Cg3#0x-(LZDdS&FU znfc8HDq`Js%t*R4KQB3`Q*yak(L-a+F*1C3VZ{_DZz=*3nKE$Rnx6NN3)ni%a}?LH z(w(_bxui4J#iC;)q#d!ry#L|SvBr$PnAJ3fFZx0XlE8h zL>bszil3;~Q)Z}~Jz-+Oq}10|@mpUjqV{&$Eq%<;)I0X~7GCt+q5YJYOYs#oXEO0A z1KVI7R}ZtyS9BOfjUx4@#t)g%Asn$*2mQT%K7lmD^X4TaF-%C%KrihG^`y+z6`v9SoEuG- zaXC!!#MK(hRz4bq=~iYZER6OhN zs=e0pECR8Ff!KF9bais#j8gOz7pN;+M;@&dHu_WoCIc$zG-V|OWw8h9lJY7n8%DM|9jYRdan2#eQcQKqmt)A>To zH|D;&9FCOOjN<&{J&qBKi0wwKvOcx`^|4c$Ig)Eq6$-3%SQKpQrX zgn8%YbEZ9pv-S-!GJtbYk4eFet5I`)cF$~2SnQemlAH1XTp7O7$2$$UM^nnFm}1Z( zZwpy2c@_s1F{ekCL(sFlc?V{ER|)H-Q`O~`MiPsn7g{Ncl1(WfKV_!MY4ErQ$V@VV za(Wj!t$PC6=?tiw4G#8+$mtna;3ie9YcGU#XC8-zb8y=N9)`TZ-AI~sEVd!9A$vmk zk1RbM*J+aChOQ0rie5Rugn9E^z?4s9e+{h^2}LM#f5P(G-)3W`M*9p%Xd& zPB7buQ0pZ|IF5497VyyK`hj}aAXx2y^_V$~rwx-3?-uc7SE+>rPIH$V=og|19K@j+ z+yiUlvH|j1z#V?90mSfQ4TQcg@2qI3f}M*2&;_sp50X1rmfm7W=)L!Wc;HwrE~(o! z5;%DvCcraX4|E==yTwukI7}&>&=}HjTe9z%d`!RQe2$K+{+kh4dlh_b+ z%ke1=$`R6)0^VOMHfk9JH$U8@l%yDoJ#x^%h0SrC2M?#ixdm$Ez*|0LnaNQw)j-86 zppJLx6bB1RICL|t05=tuov)BgfXOJV9veuZyzfB;EV<$|v*;s|fR88E_4kij;iFFY zk8l57C;axMPWb)j*ys3%J@bqG?|-AN`1U{M`NRLY|G)p@{||q|KlsJ|_n-Z5zp2+x ef8~FP|7*OD_<#J_|KO`&-ahB~X#WKhIiZoYMG%?* literal 194559 zcmdSCcU%-%_Wn=oriv^mIf)XKAW6hPFoH-hg4%*2h!~*BIVl+gLChc~%!-1cQ3OOu zf?`IrB`T&CQIuc{{OVTi_+9riz`cL|=C$r_4>RxQ)UA6?J$1V3U}v>riPcE6b)KKch5!$DRUhw}s>=htRjrtQs;Wk+ zhK4hZ&1M=Isv1r+n63)@mk%#55BV3bjh#60e-;vdLUKAbu3vwK$8EZ5Cy$#IO=!LQ z`c2k07kHlNh?G7Yx}zH9>!HW5;`or?W{&=fIa9M6XfK5Ch&YxC#D(t1Y{U|H-<_lJ z0otNbXabP5DjH9xG)(~DtVhA|!Qs;77W4CTM$u@a^R&-H9&EZG!TZuilOKx*dARB0 z30{{iO>y+)(>@P*yke)sc)G69lmX6WgynP7GUjr z;ApPktS?|>IWSJ5bDhQ{vmh-|p0oLaTgLzjKm)}H;5iAw?PCD>pn>)P7%u2D29O2~ z)C0gyLEq7Vb^OpkZvuF?NU(5ppsgS@P?-RhTMC{V1IP;vbRmFc@5Tbwz#pUm?eSIUkFdenu|M(O1HiucD+bZjz=@KChJ_?G1=>RA?FsRDggU zrL~L+O+kT*a%&OR>zoku}OtmxL-@EhL--&wg^#${J&luCY0oMLsv2ov*kDL1YyHVrNPBeZdDK{i3F>>HsiRWwPeG;9^Lg*>6S5eCin;>g`Mi|^LROAXmQZ8+%v0IYC^B5T4vE7je zkxPQfw7@Ze0+7J*0Qj92JSLD261b88($>;K#{%~8Ljp|*Aa5hhdn{nEAS5u501kQ5 zHjN47g#?NMpx78dp%n2R*h97>fZZZAa$AqMZ3v)0>>=wCK+bvEtWggc0AUY#I{+>l z8`uqd$Vvq8%S$TrMmuCC>>;lsfS-cLNIl|^nXrdE2LP2R;K)`>EJfT`1m3`$Cd#7R zFWNqEVn&1Z1qRTeU6ChI6~`sf;sA6B@rSzK{%@xlmm*j>t2klCj{bkSEsHF1j0Cr3 z&qNlUnUSQ=yP?@*ZkAEp6COPe+Ji9z{U#27^qz##RNPF<1JIGnx0VerT)BNHOO)Hs zhiT-c%i&)ST)-_zRqwvOukMr-9%!fGNw~~?N9nIXm}6q$4U8w@Gxy_kHWZc*K3c+Q z?hl|h1MG;IWNl;j5O(AH6B{3&L(2xhk+;(=)=X{;^mZzWdBUShqdfx5(e`~tfC$3A z$MSiVUeeBv7O0uoBKOX{vG9TJc*3(RiEcCoa}yFXfnfI1O#pM`ZGXRp4!P}V#J1m7X4V`&`)(@Z~-Uul6 zJc(Q`l?s0&@SZ55`S*n+N2OLQ^N&EI68GyD&IqZGN+n{=HAIS)sG}$3g+u^#8S#fI z_#ggiE!eBt`_|iv+uPUM#HSWb>z~P`8yQYBl6LAe?B=bUz57Sc+~-&34s3HQl0DY0 z`kz+oL(t9awh@XRHC|#Ba?s)>3hFr?Ar(M%_!IAcU!Xvpw%66ebnJ9^p)22eqM+s` z(|?b#47yYB`}&xzT>|_vh!V?yWeb&z74Q@sEnwpQJ!cc0J9@x++Ea9Eg$Qsge8Buf zz^ai#KLB~e5+h`DAM(cNp%lSuHlrDg9x1uQK(sONkqQ%J0Zi!H7-X9V+BPC+YoI`o zMOB6F1M6$;ISP(iq6!w-eeN2ovUDqYK?{bmjyu5|c0o zTXg87n)m$d$w+ZZB|hQt8lW#3EzZ4r-y<=X6E_4wHFUBQG17YO-Fx~M%CRpe*3*9` zo&2iC;ZIWi?{(p!-IBgK;>1H=7fut7I7^3q7aabm*x(09SfYBTpQhg$8(WKnCHk-F ziy^QXHAq;Z|Gtk#C#&J8i;z)|ga!9T{`C4W7a`+55|+4>?`x$$1lSdScEaDa+gnvn z&ql{a)YeX~R)0qdY<<-eAZnHOHS8W>Px-^XOuD6*C#vQ6JEMskf>a+01G?^}^?WJT zJOey)0{O{r{6@Nxn5#at)fNAL0rCA^@OL~9QT_Nn{*!0?_okzp4CYo^MPNcbdQw>o zt!x@k$9?=e2t~KieNB12BjaFQIbFKPa#@4$$_D&hQS494Y5dv$ zxlb3~`GhBFt)L5_jZ`ISSw}{b@R+u!J<)DOQKAxjBTVp`PvRlYa;JkejY0p zKY0T>;`&Nhm|0Z+_rGDO$4{P-kXNB&7&R` zsOPt_&|hHz9u_c3m7F5hZfkiU_~7oh6OS76tiOPf--V8_ycImq%bQA6y|lH|x6`Zs z?47^&<^PK`-84l%g+9Xd`Tv>=(v1cIBl?nPrd#ntSej^Eq&I{?3JaGf;DNH(Pv~UA2b}KDJ+}@;6Jbd zXgJ7HShxlO4|2oEJ8_sbzlyTYCjj^(Y!Ei`t0?t~!!^xg-tfhp}g{bR_$7Nra%gRfmG36h~1|Vmxsi z8jeyNbpiZ2PJS5y6*)?AR3hL(^Kdcf$WiRe900$9OF+X>>ZJ8*%I%EFG*lbpPcN_%3Q= zDE1!E$1+Fhi00_#F=L*MAFz+Gk)zoc@O6~C6ZRRFj%HuLH&X6Z)QvjKIYqNC;9DsV z6Y5SKhK^=mz&BGKC#hR?2s)a5@#Z6T`z9&sULA&xWM8}|0{RZPn{|*&DE5UtiD>Kw zUdPEV;m0bDBpjivv)u`J&?H<9>_;d#LUCkE19%orK12ZpM<|Z$6$Ct(hx%d{3XV`5 z*~S3wjgwE8L%|X33p)V7**N)-ITRehzOY3Ic*tU$eAXNaj$mKdO8}gO>%#696#K%~ zA>g4JxIQ!-WuI>Y@NArXE&^s*Q0xm^k$?wn$EUzXj$&Wf3;=(P>p;U%GITZp54OSe zpy4PP8Uf%p@M+L+lnmt~;31Q7LjWJEpeLi+7jHG9pu3w;jUyO3l6~=(1oV?|og)xC zSafJ}UnmN62K0+?H|t%9$CGu4SJcNcXfQF-F=yU)Nz!yQoQ8E+^I0$LS$*1*UlE@GxL&30vP)FPr zL_StQ--T>nG>L-lv7Txi!O+p{iwvMQz;%v5>}dAIl%Q`i#}!~#2CO=~IT8o-i?|Y? zk7bT_A)2G!xn4Y;iqwrd%&Mc=7ZoCM&s6G89fpo(Un~Iq7j>%+K}WMMT|5MRvln%* z4ns$>FI}pD{u1tH9qdOW`=SP_fC#=6ro@nNl;XGnz{Bw6&~TLEC<)*n@RiVTl;XG) z)UQ>z6Eqy9I2r)>J$yAZ9L2u)67VoXd@VE_#lBzweiUB^4M(vrU_L{*814!SN3t*4 z03LyFfQF;&b1wk@gl~j}BiR=@0v>V~XF$VIB416wLk)29G2O9D07!pBlngZk@H~7y zbmS-*8cM*!L~%E0I7)^J0(dy?4&Y-I^i)*)(nYq@Q>n%g3?0e7bb+TCH~oU^9D&%8 z>`NDToYB(@H-=pqB>U0@o@exYiIcA!!K@5Y|D_8&(71UKb*ny>IZ8z|N0+R;cs5_B z?$lu-N3t(n;DJW3$<(bn1Rc@7fF~NgvZ;G@7&@AL0gp6p;fK3f2m2ApzJP%ep{Dp2 zm?}WRQHmoNE)klKZ-a)T6h|;PO7(fyB759UNqu7^7 z0v^5&4}gZF*cW~Pufv0&;VAZH9s!Rq!$V-jWl;YjvH zihzf9;epU_l*pG8@Gu4*3=K!gP$K}pkB36TQ8E+^vk0GoheN|rGE^AAPvMaOK2|}` zK(;SrJN-JM-k$)PLy$Pc(Y9QTOU&nWGFubJRS~i)V`?b*l~$Iih_5Pc&{RqwdvV=xFu@ zJkq#T5AJ3i>_;T~q6tcj8@>~!3XpJ=;^+zBkMMYCI7)Gp0VT#9PlSe}6h|ijzknx0 z!%>Q(DFKg=$5Wx0|eM!%hoXgL%{sTsK>tOIm{v|yb;5Rs7 z9}YQwrSAc;yRXOm0e&QxWKPXCAd?Ek z$0*8xl=aWXa-r!6Wm3_UEC_s99yA@HPAZC%bS8ETnvPH?74=DaGj;-+4qqv=6jcB{ za0!+VO-C>@iWVgOCUzQ{j^Ji;cmO>}3p)!|F;%9Os06ka$y9iB3 z*zY;hNV*?Z082-4G&w?m9$<@|fu^Ixu0_&|v2)OLgj~&$1@u5o>;g0$Ay;!|ko3LS zC1^TAuI2~;dJsQ$8PLb_9ciex#y*R@v`S%Q7Y_!HWNYkGNc;{g3O0HqTVsES#DBwL zVDU({#y$byH?GHaz~Yf?jr~3n-+;xz;*o5PeLBFqn_~&EcqCh6e}u$e#F8NKXzdyM zSb+CX#8Lo$EZ2lORY_Woa7`YmSQ>zjWotlEq1c+7abz(o!>&WqQA(vDS#ESO7Bn5D zRN^H4Fm@A~j#4V8ki`tcN}%Z|rBa@x2VE&28G#w>Zc>z6G537Zs6V>-Wz6Nq0 zQjQv+``V2@674@{m7=56NJ)}@YxI$5f6-Ca-2l-2w4rt+6+6nhV)6EOWz4JSI^<~3u&7Y+V3-H=11klCk>W34wAn-L+8JKc}9_2+#{Zy zwbWp=)r4dEx6bN+(FwZ*49));X*$vj(Hs*He%y3wI2xP)$X9p)QBvRpH6RU60HiFu zfG!Y-m!O8E!3lt@g%?mF1tO_IX>bA{ap48#kOH4@Ua*DW1VHY>3-AMh1SgyyUI3&o zyns3>a1R%R79d>?ynqxCNHoCd@B(OgU_=TW!7*q7((AwBU!g*wTk-GLXF zN(ykOS7G4<&@x#82*j_Z-iCz}K+EJ=q(Bw*LM)sBS|-zhK!VZe@5KIb5C3#@V6Oz4 zfbJJO`ZTq_=qS#IY}os~8-1GEUvw1bLpJRFmybS8?Jqit^C27d{&%QpYGZhD;sQoE zP88=uHSG1VW{|p2bQI@9HtYj(u~uk0iu0iw_QF^@EFH!9Fvx~|U?}z$nvT#7VUP{` z!1q`uppTiZe_A=v6^%jm?BjZfuyy#D!c%a^I;g10yX$VXaO|m!w>-i@n@+Q zXrXoyn)6}k0D*)F)H}3r0%(~`KHrkClX{UBP5>>FXOl!#f|ct)HMoO=KIh9*_cPMW5{KC!|nQ*+yEQsDG># zG0q#wTGeeJx>gB&)L1sS@X_ie+1yWbr$)2E382+WvcI4Bm>SOpCxGUB$QFN+Ic@}X z)g{j`n)4yM{7L6=6L10kk9_+x^Mk@mbIUh|Y)X z_$NH2-o1s|MTpLaZ2Bi!Qm@~_37|P2vhSaGk$M9cP5>>F$<}|8JoOqboB&!TlimNM z#L?fx{c{EWXRa`;^P#%`b)(O4`-_g^e8vM`6=(+8uL7~7I3Ke0A9#B78E${Yj^cdC zzJJhoYKGfLSD3%(D9(p$`UmYCy*2O`9mV;O9si(jRBHe#b`0D`FTplC|3EL0GG#bZV*_T=;19lI-#)ajD5}Z~|z~hwSnvZ^oBE zU3JMbjOKjEE`RcK+#X&4&H0dx{*<}6BeVdb^C5fvDFyg4cmXu$L$>=<74a3&0*KCs z?D!`RQm^eo?IJ|yLpJ@Bwoq^G!U>?IG1>P|YNTG?g%dz?K4j}Zc|P_2E}Q^TCbI<= z3W@S0Um5)+-apq!Fm)5*O2D2E=z%{+AOH3j9l`mqCjolUM#z2@h#kTCu-!@e(l1i20Vq0x^I;nUdWgd4eSyDXM{qvu0Fs_e z^#x#JM{z!E5t80VH3gvPDEoa0poe-ub_B>7w&3^WK^qgc4iHH4rRKnmSr147q@vH> zMhY}jv*6$akV+<75eOvPQuE;81dvK5n?VY&sF`pho#Ci|tQ9dz9LZW8t`<7Rn=+Xi z3I`WHlJj9lfbdhYa1W@fE_sHLoDZ9i6d1mSAf_tqh9uSwqqrsn!4#9mV;~1oY4a zR9^s!j^cd6NP5xeO@aSjcO>US1N1O8swn^yJIWKz?1dyf1F|DPjvPjFJ{mwE`7kv? zZp?Z>3ZNDJO+X+;h#DgYCxBKmCy)Yx)F?SP0ko32iWF$4#>v46pq0$&Kp@qD8Ywr@ z7W!kYh(Y8?*6Q^`!dj)4;N-igaN(mlA2ASqnl>H-bx|a@5SsI`Ck6K5
      lM}X*j z^nk!Few=(G6;1#x3A{-GCQiPS3MGK(e3XGe%2GTU`WzrS9~V-f6pw`$KucqDAdoth zn(hU+L}+OoMG73CCVasOprtV{5J(fGrhJW*#(%Ce{|rKg{I-j21?V9*RLcsAj^cdO zNcs)Pe$_vNkYQur0O+BUM;|)(*UF$cA4!tFhZ;HuwK6EqXDOhE@lve;C_0MsF(Bza zR9^s!j^ccLN%|YADF8!9ay}TKhue0ko1SM+)RoQ|RCX&`RcNAdn_PO`?MnKr5MMq(CS&jSfx# zt?d&^3UuP+bhME&;E%N;#+V~nt6SxSwc52DKL~YEB)1Tn^H~7G-&Kwuh893{K9hk! zx-L$RqJlaBW9Ky+IR8Rtl&SyLjNDapiKra!Z^I1s>e83OE3!tU32@ptI ziRZuzprvsjDNunQffqnaV^JWmOCLW91V+lTKUac(W+=nD2RlFy^`}}^P;?aMqf64; zAp2GS%ut4neLJ9sIZ(6Zp<+jIK1wA0HZ@!xijLxZ)&Y9>RH`)qMMrTyb4dC@sxJUV zM{z!pfF41ongTF%BkI03Yhxf}@WnvRpB)8GWqN~RGhZ~`Z%r@;xJ zIUj!@kS>9f1JvLI(Aqx2q(CHII9k#FW37lG=t$Noyq2(5>7Vec(0dfo`Ah}jXE@>H zv?{3eL3BP_Nr8JfIj{;!0MYp<0D-i8{0j6EAv&M6Kw#H6ya-+ZEsbZ90@3(2cmcFD z4kraT_zidgv^1szf%MgQF%TH*N^li%o)3EwpoisBEh{KGiu2I~^l)Lgeia!zSbSLL z<4Mv(sj>7>v7oE zE14>!Ko5QwUI49Rx&ndp^*A|QZLG@{wM1wo(}EOufRh8(-~`Z|Pc#t7n2D1!)|`pD zJlfnQ>IhJrPobg|c%SzYRu6v)kh(sK>Ode#0ec7pMoO}OoE32ZXwGV*+YaI>_9W~P zbogk-N70B3|0nhYS^&-XC<+6C_!rbrF{mAcW_%Q<0)d2i)Lbz*0i-NeR3HT|V-4_2 zgp|dKvw%RN680Eg04a+V>7+mk_7n(=v`7DG`CLUD=cA|z=>89(X4spObOht0CvK67~jO0I6i=XpsV$SPQ%WQpwDbB?X4CHh2Lf z`k2^T`nb;V1G?L&c!#1e){7(IEx4!_5^VFTCXFX6V*%4rQKS zVISa^2rZ3ggCj^bIGgl5_;;lQWK_ zU&P3k;Yi#6uh!d~#-z^rzS@*d2-Fd}x3kUn)6X31+K#l8z)aPqVtgi0*UHy z!^SBAv^+2%1$K`JL zM{z!LNctf54EC%dIUjyN58MhjR2=L`B0L-zU;Td8qkPy&d~hivyJ*})APCr>ik7hXAJ$3N*N z+^}&{0I}^uHvQud$Cj{b>@B(OQOt$_L z+Hom(0i-l$klp`82Ymc!C*aQ&7yXR9^rpb_D0c zAbb5mnp9H&hK}NV7-XYAXfNDQaYJH9qBtK0+2s%BhinIs^LLRR^I?!({seKjsrMj! z#NXV-Fb38tAp&mdJtctTd>CY-Kj9B-te;PGN3{C*a`7o$Pe=apk3{C*a`7p>{e=-g?X`DONVsfl7x zM}X#h7-Yvk`7PYAaqzJ`A$&pJ<3{jdo@KW35n!vDUYhwA>nr&?BHUc~?%#rcq} z|DctS{VG65aXw_OCcZRx-&(e~Jt>MQqHAB6$wb zoDbRPPl=-jiNOgVIUlxw2J!A#$~S737@Po-^I^{i0;w)=lg7z&faZMIlSqL&xJl!b z0Fv`zy90r=8E})vNdYwH!r;ApPktS?|>IWSJ5bDhSd z;-)1M@;v8b1j(nUMnCv(b~@VkFT}tfJlWJ)kcb@z(T;HN6_)S^Uq>8#`WHcR0>{V) zFD3we@S)(~3xa6$(U((*2bwqlh!?-o1OU-ygcGz$NKA<533Y~4qkKK|_*EPq^4rYO zUomHDb_4B&@EsAye>M==pn0fGTMdBre}J3+djq+xQteF=_Z6Y_td@<)9o#7=cR(&> zs=r*nrJwb$kYm4`k3~#BBbVmrE8)slQBoH->BeqsEUg8Ye z&i;SdN|7awkzgx56Ipm>M$&&a=h}P3`I$MHz7mA$@UKt-5Ni6rg&O0gJVLAoK&jcL7w*CjI;I-zS)Q{B$!A=+b{> z3b+NSiuEQ1`-%DreE*-572`M33Z#J*u-`^cA8iFftN%4vkof-|?L#73eOtQuSka~< zM!N$<>u`m>2Y^T0v3-F7bm$$M1*qffX+K9>17gQ=XWm5Ev7nq94$&6_=tvc1Lw9=L zE}qA5<@7no|8G?^av*}k2zy`^u?GP2e-D1-97q61ujWEm9y3q@$Uv`wK);*P?g8Q$ zfeOF}nob7#gswJbpnQ;l{v-oELnG%Wj1edwe4w!)(1{D_lR%)O6o8qt7RA68fY&u3 zr2^>IfH`^r2nb5&fiD2bAXtZ2bkaqPR04?t@NdD6SO8wv6VXm9q1%lWZF(?TwDBO? zr7CptvOoILLf6*UptkDwjU8+f2o|BX?gGI&GN@ojU)ui@?8r+CYO8?-o&2SGqiqCo zX%V8`NiOX%`e|^^tcX99RTcV=8<;@Y$@uSbvCaaEclLW7G&>uWTzr<#@muSC_Q~Hl z_3pz@vUWTfr!IAyeQ(_ED4q#|!YKfh)XPhN0-gu5R;-k^{MMAw_o0jUi?(#d`~{T@ zS4c}s->I0u@xHS5%B(B5h`*#>_r3g#>3oZ5`L(I{>kCkY{E^GKT_04H9 zZbwUF`@8VEPWgPh118~B&qANRf0%3F^UC;PqszzNDGha@UXRZ;EWKXVbG%|W>Z^ya z(;L^g@!v{=n|hvP8RYlml(>|3%5>@)vMGC)K_A1qy@8J~Hlu9)P zYjC#}HmGs++*|f?{A)`Un%-wdnl}Y&a+Td%_He>8BYg_>Rk`NwE&Dm#%*g0M70X`! z+9-)8aSiU=Lj8$cHFt|_PGaUDvrxsVSG_h$x+z10Yv69Nk5ipF7*d#L*(+5WHLl4) zgRAXsv6pi?b1>Zn1~snK`(vFmGP3e{GaqW)5yGjGou)Q#+*8RHn%lcOTB=SY!@* z77owt^>82F%PGqo3@#kD>b0mHl4%;&;QA#EhY8fCPAqats&`R5czcpzcx4S|FY!6O z-et03`12ahbK*lry^FeG_=6hGwTVTI#7{I0!{5|!ei9!t>YG&!!|&E`c1UQzX{h1co>16nchLp9)cN}O`TKVA^<~C#&y)|gmPZD(Mp?H;ZElTn zZjB0Qjhf#Y<=z^#qBV;6`%7A*wzZmTFjW*-8N%#pdY2SmUvezhH? zv)|LZg!%g7W4Us%+~ehuzOAK`n6C0HePQ-~dY31y%TusxDqr8;Snj#<$iUX9pw?0i zrmF(0K$zV~?^59F+ZD?-i{+jwA7qygmXr_vE|2tYjk0PTiY*_kC?7mtKDaZMo5pJc$TXYD_Vy+9MU?JTt2ubmV277&w<{R zNBq+YELSNOA?Yf^a#dkP>oJETT8HAx2UBCY`}z9x>0PcEyG)+dBEgE*We$h64(%!* zJRHlt!Pn%?w43@249~F zy~_e)e-&a!%d>`wP(oXyJX@ojTBCwnqa0eJd|HQ6%Ln(zatrwSTAFtBl2LDP>06 zv<*F}81#teip6v5g!`PNy9#vJ!Nh;2uw7TO%5E~F3C636$oCbI`zr8f znM!y0=&)M|OffUswykt++t7=O$i9lmjEcyHipYYB$gdTH+vB;fh5Le~yS@_t=t|bt z<*c$>%$6I>Xot3;=8D0{crI7CZxHXZis!agL|V6*UuCMSVu|as`}Eo3TI@yAUGxcE z^zmKl!hK8Qxp(5ZA1VfSR}4O?7`$9D*j+K0R54gnF?gn8kofxtDh6LxL@sGFzs^)~ zVrA&FHKn_xg!?-1z7F9&DZG#P|2Fa5w-u3#+sv;q^H#AO^w|zm*baJZV$F<%`&P$u zITeH16@$cz+P9hCU|L*cTHI#lIk6h_*~Fp=3-=k}eGB5b?G=$WZKYS4uB%x3`s@ZB zcEc1lv1(I=`&PztKUEBJDkAOLO0P3romd6>Y+{`hg!}yQKD&5saXgne69e(w&Wgbu z6@wVzP>6C;!!L5cQ##>s@A+NNoo~ImenoyQ@!#8D6aSg+`TBaUh3!rMJ?}N%uN&`n z&-tf=!N%Xis}i;POw{g2Zcp-al{wCCBtD7~A2%lXwMZXln-U*&iH}=}j}wlwZxA1q zh>xDc$MMJ6!NkWo#77_EBk}L{5g+;0?hmd{^0OfRU2)>0I`MHc@sapH$>$lQx(ZeR$=R8}&58GQTiqLoJWVn{=x9{(+>mUDnN|b0>dP})a`;G3`{Yt;}qQuKGEXq~dGrFt$ zrG9G3i_VBHw`kAnZs?c!J#|QQIDNQ0y1lHs?Ca9%d%V>Z zS9}!}WvcIf^X1Et(5y)I9hW1mdAHUV&lzWtu)OWr3{m^kr)@uG@IOp4YOC+}%@Oph zbZFf+W7fl1|8~X<(}z2I+9PII=*0-P&t*;1+mYJt#+soQYumnzWvsWeuHBC{`%=u* z_Qfp2OFPcDZ(+@h8rN8E;;YM0XuK2XJBOiSS}yu+dA}E1$h4}VRfDDNop88g0&B8& z{MwG`EM4!!*BxRk^{%*C9eS*(T?w~3lv$cx@!=ijEd8!TZU=9Os&X8?LoGy0IU%t_ zGGvl+{Gtwn5FO>j>JBVq;*mJb4(*UBM-onV$c1PeiTCU<3(-50_`X9hM9n2mreku5 zwoAhPj`1OrUE-ZOOhR;B5*s^2L)4q&OgnT#rZy+s=uisLY>p4^m=mJkoY>dF->+&O zC*GmnuVtQ)(IM48$vobn!>C`!Jh7oexPM}4oPNjD{wbvi1sw|g8l~|*9kcrNN)x|! z(EHmgzWR_!&Z&NyF6+p%;PJt;WMWh4J-qbw^)DxFp8n*IES_anyE;=+QZh3-Xy*5? z!?&UMYEf}29h&{xQ3-h+GX0aI;$1sT`*oudTRO!1)raCNI`sRe4keUzsLYu7$#qe? zmZIpQY6IpHMd9iyUnWCQyt*1=&dm|htg>M)%MsD6)@Clw!B1CtG1ugXovxN+F3iC^ zt5!2t<%oJ#n=$Qkgx^<%GF@`S-&YGVtr$WwRSTF)86q;(lbJRQe1DY(b2US3fAx6g z0tV((wUW7#A?j3Z!n9)uH&z8Q*D=H!t3{dfz*+zQVeWp~Kkt~MmNXte_dowLd?SxK zw=W-fzp|9zX6!^XxB%#l(22Efc%-O@3RoY{BZCk?PVfs-}y@T~46a9!s3< zkP&&(t*5c`(N$AfgD0D>g>#KJer;%K(zf?aS^j%Y^YHW`#=F-mOV_^p{NUH&2fv?B zDf6k)G2hnNmpY?ZX`PGMX`5{gr|ukxo~^R^V@;|-@Mrn2UL{ed?|HvT_B|;tg4rHj zBRj3B$h}V1wZmuKg=gW+su5*%i))#N?nj+E0=UeGlwrJWo+7#Cn+dEyX{0558pM0gm`|kKwnWBRN z_xD~}#}0aCvChJUImg_8j&fFNy6)b(-wB^|jFcjCbC_ArZ7R+wS?~TNy&BId&iVA~ zy8WUrSL8!mv{#r~{ZLX5ZP_cF{N+~6uZPPDOBG%$%l*AI_sEgZBVsjAr`5a2`p%qS zJYNW_G);|RG{1OW-YKZMzbNo*>1w{W$Jb?cUP^CS##3B!v99vsOz?xysPnv)l@o*e zA|Gu2OxwM+&m!lPu2Pkm`r{Yx(@K@j3$~GFuRJ$zMmDtmh6aMq3lWXM92mXUy z#Y02ixIYJ;R=@Z4;hy<5#NGB`t-t(zz2Umxv#ga?b#F^mJC7X@4leyEc-rI8`E5_n zmp)ms?$x%VMK{^G2k&*%y?mE>bA;lWksG|d+Ul<4!;hL9`wpkau@>yI(sce`vToB#% ztIhP1in-MOhRugOzRKGb#n))n*ZmMv?tEvE-E%AC!|#vU(!FzL(-#+PQxo3|V~ zb^3(k)f>KNTVtM{7QYmiS!>EvDz5&JdPd~k>P;W_9{FPTuBH6vS(oP?gW8Fj3w?)N z8$F}GZd@`L_;sVU_s8hKuiPD+|vfn%VFC^FysumUKK|^wwQ7 zI5qIDVdDa$?JFYRmF2i`=}h_6{=_ov0y;k99#_ z8G2e9Gdf)_y=xNh>GLyDVaz-+A&(I~)LC|G=x4R-EtiJjrob6nyqioo+YCZcB=94f$aNnK1LOKpDv3q@~jV>NL^OcY?-Eh*&xow z_eJBkq%55oUSE1{*oL1uzWuRA&ZP2_@wV@`rR-4V995Cr^#(T-QrMXL>aNgD{;2w6 zQQlVbO4;|^8FdHFo4uYDvSRJ8#5mbR-bG>(cAF~7y=jy7 zSj+duOtQ^9nBuf-rPAY)_l1`Z>ASyGkUp&W{*7wM>fEHqI$0|dyDL>1w1r#_UOdKM zfBa@vuJy_LpA5@4OR{}Uf)q2y*$iZjvy97^f9xo_&slWp#$yXACcHiSeDa%G`dQi7 zM3cspN6*L0zsuL0_Q-ngLeq-njbdqwYA&aF*Ugzn+p*y4;qv-`10iRp9kjA_y|qZ( z&UW$EdfhJ-0&V)|b7tSP+NZc!ZpJ{)guZ~Zrl&Q))FYDFKN{SLHXT}+>x%A^v<=*WZaO1qynbm0E zz0K75;oXPM-;6vnG|mSebw0`pdSLRy*2qrlR=vTL2VYLx#=3twUTN~2%X3(HbI9C} zshJIyS945%7#vx0LTSf(vvZt;?^4HDnZX};Qm#uJJ{M9gL#uemjXTK-x>TJ3X zueDp1>XAJC`5amYM=;}?lHY-KlfymR-98*#Vz&6)%$1r_;y1rfudUX2rrVS`bG?4U z?8_G_YqM)A1rHW~d>(zB&-#J1zNNQ0?`kY#UrhWyooN>vnKx|@&`kF9=vb6kSR3XD zPsm(nSTf%wzC$O>^G$GAv4tpl$vE?XYA;09m*yt^!qOlwhgc`$)9nMDhH5zw#rScC?31xyW2JOL68)u@5hMzOz3(|KJrY8R}AZ|LIR@ z?OB&~vrDXhs~}X z^J~{UzcPi*+E}yfiu%R@y**P`D-PK2ejso$Q)ohteS?!>XR@bX-? z@RnE*(|7LUckTpd9y<4;t>c5Gyi-r*I-5=EKF4{r?eL0*_;X$Mu^so;=-Qq*_-F#_ zmi1YU!$Of0tha29(9H-s9(IPOvhnkd%Nz8j7=4b*I&QG~v5eA%ql+dc&KN(Cvd2w$ z^_$6N^u;;x;->zQBYulEb^_(r}{u$;I--njFYpL~U>#MgU_2yM|<_`A~V zT2alIflr5S=N?xXf1-cnQg)|5>y zZeHBB>*4N$Syj@Fk0QB3Pcv7aUb^Dx`(v`#^Sp|(Bkczz7yl42FOha!5-EQCnd|K* z)>ift?HA_1O)C))5E9>c`Puw&mhACA8(;En*SNeE|CFuvMAL8C=l44C_jVg`=V={Y z?z5_W)2|s0yWco>Yq|BVwNy*wOSHQz>~*ZB&ST3>^%oNJjvWbT%i6Y|-eH?yzWsP# zn^=N>t7+RE1@#FRCG}?xTrjXoR0@7qePQQ$`{_&01po9)!0k3Z3wV6kuaT>%tvP*f z$;9w|&vACa3rm4P*;bu1J@34-@!t=P`S>DwoA_r6pEMEJ_0_@F_TbT0;Zp@+)7&B0|N!o&)oNZUMqs)SDizmg~W`b}+-8|NRoYL)FiB*Wd09onBtBiMKK-#-PKZlCqh(y-eAIkvoYLEAkJ?%{Ces}AhcG^YOtdDh0 zg&78g#g{gI)pYKZ6!)Gq{qe3tYQH?VU#wrHzt%3_y0&Ot)3<@*WG#oqcFiAnyGvBN z4NcM%Pu|Y|np9?eb2udF6PtH@qj4ukR6<-T`TOcM&ua9ff8MFv-|TzaSTIg+ru16Y zi&6g{dF1V9-c?jo1W-7tgI9Ks&(|ckmt3luc|vAC%wP1uh?o;U9I~R z&6-7bZwCZB@8cLgjb6_VS0C3N$F4rReCI7D_V&pk`O`lK^YZm4a?Up%cS(E{u)^VB zdHCATSsqIE`5t=OUn3rz{_LBnX~L_gmit(t4h%uni1*J z<1bE5J)=B6`I~Lt*>~&Q5L-iv zx+f-XnsaHs;3r8w<2Lqk`BM(34UIP#C3 zp8dkU^`&*-@_qxCea&AweHR2K&hA~qcCK}JL3&!gQ zOnwwlH|I|1(mR-6d9HiB!iBYZT3ITFS3*S+n)p`QJvzBbzWuS($F<2y=cG2Jy4VV> z3M%mXw6&2na8KgI!}p0&AsKV)_RL`3jhHOAbM9q{GOp%_4O}Yy!Q)+ZW@^Y`#XYOo zK~f6lo1CZDU0!ZtuN$DxYAEV4j{JV*Kn{<2)q<^Cs?-Y01(m`UDZMocKhi!BV`UQ; zx%hR-_*9!d*`hYd*b~>X(ryW*HJ!g#d#%2CKx+nT+?jy`uZ5j_Rqd-!d*+%g{-hJ>f-F&m+3Y4eLe{Cx*`!VKK%{uJ`U-Pbo%jzci+0nA?p76X7xsz=r zxypa3@+rr|m-g5lEIFI+pEkAIYJrIC#&=)0U2PFib2)v=yY^E={~Y@_Pc&X}{FVH! z>*dW8u}|()a@lP1e$C{o$IJIfk7Lm{c+0wdf5WeFP+`C^%71S6bL?|L&hARNtU-1A z{-*^w-KWbMu-XQD$NKB5r>~6=S=A{sP;~XNW>MK&PTJlR_Sy!vgD>~nRkT!B_3mvK zogg1(-5qCUvpPX(F;8RQ$J2{{xhR#+PCey#h2LL3*P+5KMf`?#k9ywzAQkEFdnXEd z$gLE4Z@)NUV!_pvK-_D!bKPz7HsRSF!>cvFYkTj z{KGle?^XA$4VK?ot+XxnS<{wURt`8c2Wu&8UNz+*{nf!e_r(s>)!Y;g3-o-+<`=u|DN|ntVe0EXqr_lnX z8U1R{FE3D~SN7ZaJbU-Xd@F;8S+_1v^V5tMXn}{LP(D=kF|xTs7UM`A5h+wX%Cj zlcqk_F`V?uUS96`kAxlLJQUWv)8DnwRA z^z}DSSZl=5gM8;Nu34V9WE|h4XA<6y^cy+RB)>*Mi8OgmR_ddsTT>Ghky}34+ zwoY=|MuCoG&xP7Y4|*-EfA{Qn_nK*inVqG&(R%*4_uz?#te*#8S#OScB6YmKwC0e; z>jlsCJJJ`g?N&|O<}xYZ!;UqR>@M%mYL*#%So7r6eA(NVF4Dt8cfCw(h;d$>a49kP zM?at7>SH%e-Wce0{7#&^@vxnMxxBzEEpEk$lxtN#oHKj6%M*LDeLU`mD3cJJO>rNF&bX_`&>mA>A`^`F-JUR}L&|MAd3^Jy^+ zeF4|RcX=59a_sR7DlysCTKvXDJ&-Rhq-BNBf*+HXTs1tC-*RGsDYN5^cd(9mn-jfx z#hIoQf9<)q&OUM!ZtT+h{$hoMy2Fl0b%RYJjqeUg*DNqQuts#@joXcBOKeZ&$|(qa z5!u%{`|9EBKwq9ZTeHpWtoOod>Q_%noViv?zxU~z6|>N~f5!B2&CREZRmT4ip^aPH zd{A!tWJU;QotSxPr|#L4C$_LNwm#W3UB!RuD|y=QkMnn}5;O=u9sBV>8tr94_|3Mn z{AIID3b(B|BFC^SdBzuGb8!6h+n21(#=R03q)(a?^Xbd;j1a@+ z3$qLsH!eM6zv!Z)*hfWunx4=h`OfLvm5ruKKYFU>QWf{`hk9-NZ~nt|ZaMP=QiU{5 zef=U?dvn9I-GRk#tVF#|+-ukx&7S8Q@j0Pu5B=pa2X)gKc{;f@@P2XBU0L2 zc|1VJ6;y8Z zHTC~&bt8C#q;^)DRb^k`lq9t{-VN_VT6FQ0%#=;Le>?Uc+Qb{YnboEIyy(nKC7vaZ zb<^o5$L*Nts< zCj<4K-?{Eqp2~4r{d3@fQ0GmnP>EZq`AK^-Om?!~ui?x58GEN|k^bgytdcPQ9YsqH zB~3jdu}stddi3?y3o{$5-WJtV6C`rFiJ-?*w)WxiCrlU;I%8&T<{+`d6Y_=oJ8p5qa(cR0t$V#~dz zwK$Y%hVg&f#(D7cqWzkt^A^T#dtz_-?;5NX?_b_h5HRI?HvbCajS~zS?(iKut~957 zLE|>Tz07>e&w<}_e>x@@C0L%z6XlDaKKHUML+{ssYRR(HQ|m(_-|ast$h;eB;IR0dLUTcZ5CWQv}o>*~P7@gEuwZwotE@=$7j-~{$J=lx7AnVqfEuN$t{o zvkIi%DqmRabjX9xZOx+x^5dqc+*fW~EvKPA=WH^sw0&Wql4^BCjY0IXrI)gmgsVi( zD9?YJ!nV1Z&~tS5{qD+pcFlTC_|UO7e469dMY5|zSLcg-lCnOW)7s*}Y;e_isJhE{ zlfkjb4>#z#iTsyyPJI#6C>?mUUEKQGM#kgCjF;CQU{UOt%@TS=Q`fH1+AFeHVT6!9xB z=MIhlsl05gdJ_fW$ZFP{}LjB ziHS-ASq@o}E1Uvl$TFfkX6SQ&r&HNnsNFaNjEw?~lKjj+Q#4+{V{%gxgVU$T1sevv z5H}6+NLI>f9(wvUQmDXLio)KufOhvDZPit z@Fy=2*I)4h`^^jR!~WuhyX1fMf_{6!{m~2Z&t908uU;ts(hIMjy|87R2~{ufrD-e? ztA0HGF8}}l|Nq39w-SZkdfl&Q98_ui1TIv`LqSfOQE|u_4sb{vIp@rS>6u)saBcqg zN`+KdvKlkPVK@bBV1H}<*0`o_&R5I5Kt zlG!5$i}&DY^M67kH?XJw;va08Sd(iHsIAjel;9W1D2MZ(6t(NGS9yR=XE9AXKu-GP znjj#V3dG6({onl0KmB?8>v#X#zxvak{_A^u4}bd4fBE}Q|K*>~|I@qw@Bj9f;~(39 z|EKfy?#HD0yT2=zv3Itm9?HM{n_PK3v4sy2@*t2A9OdSDn4O_XRlb-ZYl1FTLgaH4 zA;@WHee9(FAVDLMqe>INy*u!^SDxPO(q{rc#a=T9Y@Y;SSkPn z&2wx(;zy}0|2%eRuI2zdCk#p2Qvn-i`-`TI$;3BKT`u9IYDJ#G<_i`fzy$f&^M`3w zNJw)F7i1~1W;sF_m40NgF=T5H^=Ji2K~$i}WFdNME(Wb3-({7S%>A;y z7_c~~N1UlO>Kic~)V#(a8AON8F5|)k+KJC+8x{q;ri6eeNqSsZ_p7gTq7_Ut^@K?i z2=rbVp3c^|xL_n1<#5xH7Yu>xG7@1%CV&=ex!zJ}XdZ}cf1kFrubNiTJanLvPgH&4 z`1FaGmbfzGML!0*Q1+qjn}-5A47xPx*^*7v^#O@CVFPvr7o(z0Kr$$u0g_-DA>7mA z4`l^h@MJ&z^l;D5&n@G@ah(SO!@&SYRZAGC?LY;|QPOXrG4S&3!1$Y}XRr(5Xw9;flG~e7jJy zpKT2t()G}}JSZvO2gtmB5`=eBOwkCTXurU)@$Kr@@-M0LDBbj<8JV>CF$<8Cac<_Y zoP0pK-?jth#*dj81y#fXS483c+jNAuiXp%Ky-8q#!VVFC4s=6=w7c|$9X5$RBECB_ zA#XUUU+283WWr4}9V4lE=m1EQ?qETPq%-siNcn?r8PaZxK@1|v2b2+IbQn}_sijBHq1T7j(uk0T32i?Q z41MuKi;JuuP||XYIUMAQKrQ^16oE!@7dG#cWTdLvDxsR)x>#-9_8BZUQ9}3-aAWw; z_0D}VN9>}EzCM_9K<4TI$@voIV7lQdW5Zq{UJn`vG~}^PTCKPvnnW{y z*v<>kgYbq4j?YCjDV!)k^l+I?9ePsi8CZto_&mw|fl;SF3mxIO(ar)+c;$<$FKQFP zE6X6NekzL=d)KAKL8_CEiRpqKRc7m!t&Tj{k3lJ6Opk7z#lo!L_Xd<|ASURUCm$K5 z1P~thV88FI+3O>^JL`m>rKE<3J5+I&nUVDhTjCFQC$Oy09pE|eb5`Lv+Oj1c*1JW3 z0=v$KJ)WPwE3vL>YKre--{6SLA+LZOiJ3;KL!Uc+#HhC&x8HZR6cb$vq z$H(>9y=3d#0Y^=Ak8vjE6R`e|)ND}9mv3g)kg!0%8{96zFt-|eEH3DoCUm(|@U!HX z#2^bY2M-XD0+MXu@e9R(wl0!l83p15TcW#J@k(G|H1@%-eO|e>yY=uA{J1g}z(Bz? zUp%O4a49O-_#xOa;L5qu&9{5bQ`cONPOfPU&QEv_X1c%HQ}}x1q3B@s@O>r_W2_(X zuwOh-bVkyFYXKI#@`uCw%m>0BR3S%@00n7uSV_)F=WE9(+#G_>6qO}>Dfqe2Oof($ z;#bWcQOM^0h^M-(z&6*tb0$BNLGsRv{Rhk? z{f=fZYmfuX==0W%h)wAdD491WbX4T$1m8G! zC;S<1S~9t$URCtBz-Io+IDDAnBih3_hBCFxd3K3ZFaTuu^lxQ}Kq+E2k5kTpgI6v} zUlmLX_;5i?>_HTnB=EVS!35`Ue8K5h5Rl>`-dgML-~X8z{yn_#kN=7n{_+2r7qss= z|4@aip>a^p_O2Y1{m3fs*U_$L`*|SCVv^b*;sQ^2n67pd17I?Orz}Y+YI;+FpBFf7 zAyX&b(AtprZW#cIA5jO@74uc{Vot#*(kgdAek3fmbHSrEFp$V;&c(;)9DS&l+vI4t zd6fdIv6#l*R}IWuAR+__%K*K#1s9nFoS0;|H_Fjq>VAXMF%|zeUdRZ@G$2jk);#pl zsxl?ClD@OCKgx@7CCdJopfV9thtVcBfm-Ow@}S(1zP)yMUGgkQ3r4CDJOU(X;QXgQ zc4a=DWv2vRkR&pmhEW#IueLIo;8^Mc*rldn3i2vt?DKpRj`I3Fg#fh2bLM}62Q#<#X z)3(4_TP=2EOJ~XF>KjTly&eLvvY;KK(yBZ&`jZ+!t_6CTHZ&NC(|Xv-Tw0g~-&HeK zsd}<7f2~2t_gp$pi-jUPt9*bQCD~=+ciHMbH#$1#CL3G!0IEC3V?=Un-eXDlS?+Fx zb&nAdzrG2^}8KVJktA6gDV5#|ogN|FHXwwO*A#O^)vKjp?;zSHKtXEc@&; zr5k$6qrB$^lLkUh?2k*r z-6Ybw%ZFehQ8?Gm07+HE5QSOEVJGsfPk6cvMDEq4ge-}K*)oftUW;SU7Qlo29OpVJ z#i7vVv=>?RGSQUsqOu}36RxS9bX5`2sQ()-eu9}yQWHZhd{4r}>vWz0>VVW{WGdL_ z6+VBJb(>)o7<_?xf~1o|GvvF-5Y^JCG;=ZgH0T!W0^_(oFvD?Q22|3ZS{pwLTe|5^ zAveQeT z@HqGX126Qid-FR`n@TGh1QpAP^stnUa=9>>P01KRkYW{i6zYjglR3oihkBa zC=}e?Ht7rrT0jWx`#YHTRY`gP#kba^l#yeiQKizy!>{edIzU@l&`qjgI7*F%{Oy!z z{UpnXfx~!!pvZ*abBbJIppA1?l2?uCkW16+-|11nCVyTcY=V=kMS5_=R`zn|hs*n=o`G0tI+ zC7##;FYuLY-!|xuGA2?7SpnpNz@(x?$UmUxK0iy!pyjUU^Uf5KX=s=5#`Zga$C5j@ z>6(N8M)9J{E#<6j`fTcBJ*!V)f%*C?_z&TbRlY+ggg?Z@^%xiHw?Z8h);2JtFa35K zZU4?OvyF6+-&yc^njMz|!P27kp%4MQFXY3KmHm6Cl96!}E)D_U%Fs>e`wWd4dw4ij z9)SG(TRUXBSi=N z&Hh43e?X>gb<0480Lfi?Pwcf*WdKN;r#Ju-iC(4n{%W_SJPYw}%)__0VC_j6Duq1o z8(3eoI=dBWlyjt-5y)h~2mpQ)kC-h9a4BK@*iG26z$BJR#ND&}-hFGimy>3-aVJn} zA^n{9M4%@z58^!H7%$l*|eC{tkRM8dDwm*S2L&WTAb zZ40QRv%_Xf1>=Hist1&qLc9nfQ-2Q9TAV5@l9)&Zsf=dF>v z1VtEkQIv-vND>*-&_NdT1e8K?XqMgaAstkXDA`i-!_8+aY^dUP8C4S|BlD#fAfkEQ5n6(vxn8 z;hionXcKEOwzXN8DK}ct%IA3l7QM$B&o3|3lo-_i@CT4yF zPznMo7O*eGpv&||ny=+ZdQnA0ftNg$LGNvl1C1gYxS=KK6++I92S^#hDGbD;pK>!# zn+&zD9nLL2Bp;Xe)=c6ipgPqpe7r+1Ub7#jA;8!`D4rS&zPFWA$cxMt$AxDcVyka{ z$Gb!qfP6G(oCD%>*DbxbX5#l$qhreSYOkegCB&*IY-V^Ym$;PvW~4R=73h0ozivws znM{8!!SC_2aUTEWg+dO3=&q`&6oIxjPsCU(-Hb05la75_6T{31Wv$68Q<94V{gXF* zXrKndLFN{%;w#8s75MItr~$_7<&vNKwL^uPD)km-;F+)_21e)+y^Lnk7zK$OE(A=? z;Xa=YbNw{7RCG3EIlPv<-J2I*zKRaH|S^2g*z9$3GN7 zu!%jFx6Xs;w2CrY|9W`C@IveTWWNV9VSy}E7+wV8ihXv>BpjbR&HW4;e zs_0H38Cv}4-ovhLH|S~XnE8qdAZ5S%{Xwhdn^zjnOE8FrWo$MDM2-GE;HeQdWW-HG zP;S3Q9G+c{I(RL_C1jCvYyi~`u|@wGzOYG_!bFJbIW zBzy#tW(iJR4>Utu`Zl}~Qlp!*K$5U~V9B#|@QKrXn?#EP!B7>3gwj$-T2WNBE9v?jr!W{vh>P%l2EjePw&;leb zBt(8-P!3R&4#~@V$DUn3%SfRDtv4Ah6pe2-3H0RA?+fmD-9m9ivOtd{8Fo-O@9w?? zq~1R?ms?zFK_v5*)l-=}j6gO>PS*Sq!{?gL5yYql`RPLo@9H4F2^U*av*_qgK|YOX zm_gU*A#@<9@L&%jOBiG1v|Nkn%NgP@5PpbJV0xDbHnAJ5(9O{}aFjeTf49@EiM6H> zZ^E@-$OCo4z!fdGi}JI#w)r~KWTqXtaLKHKxBD?&S;t1`1eM$BT+vWuxT|;S8OsNR za+7v32L~xaj9@^paVHZvV>gaGnTHzQ6BD3aI$c0|`R6{w|N1w$;vfDMSNy|&j4S@t zx`kej+Slo2h|a2F4g3rZa^+T|b3Q{)!(95b=^GOU?DG>Cn=t7Q+n5glJWo%z(emU5 z-~Mw$0wj-U$UZgSx>S<^zzzC(Wvm)_o3;k9`-5ketK-whNl>!b(5Fb6zRr<`;zSxa z0Anx6JN$0dlGn@FDbT zK>|7@DfjY4y*l88){8$119^^d3x?}xX2mDO>as4r(h8p2@+7oVx`Vl|i1PBqIv$tR z@MsN+fYkuD8|A}@+MFr1mKki-i;Fo#EtFtK0Vc>6(q@&Ih6R(Hz_o_z&BV&kFFXI1 zgpOWE<-!jsAR6H?2KOaQ%1atoW`Mw!rX)9p^|KIfMr5LxZ73eFZGZ2#H`F(6rTOUM zE?}Qmb6jQUkKjowF1JW)?PiZluhp;Tkjw&fZNw14n@@`k=*vTh$ia27lEB7yoT{q%yEs9Wm9zOVrHnH7N%kW z#O-I>v;oA=Fe*wkkTgXYwCvnLIwNB8iq#2CHBV} z#y8Hi`b${?fBAh8sx6* z9^-xhet@kALU4J42;VQR;3`a)?)3~bv5>fbnKvIx8uZS>x7ptMDOsC7BioVV^2;I@^4r`P<_&x+rV zTQut@ZqN0F5{xI-S9Rz4VL3MEo2^(z1?oOu4o;@ZeXO+?5exzS-qb#2^Csgn zJWUS$h|ymdgYhX1`9A;v0RR7lnYRwaOn06?1GXVGhOa@D4HnEvfC}cY%$e+%xy;K< z7OH(Yu60$u1oQiULAC{08h{|CnC0xunfE;JnSAyDSO+k)SugT#mahP@((w^x)a57z zBhvt%sCH%vzqkuowehnlXD40auz4^!{i5<^pD z&F*Wz5APc?BKsw&Sr!S8AI`1V^d=2Y(GI2ec z{?1UJN?MbELfW2X)JV9I-rO#spv&F5sl*f2Bs?$WLuK~R;Lpjra^inZyT=> z%z-3CGqxIM;p*jEVpc!9m7qjQXhL2V3(uSJ zV-2YKkPpJh=eJnFlZ0`3nRH8o>hr>ZNtCub6tiDM$QBm_;%3&ZsC(xqe?KZAFNIU8 zIB2E`u4pA&)lRN3IZ$Lg%8F6}lgk#3&he2Ed9AEL5J8M*!<_`Z^gB@Ld4z`xqTkB= z;b*3eXz8?0UX$PO(_sr_(TfiD)lN^vaj>0$fgNFhq+)`28p@!z!L^r?XfBXfKh+@1 zvlifW9i>>1c1C9djEok^XA1<78MzK&>1)Gp1f{|_&dNi7#!+8e9&9QxAWM<^!4pxM z(RD6`dg1YKbF&eM2V`*?2fo&Y!1e`PTspmhV{qx4$dZCy>_dKoF0* z32TAo#DzYY3&kT_>+7yFuI%~eO!#InGy!XezRU8(rFX`6Cez0#_1hE>j>9V!q?jTv zbz;|a7NWV>)H#;BRK-$u@PWwZ251tA#Ar*T6|i!;+QBG!Hks2qH$Q@Rg+MFuQ|Ll$f)**>|f*DwAXm zj{r1p(ZiOflGZMDQJ^In?K&Qq=^)v3vpjc!I+hH)w;=v7dh>KPr=y z626!OzjZZkQ3cFcKvEeMW2q4{@bRPcut@aIlkwDLP##vcJ|)6rXtS{DA?A4=?mSE! zZ=tN0WLd;hvWhIt04NF9I(L4YeRvU_d#StIr@=D^%@v)V^$ge#M?5L@)bfFXbJ#~! z!LN?kS(FlG3|ivVL6DyOs7iqzr#);7Id7zY4E|fCR}cA-M6~G2sDRgqiaN61^PzsMX?*d) z$^Zn>q{R`8ClXBgRl!<=;F(&Xld|M#+O(ExVrKy52zn26WC(!e>WG);)8O3N zN);s-IjVhYdC@L$7a=_*l`i57A%@Ixp)7NYSPzWYD9;O+D&mSM0fe*>i3RNi80k*=7fm20UU46SBP?V z7l=rCwPzrWTY6+r4Nn4~yg%soCXwQ69qT-&zd9+XDf2v$f3WRm!Oq@Z$JD!O`F^vA zDE_-J=Vq)|1ZVwiA(b{|?gG{a!_{+c4m{{Ew5Hqy-aDwzEDg-3$aq-8koA}q!fk;D z{4-S~W9FGyV#v7m4Ru#%gDH^b<=4EQ?><{w4U`J`+# zyXZA|wwDmdAP;YSr+^OA{xjaOGG3)h)KC7Pp9DpaOqo|XN{=KKz}5$&XMA(7hKL}N zZy52*a*|3{lTylfLfBzk8o-6XN{_ejstA|-HEn}r=1g&e;Q*3Hfr%w z;NV3kvMyD9_89P2*C5-6hwbQBVC(Wjjm6R^tcP^MjWm1Xk}&E$U+d#6Dy(DYGg+ol z)MlxCuvTmy2=D&Ms{`!2??lS*4f%sKnFQ|l<3rR}^yr26Lon&qifWzf7EoQ!Fu)RT559ob$~)a7Ypmv;*pZ_JR=^b15}fLXY%b2QOn<8qwDxM&rN z1G!~b_j;wLu^>HGcIy*89b?seW9ZbaST~aNBs7jCNZ66Y?yHJ#!v+ocp+wEXX}=$R z?Z3m*(@?Or>H^u(j@a@VFq%H?d=fD)@-51V9Z>6)W>y2@fg{`?o9P=R)p9P&el8u_T7zg>U^>jhvz6Ss@#BKb1r4zt2$8=QXg!VNz(nGb;#w$ zWwsWDixr0U)~6;(STJ8Qk8Jo5EX+JTs_R*cLvIbcE*B%eJXW4wWrK{!mw#f*?%888 z<9bM(Xo~eGA4M^`XTt$0`Oce1Kl;G|IpVX~WD~8h5YxVAya|JmmSA=$A8Wqy^r@ z3W_il4Z+DpWkcCXz9`kDaU&H1E{8Bt4n)D7gy2-+V7s*TUzzRC_9wUfkH7i1xh?pc z|CihT?Einct=kR>3NVoQ?%l<3X%nP=FHE`F8JtaQKlWKwW%AXtel3*0rT`d6L3^0X zv0yb4oxkpth}s8h1HBY@!R(3|A>l*8&3J((boiJbUNe56Jw=fSm?0_3GR(vrJY-hW z(Vw$Md}xHD*^2Yv%ELiN7I{(gr>}`E`O*QzMI{Hu#{H4jYcMNk{9WfK~#Saqx?M-lbegvvhUe60Zz5klHDZM0BQ z(c8lEQ-X+k_I!_hi=!2b8)-nuR@RsPCrs1Ry{5ZVYJrDNrr083TEfT>=5;9c*2{yU zK(WXJ{nm~pfMHNuj0Z3B`I*#1KOW$T@4ytN-){K41!cc$Y%BLTB0t)s)aFcQsG?lc zYoTWZ@5NU0I_*RGl(M%YYIN)LchqvR-&v#`d~u?H$Gz&F<#kfXxYuiD3aI3*UVI35 zyYzvo`NM()x^=E~kU@#BR&P^t>)GG#Cjwqtf8?3Xt+_uxCCQ(e4OhkOJmnjiGswW> z0eqiNwG<0@sJ0543r%~F63J*00|^t-ichoZu^>_7X0F9saq7JWq+}8L^RB08JH}D3 zw6tdWLm3CNn&l^U-XZe`+ay9UNQ>EMV_ZIk^N4*9d^Wf23Zz@ZekHAAIfY9*guBF} zwk;aLlLZw_RLZqx(pGu#`+ZHoVeS&*ou?fsFyn#)CO+4L%&qfU&LvxR7v@;xhyZ!O zITZ2rUi096kDjVBTAsOAX#$jBGvbPmr5qUv;Ex3q7L_@r1dVZ*)_-TeoPb8 zXY4>G8m9F8S=a(Xq-RfnPz}G-fa05saz4HlxD-UnLVYr&OsroE*co!mu&}HL;n6#J zShUK}Ye{ku{7$Pa291*R9YC}uv&k~@Sn{mPZuV&ohQNp6H*`pLEd_H}MhWdjjd+|k z47JGE;yi5sTD$I2q-v#1%2`;2RI zkmZed;9Pu~9=?7#J0>VpZ0J`B6Rwh6Gd3rjPiF6jYM^rF0_Xth(TJam|I)BC?ryD6 z4l1&(DbsLKJSLRBwrD&nN5{U4`{q9P2|Ylm^e9Mfc4!)j79{ILj3v^cG@WxkLSw|( z2a|@7l7=Ez!bXs^IVp1%P$htsG83A-@cpC&X(pV@2E@lEK0)m8a4(> zBXkO$&5SoHvOFE3^xquyX|57Y25BrRn^3&yv=QUzFuhvbfr_fYvOBN^i$!S;t$`u( zs?#m9%A(Pdgq(hT5e#%2Qr>J8;`(yZ@+~h-APN7IJb@N*+AK2Wxs>gL(a#vN<+Dv#;8+d!XhCnlx=o zzDA<-walY_(&jvSgC^M-)?Ry@x&EX}42bt5lG3HKE!HjirqNqvR^N#Gvo?i-Y843N z>#G@E%f6@3w(CFFrjjDBR?5+oG=pS9|4VIZ1vRF&R`kx=)pFD7&)QUw`9_73!1<@_ z#V(FTI`0Kkdi@}AWrXk<&FIY4O3GhKLx*GNuNb`<*pBtT)TTH)x03%;n;MuT+pdVJ zl;jkLD!)nNC+i?D0@A)GS8}wm0rsG17dYx1sdn-WXd}E#c)wukm>xLD!b~C!1ZT3! zBM9|=nIhN#i}Qqj=9US*hR*tOx$4{~bjrURr)?I^m7k8N*!Y@21_(S8SN~F*f^s}R zKC)~*qnek+!E@CGXU3k5=ST_WR{$``?er^}CwUwRC&nny|Fj4(3mc@;&%yP-FSI;t zV|jRJ32ua2(%q8s2$1nJPzdF_-3#>{_#ts`3RCpp3x%}t0ED7}uH6dHCP_D|bcR#4 ztvKAitDsW&F;m)8uH)TmTdSSI!UteSRjGU-$piE>G5WS4JPV+_u;UC$_KVzquaPXTgRC%%zTvDwda@1OgrKWlQl<5oz=&!*I z%ZoSAk7#=2m}a^DE@zD&^Ri2jQ2CF{tPP+6e7NnFEjvOQL`S%rIViCg%+F*?kG1+v z*HIKl$rTC2eNF!iU!dQGwj_ZP%l||Y5zC*R?Mx;_xSutQ6p;=PSglPUF*``6oQ^5va$zTLr9Mu)Ff3OXM5@(@W(OY&DeUnI$B!1=Q} zEeA0$Gd>^NAd4RpGHy=(MEv+p9zspIHtfOpwatWe=!v)uvP}uVUM&*w-l|ZIAk0O` zTjC%c%>YafY$zD+o)^gb%Yg{QE6@%B>`tv^T6wggX2p2{1&@;ds$|$}(X0 zY79r{%=_&3)EVCldgvpG`&ZG*zQx3(qg(e|nEen^0hK%yn6+qhHn6#hs268DJ>YSl zYIjx*P?W3Q0K>i*P`zAx3IBZepM|qWrc}PW-{5Q^&+(?Ljz=zHRlzXpJ_ZtlXMB%j zyo(0E5kO+40uMEhjD`CM#B8x+oN-kVxvl`n{(`L)C;^pAaH}cxb@d8>U7u&|=!u;e zinVikZnX0=nC%w=9jx2TFMRo>PNE?hM(Ib8q7&g^y1mA!%GL=fhkzIN5f)U^d4t^rL_`DcjPIVKb?Z8 z1}@NfkjE@+pmRU!p-ZakjKOfrupRi7jS9-Z6FP1A25|$oHJt7MlyJ!7pw~D>9rrEmoN++Z^B)&0W~e8gOU(9B5&IVHW`EH6njtxNm{rxZYf zb3H`$bR`vI_xUIl`1sK0ja9g$-!$G*$5=I@5g;Hx;sB-7?CC!YQoZs>pgg-rwvxrB za2Hp%f=bXtR$9`8rZ$yt_>Hl4Lb*L2`Na&u2Y{u_fHsWUidh#FBX3h!Z~lp z%_CxnHh@pg$c<(S7@Cr{jP3%k)LJdUW*}4TWbIR;sj@$s@FCNa;F#46@YMs3yQqiw zVZ~kBp#g~fd0lpKUQX1h81oeL^&V>J(y~e;FYC-Ee1kJNdKbpM^SL(5!z4q9Jj_Dw zh8#!gnb2CvNv1hwXVwnwz{Ukq_}vIWvnkJ_m$LI85q0&!~ztMA0B$n>?QP>XnLdifR``ktq> zh--fk*9~$0&ENF+iCeo3<7-fr-Ladv?cEELui%Cdbb($PxKgyBOB7_X^fX5QU%2Ie z{X6$x|Mai!zy9gpy8rqYZjoHCP;CEm*xfX9wZ9%dg}=HqQf2y$e@4q8RA z?C8SoVe%yU3BIJ-EIOaQgZBMK3+)0_i#4URtN0Xq&R{{Tz_CO%&(;Gu z4bVnB?Ow0Qno4h#u-RcQx^eZV{9NZx0Z@7Q-v9sr|Nn%UR}1vucAZZkIUIZu@*8~R zpbPb8a6r9|`i#n*dhcDoKKhQGix_MRUW5k0yxQ7(t!E)$F5UA^qdcLzq53j9VYTyC z`xONn6p!VN05$}^SPZRnMzuCS3T3!KGxSK#;AQ;kNHzq;2P&P5HrubWOiN^|3U1ZZ zmc&`GUXc3G&JnMX|3fw>NHOU_b@pd7#DmLhQQRJ2NFS{Y*B$t9eyvaqQPqf=Su4?y zv-!B6QkhI=Tnllm;cH+6tvyD9SaAj&p2*v$&{@FCNx8>j(S?!{8FX?zet9iz!19~OtU!Kv_U(Y?p4BN7 zz?H-h+8@ob!NXjVoq~YK;xj>r9|LTl78=<2Obi+yhj_;1N33&cg*{T=3$m^?xoMG4 zER~KfPQv+99$1Hy&(^ewbWLRX)#RflYZ)ABVz(()-sJ0r+yw6Bze3kf2GhO`-qLOP zc=y^HvF*SmjuHGGJLo`a9~u=G;%a5BBuN?G+Dzb|DoAUWPEs=# zpZqy0$k&#|&=Do29LPg0B0m!~m_!dGeDmIkw0K_xM!wy%f0gI>%(>ZX|tvZ7*2N3-9 zv^Pt)8DsI|$24yPKM%Bs@VL~xJm|;F^Lhx(M_!tRlYK2O$Bw{)?RXxtZt!COGLVzh zOdEay25X?QpaBR%X?kh%#b+r57h>1uLByWxA-8>AxTY#?5m*tWe(jY1+ma3*Iv~8^ zmT&{zZaCEsChx0vVo&Dg5 z$_dcVn(TfkQF>Oac*z60>lp?(2ZIv?$=)kiup&?AUAc>wWaJ-522z)&lWp2A!>1>_ zE~jqirshn~vs zE>Nm=ep?Uxz0;4mA20)5@JqEzCg?c{p`^KVXP9+!uO<`i=-*n{l$0eUOp=FU`mwys zl3WI_hR8$52rlKdemf(26?--Rl+#-=HD00*xnwSE+5uxdaPjI&*Yt#s?Gh26o&szTA-)??Zsk3@uozp{=wXiXIbD-FG_?@9727~|N5SjcN_qYS)mK6?Wa zadh!*8)1g2$0){E$H>|QWeK20S)jVQ;7sw>+2jr7V=eA&`~bXl@ieVy&w`YKwgkQO zx7Gv3qs+4E?>Lo58KXO6)j=g|7bQUq3Lz|U$4qf~BLl|!`LymCzNn>mWp!qk%od6O;P7wwT4kK~M+k%V8S_YDkQMT1;o>-GUMIRm~M444H! zri{0ST%Nw_YR$iW9&VA=!!GNrt~DrwYD+iJCU8|&5de{EEAi_|`_!oK?QubhM+Q3u znSc40fBfHn`TOxd-&Os?U;gsf_x!ha{r7+U`7i(D->(1LyNG}I*Yls_fBoC_diP_} z{PRB-%ha3~4c*bklESvt&ZzlcMCauKdV+!WyF!S(iw)u0UZ;DuOuH57F4ZW6Tc$U|xP%hl6q-m+?@uNcHb)%D)Hs6WEybOG~H(SFSYPjlGT z{@gx&#6@Z8d0`diTI+ua60zb-70YL-ju4XMOq7^(3r7SUujHdbWed-`Pvf zxN3-^m?MBN^YnxyifWTwZ(%&&hXXw^Q+S{wj7q9Pow6TCJIG+#=IMb}cX3U>wW9zM zrd(t4KAx3mb29+5V*`06`k(dat<~60LoExzC?Mb)T=6se`tQzE?F0H3^{;8lcLC2O|i>4M*&j2`O{ov@A=eLg5 zH;Gh}i27e>`{l}>r^bP6748?POpI_A6_EQ9WEQ}5b{1JA|EkseAW#OprIsS)xR#2e zHNDn}^8s1Gfa*p+^Sz@()|5l8iG3O%yy0L0bep6n22=q22*maI5${7ZK3}!DQgsUC zc_}@ymg^E$Q=dn&@R5lw`L}Qn=%r!eRp?GDb@;NP%_8NmX%`*BmhlNgn;r_;Y5>Ou zY?uG`xsW?jj4r$ntIGIn?W??38;I8mbR_+d`H!;*b`W`^-1Q!5B(luDHC%Yb?U z2b$m?4XvrNP2`Pfnhyd^Ne|lf=@E~W9uxVrP!9Tr34veWT6~HY@&X)cX@Gi!Ha|*2 z%$5zM8^NDkk+9oGEqZ*!`py$};7(ZuYOdO)Hp@t#dya~>#>3~1$8PfXajG_D&w&0CYszd zO%F*enxsfS^_AG>kIIBy8+-Br2MAUDlu=ILrfnRfxtRbRigM8pC8}%yj zmkugMBoKk@-UT9;dAF&fZy+YV4yOrIXES?Ios2)It$=%8M2oWx1N^n(W=px9lkH3? zkYa_{-uDS=>1sW6pA*6HGQqYDc>3C+c5G?~AbQ71%m5NA9mgy*_|uVk?`^*n%n9%+ z+W=MYDfr^aWWwa5%TGUH#Vum`Fk5xLgUy_;8zqxCMnTkkbqj+WvF{K*Xi^75os86b z>v<^$Vc`0(SUCwsY#K_$+4_i>cF|0gdA~E+FE|X?c^YIIq2Gehmz)L_M|GI^ygM&N ztO`Z|u*v7HkIS3Bvi5SdA(9mYyn`pxXgVv`oIqAaezDGYrYoZRdB>qRllh>QSt+ef z0Z7d&u(6U&YTC*C6;?J7O#}FBB3bL#25f30vXR*PVp_apI{CtD3^H$Urpe}z3=MlG z#20~NDJaO4n0FYG#9MjPrpys~(hqUiM&*Mtn~)tam}N)YsLWW_%0G?y2CXaqjL!bD z!r14Jh`bpUjBDfX-iB9#+hbHs`+Tk6g%RbWn)UGLir`aWs+Ivx2(mX0kPmyJk(e~x;GTY!xu7` znl%pXV*ewe)X5{L2}2+U?WPsU%Pfbl6PBQ3dgH|cL&_gCEzugK$%$HWh63WCmk6@- zSg!YWH>Dc%Ca5nKCOsBmOhO{1jjC0XLOIj(XM6=*Os(P-I=B@IpEtW!z`QC8J@4ZX zy@Wy)kO~FaO;~F%9@Lj$UOc9{S}90qxc&R?QFcXO2Q=Mlrp{q%N~pF0&o`{bXf78`E+YeZ_HJ`wM+Gg8Zly8+oQHH z0}80mFz#=MSVI0G!?pE>th9O#S&<9AzdG?uGC!BSp7bI=hX}Lirf?;XGhm4^F?|1; zPIx2tyca}weIg*oW!b!vLM;Vj=aA`3TF(^)b8&b{{oI8AqpkvADG$s;z!Od>L2%b@t?Ss_1s3z=S_7hNUl}eyMh@i0Ki*k%`;pVy;OKFRR+w+rCjnKM$@Z9}l%!Dif`f6< z2YO`Whup-MvXv0e59a{7uooa;+Ox2b4vB{fPbC`Dzh5t45?_!@Lwp>|V}V-FO9a$? zbUKzzT(T=#wyGtwwSY0Qy+Cs12%)Ef!w)xNpa>$Ql-@&pi_KjlU}UnSi`cf6u$FnYDA&EU=n%SN43$a=ANnb5Bk>-Ta^b(Q2ygKc5H-D5S6%US&%_L({kAuwCK*Y9#y?eG z)Z$_~KG&S6w|j16m3Ej>6iR;rM7MB6OSB7P9%5Ev)d~KsFbaS2wT_YfLs&V^l)CO7>Q*xR3KJk_;Ww zo~+>b`{rAIH#EX`-=L~W(y;ecT;d}{K(EDsXlD1;J)4y%wIc??4|(j9>yyoG+e>f- zNW$8R?t!=xRo#4ZpnGS#4)%b3KLdn^Gj-Zsf-fMH;2uq@)yoSQ9gtI}mqENauGO@+ zy&a|=9%Y;)7Kpd!PZ+S~GdgYiO$;7_Cc9~dosI_YfgjRWnfVo=Zj(;oa7nq`kv=2Q zJO49`kT8?TPc_%d0idH)fQAUO0p1`z>H19uvxmCaF&$^b7R2b$S@It$p_em8^TLT< zI0JJ`VCR~*P{e71Hsz~Y+LZ8t0ld%GS7hPS5duqTW2=~5pg7?W%z~?+fDmNb+D{dV zn0ojC>y!?{Ya+1@pWczJ8_+1*zvT@8oFY;}LCe)XYcN&c=97Vzt#bQ^Y=%K}>YFih zO@p3b4Ngll(cVYeQ}duSsByYeZcRY8R`& z^`I#e&y0e={Gy#~zGS?`qva+9*~r{tE2zN0tj~kda?*sl%bXUzuV)$|$`k?H-)`z7 zUaS>3>n_u^i<Q)mJ2aU}gI-fLOa?QkUs+X^JBLNK!~qYf1bZvB^6 z8pRG*6)5$6;$9SDKCPvOz;&Yjt)=o9=)`_r)Sj9MpqHXCmT4`iv+!MpHUlT``87f@ z!HMxNA@4IFbKU)cRZ-+2D_-Pk?KNi=<4x0;btk?K6MFE~`K-bRUfDY}$$A-jAQR># z2MUAMrKCtd3I%aX3Q08ni*Y=6Rk2ySknw0NK>hE70WuhAT+yha!dt=YEheBjFTVlUUe94@f^U|76!Nk#W>l)+=|X;VDmHqsejD};D~5VX z>Al5RA9Zw*cOJA^V400YXmsAs@G(#!`#0jP+pGW08GW4&h zyOi>_I&b{90$c2oK|ntrp*lx7j6IkS=K^ePPSK#e@;~E&hP_hOZ{9^V^c>M|P?m_v zv2z2?@D3YDw0*pT=(eR`tm2jmADrc1Pdj*C*v#|F;LH41Of~jbm;w->^N_{m!N-vI z*Se~s??grM>dRkmgG?+-;zT2cK<-6d3@QwBWdX)JtzbrvJyszm(!l_kW-!wt3 zvqqrm)ac8)tAJ4BkOhz7V0MdbpkRU@+D#_884FDb{Z;=dnOTm=YD>O_0Eb_{Cy#+| zyZCt{&i8uM2UX?)+AGxg8hSq#&DWU; zi*S+U;SwV#yT~q_a&+%O1u(m7t_y^rV@b^O6}QAYExmfc4`Cd2wz*WcLlG|QIu9emK;MSXfJ{1g;Fpko3EIJHovf@Nn}3b+na7yO9-TiI8V?B zKAFCwK2DSLy{_vV43%V^B*Wr9wN4~97u*qPk!M443`*8s9MW}}=~%!a0(mFSxq?V& z+*vL)F9c19&S|EPQYiptNrx&~qE#gh*Xt@cm_+af=+~?~`s_KOChFa5R0F&0eu9D` zE9F`pwCE$CF^K*JJk$kSHlj@Z}*u`J#}8Ds*4SwWk|t4o~^z`*ar3Liy)O6o1jWe=gzr0S=HRq5BRN zyWa?m8TWXfZblp1=>*=#BG2#baXWoM((qS9TJ)ntO4_Y(9~uOf!G^z_1i>@3c58s- zw0gR`v*o`e7$P`hVa_ys);7$Wxr2yVCKq9b_t-UX+%D`rbW`kCjU;Pypcv zE#B9%NAw3UN0+7PmB^-d6#b2q^A~GYSz9Q9q`&C@<^2uG7=wEfNK5r68SDp|AevR18|Z>dVKI3oF@N$UaM~sC)&G0E=xTY*YZ>vm*U0{zP-$pXAWuZ|S{JJ{(r&R?-Qw zvYJ34qQk0=J7_7Sb;6$k$6AI2QR^65#0UmPdbM1j?;aY9)t@& z8!5J6$*aO@AVkX1b!q+@9vu^A&PFbSbH5mXQeL0Nb%71Je5btjL>y=> zqVgk{gP=5~wzN1dnVMOm!cD5pUy3NYKC zxw8UkN>@=tTm4KcATIJ{q_dU)eHnLtXtx{cGDYiRJ>c}WXU8P{-b^ZHG6d~m>O(wp z_u5I(pn5aSuKr z8Oq0J2S5x>Xi%>~^R&9*j`|;(JZ}gnvW{sKIoS4BS;s)xQJ|*;|2NPH`W#Y3VfS!J zEfG$Lq=52AI2Tb8CGl@6vb08ypvJ|oq`FCPXyYOnzYW{gxz?cx;s9#RYMmCs9^_$; zEX{KPwltGtI%E6yit=JUqt9)1Wv%pHz|j$6Q>uN160lp4%)pVjTi%NcIAo=<*qpg? z0Kb;5p_SPwr^%u}R!LK_{OMmC1)mv`!eU>3V3E6IGmfR_!Zd^gIzF=Q1t#1q zWI51|B7n*UIZ}eGsHhndKOA>olU0vNIgu1wl_bpmyf48JD{yPk90J}es=MW}ONwm=(y-II{CkF`S9$^t<#x0> zxnzzQcRGj^2w=4_bCo7;6M*Qhb=+6Y>{Oeu^5QU)K945-t(HezHd{R6_7#E}pgd1q zZVQR%3{N&Zh)JQxZU<{Y3tj1MPt5@khFKEf`*Izsmu0RbQk)g2ZXLKz+o7_Q28T3w zu$hcqq!>A~4+;J(Npngi%AED)ej~MlttJ#wXio$XV2}JiH+|p7^uO=){_j(}KV^Mi z$Gd&6eV%pxpK1OWzc=`&zb8FEYyMy1pLzFfza09velnSTzn?~!pSP{c!teUObn5u> zR{O$1JP<0OJGQ8x2WA$F%kXAYofZ-)81Foyf26RmjwzTfjE7CsP_6gO&*I5e>MFV$ zw}PDkrpzkndN?wq1uq)0dloZvRF3_O zGA~pUALEO-;7&KXiAghiymyn_DyW0;blnCSdR>tgM`8Hd=7mr zr0oQ+&A|faf<5Upra|%%{O}-BId$Z;6SXt<93x9WJ1S3mz#=reFExll1Tz3C#V3~b7=#*gZ-8cul&?ueC<;9IvK+WZ6UK5v544xM-;SV zU3m+WxwmUN`#doSj~Ihmf-{@GAgo{Q%)6jDs64+k6&jHFm~M`hvM8()CsPD20r=T^ zoLsiyX^gu8(TnhU@4EXvU4upi7G$Tu?3(z$+FzKyYU`}qt8qv<1u|JdSCWRfUm zu)y#Q<_F^=;h|lYx9{|VdpN5|K1#jcWVj@QlL+dHZ58)ShM|q;Gt(XNFYGnQ6Pg8Q zwQTKGE`UUa3KWoZ_|XwSdwLj1;Kp_HxHroV2M7QD{p8ZU_mRP4CEHLx#<$6{-P)Lj z`0`b32|(w8R>E7(aAqB|zDv4cOX$xT^d_7N-k+pw^TKn*&{8*o$*asa&4o%;Hd(*= zK_A$A48{JGm*kBMZ&(Uhr*vVxN&0hD7#5;|O}mCaF7B{-tVU7x<)@wNvITRDG%)Yb22MXX)4LzTEf3j z3BPVo!`<8RQXmOQto_;`r+T0`^IYF(ZSd(NlJ3hW2X!Cau{)f6Fz!$B-h zKf;>-N7^9DNR&ZwOfn>CkB2i+WBZBE z;C8G@XK0b>HLzK3tNEXusa}Ix%VCZQYDhPT;kx9-c&e9tI=r z!-^Ij`K7^&xQ9jv^@@ZVDYbiEI?AZ=i#i&icf9Q8yLrQNScv|$HU5|aumO^`4-_&d zE4o$G38v^melQ(S{;gY?XJn{gr1}( zMiyQFwual#ay+tbnA+U>#OJO=S*6N`G8gIc8ewP@@KCu^lu%>vZ>|0B!`9#5x_|2- z3=BOswp>~2-LmS11(9l<{42l|)O#&kDWmZ;w|%y#st;%)=0~!6Hja~K)04P*vnb$2 z*8CLNP+og5lp~*c@QFDN-8W=1se`}5MMZ2d00sfCzf2KvjGzy;ZTAK<9T|%}nPDD) z4J3yMU7XRa#U@0Wt5Nfjsxt~;>tPqn_KW=a=ewX;q+tnRJIv=VKo=)a!&oR_{1MEu z==}JtCKA+n0cX(Br$ z>;{nP&&WHn6PFQ@M!W&X&)e&sl(x9*C8q#L)-dV*xhf(%i=(v!Ku3!w6yYFH8|&B~_FA4<=yRt7wTmVMVgZ#eA*PNzpFLTpQg6ObaX zZ(^2uj=so(6&N0Lxd4U&Q2zpxGm72YVZ;ewk3~MehBU2rmIFueIlIO) z$mm3a9yP&1aVg(S#HT;8RK`}|NYAPir+mcRa2QF%Pl_wQ6# z#o7ViFmsio)<*YGFxp+^QGN%H_VFoItCrc!?+!KT3@4XClU2;^`gybggv1iutj{We zpG-8AKf$6aNb%GWn3f&K7tBKH7QNXBrc`E3>)U{hBfFn(ws>P^<@=GE12=t~?|fM1 zqb31NIt_a)d;ua*?De_5GVbN#MxcTN3Y@>0%z}R1ejX#5MB~{a)<$Yeu?4wiZ$5gJ zkUDh>7T9N|Cjd7PiIOze0*ajMscjpx!5pYW?b(Bh#nZKP$TOYuEPWOz0*W}Q0gRKg z!$()EU7y98W){dFDC!}aJcV#0!sh+iw?UNDK*S%or$@HcqrJ9>2n~U|smSDNaG)Be zkK0Va%n|3nEki|!qXjJ2>GsJ~Wz5aVfv;`P2178rwLqMlf!UsS^!k{>s=h_Fw=Y15 zvx9NB5`K&%7nxD_Rn2q>&Fp%Qnt~PCyt$j)Q%2|4lz_j@G5mKbUk26nFdJNaBwX*E zrvh4FnLrhVwkk^gRfA z#t#V=zkC;9C^op!b-~C!t#1n`v<`2RsO`m|!MS}Pq8ct~k?3%KFbXweZqtY!SM|5o zp2aP@3|rGGDzh*qo^1yF&+6KUqJgjOefK4Qt>(l*Emy!K5SGTiT&c7%ZUp(?cb>j| zlHKULb70_?)JCw4OlLqMCe3O_bC2TteuKJR*nRA@o56lh9ybnJLO?Nr+aPXJd8XEw+wbW<=-Q5T5Dcb zyY6OES@ZPNOn~>snXY1unW+Ip!LvC0P*DG`a!SF!)y${jBq@C#itFI2!C^LSt1b3B zG}-WIGLg|4Wf=Yuz%fc#6a}R3nZwQ2)ag*mCTqiqmWHPSTConvdwnn%#3e2jwO2ZZ z3?*9g7!D6G?ND%c%uqpoo3G~S4%UL=O)gcZ?*w5Y8eH50nJt+|2@woGpFhCBz2yKT z{BChzHkH2&`Q>>WHDK*I6$Nl%KKD`fvr;VaXDhg59vfp#t^wUFRIAN+d~*!*q#Trj zBFVnbtq(0g4?UOKiqLi2mg}o6ki#3-Ii*oh zW^NwR4!CPtDTnK71B=^LZ6Aq&0};I=op~NA*yz`*&o=jV8p;wKcN?_w5Vj}2TXo!< zJ#lY29CdD%`(RUsCVOtxs2+mPK7)b(mh`Xx0a&k<9qhr*zJGz)nZV(Yur09Ho%o^W zk92k)-|(ym;rKzbP28d%W5vP_D*eI#reHZTgHiqBikJsCRl?ARwyjn9)u})iS|ojG zG+NWlDqKdbq^y$=T`ZF9PWIb9wA*@=#Y7`)<(LyVb4t2IZ-p-Rac`Tb!2Z{S(gIkM za5XdzOjXc4Ui8ni9vMuZ+cK~@Y!{TI)_oE0Z#8(Aon+i*w5xlja}rjeY#;Kos08wSV633I4(Ma1V!X@(aN;T$ zSOJw91MuB7#Zhz>y)3an#LiT-wJ}JTb_%3RA;eoF7br#hz#tGd(x?8+*KCI_($de3 z8yyE;15_*RX1}C%T*r(M0F47=jf&eJD9?OVcz+4UZIgv|EpR2cQ+?8ldCY+J73Y`y zI~Eu8b0O|Jab)Dw39jeft!Xh5{9(njhQQ{Owk!;U$jT$}s4S8R9Wbk>2ua9Xo?>?OQXR2=y^Y@egOM3Q=`B(j$Tuo+08)2{SL;j=8`~8r* zsVE8DbU;-<*;r0?=2oOHGtK&uMgr(r802)z54h(mup~kcs@uR$OI0xrssE8@)iyqG zS0wXx9);@FK(OdimP3XUGQ78Oq|^1ZJV`4oIoWs(Ql~o^bE0tPe3sT!RdyUdpna!O zg0mnc*ra8j8~+JFtbaPe?sE1N%We@14=CL2?yM#6$Z3zwMBt)(pY1~v#j+qk3xb2u zp@M$?Mnx&Q`EzoY9Vl3bYfyjo2nI}?6Azk2$~RNg@TtiwSXORN5I}sNE3RbSkD6@` z^1!G_vFU^KFTP_tv(AXrX4H|VC&xPMof3jbI^|L z%=Jy7#E_3KI1(0xnCM|3`2OWD)sGmB9++outL7oW?=;3`^2OYXoG^mE=S2cJ>-Ki> z&qAF?Cw}`n-Kk^HPL=?e9dv&0snG;leY`)kC<^>wwjP=tymX9{JTkwQY8)tJt^I?j zC^w8Qgz5F746m}(aGWvTHI#&{(R^|{L{*Bv@agv?hjA7QHJK$dnO)&jHfP+rWd0ee zXBOc#mOFwi%GAi-$NCPZON7#50f%BX?84;V75y=b@*}Dhnr>#Fj5gXA(b1l#H0G%O|gFd<)%fkOorWhKn~18WK$A(B?v`>-Pu8ED^k8 zdScFWM}!|#am5*((^p!76?0aqJ3QuuH@Ce3cL~ach%eF+dygVFnCBr zI9Kvq7#}1MWJtO)m%F4aHzJhf$q!r%|AZG^wR$yBPB08T<<1o8X{b?d; zJiJP|XKyznAv%z1IpeW32w)Z%c?DRKR=Mey!^g(GLqh=cjP;7-BGWt(`H@qkeS?e@FezVV@*lHN96taH<&{^|Uq*QvX~&0I~Q_TKTa|9^=I{ zMU|?{+uweS(wq)Lp)ZN?7?US5J_}prO^4Ae)590)zxFgv^{c@u-RwTJ9w>%nnJY?J z^EvDf%&-W=_Cddd6PvO;ajyma{CvtM%^2ITe%#Es8P9pcVixW$GHI;BAQqF*>nz`e z5m6{$l;qQGQH3vJZgH782-!5sjFML>UwBho(_CKR#1XcAUVIv-!u;K~Lc+NB!h z2{4bjZtv7lVWvB2sS(;9XG76m$#Ks+1IZl$Vix}-B7FIf4 z)uwBGL}AhvFF~~|S!ha(19`Shw~S$?AW2QT1EZCun=nT_dj5*Ws~3>3*)(#iknR>w z@r?#?PHu+KfSP#sj7NReNZsE_!vl~a?~mF#PXJz1a~*qHPA@YKKeWv zh9q(wLH=*Xns5=>hHoOX?O^nGiG968i`&#ROrlKmh9H5Wp^zaA1Xp@}Z6bn@N=q24Q%TjaL~St1HeeI!$@#NtwDJC(J6`}%|6Gg?EYfx0pQ@txLHi4pWiHS|Xjei^`sjZwQ!SlX>a<&dopY8!UhuArw@ch94XW2hGZ4GMJ#yzJ`AaY>z2+QXvANbjfK}5Gm zF-`1RrsuUbYJxOWN4l2a<7XGaXOAOj-_&|Oy7>F1B{%e@{|El}I*$M6=il=-*7yF; zsq$5O`!M!jHkC2|kF*c|?!4b`{h!Vs&#yKAinT8Mq?5d#3XRd7jZ`m+-+O$ghjCL_FUt}L2Y_bJT@MtWZJ0Ua4Ne<=I+SS_bu~hFf@rjKy zT!GN+#Kf8^+$+5$)s>JNK!2hl;V0o@a7e0Pci;2D8Gy`UU9{c#eh;|5M}+s@@OZqg z$vbe`AuZ#X?As%>ro^=<^3j0gV00z{|K>BrV6EzotkATzO8LAfQm5*03pC(AusjGcvY3m1E71 zmLEl@2zycDv679cHB90MhouRcQ#f7fhhGAh2hdR3Oej^6aU(*BjLH(!mCL#G_-%4W ziZ=~4F_z%_yT}G1Hy|}A8u-t-peC6}0kxtIT}Y6(MDzES-&q%mK1mC4c^|wEzHtLY zgoC9w!%2YDf(!|JPEw#XI_$^=`D&}T{p*5%Ut5D(s3_W@Yst{v=$zxnLHKb*B7`&A zZ2cy+6i9hfT=zuN-#dNh8{n}sn)~;Y-~w@;%yL^$2Qg%go4yX)9uOP}8y;b{qx;fD zQ+aq$QZ8PvhC_59G*U+4!vC8xkpC$2wEEzwd3Vnc5G8YkGWlbsR@mybi#f#|^aZZ` z@b4<=a0OgIl$UbsU#rs56Z&h5}dgJpGAVbiWy(gF2DP~S@ zbD@^5f1H-bwcPgf76PFk$&nb77c!bw)-qf6y;*wu`(>;FzX3=%VHjP}3n>(1V6utVjzEFnp+7G!_% zpmg}caxs$hzf=jKWL!R);1J2~bYhZ8(4s7k<1fN8mfLX&(t*x_ zHQkw1lO-W4vW;z)XB;C9aeDSQ9Ge=GIkJSFrCg*jR& zLi{lzzVJ^M*}!HE37j0kWZv#UA^1GD-z=<=xlyfp_(Wj$lCmnf1Vll2VWR~W!Ku05 z0mgfP5_>Ur#i+Ro&ZDvnriPg-bNte2YNu-I00xVE46f%UNz$O;Lo1`z|E#jwaD7mou&|Gek@nuPMl@q6z7i{W+O@&BCY zKMv+S|I*VB3#EN=8Op?{{d3i3ZCI<;-Y@fXQWzFGsj$Z@L7Lyc?qVCKOg_H0a=QbxdUJJuAO7ws)JdG2Wic zz^#GTME9)!Jz5YeHqrLfau8(HZr4u@+Dm(qWJyd&65*3xFl0?Sg-^zebK&^-ixXfL zcv1-idwI1GH+T;(H(9nOFfEi>qPv}cj0?8md*+^Z_|7ey5(7yxb)e@nf)T4!u>2Ek zaQgifOwj+YI{P)a;0es~W$uw_i(ql>4+J{Vv}6bum(!wLaPMl2cf1Uy{FM%V5Iq0X z7($phlfIrpB!a^^oJE>SkN^EELC~t8msWwR6xUzkkUORRPcTATQ}j!PeW+PkHY6Yd zHi7tm;X&;bXV404((~4cYu#(5I`FCQ018HLja|A4(Z&aF_l*903jJh4JPo^!!Yql3 z1;^R(1?MsL-LO>4LKsrU^OO>uM~B(^-<*|pw4l{~gvvJ}Jsmf3Rz;}Fe9jr{PLsa3 zoJ~v+-dtpQtY_Kug8ASiG1WPrKj|xV@UkMF=#v}9X8G-}(KFSBbq5Z;eIk=tco8ek z5s6IR!mZBFB8C zWzz<^w{`xK4yjuaR+DKjXz1K7P3&b$24>oyPyt(pL=))^nG0z466(jN&N;bV49BZp zeMvM^b(s<64$TRqRTOJaxuo|PKoa$1A`*7M|Fxa?>2c^sO$|}DjEdCtg6)JS^>#AA zK$v*Agnm`}O!>SnB5rXQs2EO+a8-yknr zcsuhvXoY0>j6}(Ddlw2F5{lOUGV-ELiOLvuT(d8lWtc9ta%m zo{3TAcc`X~k!;)G1yV4PP&n?dy4l(9AWT<9=$|5H6q&!>-8Zs1e<=Kw1$~C%P@|@{XKK*B zBnryOMvRL=0y-YT?-fhBIB*)s`c=OVi8yM?&%~=AXt^cUdO5Ap+CDb`vuwhT@?IdC zvdRHBs0KUjSuICu6~XNEaGwwd7G(X|Ku~xsg}Li;hZq#dvcQ{bv(D#q68ZOa4VAS~ z;bCc*QbEhs^SYoNO0a;$Me7L*x&Wz4IPV^NRC}E}y6F{C57;msxMwuc%JG)^k76au zl4)b(brkcjrvbZY>Ex%S%dC-vaYKs?2=Axjfea3|eh;EGfUGxl{8fFjNtA!DgePAD z@-z6yV}gM{vc@gFx5x$(7sWt=Y76uMFP-oVZZvI5nk`qF8^(IpiV5Zx%axP!`*Gg2 z>({Pr%-ylLAnF)}8aApQ=1qheF*m<}CrKrVO%U&G1nZ{(lFM>`09=pYY;5nFu$9h@ zZY9GKSRTy}We$u|Kf}PyXmJ_$93MwOR z?*nZ?I7XIvs2Tm2)VXM3IX@u!Nfur0uSa@LAYTB9U=jum4op-2>KDv_V!@d)0t^%z z)QS+?b1ooC@?!1T5Wq-ffvDIu*i6|Sz}Ix3#h(nB&vz&@n25jM7E*R`RettY(9ed3~{2D!j2Mhv&*IT zBTP2b_Cv!WI{kL3xtSJtmAhXset99EYnq2dj39WHfayr4KoT1D3f7KP1qD&ynzo>e zg6{DPXDEt;VBY`}qLg3c?H#QW6BS@bTW49|&giQMxA>m0>xlOn`336~-y-LCx;T3x z=I=HxBnT!Z4M#~>$^|*qpMgeWsDOrIy;=F3lDzMewP}xhfHF@|>K!J5v)41%=W7m- z$$}>C8z$n%M1?$j#tCNbTLdja4e|gWGTZ>Xz(+Cs@0D-ZeDU_H@vO#c=PQ>%xw`>g zyVPom?;pB`=F8h*ck|%b3@7oX^dOWiAz4gVO6%_LRy2t^Tk=-z%3&sDONBSz+P%nD zA_PhoMA54?Gi4+M_s$nuJCZVaXt+u@wkmS%)JRszp9}OqLK0)oo#bNhMmPd52M@-_ zIMjk5Q-e;dW>Kp`C%OR?@byDgJ#@=tFu8}X7i0g{3TV0v5qk8%0=iv4j}46~2sKg4_WNA|VqMoRXLwK~7^36E(3kw|c3nQ!`5ET>m?=*#eocAZ)|z0uzjR#LWr7^DbgKLs2l`M zQf?QiykQIsEFPyOb^nB*c4524ouX$+X1|s^u_zPCXsj?W zEYMq)k===o^G@ZW*uUW`l^eyc7YbOt7?>_xz_IP)VC=HB+oW=2HiPk?O7osEtLz}> z)GOF;eq$a1gvx#P3I;^Ik!~Mnh6Ko~5lBkT_thazVqvg|s^aEalVF=-QGpq5&Jk&- zkc9)UgBkhpX-gU9WZ5^pe785eWX0BAKe2Suf)@e+5*G z)tI)cZL>i>jUr!MBG_~G7)Z=RsmthtPDu9&1Li_-JiSNe#e--lK4ZHx!YY6pa2;lf zt*uf|&!W6?_!3Hn^vwceQ>W1fb8#!42@>HYOOo@8G~J!7U8;+&I*{m3JN&gW+DBhK zoUmAEi`s1xG8EBoZ$^tTq^WOi1K1b8CU`ql^4H{Y@1%wkOdq^b0j2+5LoS|`H_231 z8+Y0ICc15}LU2}f2lYJTbMz~#8LW(IlVdDnE%JCXxe%;hY0vq|suCT3nhTeCYWwlx zRzqpS{Js+0v4ku?AFoyCz00F&icF;}i za8`%xQEsXB&JIMMSHB&(hOC7WvfsWzGW*n6B6RowNudMjDQ^5EupYk+2e6h%(@mbG z)Fq(^(DU{DCIX}6Y92>gJu*C(>!AShXMKoLlJk1KI*6TAw1 zEHcVdzuhOr8-=J_O;}Rsyvu>$IrhEgxt7zz_}=B)cuAhw!5#j~VMKHaH-(&IB1Yc{ z1nB_K4=`E@t#}QY5=0kOkL{*+8|WLLHR@Kg%bH>8v{X~nS$Q#Hve`OxC2R`RhtxNu zbXlH#%&#*tT!W(>UFIsnB+79c*^4ZHqxbsqaWmArfN6-Gv@xb0TbI)f9CR$O5 z`m_X1^`ll&-oXkWEu9$95K8bqsy1@nES&7oE8Y`LSls&5h_xDV3i4%tJBC7BTy-SYh@<;V4M_m+(286g5Z86A+WygZ2*#qWbZ?F2aN9Q1i*47rZL1XAf-pHA;OjZ zhD*?mz6P$*z4ZDU=nyN-6&WvDNk=}K0wgm{fWS4dV*XgmEH2Nkxbb5|P?3D%IyF1I zaqX0({Nyy0#brxP(GKw6Ry)^zH~GPf3x+gQ0b!BL9w?;61CE!_X1SzY5-#FXZ(gh& z^-y9e&~wLtGxW@~3J+892dU3T(-pHhw*v*A7YsT}VE%P>Xzl~xL+TgL+I4ab3o`1& zvY5>*!N@t>t+<-sEaIOxccg>Za2=$10ZXfK8Tk+PVV!{4TXz0+U=x10j0@6Z}W_*Wu`$Dn~BTxua z%@3v%11wJvVaK!L7mPS$AyYhpO=lheiD8Mb);a`aY+M&yaXs);vwtA(17B~ZP;c{j4NjlQU!N+(n?8S z^2A%`VmOSOY%F1tK1lf^^NEGd??C>5XW{ zOluNWjnPmMmD;5iD2%A@k+3DFMI9XA^R^Vo^odx-=T+dq!6JT&7l3iYj6M0rI{;ojsJMVe8l;%B@tjoNKcBVGlxgmboOG zabd7JQTJqyA9r7tT;#d;|Ia|*Cv5_*d$w!UpUf(n?1V-)FC`50(FF;eg=K!4g=Hz$ zGq(Vvc9{AuQ^%Y1f%g=DCc=w~uo$bn)~hP_^t(H+-eIVhrV)(&eOyJUz`uGq1-R+%TEOVSK84lPm1?FZRf3A1@7bwjuU#*O6kd~v`++dn zmcP4^mJQJkL#@z=`VUHt&m3V#vbB`*PsX?)at`~n*E)fR{h<<6{>LbtnUwG|A?@7=n{W(W$ zEQ9Q!T3Z*1`^|vMg)h<7zm{HTI@rY?_j35r;mx%pe%BhiymmDn1i7LQf>U3}*05U% zLNvcl++`E1%Lp>8`ZD6Yc4_|RL9#aJS#C>nFsK>9yX|c#os4UjSm(fLsFO3932z(v zZe*3IPFbCjw8DJaojHunBedf@5;0MJUZUO27Vr?+M@$$Wo?2|&5r|^&i<(hF8|i{EzbQ#ljJr?mLCS!`&ENLq4$BV-X*{5&*NOU7+_tF!gnq;)7q2PM}UuRB_QUbMd7~k{ls~h^c z+^(?wy#g$>?+IBr>ef+(fL_`AO1xWYbaWTEc(%0D81F*jC6le4@SHk8!C=2lVVrj# zi~E=0d!X~8;YMK;x;?I8OPqvVsX*Tnv)!>{8)g{mAN32%QyvpAL|h=^UjobPpisBf z%P{?2y>*IAD_3%dH$bD9O3VoqX}tlXYV_ggv$9TWS^C~Cl^mKHpLUKdzuJBGEQe!i zmK2+xf;VAJmiREXMY!Fno9Rz%iaQD^IzI^TsT<2Me`^pasRz>R?t6VSrUZ~w{^yCy!rfTeHa zO}!G3#`5Hw%gPrc_zTy`gbAq=YAY5Mfv{5ZvFkn6s}0alF|8dF9Jz}eIPZ8(QbNS0 z5}v8nyQ?1IV@&JFI*!rCG#B3IIitPKLyj3_b)HJ8yT;o^QYgv__zOcn9791!%yzX{ zg`o@jPq5G}Mt+E3sdtF0tL4+8Wayu$iUKDyPXNiKJb?uP__W!2twYo%5H|F z_P7)HRE?-WaHK%>qXR!8bo%2~l2TEZRg1jUCzG0rRz{>h1j^*-S2iq1Z9|_TV~SUz z$oodpXl!Z@gToLtH44scqDJ)vm|sZY-V%^Q{v8zwiIEGg^YCf-4`yxM6JoY}L+nFm zL$**&QQTE1YvDoFf?a*d*O61cg^JHKWS2gTV;<{P{{4k3qt#T6aQlYaCt^N~B)3F$ zEQT4}2#;^|N$Ig^u>H!UKB;Nc)|EbFu!I?Wk^bWC`V%5`?bJckm_PRT&$Bneh6V2e zC5~_@5iDpDWL1?Xx)GC~ObB5O%pQz)sH#n+EXxx2_1KOBdB%Mh2tt^V?627XM!70w zL(`Ru-+$R+-#D4D%ss0m$Lsk7@5L)V4@C!Zv6Rg(x)5ZF){b}ulg1TP=dlB}wrD}X zi3g&31b#zN-C=2rQ-w5Z7cC2u#_y6A+D{M-&n7WrCLgC7?nvL}22DVu2E4g=Ud-`w zy|8+)r_;lVU_+&rGAuBH7Hpr>_5FOv|L*^LT|57}&pp@uew4k~|E&J1 z&pq@1e)DhtHursM`}ce>TK??gN19&c*j9u;@c;VOZsms92ng{Ap{=r6)-;6LmVAV9 zzd7pv3&|&GQx-1C+GAs1EA^~ZuTO#MTcpS^JSmWya6!lugS@<9p^#2qP5p|o$%ox& z3v&pU)sTWa1|gBqZTH^V;zF>cuj(?tH&2ewJQ(#m-D~fN>-Kj>TkM8fK&3(o%;GwG zqaH%T+CIjBis>rQRKO>vHeJO*zTl2Pb#A&#xhbCqlo(>e67rxAPpBqqW!g5$Awz3h zTcjJ*gsm`ft9|8QiTWY;~>OyLR=dTGu`p8SApF%2h*SJD%vI z2I3>~E)Tqidr;k&T9Py#>&?XDUSl8aJz+^p2kFgNTt`&O<*lLfg{9jPZQut~{SADTP~Fo46-ahgqeD;+fAr6M zDKRP?iuvxDpV!~3g@qz;@#b0D`(8=ICCfXtk~d2Fy3dRGl;`$Cv0L{^CU*7C)7jcI z(*D{mT*`^TedKu0fir;=2Axr<&pkrZy2s!)`Q*jCU42WC%8p0grmfCGv+<|w!TV)H zUwUJ)hGazuHE8^8_-Fc#&%;mkfvo~4%2scb`7T?ro4RrCi1_@o&Fn?ze5EF}%@ z6H~a%HfC45$~iEr^T5thv!&zp7$fC|c-dxv1$S-pF;&`AMcw$yLZ#MGB-6nKjlL2;+@QeDj z4AU}ls8yg@VD^JJ_3U^Q-fXdT-M7ON^1s&uQXvCNt9=eu;TkI(D%hPeE09GYndrh# zJIvw;vdRU-0L!KfRYHU8FTSK;(#R@VRslKYcXEQP1xl291QstveS=(TWDf}8^vF;m zSF~mWtqL5UtcXW2e&jO$>b!vEHSmTQow;5&$={`Kq`hf3Ci}^*oSS8dz=lN)@rV&Y za_f`un2djJ^?jkt^VVJR}C`}$yJAP6}=1yxoS(DeVpsCSszAr~{&JFqCWa|cJ z<3}TY1Xv1yLPa~~P^4S()!~Zl``m0&|E-(H;BNbn+B;^5wWMOMB<=mPq$!syapo7% ztY`b68^lKcN%^SWtwtWYD&DK~i8ybH#&A}>tBdkIhTg1-zapuM#88ghiKi22cDIP8 z+MvMcYd-RoT#kBVFKLQeYzrDJ&h({TKYE%M)@JLdS}$>^7lUseozdJ(?R}@W@n$ysJRe4m_c?0 zDuQ0%GY}_z0e(}vncN@|rg&BZ4=hoW%4E^6Y}diwdu2*EA>t%o92nKVyPBFn1$L$G z_)I?Ohe&lHT52E~jjX(FE60`EmY5!;S~op1lIh07EGHySVlXNJQE7B`8YTN>~zX}!lko4=M^1w`y3)sZh)7|koqfS?0s33y=&I4 znr+Z6DyVXOduO1B)eGnc-2CeJMD^!Sx+lLkFqzNDS^sE$Z4t~90}Np730Gud zj-MMgHLTf6X!c4HbFaQZyTC+c4$U*Zq5mYkwuZ?xcuUf3l?OQ`?OIV8areHQ+BWx9 zQCUnMM#TD{#rvs65NqI*!3*aTWtw09IU{TAXNF}BGFi%5Jc^ewq>3PQ0vf0@ivPLg zfW%M1AN$dEl+$PJZesU@{t)cvPEfzea_9MR%d1K$z0Z#$JT9<4L7XT9hjhjhyo1tr zP@wlRNH$88_LQNqeCgPCRN(CK(xuI>Tg7%GJcFWiwSzb!Zoq#z(;Sr0?F2B2Xf0vx zDDJa~?#IvB=NsG8%y`~?w^fF^71r)~|A;DrG}08#0dk9t_PMWsI9K6f8hZYyRidTa zV+VDHITzG_&$vJ!qT^!DT%_a0qHAp9SINfaNlbvBB~`uciMci)OPP++{lKP;QNbXC zk3Cg;gv7l_8^#_(<{kJmbh+5DyW45hr+EU&z1dv6u~h(*6lZ&&PX1iQQ;wpyUJLTg zf9=E5XLC$(oP(K0+xKt6d| z_YY%pdN-p?E`k{E0EKTO>{@ud!&^N?8RG>?e^K+%oq4u^<5XH~f9yO|dAFlaWyl&f zci4`Ie=M`sy1aM_1@PnSL|smzcdRY3){vG9H!94@Hw%6YI?$FI^*>cvWGr`)t@wgp z_9U;F-Rq&{8;HG}CUWUsp!<|kaM@=lzD?G2li8{EJ4+CF`Vo{Bbd_g6H%UY4;d{@>Y0?TlPTnx8`Iw`-@#x@7vYRu~g!61q-<%tP zbMbwD^8V*g@G6b?3r+Czc)-)<>jNaTsUeFn$SN%dwv;O5+FL>$RljOy?5n&h_v{P<|xu;WaN`;N0Cf>AV^1 zzz3TQ&@4#i_=*HYbr~9e=O|!GmX&Y#vDM=FjrWtBgT!m@>nnKkdHk5|<*cCLT#eWtIG5(kcVz&RanBFcgB75jzmKR!3Vm-NiIZa9 z`A`6Tg8GSXrV#S}miF~%+D{CHcW;8I7he1k!WXbnqJz_p&f~0QX|e}ek&MgDQYyV< zhy31J?PikX$XWlG-pZ;XhW-{$4SS1lb&FiKO7Yt>JE&Tx;3wl7-Yt*YPxy;3Pr5u} z6or_M{BPkiZZfW;4_Ine`LNla*UK1b(a80-((709;Nj65GPjY}(Ld*mcm8!@CeE7f zdV`9BKV9y_<6F4Om)fb&3r9pv-Ugu+`so@|*C_H!`JI_gEXQ@dc?;GEHTyXGlQyD= z-syvM-YoUFW^}WSMB{H1bP0Jl>^U*`?`1MOR*6aA;uL>TS3#PnUp+hN5vhI{jo(hu zg_BX;0O4^JVJO(KXc0DKqB_zt+e-C#NX8z7g#svvDBnWj4a(SblmZ+He zX}Q;AdEPJ%U?K4mf>s#0a?kJrisXqYaAwOq;qW>a`grU`^=u&juFPTG~Cw9ua)oC}|?&7T@J&T1d|4<9W%#s2lhhchXX^s^vzC^Gn+w zp{C~hg+-sM)4EKOs&;%|jL{dZ)bbmu!i7*R`X>ejvMA}5n8t#>bxvuua3qT-y5p!d z3-?Xjf>7{~N&M5>oF(3|3|Mb5;+PSjNK{RkDBPFVerbM#>tY*)yYryGQiLrCO;|32@&u8etmkH191l+Xi4=oY z``;FJ&?9-bMe-qkC5(Y>Vaki+v0^mjlF>S0?XV<$?rz^2Ga~%m z`SXtIMk+XwkI2-4nR&lv#VCN51!=P~x)PNzA!;SuFO11P)+ysz?^8V2FLl@NA~_Qi zXHEUJGx5alI!yf?<)t*M3R&pmE`D+%67dWvFsW#|Usj^!A7X|7Lf!xj8qmu7eQP0^ zvv!Z%#c5Md&~0EIv(&tc3-LzL{M^6L%*2{gK^n55|I-xC+pR_sB)E)TL$Air-<_JW z^E*0-oto+ow2Pf+d^$v=ci7`FaQ%r^YQ>gxC!?j!KhvA+tT1XN^?xj$g7I_ZRQ@sHKviAc! zDdq%hnWT=BPof*iRV9f8(BM=m)*HPA5oDYw&ySrk2Ae~ABXO~Ie-QtOvJS+PQ_j70 zP5a4b&n5g*6Qfb%p|=@>-A9hQmU$yUj@^TMRi&hcY z2Z6h`=2#=5mkjA=cVln5q!IiQ{WZ%!5Xx@Jp3{&D0*5lwC1+ADy}5pGF6^enP%U3ensthZ>m^^u*JFG?gJdLKi8g4LEw()%Yv=wyvTjv03R0+ds`FinxZ=3=WO zTVVc%F&S>X%005G_J&}>twDu8CcfW^4dr7IVMOw$H$EPKlPrWoHEFI9Ymz>8b^!@N zP}rLeRf`?^R7QOy;OiBDSmuF$Zx;BNT=i{w%e@6H2GhO6zy! zda0*i)xtWw4ll<@%xAVJ^`D>AEB|g9*J+o6VU{dtu&gk+Qhv?DUxO-m@_npQD!{yh@Pk=KR!hD zI|h|IriQT@PvYW)5w0an=aQ(QuzL{wIQ$ryyg#gchx%(noteaw{qPN=gtRQ)I{GMu zc}JJo!c}8$rT9S*2K_smFW=21x2up~kG@~V&i9<>g?tMLtNmI;Mt)n{GflXbwwBOF z%!+~)!P&E2;vKC1Wl;{o~rhNxoet%6^B z590uXgkY>-3JCzqD(V`A(a23fzR0#R3&GbN&vWlt49svmDtWQ9LftiA~)WlH{ysw9cA5g8HCc#*&rbCwU%ztu2NP&z)>^o~>WJp;MxL!z&9?R$qMmUd}qY?`;FICVw4tK$wEpPfBzE<>*E}0;)%ntdtp;k71k}6t6j7eU6 zJtHmcv1C%~P@;a>d+9W=%^-**SDEp9t$OO$EohNfmV$Ugj@3+B#;w9`k3}IR{321O zELT4s{M@?xS8bHzN6!&L-HMz9VJxkpFS4NS?Xd*Z*hiyHZpspGmG)u&6!_km9+j*f z3-mpYgRoKc6BHM~l&Dar`jEx9PPL%@w>~T5gbQFUWgrHpcoF$W*{|Q(RZp$9SP*BT z+R)|sB`Vv{_Q*8;xIdZf4}a3foZk74FmI4x=7F%>S&|b^|0%w@DM-fXlH#a|tZ`Z1 zf;MKWsDabwiCf8ca!()O{)nY~b>~;xrMwE1)>9bt_G}*d0ij-Gp?w~Dll9QNXiK~2 z_+xc1f8i~kia%0RJ=_DqBmTH;=8nX&4sTb%w#L|_IM!9w8_f{hym`bgx+asN5Y|vczh2?;DheO8@KRJFyd~uP%(C#6rKT3*P`s%` zE_hX;GAovRM`mk@QqyfEQDO$0!s>aHLo_WdJoWu3vxL5sz)5Qphd#F{;hXn@_mKPi z$y<~0pxj4ma1~6ky(gSUOfYgJSJ6$o{TcEdXT#2O)5!Um=v$py!NzNl_wDie`nrk7 ztI92>$E%OGv4mL9tK=<>+SHui?NyLqd6&-B#ZKpPSzOcdm%H{`*eTTUv>OXZX?>}hBWcQB3VY zbS5paXlH3XT^xMGil1zio5gwKuAy2o3Ilw|{Y&cgMCh zzPZ=!p-tSDqat9>(sA99!#ZgDB)hHGo&$0@rs&Yqb3JM#_&8$R(k{N8?rzPw`ng~< zGL>p2j(-7ilmY!QlV?zX$cV6KhQ(Xgns=7Y8=Adh0Dz9^_fI%-R0QwUn(en|xV!G1 z{KRa}nCo&A?`L=7s0iFXiQxjbX7F~qjd6*zWN7udfz0F$#yh&*47iTl(zW^yqi2b4 z(H>MKJZxMG3OBE0hW~5+YWtx!?fg&#sCkHhysF*py}G*t!)-SwKD<7mf~GhHC0;)Y z&7cUjM$snhp${2!?a%%Fz1AiGOK1@EW`S@1c!7Ag<2oE^o;V@d!HEAVjIAweIOnJn z_Fuf$&lKZ$#0*^hBU2|GtNH-fv=fO;l{w4S%_1YYJ6lb$j58k{SS)r{lBNrhQ)v@> zAH6%&59X8?g7mee?(%mg(Ro@w)9+utQ*jTMkX1fiW7<0q3BhMq4n`>;)YDmT5-?44 z4Gg@w*xmEf1DY)OY6069e0u@|+&a60b$~QoQ;_55v!K?|%fqK5yS52l>mC)Kt8I3^ z@s0x9ZvtE;U&*k}XrU4JxL}asL^<%Lt&&f9J z58Okxz~+_F>o;o#n9NFcj;lDw!R}*&EZoB~#}PeRZrQ0Np6?@?O%o$Vgz7{D8pYlp zk}S+Fn4MGqh+8~FvxZ-jIrfNbMiiAi#*EN{r!Mjo_P4IV5tTd6ds6`~`tjIuPza${ z`WQ2E4%xWSQ*%2H&bh?%VUP?y^SiLEBQ-1D6j}>Ej^}@eYuqU`?FktUs*5~HduZ}k zJHTB}a7yMg@5Xrn33>@>*XW|+Ehur=rX=_2DGu7W9q^A_p#+kr(8)w?^ZjpvSa2??%ef5*rq%~BDv=M{mEM`TcYa3 zfyM8k@5(OIvW4U7SzAdC$IKyWC3v@a%_PGR9Wm!4U;Qb8i$|z0^Tus7`{v1e&UU$c zp(;szDW zQ|@m>Wsg0|=8*CWJs)O;Q1eSXg=Y^DHg{Z!2ZaFk)sElMtN2R^fc%@4l}2SB&`}|Alh6|41I{bi=SDs6F;ujU7VT|u}*tf9((gOY4xMqashVEx9F;s5dON4R0O|Wo;@l?F2NYTPf6Ot25&y&{JC*0O{ ziw*zpT~TeJyVXI&#jZ?I~%L><7@QqG@^4L~<}~K*f>vB)J3v*g zTe9Jf5U8a7?$^$flC)p-sJU|9I-c_6bQzl{p!>=3wULJmW%Mpuley(nz)8L11@Dd> zX5-YBa&r3zg0+w^vA7Rx7oRtux*V3V66b%7MQMq(>K^^9qZ-cK_C%@@kzk|W=zXI( z1HsvzwON7e{qD&=)Ri47bA%@gDo&1_`!hV)4I2nX<3(u8!$Tnhp8!iZGhPx)eelfLe`!T)~4aN&r-Ec*H{nOFxR;%O+`?f z5jHxcL?p2R_Ien@_emXlz!nJx8Gtf(ctg2k%UNF>Lz#a|#_K{=m#SoqiX?TM=K$nD zl*Oq@UEHTb{V!%j`v3}CecwrnGEc9HrqSmU*f>&m%70*fT9MecdW~;;tdJ-Dy{x(j zU4qoI=_5Jg=7gB9R??S zou^dQVpdc7$8D@p`S%q6-A*Q*R{sHpw%z{$M(20%a+>^@`5QwppNt&^Z$CEW&MP-E zJ|<3@Tz=)axRRoan3lSZr=F3rUPjNOWkSHzOhb6f_dEW)HbO9a!#S<}L!9cbs4{5! zH2-0bGn}(=UayF6r}6pzu#@rG{(@8fxk*8HWq!fweo?1{v2!(KkBPH<^#0yKWB1Gs z5Bm4icA6vAbp!pQyg;6Zj0N`n2?l{8cbB*d5>R$)Q<^hqCQq#gz+kAxw zg`SC#snTXPa9*|Bc##+2)O_vw4_$7bE13d5Z*niKr7pOq+#aAp1Sa+ zDZV5>FdZRbjn?y)#{q+sbrlR_V`#^l~VSoWpDEeCbDp{6RICW z{4dI`2LHUH;GcKYNs?I*ua_^)8cl!-WkU$T=psUW>rx`WfDxkAYH+0MgwN0igWq(n?D>5f2-?MvHIdAb|)M;vh#OT&7TJu z+#WK?uwv*pTX!o)Rvpyd%$K^Y@^w*k0+ zSxN3KppAhlT=9$~VBgDjfSq80apfH5Xp1FNa*+ojnlC?n*Rbqb$%LcIxtp=KlQcg^ zoxgdtrH`?sZlR~}U`MD!!lErk1*Sgi^9VrhBbF_onE@8tWELAB?{;@&UZJPkwq>$C z3}al}Mm$>p%7S7esx1ILL52}B-3py?na{t32CDapsQ=`dE?g!@2r_@7$59M{4XvVA z$U1<#uHae7GcVzD=Fmsd#}wckJ}4v!_9dEvM0tTsj#q6Y*dXy#et+7q0jLuUAwQ5VrFO{U9^$D|bifpFN#M3W z{}MW%j5{UM`&S_o8@A#gfF$WAkUeVeUeaa;ZN7E*Cf;n5!&)eIDJXm2Lv8>3u?{XFC2B z7+ELj^3Pl*j$r&}0z*Hgdj9Dh6sEnj1`SIHp0j}-gGWb$+{xRlJ_|_C#oP1%zo-qp zzEG|}-P0Is{Fi)P6AN+*-%O@f&v62&)Fbv47sx2{YB6G`MXQ8+uC`7>>G{+WADTUc z|4k}+VF${n3mI9f3x6zpvmQ)!T@ma8lEmwL6+W7pB@3tbc-3)rYsf3$7!wM$psv;c zp>*&IJ& z@G6pU?Y`5@bK?j*OO_IUZ`hqkG>n=fS74I?efL|p!_Rs~m1L5xgZsy0WU~8R1Bb$X zpt9#P)_wU(6u-7psA_Lsu;620Pu-MOpz#t!HPHCw{_$kt=?owWf+YRsEg(t3rT%v?N}5L#nr;L9=EB;4HZ82UqwQ%*WB}0? zeC%KK$s4O`_K@=I(`$u7-~OHJxV$5QgzpC2nE<1#4EDopbMSN&)z9J&@^|k3Ql^W$ z$U_+k3jS|jSJ0}{4LHm*v+ioh;v_ggLJX3=mq+E z@CI!*U$N9_Jo!e2-V;ppAEQfdmG|qsW0!(I)3;7X4BIKjigjJ&Qn6Hp^&7V8d={ak zP7e5}%g59_FR&4;<&vIdh4H!E2L*ck}ylJWBTa&J{YbJFl(Rs$qGds2SKfg2>>u0AO*WtGvU9KUFv0HtSMTx%B1G|rKr zA4$dSEnRToLP&Yo`hDMT#LNu1Y|i_1Sk>k=J}S+*hI)Dd8i&$au)Q0(Y%-eJ_B5F1 z51ar^5S+)FY>I4gHc<93l>vI&Gq{D~LR(FeB&eSKH@vSaYTAu@j*qU-pfkD8_d0rg zH|M8Nv)~QNYFJ(hGb?I|?2R>=L&y>t8Z%<~j%Ui&iZ4z==n@%v1qF7#pwt?gL2;KovWwzMPcUlnZ{vOD! zp7zMRd0Jq82K{!%CQ`AcCtdnD24cBQ|Fo_b^g4WBDp-KMU@O#Sv8nm<`)p{(vO~hb z3&SBKAm(8-&VOa<9``zxLkzoQV z#o4Z!yq|42>ZqpxRjJ=?Bia`#$^`RA3o<_;|CeV>sr`{8M0HX1n#|{a!OG{OmW)(a z6>agNNpqShmcbC{*L<)S)|#ge#*KcCyE!N@*EkvR`TJ*}ThTb@=4Q0i_dM|H60$$x ze65Qi_wcRj$6G*k5s`P4lBJj~iMJQ-Re*S8jLQ2W`f9)1QDrgmIOcX`s0inyG- zy*3~iArboO!XF}U1KgRdvXRtk0oiXmzypgsv0>5$-^XK*2q=mT(Lc%nKTU36ttZGV zNz?)gbs0*o_Q^|7wN{d(6S%JqP7Gl2SAS;Bo9# zEl+v0{j}S?q2{F|38^);NRAPvi1LO9ft@N>E8ge$k^1VXrRKL z5btP0yl-(_y7QSw1`4jM4h8O{16qRB`05YiEdP@}{aKZ5@B#{(Nnuv>Sjd z4jN*Mz2*0=dtQyD7n#_{O6R{p zzXrNt(+OM%16PHj)})W)6~)xtM$o$f6<)+yP$`Ec5XQtk?Y_`~<^*bGo+zqfa*a>k z+^QlQ# zZ8YTH4c;x#hf*KNSd7SRGX1IqGV>mQOcRD7VkZTjXJFcOJ#0Y53KTZ8IQ5*3XErbr zz322JY*7O@z`B7n#T}Q!=glj(*IYNS_7iGTE#KN@7S*(h+Nl^$d8?+uoeGaCtXFN~ zyGV7-Ghky=5Ng844Zgd$%~c!zen7wf=dxSQ%YpxG9{ub&0gMnc1qu*ek6+fNb}ZW4K;NP=yE3}-5#Uem%PYuSkDGr|>X9f;+{ zo)2rjD46GlWNsA*6OzYQb``~l%@=}Y<*9hf5V|Ui&#-0n0N6tWmg!-u<$n1m&GWxk zx*}L3c$4Yj&-w*=l-iJg7a|{%8FJWAADg{Eu%6KA60a`*ytDmip5rGEzqZbGVFSl% zI^McBV`}F4kEpz@XOoIn-td6L#q7V7^MiRfDZ;3unJ{-8bWi>&M8hbGip2#9*XubY z)e+x<0C4@lY^8xrZ+aZ#Tc(hT+Sh4Md8G~4tt5-w8-?^QdeT+$GlAnLp+QZk&`x$tS{5pJrQ476uT9azwGU5t0J(C z3|v}wTob*W1!JN&b=EdlO90Tn=yqK>OuII;?KBYgAC1js;gDx9M4j0%t=Z84HmILF zjRhbd-HrJnI_~+eFOLVmw_o(#d#QqMmoBznphly_$8m8))_Wd5p{#-KDe-N`zCsE= zx8EhmAO1xdb2&&yv|E*JST~U1bTgkY`q^4DKEM+qdb7>P^4LR{Y>9A2f4*}3!{WC| zCA0ycCP=jwnp$YT5D7*s6SmKSL+vz#nI-5rw)W&;)~ifAo#J_&ZB%atjb@71(7RuG zIOy5o8I_j<(t?K@WGLWK=JgE`w#rT$pscWf`t`K1#o?M%q)q)hP?g8cKlF&@O#xy5 zLl4)7L0{~C+)1L}*$R*kT;1+g^gsgBm>a-vp-d1Q>A;St|A}Sk0(5&#uW}X)fH4v6 zLq|jyYUucZNe_Fa(>M5KS{p>~#ld3#AY}KE5Y}oYyE3n-y)HD`2Pk`$b3SiOpeUgV ze!dcn^BZ}vt-fme_p=wkQ82HAQL+~nnkS_Hxdx1K_PgrY73Wur!lG8cm~_EV`6KxF zD7ZmvuSJwihgf|~cKyrH|D&ALZ$EK6^oU<+SCK2T#pMP!O;5bwhyXzq4*@6L!Psq6 zG)GYT$DVsi$Aa_xOY_FgZo>>Y@m@{>;$We~lWV(-V^`DFi?zhb&m)NLDaYA+_;r`8 zr~Wy(7W-uR;|~vNG$}6V6&gVsyrHrTe~A^Rj3Su#z2>lJ6vo=nEn zEG>o6CKC-W@%Y(6^Qp$-0w2BO?GnV5%P|ct8f`Z%vQ)4~~ZZ{-;{ihLqU= zwYEi(VG@Qs>~YU7nPbXUKr2qI^l=_q1#)fNaMg)0#_UNT$z}))5}Mps1&I&^i#zB= znCs>c5^d^7KsUX`nEzh$Keu)_(HQE7VM)(zv**MAE~5JJril7HHMhjN0X(*OLM}uN z?yJJe?^>xK=Y4`EjF9oyBR$(fDNTw6) zs6zlVHQPNku2n|wKekgLKHlDf1pXJQ{x@;*KOMBH^LwfwT0$B!b_cfnvenx5u!stm zsp-g8>9TJj`-7~}jYceiHB%0Ir-S>qdfXFnIzC9gOBQB*5hjY$3a3i$QNrAT2{fKu zYuLrXYoqUyE>2W1X1rtr&PJs_+e*wI&$ITRjg;)d%-f8lM1B0!^Y(0Llt*BjW!EEU zqx8gv5|Tc8mXaDY++mmyj7bMHF))ymD%qrvp#f&~r#7!oiQp^^dj+*adx1Eo-GKo; zP^ZVIa$o`YasQzu(71lwu1!!3xTGW0QN^2aays;L!Q9{`)s#zRFnI4O!W~I;7?v+{ zN9Z0rzKWbf?frFJ`a6{uVPnhF59SuT%bhaPdM|YjqJmp(3??SK)EbM3ru9ycL$t0F`YS>Zl7nHFzWSSa0!VHyJ> z`hBQafs8rRQ7mY2=n=9lrWfPk*N=M&jD;mP@VL_anKk^tXtUy}?|SNzTBaD4oGIwm z^|?e}@%SfVc}G51_g=hX zH60E>Ex^Dj(^cXVDW8k2>6&CWSGjAjwSfxTiL^+PbUCNvdfQ!LuvqkTuGDbSR3{48 zCcHn9S6$r_xnFzNx3ge7=eqTgx8FRMdN=!iRpCq)`TqQ%dfP=I(2&r2z9bQV6MMcL ze7yh>B!P_3Inv}Yurh<6J@=EnE(G-k^%p_EyFGgCbWcydDcaH6m@ zh(ZM#EY<2!=8oAdd7P)njFC;KytO*npq1+1mf9UR=S;8c6mkpmXE=(xfBNi>zU;}pR*Uom}c@nep) z=G*p!|IV1p+|5q&;83@g~m3s z+aWVvH%Uf4?Le~OszfNfFZpG_PhM;B%gnyJ-<(0u34M=4eXrY3a~EpCqz&E@Op|>t z_Kop9%^cV2FHmQz-#U#Dnpt_!zc~Q)Pg(!wd;}c5 zWtVU@>wCliZ9bdq?ds^KSA?3~g_-R@nTHDQDotKJdrh7nrtX8tU#9}5 zK00j6M2O>7#zcU}F4+U*hoLoE*XofCMXu_AnkMFUb7QLJXjS#vRo&F7M7&HE!SXG4 zN@Ew~{_L)+Rmt~Gp5v0!aHB?kY8&WZ&_p&sRn*NtOQ+%a_@+UQ^Pt);yk zE1sP&S&TkOS#x;%>C79*X;V+$IWb8SXFZdD23G@5FEAEp*GQpd$FW#~?9wsqro(}9 zEz!O|f;6U;H^$r!7cyO;Aw2`}!xgupUCpK2w84mJ64WCHN1>h3jS%Q=Mm=ZPa&9h0 z;JNJ4aV?2{+zLF|V6NIRHIV7{DpZkLpI)%q@bsDYWPZ0-(bS6&Lnv4Z?1)}rK^L)Y zTlv#^V1?F_J6$9$lUlcUl_&TqU6)`kTd-2gTzLTy8N$yg=3NPO$H3rMM>v6(QpYt- z1TUkvQAlzi)qHp&G{_yJEM<@j#n$EEd2gO*6s{T9U!@71=#AtBC+cCuXn)^f^Y5M& zgZz!rP4oK2f33@-Y0YmSH7Xt~F!+}>qJMH6^J2AuEcHvHAya+&X-|R6;lA}Lf32nu zhK@3BLb_vM(4D+@L21ou!&jTSRdPAii>b(B0-D$@^ahIWUsNKa#<`Ot4RLc0+O?7% z$mNOwx9mbuH-bM%6anYfnrG;gK?mOqN58N8I)qBsgo%)h5{`cDW7B3eO%hHf;L~mN z;p30?Yt(0emK5?PC`_4UUnWvG7e^tMg(0=%13cb;#}6E%3Ud4emuBj)!9&WO(m0|1 z@ne@ju?CiIoEIhK+h`R889nTg*;3C8)fr+>w+`QM;d~@ZFoLOU0KXpG?wU_X+S|NA zN%1Q!>iv5rnaQAN_c$E1onCQ!rVE0<9J?F=;?c&ER9x)g9PXi}VjoDCZ@(2NSoLCW zU`+}B(%ozs?vf=5ndh_4Lk#OU&e-_Od*NL@!);|}v!vNd@JE}FpI0wi*Z;{OZ`eDuF*%&Jv!KbA?&4qL*8rUDB)rdYd+VB--}KGmI=1|6O)5ohzW&E z-fPGvLYW`0uJ*K?tgQyu)WzDM@EFW2UVk?_%yAYoj(FEbox{Zp<`3BS+|ZbN+t8e{p}~32@!~h|BOhh7y^d11 z^$jxTc7o!J8?_Qz4l`5dWJrzXHdZfOjGGeOT9S0YF0DEKBRNMG;!#wg;_tRnds-ef zWy5NcC4nBjY42QU-|s8QA^RTgUv{t0es>W0uU1 zj`jz^{adUGeR95Eq%vhTjF;aRo}HYfXteujf}Li(O3ox>I0R$m&Z0N0C`T|R-SkK} zQ+NCc3?4nA=h4xALVXk0J3T38AfeIpea<4ZE0aNZv?9*(OI+{qB59_})aKaLZftSX_0tq3R;L|yk)(O)%S4an2+mlY14Z~a257_xTQM6 z4@*Il8_c@D?1N?5W=53vT~i_o;Mv{|t9>9n3>{(>cZ&*|TW!`wEpFgPt>!-sxkVq) z4)sq6(>!IFk+Ty;k9PDikMRwrE-WZeDXPf3{uENmfFYnViwT zJY4>pahSvwvpLxEomrP=T9|%gzpNXv2H4<1*ifJo=>7t zQ?9^U<6CmAW}+it`?054D9+MZ0|{Ss+1xlTQ0F)K9U1xVSe-m1Ac_X-v3FYl&BVa9 zX*n(zE;6@6idC%~Nd3H_H!GO9CvV(--Y00U~?egQEbKvoZ%Jum8gp zC)C2%a&;`_V6@(nFHe(zlKjH>F*8CERU$TP&Ah7I%#ykJF6{5DWPa-<$1%QVCW6iz ztYyY=zUhq(;^Axka0{HP-VlqtUv}$>>ls7Q#CXye%q+7Xzf0%*&WwcBQ~2c4w$a8; zxWHX)d6RMrg_YbQ4bd1?CAd@ck#m0KjsMxo6f{FPoBO`D?JxL6Oh29gla&YQMMk|P z1-+h9@`w3)!4x%_JM*0<1d&P>tl zuU(9{Gvco=NuJ*`x%rB9-_93wdHdED22l7ju8lmGSM}8Iv&H7a2T{sC9(11b#Jf@( zUitsn_6Z5mfS(L4wpT+l460x+^K(;3oWc(swWP#)>v#ur{90@-AEa(*J@f^@{mu-| z0$Z|dD!@Kq^J~L|m$@}$Q+bl)iDh3E)&Q?@11~5|+4IMnL&0*Hvt5^M&E@qx@mkih zk2Qw6Bzm-fA^{|Xg&U%k=f`RC_6OleZiIHTzQme+8P+muvd(@Hd0b67IpU(Q334Z9 zY0AJ1BQuGxXm-l0Rt_WapK2+n7}9wZjio)8*xs~aJj=skQu}J?^Z4$h^ox{v%EjW^ zS0Te*Vi-4qnp0xX2kw*{JD_TRU5RULAh6yi+t@uHc6LSA2W^7*Wh2v?rmI-y8S$(b zKSKAVcROvrs1R}{b1<9n%tE34-NP+N|VsKeyU;(`? zTI%-yjrEmms)Vz}K_zq&9fIuoVjCN>^94U<~&!6LS6;e(_4Sm8K(mu1d) z>WlIY1LBA|TA;zqFK&9u&i6XKU$0ZS{d_u+t#uaqynKRq-Om1!CH`9Ms}mf%Y``2C z63>AnX({AY!AcJa6x4e0oOTd(7Fg22m><&Bu_!jLR^wqf&OL|-pL={#T62yIy%fg% z5M7bPeNULfhQcVlOvW{naLU8l)0Jj>-y+hquL)?Vlmy|P2%v#Og{-W?ICXzqPfwu% zp*AAJ>VkIZveyJRMmHQS0v?@O)IE!+yEL0Zt=(a|2ZzkTxa)KYbx8o*`TAPJHXASQ z4z#^L2P1!+ef|*Sw|~Yil_&OX1)+)=YgV zsfwI^e)nb4R@9m|_IU{}k?bLe6^Cfiw(~s|qYRqhW#Pw|V^{^C8hVF7#M_wx%msC2 znyg+g^Q5_k*#Zh$x`uQPgC?Bs@)0is;*_kG>G;$=BV>1w%rFt1syb%j1SC)0P` znWyhyF{+)cUwq7^OPRXqI&qRiH!hYDiyxJs4bvsEqDV){{XT+=Xy9YgfZH)!=}si~ zTTdmRrPZ^k_aQT00vs^!8Od!F7Cuv4; zwjaFBHm(fZTfoIZs$(ri*z2#X@=M|Hf%?2lH}6NcLLam`xCJSUc%au~t?WwqBx=y= zKMM;+j=snLMuzlmcP{L6k&r}7f>B7CY0^Gu4SOcR&6vM9xswg+ZuPPTnZ8%ma`W+A zNGpq3qbbD9ngw1wN174g*eh>zgPL493P`zy{jH>o@T*&Ki;{b&_aS(29d!ivyZ+hX z)c*%!K%Kwd^lyLTzl-s`_%8qe0RR7l*hdcRz;+(sC%`tOiQzS9WP=0d^Z*Z<&74y+ z&6sn}T!L0*cvT*n*G~du1Ckpc2o9RvRV@DJJN0*e`P=8eyodhxfBDOL_hZuh^{>S; z_RhA{L-}9-F_#}tXyHSEJP2fXN4_}@{?5>(sMb0E0!5Np?Vf(;oE4{S^* z(6tDC3oWio%@DNBz|PP@p-GS-s9)T{6k+yHy$iGQ9ermB)m}f|K42{!Wtb0Yq zdk{HBz`Gst&zH4(((9dJpxjipx|~a5>2uD^&KK!uNOvTtR7A$^4LvmSdIb#9w`AY)PF8c$`}!hrRD-_t>GzJ7fF8GJ9)^X;vy8+NcgTx)<6bZNO`ansmc{%0_q3UF2V}BJ4%&dmniP1 z2Y7Dni9+4IiS_FRa)mkdTd?f|!kai+9OGcgX`209(gGFYt`PYV!_Ay);=Mz5){UKZ z`NylYcr}Ekb_+4mR0+*H!WGOo)q%UYKaT7`yO6V*T(CTj4`Y1ECtoJC;u_$`-4rYn zU5K{(`l`Jss%hnrc->~XeX>EhqS-k@!}-5G-Y$frnhYjE|lX{*4m zMX7>HMXQ3Kfh9>#$0F6o4cGeCIwfgr@a6cS$zU`t?2 zU3&?aW6iTBLKKTc+^j=ez(s2o&`~JX4HGk=Y4hxZh3}c7;=PJ5K?U^h)&+j<*A^Bf ziuf+o4$t@{*0C9i=w&pLMlVQz@gSfZ{JxKZlUOkbTTZz7;jI`wE@2!WjLTJF0L{J5 zZJg==Hj$@XwKqGvOO4LxD*GU}2VMSDc>QrApX7ZwhobEaUi+DQ{Mu(><$ST7Tfc zR6xl|xE|?%_g|x=L8pS0TlpphA)_0Psu>eU*)R$(PY6x~5T-p8M|!sS%=_qz!#qPQ z+BgbU?XPecbxoR!(9HlGUi1WV350gSZ5=7u#7G85s241q|0Q<~!Zg20u>06!^yA}N z%-AaU`2j~w;IMwi#zS)ck5nr#&KJw`IfR36DFQdhiZw!MLJH0?L1zNev?u~u`wQ%h zPhoH8i`q*mfxU|&MYl7OC`7FdVWF*qw#bCBk_y2&aJs!bhyw#xsA-C1(>3Fh8>rJ&QzoFS>LL5UdV?ftLj6KqaLvk)wnLI zwuJL0j~7~~v%q`G1YQr}3iik}@3sOfun(Xi%0vzUL{HT;Vt^k?MRo2n%GMs1pel@l z#c|t1F>cq&C(svksJRoO0VoZf$Uh^#{3!NnszhWp(O6*w?dW@n*7h8>V%pP&#wJ>7 z*1HBgN(SpgL>Bs4Oi1+OgG04lKdjIvpB(X?0%YiDx$`h#eaIw z@98i9;h(+nAOHFK@809DfB(1hzc}Qt|E@!}KMuh_uKHIFku6M@60W-9pW9+A@{<|c?Gp#xjDVuWf=)%I6(%DEvphhp$$O6 zD6;h%CRs{tLcn*x7dTQhz&VOi=Z|y3kJlRQ(~owyp5OT_U+C-vMCbvbZG!33CjkZ( zhyt;G2+3YSqH&2SLbWMuF7sm1v^XL}@J4@~Yp?){58+{~cOTd!R^MUDZ_^86{y>4r zG4sf!qP|=FSv&^zlY6eUpr%oLxZEp|6ccLD-3IQaSl%9tY&WJ_srUJi!7?P>)G1^e z=)x!HE(ubiw-hdNv!b|^L&A502102Y?3=IU!8IiTvH3wUVU_D$v%~_9MeTkMxek~> zlqtE*o~2LfukNZPjFs}kfHK{~$8CNT0J)OU@$C@02W2(Aw3#IBF6zmDle?Sq1rQ?S z2dUzTY~p5iadY`~xAPF%%h^QO0~H%ydji-nv*oLk6ExyGOdG(tgFd9E03ETedw(+* z5@G3fCr@r*UV4i4a&S?#={o#S|0Lf+oj^0nzTT@zNhHD)O1`Yc^}v>7yiCifkey|R z@0!WXmy~;fXvy+Xt`I*aCzW5%PM_-MEoP3N5o?mYKYC!ZmnxNtX>!=nM|jM=@*{V z#D+#$3QF~Ft9fAA6$nf@N;Ydk&6KdKpgX_6l;k_3;UJ)JGp?9lNm8ZnBGusJ82}rY z2ps#e-R<7iFwTRALjtCr_%$ZCJT}f5($u?702H+|C*U0PBmDAqiy?fw&07;~6DsNi zyJBv*-U=I$!-oRe?6T(Y1ouVVBZLiRDoY2XPd#s4DaLt<2;|IOB}S}#eph3_V#Zv? z5^zv_E2OB-_e$~;i8ci;_@HYZ0ycojiDG1Z&`~^Z0^0!#^ox&b!&E1=2h^J~p6Gax z+xvHj?m=--J_r5ci1Z#NUZJ`IN|V`y7_&w}X$5EKG>Q-0c;vZ*jGn@P_~*^whK3|2 zk{hs`q%%#wp&%m=OIYk1O;QJ~V_d-#KMEn__#xH{NSP|H^g-mvV5Sm@2zRbL6!Bqd z45l1n@>9<6{Mn4cE`tELhNoE^0TJ?2@+dBJ0gYTLkGfSd2MNLU2UlLUxXXG^Oi)lT zjIagbYO8|MVWMo%QHwGaHrg+-$$;=_^lvaT$VT?hMurEq9%9;-gL_`FRy0b5FXU$ueT9~a40E!meE*ggA@)G}WX*YNFpo1-Bx(-ULuDjN0@9&U zP}GIK4QiEKk9atCtw>mJFQYuT9SwZ}GT|ub^76sh^}Tei1Y^JF8HpzKwF8Rs;iPE0Wh^EvoPZ2Hki z;ecR$_hmr^a)#j(IU6Pci_m_X7Was9HU=(JVu~AvSd;UCw^c)|TW2n^P^j_Hbn%y; zVL@bXGg@=UMkmc+-!woV2+F7O^>jBQqHS>np=1^u0kzNzpkZMBrG!b`G${WlTRk z<56ZdWV2JGk?nMEEx4#eWGSoQ?#%n=DdYco70^{p5 z3`CD)dmIS>4^)pd#p8xkpYVYIy}5*k8ai+UEXpO49|}!awNaYs0ZTzsH^tz*Nc(aG zJ&Camuqe))L-U|y8YDs>Y&UWN8odGb40IcgKxI-eqz4}LnTd%u${9TZWzNV&x8L4$ ze1N<&>=$b9xrZ0Sa-Qh*aRM-B)<}-@f6Vdc^T!?k>mUAocl^(P_`lup=lb7p$M!G# zA0oTygB)5vWrZf&=RZ@be8Z)Lq(wP@{p^U`S699xH`V$PgaOIJLq?+l=1G_rN^1A= z36pRFgJDdjM8-lxV&b9QcxJoaNipREXqpQBfCZqpPf_C-RWE4~hublT|-3)DM( zI2E%8EnVC}-e+M}1lxz!+s@=JYEtaI#EH3IW@#hKl_PXVWrUa{NA43uviT>fW}1Ot zfP&Y-k4I{ZT!O^{VfQCqjAK+k8Yd(;RT0e|6E%KXfLLE!>|aQ+VOKV>Y*gSHPzd<( z>mM0)Z%|Q;`1x@Sq0!p+|@rj#MDL z@*)sENlg2ivR|qYfQe*koMZaUKjaBKzwo~GSnkWkAj4vokGgQwc{qodj^4cQiZPKD zWUgB2W)0L9r-XPEYLMUL>M02@n&Wq|)!dExIF&B6Nq06(-USENW88h*<8WigE?)4X z%H*&q%Xl*+`4`0$17AEKY_^QOq3&$VUj&&Ict(1o6>lwyqt)uRGw0m9!Hl{OUm$ye z#s->6H_}Ay0uCE9Ra_IOCedj_SW>chYQzvABA9URNyf-i)`rAmGz17svc=l*{vIAD0H@*s%7~?{jb6DXvR#0bRX8VwsL%9QzbzxW!@Fx#-hdA~pfe+253) z-7k4@)uo0A z0ob4lgo|~_o5=-BGuGM(KA|#U}il!R=vSpGX>=@T{_#8 z)3lQ1*WvB=ayH9X^o6*Qd7LchRU?zFry!Hu4@7vg%{7*hP)TLXj{_VrytMFHh~HMF z`eV19s7u^2c|=Q;MVMFt)fj|$t)&7u=3w5()x&EI?+s(xwuP(7aTfl zFZkn}@fV~D%SQjjBJYHrOmV`0w%~k7J^5S8?=Geb0+fza8^Zh<3nIOziIe}-B92;G zQt!GQ5u=D(n}|rk{JiEO2us&Cfe7@MRjlPCdrcr0$fNV zUq>0bUlb#>A&SJWEP5Iq0KoHk3(bJOY?=^p)d_q&R6Yb(EOmhnRSGR1&in}D{< zT2E)6XOo{^jdx?c)`B#mohyC!I#E=B;hvzzmU|{tW@>&s!YguGK-GC#)twX?tOB(y z2ehfBWiaw^Vh9B_H&2uJ>h{vTgTN9>z(2>gKyt0ISwO=y&?1L1ZIHAEJN}p$Hivol zXUb%BIzUVP3TU0I@G{5%d6r2a!eo)PocQK$f|-|Jr~5#=09%0X*G;=4iX08K_srhl2X#q%;hhb(y zgpj}8qStPMLj$M)9Vm4nYH{%)x{>wXI*E%F)z3x)F7Bp5c$O}rVhmKXF}@}~0n&%m z-Pb)-7{iB4g)=pzYeAsLr_g}atU=HY|C?mW)Zwf2ma>2tOAK_L(`~d%%XA*Xh=>pt zR(*RtS7gLeu{kSNwn_h8Xk^es4X0huaO=YQi7%Dz+15sc2KyiY1&C(pxF{ z{T@zchGblzZJXMhZRzer3(mM3*GZeR^C6|RE*WsTXuqL)Bo<5_A~zG$gc)IZJ*N13 zdYkJwc{m|t8G@A!>qPKySvBTk9egQ_H7d%a1vh*|9M0oDh8zqNDvp}z!BaG*P?gJM zVUPtX$N~m8jT>)P5gb&KiwYDO)7&jin}2PRgJ9k1xKB`XOg} zP4LCY10J7{+ONi@f8Q@wvMIz8TKUk?bw{P3K@+DS9mYD%I&EhQuXl`{;HO^<90DFFOr{oynF-}a)! z8Huy$bH4!eUq|-&E$n;deW_fHztFnWfA*p({rUXaiy9)nE7QxozCeK3CUOgf(zQM1 zf%b3|aRUc$ML<>@wL|55p?78A!QcQoR%16R&qrndZhJG-Ut$oj2dX+1M&94{q6+fu zrOho8r~2p%f6R7$e$+`6FEipXci@r>yNz2Gr>`)e>1I$Pn;O{Ix7$L${qe!vziq*B zk8(4*EFR7%mM9{H(YP(-XMTiRi2F@H=Zm!ARMNQ z8>s0e<`d$Yq3kcVL24DhlHX-hG6xNMj1#YxKSr<;v zvG!PlrxTKS@;6#s>i~ZQF=h`%-Rr>UPUv5Gtxzod{zdgFd{qfs7X=At5DIP3iW`@}W z$@Kgore6Fqa$8I+Wd!{p_6^=k2!pgJTXBF$O;)axwu7VT@U9^*>GvCRGs-cVp*rWs-n zqT-`ybCMa@3FvxAl<|`40iTv)NehtLx;}=eUVhqni?V2o+2@ukWv|#ddZvKz$SCnl zSR-J{rG83_lzqMA0ZTEG{RrX1c)R^8c;rf8TGp3icExp=w~1AzVWfHM#!Qt93tYb= z(IG#qVuGF5Vg$}A^W9Zq-X4ox(D<|1G1P^k#TsSJI*cQ2ZMG5LWoL?~F4tQ`yc#3! zGJ(h`t8xuG^BHw&JA#_*k|ImhCe-u^6=6MgxIc1o_L6Xv92Ibcgr%zgJcmmy*wjV` zL8H{YjOYyq-pKcGzxxCc#e7}Kh^Rz5iw=VzUe5;-x-AoxYp}DX+Hi$S@%?lzXm`M0 zJ8p1KsAlm!zm_E=tt+`!r{1$yi2|)+)#ugKkdA&eXEzpmnfWC~2%5~4n4VhE5R4#c zOij;tOiHta)p5~6r-%yt%~0tF$vyf076IAsqnMJL2+z-BC`jVt3afn}rSUBec1iGa zwd@dKoZ;9RX+HV^eUg5Um1sc~nI?e>Md~376=q*de==#ArlHS;KPFH3f!Si{LY#ZJ z#FG-UQmFL9XNj+L1`M(^D)vi;VzWtM+*V3flrs`)DjjxI1k5Ad$TPoM1fWQn?KKc< z9wqf&*t$g_TIa>RLD|>#UIE>d?TIZBn1)-gPG!tJ5M?#5M;K)Qq$))oL4E}Ro9~xf zv9zUrDkZB)!=pu`vG*Q`yMj+L9kw=qB^3|~9+ICu0n%)xr12Jle!1hnScJ<^y~dun zir1{N2U)P~(Y~>j-=q$y(^@Kv5#Z~`72$+i6#?y{ZpKB4uTdFzBE&aSkiY)VU;cjl z=Y68=U;gs%_w_&S^I!i_{Fi_G=kveZ=l?SQxc)i*>z~i_+5M9GZ+|PMU*{~-w=e(u zueo-8g7^9!ybre3kXQnff=5P;`J?vn@&pvY_}@m2Wa-F)M*4`)CR@H);ALGz#gXp| z$Ke>`0n76BosYLSn@#i#Uusu5+UHT5@>~6eaqT^vU-cM%PrDXWe{1v}^m%}TWZDQo zV01zM+khon8q}%d4gb$a#SPC5Xwjx_5i^&!u$;#78jC~0{V>(hU$5ty5F+IQH z#lling7qv&SHGB8vXLw+026_l>P2smJBBZAx-7TuJh+$)xWkqa6{Tod!A+ctSb_Ns zeP$ec#{k7->%B^q zmt9NNA~XkQK_a-7R`+T-KSDI#+YGVX?=F}wMy<`VMHXk?b8ENm^9>E-sNIW|ygM^I z?CwAC=%b^x{}zWNrkiflF}F0Fe+`8F3s>YlBfK ziZ(Xyszh8y7$d>e?qefK@Cy4Dj|VQ6{hIAU44sY4mbXVIO%~*;2F16I`yL@N2Ij=h zD}hVl=Omf2CIUxf74)lwG@KK7vhJ$O1?q=|qu~CGkIsLjYgn5nm=8$#tc6s8% zr@qx;!*&&Oh4kBkq^J%P&FA4K|7Ef9s+8Td{i5#(SwEJ~f$2=J*cqModP69`e83P6 z`6Q8XeX&h$x}iU@B4fy#!Gi?va@h9;NMx3zRe&+ug&oIB*uE2$p*UL{Q2tS&X(GM- ziKrv;#c9Sax5t$@{S@R0J#&k~%c41O*)F&m(#b5ju+3?8>UUjuoWmwzn} zXruY!aK9so!o#60>B*CBXS9oJpv|Xi(y`}>K=o9ndq+gP|@}BtA7W!WmaGAry+j{ zoB_?uWo&C4_Q7IFlCo+2&9&0nnQC_nUE=OEDV@BDg)t+n83Wwbl?jm`fMz;$trAwfp@5FB9X+ z-!DJ{JK++hj*mXT-$Mr`9^6bSVQzlXHSE{@(AiIJ7o3k@sC2gMdHG6)X(5+-!J-88 zy~N3UevD}81gDrdB7Ed7#vI+wUj7($L-ippp{Sl%8uIrc?FKa;| zJrP>O@be9ji7-TJ6itCEk~?Fz5lhf|D01r?_W2`b8MM~d5Nt7r#8rSzsH*$gSag$i za~+HEYEev6*%LHZe|d7l32Ng!7940vleX+~2H~(L{=2U>i^-#SY@Kh_fHg z3I^QPbJ|)2*MAwep@XCp}u2={H_|*13G+1=g&Qv*v%zs&JD4byVtRN z`6x%&B>wS)lO|(7NItv%nw~?HWg&k$yRPfMW?t_*M$;d2Gs`c1vv*xhYUgColt1Mi zomWnIo(>hsScJ#HY)4U!E4Nndi%w}Uyx-o6HdUW68wqvpW~pt_X||5|LD`wX2y-_` zEw=CTibo~xddf>*LF+7CI; zD>jsP=JEGj@VD7W^*A?8Zj4UOlTM|Q)1Vs0i*}wWJ!zU!znZ>W#h+u{WrD!3P3c(U z>Dc5sXrx}f#QJ-e?fczM{Qt2u@f&Ywvu{3l)5ZvhHA%P|+JEZNV>ywh2~3eG%U*^4 zo;fC(&}R@llb!mI_DNsocKd1chV6CDhm>nCr3#FMzUB|ch^!kTApSiEgq@Vip24+s z5Y7$Ias5N|s~fuc0xzyq5{_Md0TJXBvzatYW((@z{fCpY7IW}A;1cYIop=>w1@UWf zqEha(rf-vAyK&~D+g;a<%^Zt-H*jMq!$ABE++509BKh7bS2AxrjGuVo4+>M5GDpP9 zjfrE}P%+ZO{MHT@bX&bT368+^B&sm8mRHmCkP%&p8#BOEkIHD05yvSV!(F$Sd1di- z>rs%n!>OjK;x^h@a@5J;?6pyhp>;71kbGe-gK^P3mXQ6-zjdV^h(Udg3oeTF>>?cG zL6dacaS?Hu0Q9Qj+eE=bYlC3hac4uxk(@~TpH&W>F2b+N!3X{q;f&7X|A*FhJoGaYn4sPh*`U|cXM3*{25lEGD<*J8bx9CGxn zWZaF9xbzCIMOCN;Er{g9XNRjFt}259|B`K=-X>e4=uDjJVabFonw2;J&)C^r zOP2sI(41Hv3z2ucEKtEy{=sA(LcOU)KD(7)2HLBCQ>bmP?zIn<%k8^h|$#J3)B&ka>!@JbsB&R0s&X21qpFNWvPx5tUhU3sR zk;}$3fuTGj5)!~j$yD!UzF2QjB-ncmpoHkMv1B!V!?eUs4Y}_W&*WXhpo~UZ-NV?v z)%%fb(p)|m{6O}ewXS|9>11(@tsUN4!@ej%Ti&lIF~y-i7PK=<8g4K#W1y z7N0d{J=#=dy{9Z4hf5{px1Z7B27Q^ZEs)I1HtL9*Vhc?iTf!D|8{u%=3RX|hB%e3& z;}@nod4S9mmufz*4vAQffG)SVRIm#eI<0YiAmH~zp%s(NHeqx@6TRgML=b%^@_B|O zcPLbKhR8v(Cq)Vfw}bXjuecr{-cQ}t{Wh`S*Tk*a*XzL+-}C(hlU(NSLu$)BWR#Xo ztOwf&MLUQJGQFOZB$~R)jgitA&%#cs-9~6i@DdiM>B}jhriW}@mOo*)?)xKxaNGJXWZy-Zr?~?zc*}3CQ_~WH z_f;@;V_w^+puu&9)5=3Td!=)Vao#Z8qNyd_Tda37v8eafTz(ppsTqG+d%i|D7xqg) z{017Ul)+b+Z%)|R`(nru)eYr2QoS3?Iab8qzV@ZO4U<)4IQ7Nn(1Gt6NqIWzB#rt3 z;#EicK|aJY(syz!q5(I59h%+t{ecF{ARSuL<{@Z_f+fpZR*i z?CZgp^zf%Eyr`dd<8&+;H#~f0#H95-`}Ndpz8J-fL+xgP{O0x>x%%nT)%z=7{J7X9 z0DJUAtD@02bTO;rXvZBl@Mm$ zPl8ccz6W{HN@Q+w{=N+ZkF&S^B}0s!FGldaB-^@*_|?1JE`2IS$!B}WEWR1Yw?Vcn z@Uv-TnW9P%$JjLc_Lk*9Pq5&>#+IZw`9k9VhOzZyOF zA-Vj+?eeo2!DqSHlbt<#Jkuz`JIAeQVqCAnO3ItJG<2$SZ1``F%5awC`8 z%{mJ)Z%mlRs@{1VG}Opoqb-p)Rm=^-!@f4eBKKc8qO!NYW@mF_R4UTT`q-~$51J~t zSAEBg;_}YhQ4~?%a)1y-a}XE4zSPK${dUAkj%n#lrgR2AIDLJHNpUk;H}>XzaP& zZI<%)3psUo9s;rhY7sdCvH3H2Dpwl|kWojVi;xjOcl-9@P_`Cs&9`9p39^I6ZkS)( zuxAkBjP;>ERZ8Y4#3(bb)A^9kO1D0kM{?t^Fua1%Kl+jPe)4{SwSG~79^V;W3RiZdEe&&QzyvIHN(%8ox?<(7EZQVb0-|_lkSrL29#f_Y!<$=hDFP=x8yjVq1 z)~rX0TVCi1R(<2iBQIq9$p|Gk7^mu%zo+Y0nx&;4s=l6PjqI;THfQ|^A)lbX^o_jU z^P6sZeu9}JwD0s2KKBZFyhuTikp2PF%TUhj(O-47DwD+XM2o1Lkwp5vMc>)CN#U71 z(j%pMY4XP2vv!5+?Tg=P6829? z#I6gRJ`4xKt?A!OeG0vUEa2}b`(x4s3>W$w8?SArjp>4@<8;cS(>Dq%C;+YeqcJ9sr?k>14Ao)gII zL0S{7YvgpV8HYI!LCTBvlD1J~v+0TO8B>4UldTkW+vhq2o;pyHI|Sp8Yrj9X{cg!A2#nZcclEeOdQ`UZVr?8zn z;|dqqsc}00X;&HAcNKm974RB#rMoYmphI;^ z)ZTloRl8&bNLdgo#&hGB{d@`q1IBb$^N*u?b++AQO{e0aD%e*#``9{4FdD%k?7qU6 zDo^Tk|M-hyp2eu{&7 zsGdyGQ4M?1x5V!c#wF{VZyO^wfS{oCmP+T(khDu&bRJcB zzj0LwybKB8y&9>T*TOnAs2plJ5`GO=+tm-ep^L6B3iUQavK$nM)!FiUz3QrvX|U6K zI5B#zqpytcTt17I)=wK9=I@gaL)BOg(%!iI&XCJ<%X5rN_v^Mifm;o&xseX1VvNFk zZW$&ggeB#oPwa&39#m~lQ`3BvnUE~{X?zZQr22mx?_GT7B zt=R07^vJi$mr@%k%qy+Ew+R@be9_ajt=IONx&yu^EbuUme0h<<^hI^2WXCUt;PexY zWsEYDk6{(^X|A5>mg@x=H^44t93p1E4%BvX`%z0i<*v(%lZ-zjHJM0uS z<;3{4g`Zsa3Q{;CLdnLOEx)i8`&g@7sv~4N^b4t0W(-#FZX6Htz;aSA;}6dj*S_uk zNIKP#pT*Izo#J)PqkQl*+pukvYz7Z^AS#=HsTT09qA(x874hNX3bifNUEW$s5Xkpq zuR;b&K3}`ZFsbKkov%&)Aygh4OgEf6XFW#l5oQrG<$nh{V_paZe50 zxX6X5X%)J@-Z6B&`bMSJprYgclfp-kQ+a&YX&aLt`}sR8Tk{!~kTXv7>R7q$VmT$* zwhwY{cx^la9vZ9!rAh;m%!+IZ9T9?$>~U|!JB{@g;m~5I-GH?bNPs&B@3|RFaAaft z#Hm+YFfBb`^u>Q5et-qLB&syi8!SC4EQkYy=eSegZi-SUl8~-7NslD%5qEq)TnW~^ z;P$j!fsQSybnr4xi^}rm7aja4lKnbIdPgq3xWF853eOoShflh{42yvb=4H z#079?il*tI*O~e6BKG+wKeI;~;f>uIc%D>xlgCfe)k}@~U9UK!NpQVjnsme zXYfiWyG%V?INDx=mmbfAqg1Mu0<0bA#JNeNQ)0W%9*HN;Vkt=lk#)dTxciqOokz$% z^iy~D=*US%r0jtI7<(jqUAo0cTnJ~}MbDylui?0H2i`y`MibwGMhNIUwWl(}?EmNd za0e<8BvN_!+OeL#UG^k6qC_aanZY{CQ?|g@_G(1@UIl!prGivTgyFXrK zW^cG%FuKkY&*m?n%96`G!eQYzM0MX-;xEF&*_B4 zI0|Yyw$1FM+@&(6D#MqYe!=Ilvlge0=cq7_%z`GKI;yTs&hIgw^1ev3a|b?1vssIq ztj**Y%I=7a%Id-AOLA05!7yWirbymLTI$H=ZY~&KYmw}048{j#Wgh2W##U^b#ql$N zlyK%JyaEo)JwH>TrvKDga-co+CE;ryisH>Tv>Q9N`Ok;lZV}7(Ci&{lx7z|X$;<_S z>7Y1;EG5n$NKV3n@529%bTdZ8JT{JzEYz=a_bGBzgYhLfGsa>jv5o~CkPqh`3Qka zpJq%F3F|mRnWv+4txf@+nS)fGag4Z3agp5^^K}quAzi{m`D`@z&)jAL=TYif`+CLo zX2tFB%94SQmMw!DV3^Bh?%K9#bN4Q{LN4yM@&=N<_^?@l!d5pKN^r0UIC;LxwzO5q z#BL0qxRANsxh`uH@6BuT33H`2HVfL4Un8ii;jQqsHMI63dzKBCRE+$FF(>cAe9Jpg z>gOW_s=Wq=;<57i1=r~aI2;?s&}oEtc*6 zyh@`8VsW*E+yM_;!vsEARnbVt*UH49mdQqJ#Io+XjB2z&XT4 zAHy;WrBbac;QzjldDLKgy>SY;R8naefwePoY>7^pa=0biOgx>!SHMz8Pu3tab@kay z3qG{Kj(NeNa}>U3fFa~DBwA-ZKUsbwDt1pn^6bqbPl6{tD~FR*G3NWymA3Lp7OBdV z-a##C!v&sI$ppr4Ov0b6_^@`ZTjEI5;a)=!dIzaQTXidp!V{+lD_*rtuhrl@XRY3g z8C=hS)OuZQpYa&?4(FWik?;j2drB(}D5f`4UF=hemR(aSsJS=J&_?gLo3fpaL~z}c zx65+*uCRgRlwHU^1*h(OwlJcKV4gN{G>*cvD-6^K?yV`i_Eg?2bJ)i&rGmRI&SL;t&X1`_S>G9|v)EPY3lyO87^{mej((`5S2JjFcAW?%4L;pMiXDw_f zTMRzMWb1McY}B)}n6QwfoWq`kst#j_s?tGe7^BF|wz zyf(p$386Qp6JX`?4?*KiNr#=ZN`_k?x}gF%9CtG8)|RlcG3TUtLaX&vVAF zpHUU*N%Qs_GCuwgfJ6mCc}ZB0^J=_dV?q$ zVeJx;0#u~+_rtGe2YDo;nY-wXyEF%?EcLpqMY?#scFh&`h}4c?MQc*#_`izUW4%9H zmZw6&IJe4sTNYx;?lKxlJUq5-a?l?pT*$VRvJh<*6oN>QMA+AsyE5^Gd>U-EqkESs z#q?#AxY{VA8V8LSJ1wZ$=n-3}ydpv{AtImBOTT=;brle`ZNc$kn4M zoTK1=O|3J}U#}Z~?f9#&uTx(m!WTzJ*A=sW2IqR-#yq0?YHgy^FSeS!p6rOZ*(c7i#@sqB#|a^kK9LKa3jzIX<2_4zPAH8*jZ(<9V-8s%_=1Q31wDd- zK>5e64F~`4`11J>LderET9Z6bDR~8D{T#HRV#7iq-yPE~ugkfQ)EP6Js@vqu`oJc4 zX4H;0RbZtZTcX38)Ey;B+K>@W5$!259jZzvU55pBzm+**fQfr2_j1=ECZ-yY%eQB@ zkVn1gS7Z4dOZOJ~i=dIh@qN}ByYq85U0y#4t`&~uE=i9gJ)_<`HRJG5YR|;~yaSHJBSwqhVsN3XIsIkfDaf=wuW2ERE4hSQkGx?4cC@p+OdT8#u*B$7ZX;Uv) zIn@p;rO~16$>LAtPSxwAZ#npot2f<~mBJ`V9_5}C$YwsIlk`dbq{?5%3xoQvy>;3yDJacJpW<*{T9)(J1!jA)ney@&J{mdXzv`4tcPZQ(KU? zlm_x%1#oRJK{(a$|C5tFEE{1JR_ZMQzxcZjyh%227xwRVO3ytY$pI5gwu6Ciu{^fs zQ|IQ#pOjd*dt7LRP&*2NMj&ysV{lF5-T0qS48kq9VW5Y=zgvlSi1zoOP&$aZP`@t8 zsQKl$V2>))U?~*AYaD;`7=DBNO<-E>kWjsXKlPHK?%oZcyp9&Jndj7xhsV1FeQGI5 zVYfgPq~6n`g-Qce5_o^&W2-|J;EnI(jpKJbZnRT!TaEQQ#5H~8%T^BmK8Lu+ulkHM zr@=%HdGDxSdwEJn=5j=c;xti=a)%Uhy=fx+I~P65#TTJQSUWoxs6G65oT2vJIVA82 zlfWo!i6{KO-m4auxX5tQ!&akOP0M*y|72r%@MkXx{3NdaF<;J?OWrd-TlL37CcY&F zDsF}HZ?E{3;~kFnA2P655v8Ye-4_w@4%tVg-ReXxDdC>+aQYMLtszCEMd?|hA;PYd zm8SR_90l|L=EflmM+-&~`AUC}Z4a+8-n~Heez^Esamij7aD^VogG=by&uG*(B4qT> z|63M=^iS|YB#W+W`GKn#jYoB^JTK6?0i&9a^g!|d{v+91u=>D=z39>(_?*ZFUJGXgGc^}?BUMp$TQx5bl}_kzvb(p zL*8~CWDhH;x?rd92+EFXb9ePpw`pWTBH5ta@Fl4JaO0sQC#0nhDWDj86j$TBd6fS0 zaQ-_FC#|>`!j3?^RhMUJ@3N{nvjj=kXK# z=4Pn==f4!j^-wu{Q{)Fb4`omDMPCZZ)CT<6gy*QrAGxs~b3jd)Z~8$pSp)ZBwx>m; zTfwZp&y|>n+JRD5;GJU~hM}67n)RlUWx?TWQ9kY;N2eEN(b|ppaG%%k`u%+Bx17dyhZJ(5 ze*XD??skmjS0OC|yV=L5rn9G+2op9H7%~-CtDe;@rw(sF*jr6Hxa_QxS!8z zcaF7q3pI&(cdca>#b62E-v9IyV%qz!ehKY^E{EruJ_^5f-+Il{t&CA;2@8>B<8%aN6axgKpEhKKKJ`J`-AlZpO z-?z3Hw+ZmZM}U6zuxTf85jLF)dzfX~*>A@4tR@&MZLz0!siqjUDNs8&#Ad7}=TSDm zbFnb>4#9|XlO!laV2j+*c8q`8Blfr1_VPjgc4gD(y;6nQ)KE)e`_y#?B>YufK`Rew zx|0s6FHBD!6>FC>Lg==}Z7VGfv6AoiRY^*%9CH*b!tkzVbVAOyo=lN$YxS#+-NG@V zCU?NP*NM*IzzOI#yPPj=G>?PxAoN4s#?Y>?;^_(?@9Ks)gF#qzq6H6GKDKi2k^>dw zAr8-tRvFYSeXV?c@Zvza)-znpXj|E=TKC;^j~aYB$Jqm(ZvQzY4| zT4JEb7gdPWQw5UE9$M;%Y|L{f&?D5Z69aF>Al?!=SuWq8z_AA3Cs-;GTq=8tZoij> zBW=NF*?RioWI?McP0rRe78I@fUzryAD7erP@Lbq1z!9sfn}E45rC#Q@6Y{|dPHGxT zG|$;x7PbhliPC`gWEZL4_Wb~Fl-L<(-LF`_-VRn6gE>TYBFVD;6~sfYe)*us(bkg> zyLe^5PVH$biIBGytk*81mt4-e$yO?mkB_E zyfrl3ePpEGts^Ty+fnd7g_hCY)WKe{1;tPLCu{(62Oe0R(F zjCH}orinnqcmq;6Jt#x1xEcI;j-kjF$Xru_FuVT#p=Lx-Y_7P*J}VEGi79CPLhIZB zkrGxW?j9jncETasahE*;Ck6dP%LFa&?sv@@3|M-qiD6ET#hl)f#>>V=B^>I#m1t8z zqOCVTjj+@>wW1c*E>ssvB&K_8f8M zwEW2d$!I)Hjj04(j|Z0wVtY`fYV-Ij+aL*xdzN*Sjz@@0zgvaYh@4E%-Q(@BDAM8T zRHO1KW%9-KAZ{?yApEE*Kx#WpsjWk)BotIMYKJI{NW&*+3ZA^#g2*`;;NB+0fg4sq zY%%$#mfIpWT8mNz%W7gFTD#!6-IR-uW18n_)VzmY>)#XIs%47}>L#*%PQUkq<_u** z!rn!xGgQ>@ART?w`K9AB|(0*)?6Ty zbSAzcP#}-8FZ^5k{b7^E$xsPqj3`r>cgpIIL6Yb>-OESB0t~@HWKfIf-kh0ez`?gm z(DX7@QN8RVt6+YGKm3;*Yj%p%{D_F#me~Z3WvqM${j2*7aD4`?X|SmqTK$oUgJ>l6 za+Hyl0@LVh=sG%R-L+rFk`p8!`$N#cy+GH}K<-}r9MPqJdfK@#d_ZwNO#03m4bu5c z??bd9Cm8hsrJNN%RA*=`a6r(LL1F|Gx=|$y=7itDWwTo$pr#=@I)XrG#+c%alhLF6 z@VnKJ{A9iVqaXQEARHxWk2aTyYCSNG*<>XKI;eOR2c7+cPcZM74SiXh_m~V!r|)8A z+yUm%UB?5%_OZA`O=Oq?ZjZoTV5!@i;DqTP=n7T<6ZV2KHHXoYhc7*T3)&8mPM&4GcdngfZ?``Yazm(CP|2AJrBU&|S?PqHI?STq&u6 zyB?uUvhG3{Js1kBXHGkr>u64JPdW8-Tr)g21TOB>WXy7qkJbhIQ=r|w+=iYPMn&}j zHJI=NHwc>Q$qGVlAQhkg{rCUt&!4~h^XJe1`I|p~{`)(=!=L~9=bx_s_RsVG@_xL( z`KR%(>wo<7e7*ZIY5w6Kie>EWZK;RyfBt>`Zo1HJhX8pP_^Bpwv_JmrzTQ~6yI~8A zl=X?Fd7*tjTH7rTj`D7YA~inFucusMBg)Gw=zGR zn6XIU?Omn;b!eAl;+!?zYJ)ghFRuy*@f>3aWqrudj!>fRa!$>r$}s;q)*LtGX9)Zx zogz8%0}Om&ndvr12+;uD;}vxdL> z8&5;O>@E3$RTM3pU=9#x3*C~7{SL}T0cCoZrS=}MdocNs!ZGQ&|MkkB(MH%k&$KYa zNvy~GCfXZ7=>mat<9A4$(O9|p-rC)|wQnr@W+NSxiZ%3Rgixf&)^(%gt)=q-?LB&8 zxJuuZ(TBA5>-Z?Oxw0xCkbwh-4{lLpV*SPr)fE{ZTotup;#)>mg0i3 z&-V!y)!r1@Kij6=M2n_VNtDyGkx9Pb`-GJw8dr#K(V4W7OR}`$PI&Xwjm43{ zAu7&JY=AXPOH(9qBJy!3h))J+r9q~0^be_K#KO9K)FZ({o#=g_{)X&Ykjx@N=BULr zvC~~vFCM3c<&*9)&IjNFScxFyD@_pL=fxFVh5pdJnt`w36Stee{gk9ZZ!cBukT}ev zjEisC)Oy7)M=q$rk-!_M67|}{wJ-J{G+;~eFVLEWzb|G0`?%d?!vnmK4`9kEj1u}x z?;=dYhCg{ux)%OXiOdQ#oJ`0P`q5!*9cFm(18IW2l)mD8etJvFTxbHS)=H`t7hM)y z^*p|Z40NXH?=@b-0(jdrx^-Vl`n_9KzJ(DDXc(5DA_~l+^tU84O;_!%Mh}4(*~iBk zTF%C!6q&rpFKSxtYne# zikb_kS5(+^PRs<(T|2`O*?h~0@szQK5Z3lp2kM{&9dvZ41f1NNimroNH_v-15=gKR zF1Q5pR;fJp#lN3US8_d5>H60fP>0j}qWZT;q!=;+L9HEVk3MT*KaJzWUoh*z)Xzhystmr%n?X@x3(NTs8lX24S~>U8&r$4}U$z5HlEDj9kE#V#B|6w(H< zCtYVJ+SYmNIuC)*BQ3@U>ARpGm?`nZ_IJxDKSzw`~;%9HBH?Gar164UV(usH%?Pqb8-u{uK+Q0>MI$ zL5T{9t`yL+ zlA)v_F(`n}ErMX3o0ioyFJ{?V(udvPAMFg~k3f*&6E!_UsMsUuLR2(aY&?cRBlzo1 z_$Fd&K%69NfqN!~R}iqTUxir76|#jouVzqEd5ZZ5uIy{%pzOHmP!e)OV026I1ui$q zbrol$Z3)eIg_2fCD`JZ~`N+Voc{DK`NWZxJWTz5%x)twLaFFf-9{u3Vg$A7~k|M>6oh$po0Up(?!(ASo4o`=~PntqCT&Mqo*H8c({ zvX7;!VRiVMN1j~6S2qW;EIR4z^8Jg>`3yY;bLi8eZ|pnZAI2=(ifc{@=h#O-2^~E8 z8`$8Ha_rmKUOpix@@)-Kxk{sRvD^hXAR@hv5dim;nE<<+IA~bv)pPdZ;2#>ii{#i= zo#fvp1_7bI@8B`n3z&%h39Xh9D%M6~S*1`}!yl}?(KM{Lp!EX7C`-A&KrdDHt6_Mw zD5XZ5X(vZB+2o@v(S>L7J%DVS;hBjp>J~b0`L5jaT(>Tb>~J#U0VxrI80yJK&$4KJ zxQ@$jp&Sg+=C|6K5om+^XwG7UhH~Pbj;+K)Z3)5eyBEH&>?XA8T;@{Rt^`{`I0opci$UiQv5$LBqK3DKd#}oEZ zA1WVtw!83wLih_C=A%FTv*fRAGI`xQ;tTC@>6X;>Yz8ZVjRkG}@bGD{0zSVBIO01T zR#3i)JtD5P;CC6LA=eGJGc8e6`p5<{XV2Ko${O_@z?jA1A&qZ^>lcB~OgpxB#VTvAXihnA zB4QrG^o}sFT&lvnXLg^c-;`=P@4(ciNsJ5bZuqR>XRrx(ATX2IY#2;MU%BiwkwYS z+S3!hU4ueLD`KWL#UMPiD&BIu*Kfg^Vj}^bB22`%T zsP7V+#@F7VZ-~3wlv@NMHKJZ*xb|_A3rckRIS@Vrhvd#2Uef+FqzI<)PDpJ3dY>Oq zsKH(fg#F6uN$NuS7-%RoKOY9jo8zEr5&)**?P6;vnk#1ty&SiX!a^0xYGavhcGhhH zsLEx~-G``Hgu3LB=(eLOHX%)H~4^dKeQ;ryJGz&SXCR<^kCEy8fgRTCyniO81wkh*K@f|1o>px!m(fnpO(zDwz{Pb*KzwJ@a<+d?u#KNly zG{UYu2|%bcQte`v8VDEQ8bhb~Lf1Db9@UIB74R+v%o@<&bd3d+ zq2y;w{^D0?y?105=!@n=&9Dv4J`3i#$8mq=Yl@HUM*;BCXhcFc@+X)zWJ`Q(gCUCu z?Pq|Y)+w)0JC5Hj5BY`aO*QHi{&~MakGG?W4f=%j?WDW7Rrr>B5qI`$E(a8uD}`ET^N` zTZc>X$R!I+=YZgl^K7JKilpR;n31wL2IWK{m`_yBqN3PXcuK(mroTTG`B!k`&X*}j z#6gcZQWf&rSGlXI2A&htEKba77GlTHOjHk{=OX{$NLJvFTSFB})Q%?Q1DtqSc<8Cf zQ4W~_%671;;>6+P0GrTJiX(RXB6tyo zW<2H^(gQe0Y_R0iK*KnVQV{4d(mY|B00$Bs@#-eNhd-c^Ov{Sr61w{7u6RI;Wp<%l z$e!H50TecOp#Q=*|MzeIW4?+0_FwbOU-N&DZ+Z%TP|kEu8C_rFBY5-W8y4MMwmJzr zxQk8FhtSg8Mrxff6{b~H1)&J`Cs>j0NPJT1+@^w=8c*4S;xa5uU`i@Jq8TdPQ#J_O z`^pdfLHoTiv|R^%$FJFYU(7C1!*lJr5ez+n7ei=| zHF5K}0QaFd1E>1&9+d>#nAL$r?($KSa53_OfDFQ4co^kIn756vJ=b-Cjp17pHi|b# z zhbZBuV1>t81vqw3-e7oGXLVmE70;Mcsj7yc5Pl38W$3u5_NDerWmb+^Rhh}XWc!+C z$36z}l=?(irh^&Mj4^D!A37=QOt91~5xyY+Cbn6BNpOYcM3nfBvVsEL7jGFjaZy@n zQ9YDyVSBCTKP-sAv8Dt4m+@(Hn2#9RM*MwZZ$3NN%yMHbEaJHvrSA`rsh%dYz^?I! z7Yi>CU7lXmCop z$|e-6+CWoO&=`rZ!8x^KYhmoy;xB}V$Bujrltf-xO>Nx!|1domeD2w-K)Dlc&_E%W z7IDleYC4?aLuui=_4vWz?m+BP(+}kh)`&bW7O}TO@%nmsCA4$BF;+-^9L#Unu@CqY z<2u#s%E#Z1`4Uz%9?^)(#mN(&3U~av;Jn6Ac?}xHW!OydpCn#D-iPilyZ z&p~dsX`2aR(#Y^{PIr^kw0^hT9`y0%7eCoq|f#)SG6ca z0P1f7y$1FM=tp2m*jh1(mm%4{!^ff@* zX3=`H5-4a$=H7P9yWmUeSIeqZ~JgbcQ&dPMpY!7nec z#E6-k`*%IQ&XT87 zj__-noYYec?f}YoLfO~}UmW>kYw1g3rkzXac1^Uc0K;-sw(rH4=0)Ew*9Zd@M+w5C z>YjTN^N3V=?Q~83gsf3xk5z=`fvcUBmfPVbM?EwebGIv+BYm2Zj=$>dX-|K#lqWpr zL=3GVGdM;5e*gdg|Nn%TM-J>vd!2s+wqZ>SuR$Xl955#V8Zb3OGlyoFG3T7Q0F9jDR z>KWuo8hKKJKIXpCc+(!A0v3}P8I#mRsi_sS;nJIPXt};QU9_>zvsCio_Ja}+sSgbg zM_%MfP;hveg~ANf-VL1DxSXh!02F=gR0L7#J>S4>P|d7DCEa0S0VZEonkowQ=ahW1 zC{`&3+NFMjLY(!d46I_DUqzG{G_F566ri#Oxo#r+iV$gK22h)VW9+efQKB9i!I4Q^ zU@%C#LZleE4h^DSew0c*-Qlg$l2>>(KIv+s)OrgZJdw+{@7JKNyL5B7-P&SVXQe$- z0H1(k@X_5+(xdVQYGnum2Tn0ez|lzeYLf2&8*vmM+jR5GCf$v00%PTp(rkIb34+vQ zMMt?kIhV+V!$-dcWgV25O7aV;w}_S*KVUe;9e2;Gm|6y_3}`SPe+(!q(av)5THQi( zS&Apkj!P1dtfnPkq4niLTZCN5{%Q{KSx5aRgI)^qspTgm8YHGmMrO0^hqxQr14i(O zprak@`-eeIQ4oO*2j%Xni(TfEvas051V?~`D-azkq2{kg0W_bVtD^S(;%J`t=^alb z)|56D?f`~5s|fc)zYP5D5X{|mwIsk*s_On{9_C4&4hxX=S_pAMixlrOt%eSxAsgzgSzFOxm?H)0yi#Z?e z_l$fqaPk;o9($XWFg|t4-9;yid|hz-*KtqBp|I|c-gY!>VAcS)70xcWuQdpiP#=b3 zNirZfjiF#)4QCA&m(JQ#E|XQ%r}o&(tfZAd&$>`Dkk@);y0igDxKYP(qti0h+c3wY z@yp=&HcAOTb}RYrw*Fpr(D+v0ckXj98*{`EbKUe~G&+3!zUTMPnh5WW?>8)=Ni?`h zeYNYWy(5PFzH9%!n8UZP*7>t0!tiRHu!NOA+CSrtueN^2{b%hvZux4tzqEhG<=$~$ zt>tt^GWG?$(`!yEOt)c17<_NqlKLhz<$K2hv^|oU;@c5sO#D!PcE`3 zOj9S(LnGPHvW8w58d3tOAD5IW*u_LieG2Be@+P8B$&I9%Mjw|3klrHJ_qb;=6>M7u z0P5xwB%1BB58pz$>jy2V;@GKnLNU($c0Y~AHvkfpE26n*sq~#z07Ap z`$qt^fwDKe=))#dhThimWHSi5$D`AxzDvEAYFX$Q(M8XP?tjBULRZ41qv=5()TSmb?>;yIZNz{7$jHZ^(?!%d1T(+=8=6Lxa6I58pR^Sh#h{9FKockJCVKUPt7|EO6?) z34HzHIoc>@q}otc3{Xx5m`voCzc#*Hb5eKFp@KQak<_~RX*5Mz4``1E=QNo(BlZdn zALT(uy>9doy?RnbXZ>E)vVUk@zbT=Tu`iMjV3c!UyCspU*|C$@xP=dc~T(|e@bf-OLNpTl`5bwnoIUX1oA zQn+HSgy!iHl*C2XsX9Uec&GiX7wE<^7d2ip+{e>q8<5-A=0cSqV`k9js`H!qOxT1E z1}vnZxfvyiwHZ!7i#j|RkJESU z53xr|iJPM#Mb*TM2ld1hN5MdrQjdeqBA%&b(3>A|NQp>K1My29(<~vhqbRjiw_At*=gY@;5fo z{Z@of_He@ zseZNMmi{5X-wR3%ZrQVwnm*SDk#DF-=u#cCtU|wq>Q=oQu>PTqKyv6e_dHEX{Zd%e za-R%@=-Ngf2U*iH8H$Lm19aZK9TV3T20bGzT_Q%1Nw`}OwiE{1hZqb3IGLIvp$1F*x`tQ-uK#I`}SmvDs83|F_a33v{6UfUb;H+!lC{o+SFLU#> z(skSuV(ehaK5ZiXDjX+mZHhIqCi2p)Gth;c1M#K<&tz#_s~4a18vK%gOY*Ivnb)4$ z00%07N^7SJ`WG~D5`CifQRzC=`Cg_4{#ORx0h#;_Motfg0m~e>VWb&5^lWR0uX$+)KBX+bgpfb;mta&= zcSt72VuCu)P$5*Ag*Mo%POj8gs|8x{DbtbAshtBT%Zja&a!IW8IM+w|tzl|oF7@7R z!U59C%G^O|$Pg|-lkJHzL?^RC2gkvSP46H7@&Dwp>fhlp;@|KX@&D$rPHg}1*bf7R z(p8XFo)|nu^y_S6uwEW3BfGriR%18vb^I&C(JZs~zyUrU=in)K0IUJb zdJG6s$#S#D{dVVbTI^|!k9O}XX%>eR(~egQQzW51RiOP&!7IEmoZ;E~uomEzs=F&u zzlY$T4eayXk{&8y!0C`FJ4&mSh+Ue|NXIXONs$H`?8o^~LQeMvM9|BmdB?G??!*+>ftfY8wLh8_Irj^R)#yxJ{JvPDQ| zas}(9KZ;FVdY7!t48anTftNBrB}?&&;jjKxBv1A(;1d?qnjGni8mznesXOUEec|4D zunUEUu-`Aag-8dWMBH<29DkbH7dlwSJr2q zw;HEs0e++qnn2A)fDSK}P=4+{Sv0OthrN5!t?T(Fk$V) zgktnGP^nU)RY2VpNQ-^B&0os8#_Ui>)7S!5h1_!3btCRg?;xcun=kz?UuOnveC^TL z5Pe~q(L8vPf52tLwqyC>$(S4W@J3>U-dPlTyq&za|4<-6>sHu-=_K z0coH46_PK|8&>>?Zt`A$L+v~x^Xr4g9^mtA)j?L2l=I5_n=V*K^gLPPrQ0dkpZ-EzCOR+fg1*T-55yXwC zaO0iKrj(pLx}~ea4)$W4kJ$V}yp0cQ*AekQn!k6x)?FG>v*fmpdsuO02Z%87b zn{V>wrJ(BFDZKZMkM9RZ3mTL0M6ZGKpdnQKd=q#Zeuq}?{VI{oEgGpWz7`lXwezx#yg41@S*bUFd^@4^z7{!5^OW{jY9)W!8po+*3&6~j`mXH zO7MOUz%)}s5cSr`fU}uj8d|KQEOm_`J4OGdyO)|oPbX(ezz7xXc^)KC{u@{CNjY%g ze0d@Cam=So7r>VbsKk@86C<4p_N?gfYJ(%UfF$UeV&nr>9$*jI&y5iQ)A|%}(Hbzl zSmI|BITXsy2$K54x=DH+<+PE2e($5}w~CaW)}k}{DOw-5it;ujt)fH>?N*GH`V{>M zL+L&^^M>4swic6C+CQ8x&GBJR3a3{l1x^L(`Yv9o+#SprGm`FO^>3;npOO=sZx*n8 zncJ!c8t^W=9Yree0U30WWf5Gp$eAL&zhVFasjY&<*O^ zk4p2z)1&1{bs?|;@Y;Z)#u0;p`@bRC)N8?gvmSJFy~Ruv4~D)PaTqNZqTSX6d*uO& zy)teHurD${s41=UGOf((auE-YMc4ssiXVXKpeZp78r?u>TirTf*jzx2JD`n;uhCrm zc!A^EP^SHjC&EFxuiu+&AZd7q6+%&RtC>XOC?8M$>jU0`VsVSaIT>0ZW=T+@n74FL zD=5A-9tkQGBpT6-NqNe;E^p1!d(z#9@x+(909~QEkpE(?KfLw7{vF=>r+>p+|MdU) z|4VG)KfDD={00wUWO?7ig8pybQU;5v6$_~u?1Qlg~^Nx3zcFcM`fA`J=6ACvMO4(swJ~EfL@Ye zk7NS~riX$<3^!t+AabPS-W_ujC~7@dh!;7uAI(G7#uXESiZLt@SKAyL_QJYzK!XE| zBSM;{)Bv`|+KkDJh@t05AEU^EWn79sZ*oo6cJ8J9sX}xGVNHM0pB6A!b4}N#4X!g~ zh|uZqWmMQK{cs_u)+L;L6LS9M_;a9&de(4D*z9ci4%H?SbA(A4Nz%}pz~`KWSuT4+ z)E2fW$L$x~WrS~>_c0lH{P~Svb4k$Gyv|>A5>_6a{fp zYvTFWXCKvsQaphy;2NRcZOAG&PL`Yth6+ukdM2>b4(%f1-*my(H^-XO3!NjxX59M_ zpO1=(fKA&#;70M1CvWNnACW44H1okQY?SDj+7?HOByFo9BJSU{Ay;jJ28KI@)YFZn z9_1Fj{hVLQ^1`-&5)dJi`zVMsAY1QJpNc76Z_BDYN;5iEO2w?}tH zQeN&dF#h1hgyY+N{sA@*cVG?GHzF5;BS|?EYTB@1yw(J40|v~P|HWO}ahplvPD{g( z_OcI;uj$B$TXz4%d+v{txN1QIpEzYz4D zodcHuhU3bFR-QT$@)xB$)WT7{mkmCw4rULGdxJM{E7HV@!&~Qc3gfZuyfmfo$;#Ld z`$g>eL;I9V({<6y=@7)AoS&q^MbFy}WKyP2QyZ)bZ>N<=0Ollc=aF%LY}nMJ<8O5abJgO(Ot~$86Pz`i;HFJyHkM9-k^OBgTXof8vp?R|9p2x4(!Tu z>sg>HT+OhM!GwY+LYkze>{tlEqs&dN75*O2vEiVZC%KE77nio*jaGYiIhYH}h z_hX5KH2mYbFr9jO@mbijZIc34SSg)%7VzT+va9aE!hO~WZsUx`I*Av>6tDd|zZ5_v zBp>`BE7^e;XS2xOpM8Z~Z*I@q26$PY3Y|3+qNhPLiy)@xqEV$&7FaTfSDe`I*>MgI5Ox-o2{*TjFZk>& zlLAcph+1rYNi9P#U3H?bzL$cO<_-O=VcO2Do&^jKPR2bNp>>3lUM4~D>=?`s|L;Hl z%O8LI(;t8Q@xTA^k3atIx&O}x|KpEe*Wdm*|C80G@3oGy= zr+i{Bz;0b#VPDY=5JO9jh{dtA?xv5cP%=9isXPIFjNA)cDr(q^^q>UAqnjxsP-xw{ z!ifZ38#9{RSOdZ!deIbid>hhCP_c&a@J^3>RA=*|NFAjsiw_H_@k;X*xRokD=uj11gP5+}x7Xq(835(0JW-R`zS>|%Q$JuYiS zL6R+*V$xQDR!D}Ktgoj_4hBy9#z+N1_oV~B)*2?SZ5DnrXZm*Gq)bKUgF*KOcTnp< zApvB0=qr>89?~%DA26v!s)5laK>-Q z77Mv#tZy%5CJ*rq)*gq~ME9hsklR43?e$eeBVfb~=FLt3GSyNQNZ~mGjjVS>;)S6)DL^fCWNXyr(jRn^ZGAEvzFQ=~6LFmunS! z36k*U4SA{F#gc~WE=lbM;neFH-CSS*zS^TGD41bO-~|Y>FF8$H$d6GrfNNvqn`Lt5 z>M4amPDf1z>9H?0Abn*_xne9A!mUMR{KB_2FxIsWx*54;7jzit1dc!|uG0JJYwd#R z+)!>X`}qD6Xy>pe366n#dy^s=^-9%HVxglqHgreE7e#%M_6Tm{JWh$xYQ{AI!>uhb zN!>389vv}7lo;QoE4|iXsCmuNms1=c}0wJ5lAAF5Y{Kc zO)o)^JDMdUd<5ez69|pTC;Z4OZ*4MGg!`;tLhCjLIs$W@(Y2>$*ay(LXas=-la5X)Xu;J68GKgG z0+ql?$G#3)tJSP*(Ix;lW~xuZr-7HrXRWP>dJg%gB_-^Ql$F42M#8P>q!|{h_EcK3 z6TQUUVi^%{toa!5HI;xKN60?E)1vQfYrTl^yGDoUdXu)T0vqwf)UoC!E~~XmPcTPb z)&#OCk}hCE2y@X7!VXdtzC*#<3aoJ&y+z5WyIpu3$qkc~pv#^%Sg%$v zbs)9Fg-MmTgS*dr44O$Kqh~t8h(9TN1DktA+qa`pg_S7Hiex4ibVNMBh!E`OIbhpGSYu{rMhd_IQzHv4QHKI=q#7tA8MTJ%g?C@v_4gzsn`z?|O3yqI z2=yztb~!S@nju!GXg8U>oupnDgA7LKgG>l7BH0>FpnP}Pg(x+SPe>=xJm?AoqHUjb zhwYC@o#D7UCl4a~^b{1Dl84E*Xz9uG`s_%}@%F5rYpAbA%W|?6S6iwV0zIjkBZ-2m z-zM-AV*9x_ZHKI-h~6g^(OQ$HK8_(V=MY#z*5-`8cp%4HNC;4pOL@SFp{h5(Zu|?1=zyKrbS~9M#bJ65_S2sWvL60^!75^wD^ctl9k)j z^$!8&IcNZOkWewXZy8b6o#tU}^#|p?Z6iVfrRjTB6Dk`7I6^5txPS|00QWj|z(HQV zkYpX%m?K=A<@a_YVs4C7?BA5xK20VW3HoqRCirGeezt2Nt&hjvRPUqCW)J{LK(@al zWsA;2QXf2_w0&WN;#4YD1b6(&#Y^Yw5-6P)M}8?$U}jKFI78L%`z&yEQ0q_2A}IY7YQ+ub=XJ-~~fbK>)nd86+!OPXy~vFu&oKjg-dA9ACJUR_Xh(v)rp^ zzH#47x`^q*2Jybm7+bp63V3JZ-SY|=ec@ptS-LM?FQ+Z3 z@6Y*5Px}T7L>6bYtJ&JZbjj(GZ?|!}@r7zO1H=utoU#~oj$TVW9gdgV7~Lo(s%;`+ za}LKtA-_&HOTA{Bdfa*~qZXa@Cz#*x)24&Ncw(3Q3&(HxtBuctx0NS9!Tdz{2DIh% z-Ou$UK28bV^YwjFX2iZYpvoynlgs{o)LH+2fjB0ib={cf^OR-d%b;OPA;Rv&7VxhFot z6CcfI^mt)YSbE`;&EG#`#YdLYpUt26{)S(+{raSvRHndBFu&nXoBSiD!4tny|Seope1m7y1>!Pt0;QNe?;ioqGasALo|Mr*vULRS1`Oo_3$Naz2M?S>wk3Mqg zE<~NDBbkt}n$0q^Uw7LhW@#FAo~B1*ysb|+4chdUSPVFc^&&`mNsx7IuTOMLN9ZY- zLmw7>Vf==DKkrI%DOWD#m-%j$vsO@;RIfw`)_(0qf7z723;G)!cXThFYQ~t_aenWb z+tFbL+OT_5z^q}YRDx$-1GXp?v?G3q*GPOV_wB3(UmrzW6Vgm5K22J?f(9|U!ZC_w z%&042LElJDmr&?IN|430SK|cO)R)2V4b^8y(9~j+%Y@qTg-JEalv{ju!B}!R{5UE! zO+4DrT*2sclnbv;o2Dt-cn_}Ok{V@Rgx81UUP95`Yk_EOWBd@*#!$GF1VXAY?v_xH zGw$5mWQM_L)YDRc4t`~KKr!!0)$HSZd3hz z&^)Z+2{XNRKj8qv;g-u4xZTt@1W7%r3m$1tym>+sit%txbwmUy|2h}_xsp9opVBSW z1}dy#PI%uvp&G~bnrf4};C}Tp_Av$-6w0_P#eg^*H(=NTN8GU9{X5VPVClUP2|NF0 zj;8QFU-;_23WDtJmsp@;GR&yj{1MhCsu*NSS!0YzGwmqJP~9I5svbp|BG4z}r_4dW zDrH-}?i!|SzN1`}o$>5m2&->%@N_j>4=G9R#KmmP_P`Zvfeu>j8*zf2N5`eIVa_M0 zAfRn)Hb&(|;uN8-+DW4IpA0!1%sdq!#G4m*Qe?s)`sXFRV;c-{DdAq=YurBspE+*5 z?=wdTl!fBSvPWnCF^d7+WPC#e!dFiv;0b8&9_k-ZTP);3FkkD`R%Dg6r=ffm$^rZM z5w_WwyEUPw)sw|4ZY7a>*g!)O<*9t6o#TYuPj#&>e8|v+y*f@(-=yuHde3joHbJ*l z@qrJ(3yF<9E~ zqK6B6CW#Ra|$0 zT;R<0NQdORUVKVudkLdOlv^Bj5H0@ZlIY=!9h@4WgT~YciU)lQ)#6K9)T3N66lFxM z6hWPyzx$H-eNr@{)gyW8UIBpZdev=3z8a{>amZMU*?l&og|Jyx9EYReT?oxh-ln~s z;f;e|Hnks4JQR7D8AL$kj;HMo0QkCW@Jp0ZTJj$Iydmu*r(UAX&#fZq4T|TG3D9_d z$7G|`FD-pvdl?Yq8~LCmTm`F0a+w&0rxbU?4j6+Hv8S>}X?5aQVOA77Lp3UAxKQnw z3{Bh&gL6|+2U%2tCW80osbQ-@#zr3`uiYb_rRSy-*u(H2y|cfBv^;t0Qt%?CUatku z2OUF%BLh)2@QxR5u)SIWPi7cLV#tEc^c83U-u3Pkn1eKk!pNz%GX^6+DyWqO)fB_) z#7rAaB4901ry+{vlNS>Z3aD~u!$mt?$rAw5vs@gDPpOmckO4E!Xyy%vX+27#OV%hA zvw+Ht;M5+m7SR*S9HBnP6Eft@4(G=U>cM_|8>6%zH#f&7O%C#uOCGlYSxbsH+7sZn)4P?5kP43}>z?|z= zp8iMODnV22Vo`)~Pp+PL7~%tQ>N{%SXyDs1wHjQ$R*TdCz(4?A(}`q9UqH`;mHK$} zo$|S70PKAOFETOi4#+e7Ui(%{ADqoCr8B6#b*NO%Yy9yu zcRJeWixAma7~gs*wX3h%040h7a5e7&{%oZ<>NUgxkfgrFmg|ONHwng_?ir=XcSwziDIN zhtdZI9;LD@8aS~N>9VJUp)2s2a${Ef_&#ps<_^igH}|}YrBhL#WrbuZ;HfM(Pw^W0 zAsi;#Ch>HHzz3$h)--~pgk9C145FUZ^}TF62c_4LI(E%N`LP@0!5DII zFz;nPKDsIH({VoI8%vMkzHxb@NRof=hEv93;_CA3RhJe9J%qjXX2xEX?;X52aOmUj zXM6&BXpkJv8XbTq4qgXPV1aj%q7$$xJb3Uq&f@d$eEdKD{=etr|Ni&?nUDXN|5tom zSm+&r9c*;_V62dKc*B`>rNZms+XwSXwOVLp0U2S%mUz!B&EVz8xB3XDfgH{*IQ+&A zl&=bYi>+ez;II%)jo+p!<0r$t~J?3#Bro&IdQj$2{f8+>v3n zK5a>Se#u%5@lI?}@Fl+7H+Owv?$l2})?qrNPp|KqiFaJLA1CWo3?K|u5@;)EjoP$Y zcHdI}thxmG+}#*)^Lm3`M=cJy6zdmcU528VJfPk*_>tQCOY%I(=+M6$gCC6SoH{h}&J(U)5^z3N8DUPBdder?;_&QfqKJIOTm} z#Hf}%njKXaUc%^yu<6c5;|A8`_f&q*IVQMR>JO1G_=N?E=n+nC*0oQ;v(wuA7Q9r! zSI_veUfyrzQ4{bIJu*I_yqi-5^u~Onbf8hp)2;RmgM7yOI0IA zrIcK{mG3o2oBXfvr{E}|#2|7CuM03T zdKKVJ<$yY%#i<&jHNVU<^%1=Ab%5X4d4{u@uanG&$0P!iD)t!%(?J%UP#%68Du>w_ z56(_aUA+@U3C5>Awdh*N%m7e>NXo^#2PZGON^<41$3hcikz=F5ZsYicO#LLb55F#^ zI*Y!b^=U33L?>d!`qgL7B+1!eKoSzD49%*_Zi~k^4pH?}*b;3fYmqVVnR`n5ie(7i?XDgC(`rb0sq0$W z6eWB#G12SkfVa@Yy%*%A)om8t9W>HnJvCYvJw3y?zu2r%ePy2Jo(8SZ0_O2}0@Rs1 z3ZWVSL^4vLNA2RlnhNKm9RLUQYG8&pA}ETxz?FO&j|v_}2zqB+1VcMUYU30WH_a-D zl&SQij0?iC$o~%j0RR7dm$we}Kz5kdfNjVUV7PRx$_5MOBtQi(bI#$iW6t3+lMmOM}yP;_FWl_*O7vYF|+?(m4`A|{g{&bW9ZzR|c zV%Jg=hnMK5SzpwGb@~A+6{sz=_p{iu00S@)Dd)?tEuNPTGlxW`EuaGgmZv00rf}Vq z!Q2O+(SY|4OF>XHnJ-T#^}eUm(cHJCtrJ!R&z(YtB8jcJ(r5ma2sGDzz$%N+4VrlT zF^BquepnO0w+lCPAckm8ZtHkCU`7j*>J%_Fz#^QOiAN`f6%v&aJ5USd7kNrbmM+jX z=??HLF*cjV)}Rq#U@GN8>+P2G_)N>(M_asYK%BTWam?ABuM1-B2l(|!vdg*!?Y3-C zX}WJ`IKnJk%mfgUYAY(Q$lMJ~9B~TtLH6lV202u;A|g}(^Qop7UXIZrWD4FAtXv?` z&Ki2WN;S5aba|gWoD?&j1PEp+NUBDjeXRHpqO8n8h0Z>d;#1t;KMHGm|HDW za0d(`PS)6LCs~@>*scPqHo7|I99ldk;H^X+K4MxA0|q)aj8(E@F%(yrTtZ@Bo1w3G z8hB{9Jpk29`1B#s9o7cC5Xrj@Q$aG`2-bl{*El)Ug|$e4FN%EO*!>GzKV*JL58x$@ z{pvV2?-YpIy178DeZjz#@>>^v(sTqQy$WD>H>+s>j<;s=Wq(GY2NYZdnnvlRNKg!u`}WqorS7{)6oZC_UCZyk4=&39rXk zn2xPnKbUr=0IwYhXKM4(wGaw{AD@$YRc+T4xoOAeK48DX4@qk_jhNr7LjOm_^}WH`}@17&N;H%)**|fas{gk&76`4 z>;rLtc8B)vL6k-BiQ36#Rf*d6vWcB7I?7Wd1~{6nkwo-xz23u=w*T@k08ob)7)_eX&}4u@+k!&TVH*wJSMS=m0T%?HJv)8S-E%qT4+p2M zYo*_}47YIDta>)tyzXR8#n$Si5VDb`Nga8<>}a%gAe3i*68R7~S{=pfXiXc%R zx1pTRqM~b#5{XLDS8yRo(``!2pm#>^I#2={#CVOg7$bQ|& zs?)Ga+Ff>dGcJbMuOqm`jQK-z*N{YhII>~*7<*e(kim2;S<4qUWp6d=7T*{pX|=ef zGxS=rE)gz27!A zZ21g8*_Et-outnpbm0(8jR;Troeh;et;~L^n!7UlVB6Yve922?#j1Cn&ci*tb#Z8Q z(VP@hk%SqoKZi3(e{8;v;B>`TDhJquk@=y>EV+>+4OY_|jm5EkT|3>d?mU|aazVK! z5z4cj>>27x!Ep#8OjclMc4i}-V0bLcVL8P>+(^^1C*Me%1mwYiVIXtW=i?nIN4h@d zvI#e04FoVP#)u~BsSJRKpH{D^QZx_t;PWtVGRCDCf=PachzJ9l!!r|(9`qcvWSPKx zdJ$~ovxiF2)B4dC%C2uuvh?B)u=54?8~l!P3&)Rz`yKuL$dN*3eS}6jRDk&z%m951)60n5Z*h-&M93V7@?oB+O+}N2+z5a z(p|(yTDXEl{k#Zx7W|05+i!%8Z|?KxD6T`+9%G-39BUTzakOVvddx3d`!XaFz^I-& z3sjiIm-I~Qhq@($<9l}u(j(A*mZjmvv4BJiS0OgW1a}@1Mo}Llh8OKp=~!AhKS-OE z;4qZr=C*)B4BOrG)RI-ne*Fm1Q00f*;k_nC;SjB%z;RCkqj(dR#K2rArk6rTrQ~?v zAH1!v4hGd_slC;WQ7cx&F{uxcK>!&nl&a%x3M^zdo|gGU5tj!rf+w~j4lppSo@y3L4DmhxN2AVJ4r>{j8rAj$I zg)>^?-AYwfl0W5zE@B~Xa#=rvef2Xj(nCoOZ>EZQ zbgy*{yYX2~iImRb5%e%0%zYdKo(;JrP`30>8#0s8Y=93eIlS3-=kAUw;sF$Nz3!pC zEO&RNW$qkjeo1RUl?Q(iMnc&l!<2Muz{pmt*MU6gra9C=>u+D&hmS+d9)xhrh~~?3 zs>%BiZiz`taSw>gpRt@1<+#Ql1~@=8)p*PWk5v;E=s!3ZC{R6YXozcvAhl^3qz?Ez zNBvwS1lF6QmL9RjX#blsnnBnDkKAK@bE*lLkd?dob~ekN@n(uWw;FMGVR#6#{GMe6 zXT>hh_KhXZs)3EKaEOvF&K!yp{Tx?2*+)wX(pA0wg1P*H!sqxCb2W$dItF(F!e~Ud zW-cJMt6PcRg^BIP|d08ME;c9Wo{v0LSKOXP_2w9{{ zR-#zx!(^uWc`zPl)fl*-7%4@aT*(I&pRNuq95iVlgGrsD&8uZ~H#0H%=CJpFbdL!@ zVa2|fOL?dQ$mFEoS9Jr2f=3kj3~dJ$9N?ChQbx(MrLUKv2!IybH|}5l+U7kJ;|zrE zw|3uvw)C6v`{;Dp#+byw9VXGR4VJ=9&dE_ z4^cGov0g^738(fZ+;QND;@V0zT??35eViT^@BGOLdxH>i8}vat2L~4A3rMt{0T7WMayy*%RB&hI9k0X4i>M?8~bqFJzqAi~5O~vV`veEmr zEi9iT@_lqBin7G?%D-cTaIBtwGuc7_wP3-sE^-Vp1t{zCTHd!)sck}Ki`wraVjEBA zDBxDSt;s}02;Qg)OH}d#3qHS3JaZ-&DJ6U^Z+cD8flf9uE6g&XleM!bY1J@uqDD1n08Bpy(i3^vJ*DU-rXo21ajSOl^Gya7jNbjG zCuflvCJOQ>Z6~ot^E9*^>G$b3qpK0_E zk^ypmfS$Fw?36TjDZKEALkhxuMzg?7{(CuiP{YKb<2yFdQoC3ByFEERmUQr_eWOBw3f^tVs9{lb$%zC25c5gMKZ|=W2kzPV?MI~D=LjXF@Z4{a-Q)ncRbLTR7%2l0_ zkQN?32KxDhiB51)vcoo^UE#6eUQhY%eI5Wg6vh0ul&(a#BV(<;=&~bN10e*qk|g!^ zffwK{{z)oAkdIDq!siPh1p@0V2-`;y$CG>BCb>3ZwnyD^ABwq&c}&(IqYdd8Y-J>J zZ{A#Ppa+~q_+;1*rlyq7FR3Ji8Gy;xYYKt5z(uLj`>1Je`$>vS6IPo3puLkKSG2Bt zUcXs!jpl6@WL_Ig!Q;eR?Y1dkR@YGLm6I1_=8-l-Pmb?MhkypATDvIA z*dX{O>c!H@g^W~$3Fo34hGN+Tpd5`2Zqi%02DYrV%MjHGRR)B2iG1pg+V!F7#sc*Xv6be{UPv@Nh z0gp?UxKEgL^JD3QN?XkbA7?9Z5qk}zLvB=LZ|&|5cK1L7?ZRxH)|XG?n|axV-@mnU zo-EnBMQIoZ3e|2_-C{)NN1lH!3c206lOVfcQKxVBm-tOf!OSq^4`PDU`J zm1Fxbomd7iX00uCym&?EFkjV~HTZtMKQ=XNCQRzCk+s-|!h2=bUKV1NEp@vdzICLk znqottTYXlTVdJ0Zzi0dJCsx%|v0>4zS^Z-9xDmdqyb6ELs;OKJNhW+k<~_%(@JAkG zpVgUN5QNcgxwXNxs%0jOoF=brtLnX}-9Pdt{hM6gSxkohY-kt^!=~$%L(};;`Kg*F zq4KX>es5&|k9eT5laLFFO>i?r3($8mCZIs=w*#WG|l|lA2jBR`LDte(m;GT`}h4^TfCI z#XQ9V(i~i{W{_ubFkN+|M|MNfoTmJvE z{`dGlT>r-ZIjN@eybe?H2`ASNYFmw>p=xBY7y6XLWkE%L`HxW>`+R;ln$QhwkO}(4 zv4#b-WHF(PI0Hgm22gwAM%dQ9Ww+x{M9_Iwo| z^_(`^$OEl5_)J851NshMuz;F(j&feLv>Wro4-Fp+g$&lAN3o+x_#d;))j%2saTXm8^r=Ron=i7?AnG24~O=+)9;C#S;<4UWc7Z9Cm3A{s;`3 zyLoAyCr1h>Nr+KKiq?0cCYNy5>?!fMl#Fv*s+LkBnsg0&%=?~7Zp%mHV*~24Lr>TQ z5(9p%#)x6K?=*EkvMMgWbOts@55Yx^ASk?-o(h)s?lc%g`Wy&l%am~^{zzY459gnf zxcOw)qp1UM?C`N83GUXGM*JYaN*6aV?;qULMF~1P_Yd!59a7NqIE`C9^O8QC<@B4< zlN)vCBHpHH!RTKpTuuI#ru9iw)&sh$^jje2ko<8>fyz4F`IBZO`}9_65{v+#5X_9c zB=H0h^bY3ju97KIm`Jh6=4GkR-L=({W=G4F6X}H8un=?sFCtuqL}WPL@2mPi}sn}`-%H>W6lMVX_3IzwN_MplJ=YV~DXRd^@!ufn;s?2}|75H4E#uJ66v zr6yWDlsB%^mfMohr8|X|XNn^0fg`_XCqjEF^IyLRQ}|On;IZ#oqvQ?OSZ-+i@=*7H z7CBvfL@k`z(5EpfH5Uqg0V?U0t#$|OWq31SQ_;U;;BaDY5b&)m48 zAMHE>NW8?aw?aAnL#4>oEa{q(%5p#_@qQjtvgaW98AMO7NJW?5w9m`@R~ z@X)}7*aOq}651!_cx(@1pf^EGI?*`CKM7WENbhwl1s;IO#~V^-jRw-jeX*Xpo$r_H zUo8UQ)!HIozT||SkHlLXm7RL;U5}ZipCr^MJ z+Nf_tKz-#f#gV+pug%X;;8tzW(fY?R?+%B4@I~U?zL2{CjS-3X+K_zlhg^W0)s8)C zoWt(DJDt!zHv-`uYfX4VK2ijJf%+Ry8)Bl5eopw-nSC`2KWe3)z!A5L$8 zz~s}M0?ET@1)z+#&o3Dl+j%y;L4uM1)+0^Ur5^+l(FAa#Sv3tQH?AVKsB(; z*decX{%eb@&7Qdw3U(>M{A(oH?4Fy?gjh6sNEQyKhgwzojV9EwM(JvIoZFfV>XwKA zh!|t0!K_qzw8yy)N^mOZ$mI66iIL6pk(^I4w9&cwU_P*cdhgIf!bqBC*o+|ViOeaf z%OEwSJWHR4y7wQv;7+J5>=UExVYMfRl6$1XWa$?=cR3pj(31nH* zTNxqJwY0TIe6*lKUqxWj_HqLPiHufiBYHmeKz1H*zR`&KRIp%Hvq6AvTnutL6DjE1 zgP8u1wB4FDxlbUIAK$5BKnch#F1qwi)#0N7Qsbm%O4a8)eb_7VHM4)f7L#@fm*F*V z!7go1O1>oHUiTFuA%q6BO!%BWCcknqGnLazXP;1?+Now{9Oj=TU}RtrrxxZ zhsbN383t1i*kQiRJQnDoPR}^a%S2iY_f|EG5$Z)_NzxAGJ+r(=^v8YRPFP+8tn6Ga zGpS8TcwKZ0KV8No9mgpZJ|qv|SU?oYWe>NK%?Za|Uyfn;p}4DPU^mTFHFCZ2G!UV4 zweqeztQ zXHK;~bG=HvDm=yJcUr2bLLZ;!;NJ4oRD49B7Xjad&VuIP6TB_r%)MZg2qyM}10@+c z9DW>q<A#759T=s;9|Oa1tv+r9)!)#U_E%E4pBF%oad-Y{yvrsK08jVOWW|Z1H@cWk-}6Lrp9V=?%La(3`JmYC77amMfB_MxVR$BzaNADa z&`_ukOwfAAmSCnX8j^>{B=#oD`PucH!6Xk$sy|gMDQ~FNAxpzhubC$LO+Ro_D52x1 zHS9Br-3hc;`c`^eA23OKLsHSv!|fZz+m)Go6n?dl85NoofEg$o-lT zE|HFr*0p*Vl25iy>+I^F9l%Cjkt#F;rWaAkiA?a4P;_lm0i4|&rEabJLsphNS~pJN za~e_7tZn**v23oLU(13|I(jZ9MhWP3vo2=#^h7d1rhbp_(56lR%D>2Evq z7F;G-RyhveJRByXhr^jA{&o>b{$et(&>A1+w-`x+oby$zY}MC{Q#~jW4R*;;&H4o1 z+r`pJbREX!5fFuKQjmV)Njb_=e+c1UNEL>gBnN;DX>9_Bfkz1kqM#=2%VkSF(l|gW zmLq3m7sy8wt|HcyBw^*p=HI9%q#_{hAtRdp!ZQ#6R5(r zZdP7~qa{n%%lYFqeGcDg^+Bb#DAgiuAX~ozY%?S1oPV|va=%xy-&e92%2+mRuE14K zn1|36Gu_l_NFnMkMs6!!NWZ{=OITC)UZ>)j<19ii_(pAMm)%JA79r0iGT{(2P4nLe ztOzg+yUt&OpJ)qj?Rgo5Ahd7J6TdHw|F$ydBRcCAxBEat-r)*9K8u+e>j&@gE(zeO zM5u$Hw#kf5Y!n6|kUD)GVtdO(82sW(3ZNVvl1O{%cyPiK0!yTvA!f4l@IHTzmP%f_ zQh#{U6uAJ@^~1fV7fw<&>XKsBTM&P18$^Ip!PmfS6xntcnT~cMLg|Ehbb62xASxLq z;ZS#<^%RfzMZ2fK>{v&PmcwJ`(1n1%LTU8lg;Oy+SFj;=btgfUKyhda=Fpq{hjI6V z*Y*agu!(|#Bj5C17^?Sdku0Cgfrj>pV<6_(C1}y=9zA)rnyFG@qwHYiGtCJoN>vR# z?(qUQ(3au2QryLSBHw4Vw*c44N+hHMF<~S6DHRW100~!Pi@gZ|kZsyfD8G%Bk5b)o zZ>?>Ops<*eCF{rj8u;c1`~dD)Q82#aEx}(}v}2`#M~x31t$qR)FkHJ1^bo*HNuxhk(-tm=5UDd@BKW1$)hgtKL7$V?>mLad z41MvLW)~<20Pw1CdpwfDqq)yZzWesoupUkIqM(iSsCGXD*U5xw#NVLtX@{Zp!4{r@ zNOko4su>BpuEJbvz;YHT-C5HL&{1)?7-E66B+qPy>(w$uliNer7o z!lrweWVfBGblu3(*i{x8gy)##EAogZFJZ6iZFmx4<94OK#|#oxYA+)=tui(zYraTW zfXwcd$(4vTbZ5e{_$QI=tx3B?uplHZnHA>QXx2UtA9kS|&R_rAELtauQLSqYlSDp) z+-3iG9%hU8@11dB62)NQQuLgoMY z{?A-YG#l?$c0o|ZO0+ZKr3jm4&%jRE%ZuzYV4d#!A-=j{)E}yc~5vc%MJbeeIm z1??xaev}G~B-ys`es8fC^s~=Fu)FUU`|4kpIczWe*U zv3Ua)&0j}u61f+VU#YKu#fE+NI=u13ZU6S(fQ?L|+e{xf>>Hb}&m&IV)g#d;b|r?5 zBcCGljvYtkji<)jtKhof_Y_aB{4-Y7ZAYnfYh1!x-0#-Pdieyk7u8`CJf9aT?!`w& zi$UoN5j^Cg`xKv+?_d1fGSYs+dW7<7n7O-@Wx$%$c^#N(Vb4=+PsI&49 zy~agE5)l<|zZI9=0x%*HMB>%i~aIUoC6}sdQl+ExcL=_ zUBG|q3jk~wCaUSU;4tVaT}l`~b{)HujGlcWOr8dE9|&1zTwS(J-`HF~>|A4IXbr|= zzhVYXRp4u5$CqeUK>JZOj2)INK{*6Sxg0Pkml3a0n+-V{eH^@ka^}>N<;_M3z8iT& znFfE-kf0-_5`I29ZdaR4$3-?W=qzVpbhBOQOr6_tcFj;A$iQ8Hrc2a*uDib)^3{Mm zW0q(OS`alqAIep}3%ON5C=wqUgGZ3JPt&S!NEn^|g8B}@#LuB>QhM$EX?#0Ue{PV` zZ5gu%XBHi@i2L3)ZvF^%uJEK^@zFppL9;Uw1!TTS(_TqwoEwIaZiCAy!Ngt$n5+64 z5>kRR^*p}w7yB{5NhJG7Dk_ZKEiP6Jpj`YbDdj+j3fQ`@YaPL6{XuBnpgW`+W;dkA zXr5OdW;06@Mt~UXo;_x$YyLDFsgs>nh3(qGMirmgQs*ky>aRFi`0Nn59?ekm%yER} zD$bpHfD@X z!sfEIDFs(9kI2n5A_Pk~E`*zM-5?MRI!d!3e@oIa;0OaQ;AlBi;aecsAN20*9pri1O!d)rLiGff8>!Iuwo0l0s1hy6+5ePX0#EK;Hen?t59+&{O0 zR>i5F^Qsl5|C&ZKl6g4IZit*q{Uj@)SN9>CkmpG@E(Z1(s3#L(fz=X#bsO3!D%ysY zb5@5gi=F@hF?saIlDmky{Ip!1n5B=g5hs>R ztY~adLGa7cqqIq0k#cBDJfn(+Oj*n3(ROtSGj({4%DUlAdl=tu!b)6}M{bXfG}i#u zE3EM;V4jWK^t-K3Y7JT&zb3cU#Mw-_J$=)wz@rTq$>%x}>6`V}x-N2|sD};eG~}vj zgdfx^6+GG^p5M*;#>;86Y?y8s_j?UmHCalonW9sGk8OSjz3Lx#VWAt~)#icXTm76a z>9@U@+_z~V>2`mwkH2%?rI4i4)GP-X| z9c!m^7;{_jBY-9P^`OEG)9HBf=yt{>gif_;mt|_GE z$pDPO*U{BlVE0^-beI64PHY;Aq}BPv7xf~5Iw=t|_C-ZS@(WLwciQ7Yo1>b1FcsB? zcQN*LmqEE@40x%HbUt{gW$_9dUD2Yuu)L)sEaLQDHb%)48kIL!nY?4kw*6KEARN6Y zg(B|JWJY=h*t5#(%(32wef&K#PywGg`hC?_U0kU2;q}(TcDeZ_%8?JOzufuxP&aBC z2K1}85z9Qf=+`*?ngnx&!GO9-aa7biLKvmO#vt+A;q&@-gKlp*w4J!4GN>E{>uu&y z!NA*q0DvnJ;<%LCM_i?RkTiE!k+Ms^js@ivC~=Oo(jU+hsiOkulRrp5RA?Uc95F-Z zk6M@;v*1v47Uk+<6cwrj7xw1KVVw@*YDjp15BJt8!p9JqH4f_5^Md`Yqfxzg!xU)S z2ftWTA=X{9aeoDwv-NQQV*(jlfE8&rpqGCn>XSPFvlK}YXFI@4i+Mavtr69Jj5JOp zFzD}Qvo|``7C$;adv&}%>j3GqdYE^&*W8Tb8>IoFl1EoqF314WcUdf{M{N=j0Nn6G z24n&=OnpQ=`k)sVL5+c3&|IX{8*VDA^E~IN0~_w7ok5u^a$5x5i=$qZ z)8VPmICX4(E1E@!chWrUXw9=#q}$vS^BO7##1Cqc*uiX9TAFA_^EsOchNNQSejSqj z$-@JacNPs+>%hltDlBtW`#tyT+MllE`*fPBmCSo0o@j-BGu%B_u-%+K*cec9bi6ws(yNuN|Zuc>}zxd-O~ zGEyMDlCtCg<-;(S?64rlPn?Rl>Xajhc`O^i-`?CbT7j$}O63%Y^w1z`@}-<)18QcS zJl>gpOi~*j=@Z;BW?oXpBEA*}7o1P>#Dz zsv;+;bN~_xgdaTFtN38d98{<D)6Z=l;wpIozQ1Szuq z(qFhpV}o$a^gU(0xfWlxi|n)zckiztk0-kBIE^ zNdtJ1+5w1wklJ}g=FqxO^s6$CV5J8$it1}borhpcvvHf@I~q2179wH9O0X>WJ2-cX z6+3;!2r-Cuil4vE58%!w88|y`SDv5$i_aCkZ%hi)Rcn zuQdQ;##KjCzz4|p_yPm(^3_!76C@PSF2QW~Uwx!TWEUX$VAbmifM|M^WM1YEZS2p} zeH))5NQ2rH6ai_oxh5>t&{qi=!yb$FR-Gl?r70y4w}7LKj0N^>1AI-OOfPWds1Snl zD`vl7m6TRRlRruw=`mP`N+6EW3(WNmDQmB>x)nG;n^18F-UQ-G`kOj}W&5tZ>A$nF z$>kn8V)|zhfg3kPkVTQ9OLs=+TqrJt5E(apFzHl0J``L{iRz;`$v>~Dq3hRPbe$_8 z?N`NV@E3fi-{Yx55v;k?5GoZM4YR36$PU$brnJ=Wf)Q1tk z%FuE(%_aLw70cSNr;AI8h@^ghgTo70{FbtU)50m5%WGMlZ?O}og@GNduOPpi$%B3* z^$9pcPQHP`(T#(iVIP90!ClsLixZEkQRdl0NC)YfBuXW_*wFq9ltE*jRFLlgP2H^dHfxb%=BG=V#aqVe(AFehtTH6F4I9dZ zF!+1*$#wPPr;cU$4C*Y5_J+KofH;!y=q;m$k!@|o8Gr|%fb2x#sYMOw&2bi!GWHyk z>FbjyY8PtH1l%Xxppw*m4cy}<+De7a`XxMCLQTq?osBP zZT59bS%cs>98Kk-SR!UpH=L&!3RYjJimFF4$!2HP8(5I|PG~q{HsYuXz6Rz!#WMud zHxv#KDi!6UGyIGIQ3}JG7WJ zw-!{A>lbKOv_80hKF+-H)LudtHBxPGIBw z36N+ry4W6g6TDTEc>;j3@=>aPolECOGblpx!yM&PY4EkhJ|BQP1}2Puf2Y82QhF(K>D%? zaH~rVR_TE*mK0U~c^HfA8Q*~UyapAy?`0ycAdxRCfpYQfOa+`v?b8tA(#O+}zN0uArtjW%? ze~Mn`7a6OGnQnKM-Us3!g-zO>B$6Npxg%VFVpw#-2n7<$u|~grF!~(oXj@?$0dcyL z#CxxyC9~FNrni-r3ZBZeDY)vLNUj0{_XI+|xJ?>540hZX#ueEFEh=d=D0}RzAlUG? zNh=ftK(JE9AVU`V%L*{gInQ)B+YJBK9HTPYt2EZrT|*v1T<(*wOlfo+`$x~Jh|)Nb zsGGeE;USmwd>=L3R2zHoJ9+nBglccC`jd>#i5abe-wAIMC15rQ3#z`@EP5x3QElkW zC&5D}Qa|S7x|l8Ao?*1hD-OR8@+-TC50zeqfAv<5@uJv_7&okbiMr1t^~$V*VDWY< zI?Y!;#nUT|a#U8B|3tI-m75U4$a3VUOO)QZ6}qzGvJ~BFE^{e@sUOv>Z>`+fN;O$R zElsmldGB)LZzMp$C-rzm$^-y0o0HHQLJrLuBQ2&j4@HqtwmL8bqnje=ZIdezX7`it(Ko9u>c@S? zAWb}O7PaH~=yuhIO`x%Fd>G_c54DW^lxpolE>chNcKJSTm^VJE>#YJ8ym3_@_iOhf zUY;WK#%CO-a5l@^4VgE0tj_Gho9ywU8TOCiliY<6>W%B);=~s3`-t~_w~FZ1v`#!1 z)w=ZNWPek3pW@TH>rb51US!kzZ>@LU)V(>4#wGkJ(<+M}gnyThD)N8pWA=;0%+P`W zzx!Oy^~VEZGqP&lLvz2JqBy>0r(KmF;yzx|)z_Fw-v{ipx-Z{z>+ zw!i%2AN^mC|M73*_3p={`O9C5W$b_3QV-?-{O4SGJb#4`l>fRk5~5C$7Guo#W9)j> zR}F%-tbc~7s=f4lV|#T;m+{=H90c@$7iLM2>*#MJIOp~kXr&95#XfWSUOAhgFgA$U=V}E8cp@EF?haup;5VB~SU6l!0r27$^$#P*FA;xGWiX+kLoks$G~Mx^ z93Ey@dkTw7b(H5;F>S|Cqv1K8WMKT^8wN*32H(n4ebIdxBAs5`?#`PC3r4k(0S)KG zh!P8i&z!lcuOTL-Ti38dy;Usx04I^0ZVGD%cCWZ-e}Kv1m(7p^Ix42`eO=oKR;vfW zd4(V-YFgcp9%C?Gd6*FlO_&~RGGmT6E&py*R5%!&8o&4;7Gpck`p6N}iXoa$U7Kbl z`>y)m+|!$?khOODnQFo5dhweH1=OLN>!ngcJJ+BXXIClOd?FZJVXFo%YuN2IgzK}U z@id2JD|R+1M4!tQlxB43rk*Iu#7sc2h2!cS8OSrC*P)}d)@_E2xh!}iX+en7wo$Zs zNJ%X1r6*Mdge{tYtU%R!_Bx=uT%KBGw3PB>JZ4#4tw{h`O8a_5Jv>oFV%M7&!l`}8 zrgS}e0|-x>;SqUlW`YpxFU#!E)FsRLoA49qhFR(+90PrkFc=uxzFLofUbl4!(q_JR zCxhQ?*9=|eMc_~99zT}4X-m$}%Zg+fF0vXT=h8gMQ|vXkCmnj}AD@{B{7AHxtT{TY zv@J{y`LeNytL2O_pvzvI)!6cAnx*`VvvqIxI`I$DvX?u`N%(3Ae&B<;vT(!7np%*H z`(eJu82cWFwS}7uCYX`+x(6?^)_Qfs{x%EY`s^+8y{F>LGKNx^8a}1heF> z{aB|bagXMr86t`BDJanaiM37Bq=6;!034; z&;hZ59{>@O3#?nf;Cq{=Q+C{YPaCUE&0Kw9v>QG6>4xpth0DGs<{86SUHiI_hio7~F~TgAWy{I*x?iTBy3Ap|)is}!Ns zxPn?Fxqh=qI{Wd>v#%fwhO|2cZW)gsPiT1awpUZ3lCWi_N6EUrMp4gjjQB;a z6LAtm)z!nKDtRuE5=Q};UBE0TB4B6>wLkhx`?8FA8BCu&a+Me=fKMY9m z5>!M+>~7=x?z-73W#+HAUO1e!G#ApkMl?MOMr2*Gt|->#3j$xak8_Ye-fcLWMQT8= z;GiA1I5ltSQ1HmvX`hW2=?=_5V9sJ4aBe`P$=twu&d0?yb`%8cS+eqV zi77>3-(BlIpi7q@LB^j!D=lZJ_ae+`GQ+Dh6jA$SaORkznm#io`BJraWWcv^kbUHY zh_q506|nE2QFeDSVfekraHxgx(!`Qu{;l(4bmA`}T&{^`Q%uU~8Mf+dx=+LkorCrTpF z@6G-=^DhYAgJqb(G;bkRxLY!up3HM%W%?PlK|m3FRdazr`+|W5ZYWEl5u{{(NXo#+;%EC1IgP)I2gqRG;XD(u5tze?G>U19ghK#o z7)au>h-T#btU#On5)1z1!dE&nq$FvQkO4PVyF&Qr8?YA2l$dR(k=^THvc==TAO<=0 zc+dtiF-K>2H&)V?ri_A`O z;!?Ng6Mo+Nu`@>A>TT2?R5#%M{1lDB9#wai5#FIXcC`tg3{F^ET~Jx~dy^Fw5ZOMk zZO}(v!-KiP#l$XQkSJ4AHNcS#AsJ}OUT6`Wv-8zu zZ3Zn3JaxEJ-Sq$G&VTub|C~FUfB1Xu{OkBX;Lc8L;p1g*2vkG@@Jo3Xg18+gwshCS z{rn`a`dn3!Lh)A z<4YfxFGU?kYbWJwPjAgUYRJ%n1r4X}hg5ymS+?;^aZ7c#QZ*XGB2uIf)sP*zgS_8! zkA)s1NC}2N%;|Tk7YmDmTYR>DzqhLIrh}B$XJS2IU;^_x-XIho^ck)I&-iZH@GWZ^ zAVME(8$X96{mKHKPh>l@A-xg9sVB1{8#3kP_^B1lZkfhoE|*FZd@(IwXr{jVHHah> z>q&JyujIX82|aIBF2z4EEU!3^v7j4)`7j}T>USgnqFg1@nlFZyOcSA#lz=wlMf-Vy z7~9UZs)LI!F_NfQW(AM3y*x_LD^qgP)JJq6$%Y+*n<3*FG8%#A@gN9VqtYKV`g=Tw z%>^hw=%M37@0%Tc;W^73E3-)qKzJ=n< zPg3Ec^3}xfJH~G@Oqz=KzD3e+!&i)9+VCj^U<;d0vAC>L0n|16RR{t_Ao=WRIboT- zSQMD1i>oEq4Q8W)`^lvBwtP^tZ*kH-X%|!s~p~_Ir;i$&3z!e;y znyz}4&QDklX1ISSU}kS!iKtLF?@#3saMt4M)|k7aX%8k6%|PdtqsK2cM6V zCZn9D5igUg{*jsnr7MOixlM!Rix}Kr0gxrJ>-Z;j$@T!Olg8@b?RCsEB^T(&>R_F0 zxqu-?){d}7c*3h$|5%`E-X9=zs=&y$qrzf)B7pW*EEJcA^9$BaKTtYvC92i0kZ4v{h2a3J_Ajwi~h5lw31n2b`80FVHpkHMBR|S z5nUZvSoE_nzXTSVGE`cuRswI=gbK(K(-?r(q6#+VqVH1OEBSwPj(l8}&&*ziiuI zL()UBGDQ;lqBMKL$RPU26Jo}k^jZQhy2kZG3!F34>&@UW)k#wOaWI}9c44EFkK?i-hQiyU z`nlH$ScowOc|6VMdROiWNapudba!PG7EA+1H+H$glBH2jxj?6-gGs?P z{R4_TkTnoA%SuO$`D<8&)5yGtC0q~1^Z>J{=n)I8*)wO}2TCk%gigPE&%HwKHvLB1 zbjPgAj-J2R7d|;w4V-Mir$|)>JJy(vpw)}Bu|@b>zVPXu>v%*9N?WG>kn=s&mofGF zo67>D@=-w{Xv|?lsJ7H9s3=gMnI&Gi_bWP;{j7hDI2GRp@HlA0+Pc0vu2GyJNE{hc zp+Oe(1T@EwB}wT>&mkq!{eHu!M}I2h@m~9e{~E&AFU>K4DR``KTB3OSfj&oqAw&|0 zl6IG=)f%kPLsWEUT3L=pNn&JGkC-W4-%}o-<9D%LcY>kc!B?Mo^|(;N!!FmJq%g4_ zQ&DB!(|E=O1T@^l6k!jPHww!<{1t(N}KPPzE47RgPA>+jDP2_74@vU85&J-MB zzHC;sY@FBhdHlZCEt$jVUHMMYI4!f@YfNd)R4M?sp4QZsEby)NWwY=L=te8AMw~hZ zZ`3oUa~HDxzWMfjqRjxu9zeI2p_qqV$h&anXh6fL1z3~g!aJ59-8WtJ{lpOi>tl4QTsUlYndLY~6-ALvAl?R~ijJ|W@vk5VX;Qpa=t3bUZOA-RllnCd!}%5+i?G~o_b!ly z3ooI55Y3%Ab%UtM!p7QG_Y5M@_syY)ugIt56T{7Ww&j71RD!(+ zu&ZjZYAr^+2MvR$lnN@IXgKGLY0@95L?bJboJqc|OkfEtHxF9ZDI4|&=k)D=klRMD zpw9gtc_F6@9aXDppiJ=D-h@-$7(?zW2%;ch?a}GksMHWlDw54D2zx)wwAYhN801nt zRz0ew&1<*JietFS6a^SWg@5suF9DDE9$g-weZgObf;s&Yj9PP##!}A{kVPl`L)jF0 zM#1rpOx;q1z7n)g=Q{mn=ul*WYFAY3qnz5SxRx;XhB6+|wgiq96|c7_22BVm;+mec zZT6X^^cwDxJNnLf)HVWi2sNMy z?xrUYK!S7Ch0S!$p%M1k807fy4X!jZZ?#3lO&d&lGsFPq+!HJjq>j;pN6k-NC$Xs( zrk^1Ur_Ilxc7|Y*h86)d{@`;K>y)Kuf>Lm9LUIJd-DL!WHgJ+Q0$FlfP~sus&NG>I zVfQ#$oC+X|v`#xut6Cx^W4E~W$ARAKj|5p+)7#x{J4Ncg zM{!K8^AU`P-tG*@=!T`F5jB~D%WZ=AxHqk6UQzyRE6u;Qnk%J4UURZ;A6klLC6gk^ zVn-_9e2z4a=dObI!MgzvfMb=BvDro*BzO>X$|dtg8ck3;eJdkR1wk*sMp>Y%Y~r=u zcP%g_lwWAeHJ47+d3kdHud}QUq!A#fasHii&(KvfZFlIGqxNazIx2&e@YO$O@@E6d zebd(;eRBwx=GT+Icqx_QskoB^lZ=7mgo&xc2fbI zUpba5K$Fgqzr~R{!~vd^3~_z`5C7|rKmOYvfBf-({{D|Y{>yv+uW$V4KmKz4&0p95 z>5c#W_kX$ndHwgluGf2*()J(!v0SFX*_LLk{^vgw^5c&@eF%`}om_EQ_yT+^KY`{r z_%d@=tiyT)hubs@>v)SlEB$1#yd!93F*7kq7R2tr(q8*ozl+RVGUeW|M|f6cHBy$` zc$!%brd1qZcQ<`O}Ror z0@yDzq%VAKc$F6+GRdqACu$SUQeJ-K4SI)lxA$WKP6MGIB};D<>W>klOcv*jx`OZc z%+IcjKUOK_03qQ6LR)}+Q}Dg8tk0U{vc-IG--o|hpsdaO-ev=Epr+IrwLvQGh8nXc z2-*HnDIx<}bw&@tst+cYmqZS|c414Jn41we8a973-3ISz*KE)~I49fXJQGkC9~HaA z&(K_V!xtk7-VVT(ezDqz3Att^>{98Ql|lz9&9x_m2LrNm895AfNI{yMxoA?l-=Ek( z55Dl6D09F>)Q7mRpy#*q4*MUd@LZdFPtPng6dK=y?ls_xgKbeP#Hi>Vh(t}9ZU}Vf zs*B@PmbDdVOJuxKSLtX7?>YBw?4N>fcKw8RRl=q6*|i)T0A$ElUQ)~TN>U=hM)_KVD}FnFUyTj7jd^S1rrOq zjhX9lDnxR9pOt)7`LgzDdrTy}$I}w^Vjw-q0ETn&mc_pCjaxqfz!|>3U;R6}#gE(O z{TT@Jwu`SZcctf`4uK!bfZRPcX2A!?T({lq9leH!07R>MM~-^GbxhV}{RDtD4>*y# zg~5Q%Q{(+hkuwdC9`L~nq$+i&F^{dqa85K<_?X}eafGXe8T5odtKl3)I{*{Bev2!I zuSUV?geGM`0qjF3<5>GW)j>L>6X=8|pi;U}$7%`egxEYbU$Iu`;|_3UpJWH&A`(Bg z`cP|X)L|06@BBp4*KNI2#Kn(=1ZlQxiIhSNBrT*Xrs425*_WHXgFKjS|&|L6f|FKBtu0xX3tG^Sw59X=Fo{y+aB|t zwZJ&U5kJ65?B}B$#(o1zWoVD?+1B1t)&|TL@dzUUVJbeZlOaFg9&mNLI(%Lf_IXG@ z6&?7rk)wvj;gh?HN`R}89Vjh+TKNNn&C``7^5oXqhldsEhgicBpb=Oa;b(*pb~<(P?jfM7uLD0n0>P;h z`KXh&mVfFnYB|N!zb1Wcl1LgdXFw6PHw)A&$o05|#lUCVAHDCf(X5(nREEt0GP0EfKR&uoXTHz|Lhk#Iz@^TD$m{#q6R_)Cy3NjW&7vD z0uQTj2fDV1URC<0!p4#!PSg)PSi%KgMP2<;d8 z&aEda?#XCl6I6HBv0#BP*Kfk^yts1e=-^b3vSdM%b2X3%>N0-<>2lQ#6;1hmDO6cJ!hk-$)i1SwpK?qW(N>l8$%t|R zDaA{Lg^&sO9Z<>qkoY09#8awms>CW>sz54-V#lHRCBrWR)ZXyWy)%M$YIDaiE<_Lx z(i#%Pal+Mj4=9mLDEe|bT#>D{x)`n1I#wCE*>SZ6X;2!$xe1KL0hKU*KE~E_1nzEx zYwbI=s-!_&mr&f)NRNe*9-u1}Kz7)uDpQR4i5MWdY*2sMpeIXHex#RET7d%IG^y+P zthi7I1h;_gC;%SyVSjPQ@p$zw;XRrtw~QEf6K2U1ZfQ&=35>yWjOcKh_>n8FXC(t~ z{YPU!?R3wR1x-fOt_2^MVvtNc7e5TTxhfO9np@H(vpz+e!zvbX0K3Aa0%J1UG;F3K zl%ee=X4Ea#NUD!^v7W1mcEA`-GuD&xiK|mO+0(DMYGFjyf-;z4@ZZPcD|~(ICpy`G zjiDXR${kMc)j0E;*XPaWpTl|c`o4MjZ(g@>3=G#CZK*P%;jl(lFL=YeMEzB$wU@F7 zie_o#3s<08eoUWsV;V|V7*OaZq{dNC@a9p!94vWR2rnCb$z*kas5H_BuXbEUW zyetWD$3jNuLTcwEf~EXe$IxavbD)>1h<7G}1sb16EMU6hvX-tks40#XjC^4vEy&n~g49akc!EfgKbc{Jj zN)cDrizRaKGJ*Z!E5rY5ys(t`7tBJ;SA-Q;*#C#+z-avQ!t!DGx5cb%B;3-OK%V~u zN^nUTqygle7~daAan3rWz4cH3^v}K|{Ja0ym;8^v`?tR2&-K6OO9Bc$P~P%#Qc35% z7Zs)U9ijhD*{ATy~d%e3^-*2BW*iI8$l$QmfV@PllU+)gE>@!l_ORp(> zsyXp#JO#ldu4WjklRrt1UE8aZ_Ec|Gs95lyznE>T0iX_m4NX%q@|j;=434Dr4;Dq_ zI{CPmhSJ^#1-_VhojFTrP?lO)>d_}?tiuEy^!rp*#DRt%1nsv~x0kJt<{5xfU)$i5 z)W2A&0hHAKcEj|Q%tXF~_&YmuaG|odbg9T5cx~}L^u-t;!j2QCO=k$Y8LyP0iEs6k zdYPQT(cR8#+hEEyrO7irRW2AQcb-j$&r`$cR_&+WgNvkW%DzT2Pyl6)ibfVJ+iQR* z%_UrW^-C7^ju@ykI>{8I(p-8FyRQ5gwQOzl(TM9eX^@uqRQOf{m;iohb(sN$tM__1 zETvLP(hJ12iUewX&9ne6YIcWIXnrXMW?F*Cq*rHc#4m~X8|#<(IueLn22M8w9LmV8 zhgE)Sp%ATqN^9vo_4&e-V4i&DTJ?#wo6fkjK+I-*lYft8pltU>R-anFvnGOYQPQ*Z?d;4P)88hW{wCngjYBo+3 zBFBOGFZ~itT1MS$@5aXkyURaCq7eXeW1;{!L!7T~R1jn?h@Vv%w6f)gzI;nEXb}pD zEBu4DgTd})6Y*o7XZH5m&wyMd)e{^jC*c=#RRqpLt_Qgd9O2BmB%P28^%F0yaU2(PF+*JB*b z;qt%zOEq|*z7AwxXwlDDJpILu`9tHXSOKAipy#r4S^bLe-cz27G#@<_nav<34%cfM z{EGJkS9~n+@NeG5QG@$Rw9hdyLTH}T|@MbwRXHb8- z$@U#v{c3h3Y?DStUyy4kpFq-DKewMBER$m0^k5g`bjUmxw(Hb*GKKK%kzBJZk^`#- zJs&_%0f>8=#7I5F1s zh#K-nZZiWHQeNl6EVMv31%N$r>Zj$Ukpe7vh={IeUPuc?{lY~t8JUcr2&1sLuSu$e#+VpH1zw9bTHt6}YCLxRp?2BSI4$t=_lSuC5#j&me59{IJNyUgXM z`zjhY%C1+4H@Uex3OWE1-r-8ZR{HE zn83Lr_UNm}Jl*bw$E2qGE101{9RPqdJsgZ_p^{7|W#=6qr1YWm3Z!MM<6f|-J3I$+M=6GsXISG(Rbf9fdb#5nVi2lS@!qWlk;JB}!4CkYpZ}m9D{;Shd@u z!@naKY|BFJVKV$ezut`yr|<`6M?VKl+~_nEhN&aq1coUO91MU(KU{|=IQkxP`ME%A z8G+UTp5=Na7m-fwm-H`&qiJ>W2Ns^dF`tX7WR0D$X&&?r+kF2Q_F&b;^X|b$WMH~a zFcFc}Br;3MUEJ(^(-|N6R;#2O4sUb~$LjzG>=UL389Js7{5z7`XKxAZr!6mc6(-P= z+-+akGxSfaDu9E0N7agCV<>ql={cSTzQ-?N zbpp{{8O?n8ECeJvd?`n0&r%k>FKJl^i)H&(Ksmu~0!>!!1s%mNv`F;*?AYq<7g_Gl zAe9~8X0Iql7fYiQj<`zbJ#O1$CI@Fa+=b>uKaT6{u1@Xtj1uK5v}GI+S3?!(-%xWB zp%e^w-l9n-V+a!OoKA4C>3*2|4*jeEouf6gvPZQw3LiSfvA{-7u43^bkUM(FGE2RD zta1?!{AG+vS{H0YCXu%$IRL)YyMqKuPbRLJBTKM{HAVQI#hNc`1VUnsWEf%Zk^N9I z_zHG_@94UK;0KH~Uamr8H%YaUjR?Geuq13M+;h+T)MaKi))te zKY9-2Y3s%09;nID2e8W(S#kdgg!Fco-uxNHWMBp)pwd5|p=fdFhS(nwLRozlVJO-l zgd=;BvoAZ2ngdFtvk42nkS>$N;W0p_9x{AZoQ^)VXFdmXJ?}$Q8CqU!{G%vMNAbJf z77vwRgh}Fmnt|TY=4u^rr(b-(0#R}MR6+(5+G>+)u~i`3F*3!2BBo!XBK5tPG!wb8 zz;7s6Km~pUm$yb&`Icw2n-Wl+#u`o>+zP#+`k3a=f=V|+{@U~{<{R2yHX1*9kdK|GD9=vlDIS5sf z`*I^^VOiIllUd+rt@t<=b@#fCVa4Gr2+$->%p`-1hr2z?>WK)ZlBfhk7jn(eYuv%D zRN(4#!Wc9AN&@hx2!n5-Es86uM(0`wKK#D)fW^T*SfQVL_;S3%wa36m!gC>vD~4zH z@K~nbG*Y(@NwEk)N5gcQi5~vx^?Ib^qy~c1cf&R)L^db}x@Jf?z&c?Ncr^BGF%+CAXQ1OIS z(9!*ULb+JLxdpOhTE$5w*MrdEILtUuWzG#=FVRo?TSrQ6itdH14(3zMnK8Ji&Csf( z5O{B+9rM(%m?7h44#7KlRR?ZM)XuN1d>AuJ@d7KesAr+OIO|D*Y&W~+{c#M!*eaNm z7dbJIUy+)&iHo6etYIwTRifUB-hHn(Hg);5 zmIp)GxYc9B>fQ$pL6$R`a~D5XPc|+cJcD|FRG%k>I0QG(*faFd3`&Z_3HkQJQvp8+ zJPgBse#e%8lwQ+zp9LYTkji2o4KQMQBet!LKyHyA!&5sWb$pRgJr)q5oAC7FOaD4xIsv>f)5byM)$5gTfy9WNr-6bExw~ml-F%7kve=vsT%&)!KdzQDsE;^JNLPclD@oq5z0_qp4;F`im$u=WVQaID6Q7iFV zSk31H6uCHl%v8wby7M>g=<$Zw+4;O&ymbHr!%r6Pw5ROuZCs8GR$JUiEzt0P7=*`y zkzaNI@6T~B>(A^tJVMdH!SlZS<;7&w%|%;;m}nut@5Pu>jK8RE@fDO%BvCH8u+yQE z#mFNZFhCu1Sd)tS3S8E!I2%14VK*qG;&XKva__-tb_ddUhBU(6kryX*Yb$E;q`0DQ zYDSroQb8@8&NFpNyg03Q9x5G)}Bb{{%5=fACJ!T0F|FA_Sk z6l+z5I0#dfJ$ae7oXe4v6qF7FoCtkW36c(md^lo{Q{1`c-eUs5QPrTSgPC0(Levi| z(Qk1(Ar1lGf)Oe2lvDFWl?{7q%h^!?m2&hvyzjD`h0(NSfo?%L0a@b_K<`O|-#d z^3WGv1bmn5Eyzs4ahLz}Pyg`0{_@Yqe}DCV|L!k;`LFN!J^kfB|I6jS{Fi?n|EE{~ z`|tkc{KxS>{&l?G{g^cW_>aXh_V%{aL-{}dA(tOdXtzUvJPhP2N4_}@X6ANM zDz6C@ANec=GwsfaH#U=#V;{+f-gz?!h^LWwTV5THK$qW2^3F_}&Kt zI%xX-YC)*3FWr;@3aoO9g!^nTxRyC9`T}kcJ$H=?fO^U#YTYmVJSGj_SZ29+G_7T6 z2CE-fd;l)U#~xb{6TY`hpED=Rh&9X6Sg*7rvkQRy?9Fv#n9<+hR5;)oNtC}3fz}7M zvBMxI?TXxU+(8=|?w40GgjfOW zjp4Sz9O2680goCd7z)9pN0+24G9Q%F-xtcad+L~R8O0?!kPH3H!2J-^&yd>ObSjed zieSFj&w$0jgc_S)((Fg0E4|Bccwmw-ZQAT6ewz%m)cNctqS2*=t%wK;Y*stg`8J!# zG%JfG#V=@Fq`Ny)C(SzNU~4Pv3RR`P2jX0C>0JY;K;X!6k|%-d0xb;yb@A!03${#} zVYXIg*QEE)JN0;Q$G#||nEdTvg3nnnlx|wz1H$RWnVj!M1DFg`M5^z zm?)YW(D8~O;J zZNw#_cM@i)Gs|hf>J!m2I1)INF%d4}-(VsFi$HobXC zK7$<4gC8ALd|{LbG0e7K|EQ3h#ooj`JmZ&8#}w_IVKkCPFUWTT#sb3OX{vo{Y7E^F zKyPJ=TkKAV)bsob!JaK%aJh2}r#gU5<_TDw>eBCW%Xh#U$^<8{a7i~s4~V4Hu^|G;}>13kf1EmmB=5y0pj{m!^tc5=}SO{qh=wPjr&fVZ2Z_j`&LGIP- zJPPl|4YJ1WTVGL;XTWd2KWNoBd!>?$2!m+wrBcD%DqBYkWy~*eMntDXEZtp&;z{{o z@GmMBzWi2&f@o2=a4rNG4orbxwmdr*4`3=W@?eAM7&4~5*io9GuDSxzL@_mkSWlPi zAb}V5{>y3320)mJMM7HSA+_Kr7C9b$NH~xkYH_*Mdg|GIQiYF23yyt-i>>UJ(=4-8 z@25eABZmk#fY`W{y_L$dq$PXukIpa=)%7$mBsSF z`LtCI;5T9_JlW~o4SLbR|KPOEkp1K3GyvRicEq(4607?x=o?`^wZ6XwP<3d@CV`!z~+$V z$rZ$7v6P`b3ogDm49-41?H#T^KGE1#av3F=ARQ4e^EHw$zwt8%V`%lAe5pzMM-BUjQRTFkrAVe#)Z0Z$#jm`eFuj`=@- z{~vQq@%R6hWBwTbdmJ-ph>1Wy_f+8`QM00xXj@UBak$dmz{ss))L++MiI>Cn_p{FS zm$ff-<+wgu44UC>fOi=iPnm;aGs@OufHN^}V~CMszbAfL_nfa$rbTP`+-Y*e7ApJW z+q8g0f6Sc*f@;U_N9`AX70BE^K>g9qLmu#;@s2sM0jzio!ZG#GK4Nv7za2lM$j7vB zyuhs-3gV-9aS3*XV?&XO{AE`}m`#NYIYzxM4+wgq@bZJ+jG+NM)1_QLXzv{d<@;be z3bopGmUr`t^M~e_Ed!c-ztL);NkR?$Ml+2pj+$VCpV$7FgLL6i0+q1H9Y>1i=(*67 zVG?K38xFqBi*pj4R?J0zjtw1x19=sObGq8CI9uN%5R#ZcGMb8EuW}0Zs?iSJizZ*( zge3SP3&43{zb8~(SlO>YC& zccmLI2&1X{Z5t^eOlj{Bo4ggvlMzxH57Ch6=Czba9MHKhlRB(rDPkAo!Lg zc}MR(R=9E10Tl|Ec;%tAI=9BXdxR5pBd$+BTAIuN^V+I#mDh@3g|2#f*u)9~q{1&< zZ&(~Yt^~UBIfI$zlnEL;<}_pwD#n!4ihB`mQ?cxbHvCi?c?qipY%o&83Cv{jt=g`g z-jk9mK*Z9^HM}11`WadS1g9w+%jcU{jtefYJC{!+H(#Hqk!uFOIk`9`nJxK3gU|`s zimg3KfnwBQ(C(JZcoGOPuphzD;O4su{Z4l!zq6H0ll*P4^J`d-?ycu^=9qy;8$Se` zn}|(`OFc+ir8X&CW;hdS+@#imzj(|lrb3?!&tKaaKz7>Dj9fQRd_CU0L4sLc@RUAC z8L@-Mz(?T;5+Hc_r`7%N7?;dJth_Mmy?yXP8}?F&bHQ7``U|p5k&(c!Bgl+B3&5fV zTR#$z1Y`>U-jogpc+Wxu`PH^qf6OL z=W8jbBk1V7d%2qfz%UWMYn(|)s)2Tc2oIR&Byz|iD8Gz;13j7=iN9mxwQ-=G+TN9t z?g8Y4LI?WKB&>ngY{I;i!@vMY$uN@c-LBmI^usJYUu!+$#6fhbxp39zQ zZEESIlX!M(T)2@*Y1$T8!>EKRh~uaT)CDo%+2+YS_0c}^#%jONAinSn9|^1ryR`}y z{h$x=eMmT{P5kK^qWHlHMRPDX`T-2|+l+=Lz1dW8d_n`H#8dY2?!+DU>-}!hk#b zQw5YS4kW%s8jdR1d2d64&YCZpBBbn+04&Lp6CZQX?NToLUpG~#cvwDamBech@c^#li2RX}`sJx!z{lY!Wfi_}9 zVD{LCK#LSu4}6sQ8+v3jk_KJ@oMI|-QVEwFUDm+0`(ClRKP zr_XN<@=hNDUyh(z{n>^aKE7)MF7fq#!}*)nHZ2-Mppu=bp!=wg-fQD94w%y_PZlpi zoEqfIn*gD`L=vU2;^`|O@)yF908}MB=%(@_G-D`eb8)|&_?K+T?(vfc%|<<0OOA)8I|J03sEHMd%H#b%`Ghn@u63`h+e8WjR@s z@4zat!OLN-*lh#7`TUKfzpCu8Q2L~h@Y!wl6MVm|T9!9|+7Saw_Di?l-75vWm!e+U zx`-kCHt9lZkLumJ($>hz-DmGl(v{SETWCtwJBFn|{SvL&N;7hN`Nu8QetaKneSo;G z){AGOUKIg|3U~G1$8V8*y1$?w%SE#+KdkTZ=3%c@=S2#5OFc(de5C&`|8L|4T#ct8 z^H)WGicH&qtv;gpr=&lnTkTMypAbhm;EU;}U}Trs=4|$DhSb5u5>?!u>Q7eO&+a9` z^>dLgDlM;3&~lOq6spI6E!rZVxBPR4j_ajiW?y#5orrDF-w#JySmE|}3X|VI)$>ll zUdbq>!osg~=>|MHl5_w2jz&lzP6m=;-!L9^|G zBuJ-tW(?+wc2?@hzkmMM`iDQc{@Z`-Prm={-};k3#{Zr_@ge#^xt~iTA?id%KgM5w zj9st#DM8Sd=o53EmrA{2@v=+4Rl%LgwL|OqfZp6nD>*_?o?2WBe6AxsSj6v z=279eT4K(OK z^j-G79)EDleLXBaWi3B4EhFdS4~7p!+Tgnji!wk2ts@?~&gJ7ZQ9flFU8td?kE{|# z^=>eO-<`3rzOL>za)@se#z)tWVk3%&rA@+w?B}C7)C$mjDB^O#?4;?e)|wAx-DB}8 zEVyxRm`L%hyi_iXuZ1Q7!&S2Q>k`*3jcJK+6s8%c2B7#`B1zNAQuC`7oBPQ(xvQU- zt$t7X{SM1JN4CuZsCV$v^}r`8EjTk?TiyAnr)x~&PQI9uMr|ncC%Q0rPnKB!9!Uq~ zRW3QR(rJ`R7_vcqO%95GnnWfJRaX%w14Cq$2I=Ul$P#zv_hB3P8Y@eHys(SGGCtj< z(>IGo082}U&oys8tS~4N}2Vd;fC&zO+nBilv7tdzR=~D zhOkkAiDn>W#MzbV;l;WU>|sQK2Rdqu=e{~UBK;P>)Uu`QR`cW#XGwuf+oAX?)BRZ~ zqz)cVhVD}x!+BcS=tn60^d$wu$4$Uk>k}uGL)w;jcH>MN7N^$V?y(ca(&Pdgq$lPLfCw(jjHM4;WDG>krP(4ZKdZ))$;k6q z8~fU)u;IZ%5aC`Flqc}N{ft$t_#>EPYCFPN&5UBLNCeK99%DJn(J2q}`nYBgB|8SP zjL#AOsG+3_`YLO}NqH@LFIQn(%nohMB#HspB6pOXUrdhTstJutW(h9<)RlqqORT2*<2en^xxMQ%N1 zjFh(@x;03)Scqb6D1+ zj(Hx;3}28>$!Es*y?d3bC{i{l>8Mpz=hUfIH(}luRlJl11fRjVA!b>kw7_IIX_aEo)-TEO>-y0%O?Co0rN1SqO6fzx z@I%WD8!&ErlPn5a#EmT`vs`#JAL&N}S*lb=sCPSdCwXs{ z&Qrn6<@0j5>k_5tPL-ZOzU7|s$wJr0brg|9y`VLnGhy-5F6hO*oG*QhXx{hIq>h}i zS1an)sBTW*U6GAs0(U}eBD)O)1`8T?B-s-H>olbftEQ@QPTJGbmF$8 zYeJXVdJJ+Yz9RP~He&%cLeZ{PThYepxQ9N50=X$S33oZmH2JFk+}bFZYVoecJ z0mBW#{Juo}!_#AvCA@On1x_lI#s|rT%xC^c zkS8o}PB{qsqeT1GPb+~0vjHuRMr)8Fn#NnRJkdcUKv*B`bVGQuQ6MfQKE7-*2vF)6-g{N zIz7EsA%eEKrbc2gy-Nv@<=02L*eYh1*Xvvg=KgdnH%%5a*&%2eUe5Pf8Yi0ePinO&NtCnW7LMm_qx{lL6^JBz>`|tp(l?-o@%TpiW0_GcO>M495FrUWiQg27$ zu{Q6et!q{1*z9^Nk9U+=n@eR5?m&vlQnHqcXic|^S&c=RI_7EV#&CiyffAPkJ8LVQ z%U`&A8pPZMJW^%J7QE&(AOd?K8Bk3gXcNd1J{oM^d$AUwI*1fl!g!)e$25@XjLKrn zX_<8NX@FoJbu3b{-t_InsMH!ns}*$X+FsG_nzn^i`DS?t^y_IcEUw&decvwkGyB;@ zf>E?Wty}a6q?kaAceZ@~{jY!f@>~4ngMWVT#}EGW!7sm;zx?_=|N6c5qyCN0{lx$J zAN(J@f6w{D|6Tu&pY(tJFM9M7|Lgbs%P-g4554j~{D1cQ=Kt&W{M&gG&Bu>9-{N2I Gywm{yL({|n diff --git a/matlab/scripts/Inertial Nav EKF/SymbolicOutput24.txt b/matlab/scripts/Inertial Nav EKF/SymbolicOutput24.txt index 5c61fc39e1..5e225c8f2d 100644 --- a/matlab/scripts/Inertial Nav EKF/SymbolicOutput24.txt +++ b/matlab/scripts/Inertial Nav EKF/SymbolicOutput24.txt @@ -1,224 +1,212 @@ -SF = zeros(25,1); -SF(1) = daz_b/2 + dazNoise/2 - (daz*daz_s)/2; -SF(2) = day_b/2 + dayNoise/2 - (day*day_s)/2; -SF(3) = dax_b/2 + daxNoise/2 - (dax*dax_s)/2; -SF(4) = q3/2 - (q0*SF(1))/2 + (q1*SF(2))/2 - (q2*SF(3))/2; -SF(5) = q0/2 - (q1*SF(3))/2 - (q2*SF(2))/2 + (q3*SF(1))/2; -SF(6) = q1/2 + (q0*SF(3))/2 - (q2*SF(1))/2 - (q3*SF(2))/2; -SF(7) = q3/2 + (q0*SF(1))/2 - (q1*SF(2))/2 - (q2*SF(3))/2; -SF(8) = q0/2 - (q1*SF(3))/2 + (q2*SF(2))/2 - (q3*SF(1))/2; -SF(9) = q0/2 + (q1*SF(3))/2 - (q2*SF(2))/2 - (q3*SF(1))/2; -SF(10) = q2/2 + (q0*SF(2))/2 + (q1*SF(1))/2 + (q3*SF(3))/2; -SF(11) = q2/2 - (q0*SF(2))/2 - (q1*SF(1))/2 + (q3*SF(3))/2; -SF(12) = q2/2 + (q0*SF(2))/2 - (q1*SF(1))/2 - (q3*SF(3))/2; -SF(13) = q1/2 + (q0*SF(3))/2 + (q2*SF(1))/2 + (q3*SF(2))/2; -SF(14) = q1/2 - (q0*SF(3))/2 + (q2*SF(1))/2 - (q3*SF(2))/2; -SF(15) = q3/2 + (q0*SF(1))/2 + (q1*SF(2))/2 + (q2*SF(3))/2; -SF(16) = - q0^2 - q1^2 - q2^2 - q3^2; -SF(17) = dvz_b - dvz + dvzNoise; -SF(18) = dvx - dvxNoise; -SF(19) = dvy - dvyNoise; -SF(20) = q2^2; -SF(21) = SF(20) - q0^2 + q1^2 - q3^2; -SF(22) = SF(20) + q0^2 - q1^2 - q3^2; -SF(23) = 2*q0*q1 - 2*q2*q3; -SF(24) = SF(20) - q0^2 - q1^2 + q3^2; -SF(25) = 2*q1*q2; +SF = zeros(21,1); +SF(1) = dvz - dvz_b; +SF(2) = dvy - dvy_b; +SF(3) = dvx - dvx_b; +SF(4) = 2*q1*SF(3) + 2*q2*SF(2) + 2*q3*SF(1); +SF(5) = 2*q0*SF(2) - 2*q1*SF(1) + 2*q3*SF(3); +SF(6) = 2*q0*SF(3) + 2*q2*SF(1) - 2*q3*SF(2); +SF(7) = day/2 - day_b/2; +SF(8) = daz/2 - daz_b/2; +SF(9) = dax/2 - dax_b/2; +SF(10) = dax_b/2 - dax/2; +SF(11) = daz_b/2 - daz/2; +SF(12) = day_b/2 - day/2; +SF(13) = 2*q1*SF(2); +SF(14) = 2*q0*SF(1); +SF(15) = q1/2; +SF(16) = q2/2; +SF(17) = q3/2; +SF(18) = q3^2; +SF(19) = q2^2; +SF(20) = q1^2; +SF(21) = q0^2; -SG = zeros(5,1); -SG(1) = - q0^2 - q1^2 - q2^2 - q3^2; +SG = zeros(8,1); +SG(1) = q0/2; SG(2) = q3^2; SG(3) = q2^2; SG(4) = q1^2; SG(5) = q0^2; +SG(6) = 2*q2*q3; +SG(7) = 2*q1*q3; +SG(8) = 2*q1*q2; -SQ = zeros(10,1); -SQ(1) = - dvyNoise^2*(2*q0*q1 + 2*q2*q3)*(SG(2) - SG(3) + SG(4) - SG(5)) - dvzNoise^2*(2*q0*q1 - 2*q2*q3)*(SG(2) - SG(3) - SG(4) + SG(5)) - dvxNoise^2*(2*q0*q2 - 2*q1*q3)*(2*q0*q3 + 2*q1*q2); -SQ(2) = dvxNoise^2*(2*q0*q2 - 2*q1*q3)*(SG(2) + SG(3) - SG(4) - SG(5)) + dvzNoise^2*(2*q0*q2 + 2*q1*q3)*(SG(2) - SG(3) - SG(4) + SG(5)) - dvyNoise^2*(2*q0*q1 + 2*q2*q3)*(2*q0*q3 - 2*q1*q2); -SQ(3) = dvyNoise^2*(2*q0*q3 - 2*q1*q2)*(SG(2) - SG(3) + SG(4) - SG(5)) - dvxNoise^2*(2*q0*q3 + 2*q1*q2)*(SG(2) + SG(3) - SG(4) - SG(5)) - dvzNoise^2*(2*q0*q1 - 2*q2*q3)*(2*q0*q2 + 2*q1*q3); -SQ(4) = SG(1)^2; -SQ(5) = dvyNoise^2; -SQ(6) = dvzNoise^2; -SQ(7) = dvxNoise^2; -SQ(8) = 2*q2*q3; -SQ(9) = 2*q1*q3; -SQ(10) = 2*q1*q2; +SQ = zeros(11,1); +SQ(1) = dvzVar*(SG(6) - 2*q0*q1)*(SG(2) - SG(3) - SG(4) + SG(5)) - dvyVar*(SG(6) + 2*q0*q1)*(SG(2) - SG(3) + SG(4) - SG(5)) + dvxVar*(SG(7) - 2*q0*q2)*(SG(8) + 2*q0*q3); +SQ(2) = dvzVar*(SG(7) + 2*q0*q2)*(SG(2) - SG(3) - SG(4) + SG(5)) - dvxVar*(SG(7) - 2*q0*q2)*(SG(2) + SG(3) - SG(4) - SG(5)) + dvyVar*(SG(6) + 2*q0*q1)*(SG(8) - 2*q0*q3); +SQ(3) = dvzVar*(SG(6) - 2*q0*q1)*(SG(7) + 2*q0*q2) - dvyVar*(SG(8) - 2*q0*q3)*(SG(2) - SG(3) + SG(4) - SG(5)) - dvxVar*(SG(8) + 2*q0*q3)*(SG(2) + SG(3) - SG(4) - SG(5)); +SQ(4) = (dayVar*q1*SG(1))/2 - (dazVar*q1*SG(1))/2 - (daxVar*q2*q3)/4; +SQ(5) = (dazVar*q2*SG(1))/2 - (daxVar*q2*SG(1))/2 - (dayVar*q1*q3)/4; +SQ(6) = (daxVar*q3*SG(1))/2 - (dayVar*q3*SG(1))/2 - (dazVar*q1*q2)/4; +SQ(7) = (daxVar*q1*q2)/4 - (dazVar*q3*SG(1))/2 - (dayVar*q1*q2)/4; +SQ(8) = (dazVar*q1*q3)/4 - (daxVar*q1*q3)/4 - (dayVar*q2*SG(1))/2; +SQ(9) = (dayVar*q2*q3)/4 - (daxVar*q1*SG(1))/2 - (dazVar*q2*q3)/4; +SQ(10) = SG(1)^2; +SQ(11) = q1^2; -SPP = zeros(23,1); -SPP(1) = SF(18)*(2*q0*q1 + 2*q2*q3) + SF(19)*(2*q0*q2 - 2*q1*q3); -SPP(2) = SF(19)*(2*q0*q2 + 2*q1*q3) + SF(17)*(SF(25) - 2*q0*q3); -SPP(3) = 2*q3*SF(9) + 2*q1*SF(12) - 2*q0*SF(15) - 2*q2*SF(14); -SPP(4) = 2*q1*SF(8) + 2*q2*SF(7) - 2*q0*SF(13) - 2*q3*SF(11); -SPP(5) = 2*q0*SF(7) - 2*q3*SF(8) - 2*q1*SF(11) + 2*q2*SF(13); -SPP(6) = 2*q0*SF(9) + 2*q2*SF(12) + 2*q1*SF(14) + 2*q3*SF(15); -SPP(7) = 2*q0*SF(8) + 2*q3*SF(7) + 2*q2*SF(11) + 2*q1*SF(13); -SPP(8) = 2*q1*SF(4) - 2*q2*SF(5) - 2*q3*SF(6) + 2*q0*SF(10); -SPP(9) = 2*q0*SF(6) - 2*q1*SF(5) - 2*q2*SF(4) + 2*q3*SF(10); -SPP(10) = SF(19)*SF(21) - SF(17)*(2*q0*q1 + 2*q2*q3); -SPP(11) = SF(18)*SF(21) + SF(17)*(2*q0*q2 - 2*q1*q3); -SPP(12) = SF(18)*SF(22) - SF(19)*(SF(25) + 2*q0*q3); -SPP(13) = SF(18)*SF(23) - SF(17)*(SF(25) + 2*q0*q3); -SPP(14) = 2*q0*SF(5) + 2*q1*SF(6) + 2*q3*SF(4) + 2*q2*SF(10); -SPP(15) = 2*q2*SF(9) - 2*q0*SF(12) - 2*q1*SF(15) + 2*q3*SF(14); -SPP(16) = SF(19)*SF(24) + SF(18)*(SF(25) - 2*q0*q3); -SPP(17) = daz*SF(20) + daz*q0^2 + daz*q1^2 + daz*q3^2; -SPP(18) = day*SF(20) + day*q0^2 + day*q1^2 + day*q3^2; -SPP(19) = dax*SF(20) + dax*q0^2 + dax*q1^2 + dax*q3^2; -SPP(20) = SF(17)*SF(24) - SF(18)*(2*q0*q2 + 2*q1*q3); -SPP(21) = SF(17)*SF(22) - SF(19)*SF(23); -SPP(22) = 2*q0*q2 + 2*q1*q3; -SPP(23) = SF(16); +SPP = zeros(11,1); +SPP(1) = SF(13) + SF(14) - 2*q2*SF(3); +SPP(2) = SF(18) - SF(19) - SF(20) + SF(21); +SPP(3) = SF(18) - SF(19) + SF(20) - SF(21); +SPP(4) = SF(18) + SF(19) - SF(20) - SF(21); +SPP(5) = 2*q0*q2 - 2*q1*q3; +SPP(6) = 2*q0*q1 - 2*q2*q3; +SPP(7) = 2*q0*q3 - 2*q1*q2; +SPP(8) = 2*q0*q1 + 2*q2*q3; +SPP(9) = 2*q0*q3 + 2*q1*q2; +SPP(10) = 2*q0*q2 + 2*q1*q3; +SPP(11) = SF(17); nextP = zeros(24,24); -nextP(1,1) = SPP(6)*(OP_l_1_c_1_r_*SPP(6) - OP_l_2_c_1_r_*SPP(5) + OP_l_3_c_1_r_*SPP(8) + OP_l_10_c_1_r_*SPP(23) + OP_l_13_c_1_r_*SPP(19)) - SPP(5)*(OP_l_1_c_2_r_*SPP(6) - OP_l_2_c_2_r_*SPP(5) + OP_l_3_c_2_r_*SPP(8) + OP_l_10_c_2_r_*SPP(23) + OP_l_13_c_2_r_*SPP(19)) + SPP(8)*(OP_l_1_c_3_r_*SPP(6) - OP_l_2_c_3_r_*SPP(5) + OP_l_3_c_3_r_*SPP(8) + OP_l_10_c_3_r_*SPP(23) + OP_l_13_c_3_r_*SPP(19)) + SPP(23)*(OP_l_1_c_10_r_*SPP(6) - OP_l_2_c_10_r_*SPP(5) + OP_l_3_c_10_r_*SPP(8) + OP_l_10_c_10_r_*SPP(23) + OP_l_13_c_10_r_*SPP(19)) + SPP(19)*(OP_l_1_c_13_r_*SPP(6) - OP_l_2_c_13_r_*SPP(5) + OP_l_3_c_13_r_*SPP(8) + OP_l_10_c_13_r_*SPP(23) + OP_l_13_c_13_r_*SPP(19)) + daxNoise^2*SQ(4); -nextP(1,2) = SPP(7)*(OP_l_1_c_2_r_*SPP(6) - OP_l_2_c_2_r_*SPP(5) + OP_l_3_c_2_r_*SPP(8) + OP_l_10_c_2_r_*SPP(23) + OP_l_13_c_2_r_*SPP(19)) - SPP(3)*(OP_l_1_c_1_r_*SPP(6) - OP_l_2_c_1_r_*SPP(5) + OP_l_3_c_1_r_*SPP(8) + OP_l_10_c_1_r_*SPP(23) + OP_l_13_c_1_r_*SPP(19)) - SPP(9)*(OP_l_1_c_3_r_*SPP(6) - OP_l_2_c_3_r_*SPP(5) + OP_l_3_c_3_r_*SPP(8) + OP_l_10_c_3_r_*SPP(23) + OP_l_13_c_3_r_*SPP(19)) + SPP(23)*(OP_l_1_c_11_r_*SPP(6) - OP_l_2_c_11_r_*SPP(5) + OP_l_3_c_11_r_*SPP(8) + OP_l_10_c_11_r_*SPP(23) + OP_l_13_c_11_r_*SPP(19)) + SPP(18)*(OP_l_1_c_14_r_*SPP(6) - OP_l_2_c_14_r_*SPP(5) + OP_l_3_c_14_r_*SPP(8) + OP_l_10_c_14_r_*SPP(23) + OP_l_13_c_14_r_*SPP(19)); -nextP(2,2) = SPP(7)*(OP_l_2_c_2_r_*SPP(7) - OP_l_1_c_2_r_*SPP(3) - OP_l_3_c_2_r_*SPP(9) + OP_l_11_c_2_r_*SPP(23) + OP_l_14_c_2_r_*SPP(18)) - SPP(3)*(OP_l_2_c_1_r_*SPP(7) - OP_l_1_c_1_r_*SPP(3) - OP_l_3_c_1_r_*SPP(9) + OP_l_11_c_1_r_*SPP(23) + OP_l_14_c_1_r_*SPP(18)) - SPP(9)*(OP_l_2_c_3_r_*SPP(7) - OP_l_1_c_3_r_*SPP(3) - OP_l_3_c_3_r_*SPP(9) + OP_l_11_c_3_r_*SPP(23) + OP_l_14_c_3_r_*SPP(18)) + SPP(23)*(OP_l_2_c_11_r_*SPP(7) - OP_l_1_c_11_r_*SPP(3) - OP_l_3_c_11_r_*SPP(9) + OP_l_11_c_11_r_*SPP(23) + OP_l_14_c_11_r_*SPP(18)) + SPP(18)*(OP_l_2_c_14_r_*SPP(7) - OP_l_1_c_14_r_*SPP(3) - OP_l_3_c_14_r_*SPP(9) + OP_l_11_c_14_r_*SPP(23) + OP_l_14_c_14_r_*SPP(18)) + dayNoise^2*SQ(4); -nextP(1,3) = SPP(15)*(OP_l_1_c_1_r_*SPP(6) - OP_l_2_c_1_r_*SPP(5) + OP_l_3_c_1_r_*SPP(8) + OP_l_10_c_1_r_*SPP(23) + OP_l_13_c_1_r_*SPP(19)) - SPP(4)*(OP_l_1_c_2_r_*SPP(6) - OP_l_2_c_2_r_*SPP(5) + OP_l_3_c_2_r_*SPP(8) + OP_l_10_c_2_r_*SPP(23) + OP_l_13_c_2_r_*SPP(19)) + SPP(14)*(OP_l_1_c_3_r_*SPP(6) - OP_l_2_c_3_r_*SPP(5) + OP_l_3_c_3_r_*SPP(8) + OP_l_10_c_3_r_*SPP(23) + OP_l_13_c_3_r_*SPP(19)) + SPP(23)*(OP_l_1_c_12_r_*SPP(6) - OP_l_2_c_12_r_*SPP(5) + OP_l_3_c_12_r_*SPP(8) + OP_l_10_c_12_r_*SPP(23) + OP_l_13_c_12_r_*SPP(19)) + SPP(17)*(OP_l_1_c_15_r_*SPP(6) - OP_l_2_c_15_r_*SPP(5) + OP_l_3_c_15_r_*SPP(8) + OP_l_10_c_15_r_*SPP(23) + OP_l_13_c_15_r_*SPP(19)); -nextP(2,3) = SPP(15)*(OP_l_2_c_1_r_*SPP(7) - OP_l_1_c_1_r_*SPP(3) - OP_l_3_c_1_r_*SPP(9) + OP_l_11_c_1_r_*SPP(23) + OP_l_14_c_1_r_*SPP(18)) - SPP(4)*(OP_l_2_c_2_r_*SPP(7) - OP_l_1_c_2_r_*SPP(3) - OP_l_3_c_2_r_*SPP(9) + OP_l_11_c_2_r_*SPP(23) + OP_l_14_c_2_r_*SPP(18)) + SPP(14)*(OP_l_2_c_3_r_*SPP(7) - OP_l_1_c_3_r_*SPP(3) - OP_l_3_c_3_r_*SPP(9) + OP_l_11_c_3_r_*SPP(23) + OP_l_14_c_3_r_*SPP(18)) + SPP(23)*(OP_l_2_c_12_r_*SPP(7) - OP_l_1_c_12_r_*SPP(3) - OP_l_3_c_12_r_*SPP(9) + OP_l_11_c_12_r_*SPP(23) + OP_l_14_c_12_r_*SPP(18)) + SPP(17)*(OP_l_2_c_15_r_*SPP(7) - OP_l_1_c_15_r_*SPP(3) - OP_l_3_c_15_r_*SPP(9) + OP_l_11_c_15_r_*SPP(23) + OP_l_14_c_15_r_*SPP(18)); -nextP(3,3) = SPP(15)*(OP_l_1_c_1_r_*SPP(15) - OP_l_2_c_1_r_*SPP(4) + OP_l_3_c_1_r_*SPP(14) + OP_l_12_c_1_r_*SPP(23) + OP_l_15_c_1_r_*SPP(17)) - SPP(4)*(OP_l_1_c_2_r_*SPP(15) - OP_l_2_c_2_r_*SPP(4) + OP_l_3_c_2_r_*SPP(14) + OP_l_12_c_2_r_*SPP(23) + OP_l_15_c_2_r_*SPP(17)) + SPP(14)*(OP_l_1_c_3_r_*SPP(15) - OP_l_2_c_3_r_*SPP(4) + OP_l_3_c_3_r_*SPP(14) + OP_l_12_c_3_r_*SPP(23) + OP_l_15_c_3_r_*SPP(17)) + SPP(23)*(OP_l_1_c_12_r_*SPP(15) - OP_l_2_c_12_r_*SPP(4) + OP_l_3_c_12_r_*SPP(14) + OP_l_12_c_12_r_*SPP(23) + OP_l_15_c_12_r_*SPP(17)) + SPP(17)*(OP_l_1_c_15_r_*SPP(15) - OP_l_2_c_15_r_*SPP(4) + OP_l_3_c_15_r_*SPP(14) + OP_l_12_c_15_r_*SPP(23) + OP_l_15_c_15_r_*SPP(17)) + dazNoise^2*SQ(4); -nextP(1,4) = OP_l_1_c_4_r_*SPP(6) - OP_l_2_c_4_r_*SPP(5) + OP_l_3_c_4_r_*SPP(8) + OP_l_10_c_4_r_*SPP(23) + OP_l_13_c_4_r_*SPP(19) + SPP(2)*(OP_l_1_c_1_r_*SPP(6) - OP_l_2_c_1_r_*SPP(5) + OP_l_3_c_1_r_*SPP(8) + OP_l_10_c_1_r_*SPP(23) + OP_l_13_c_1_r_*SPP(19)) + SPP(20)*(OP_l_1_c_2_r_*SPP(6) - OP_l_2_c_2_r_*SPP(5) + OP_l_3_c_2_r_*SPP(8) + OP_l_10_c_2_r_*SPP(23) + OP_l_13_c_2_r_*SPP(19)) + SPP(16)*(OP_l_1_c_3_r_*SPP(6) - OP_l_2_c_3_r_*SPP(5) + OP_l_3_c_3_r_*SPP(8) + OP_l_10_c_3_r_*SPP(23) + OP_l_13_c_3_r_*SPP(19)) - SPP(22)*(OP_l_1_c_16_r_*SPP(6) - OP_l_2_c_16_r_*SPP(5) + OP_l_3_c_16_r_*SPP(8) + OP_l_10_c_16_r_*SPP(23) + OP_l_13_c_16_r_*SPP(19)); -nextP(2,4) = OP_l_2_c_4_r_*SPP(7) - OP_l_1_c_4_r_*SPP(3) - OP_l_3_c_4_r_*SPP(9) + OP_l_11_c_4_r_*SPP(23) + OP_l_14_c_4_r_*SPP(18) + SPP(2)*(OP_l_2_c_1_r_*SPP(7) - OP_l_1_c_1_r_*SPP(3) - OP_l_3_c_1_r_*SPP(9) + OP_l_11_c_1_r_*SPP(23) + OP_l_14_c_1_r_*SPP(18)) + SPP(20)*(OP_l_2_c_2_r_*SPP(7) - OP_l_1_c_2_r_*SPP(3) - OP_l_3_c_2_r_*SPP(9) + OP_l_11_c_2_r_*SPP(23) + OP_l_14_c_2_r_*SPP(18)) + SPP(16)*(OP_l_2_c_3_r_*SPP(7) - OP_l_1_c_3_r_*SPP(3) - OP_l_3_c_3_r_*SPP(9) + OP_l_11_c_3_r_*SPP(23) + OP_l_14_c_3_r_*SPP(18)) - SPP(22)*(OP_l_2_c_16_r_*SPP(7) - OP_l_1_c_16_r_*SPP(3) - OP_l_3_c_16_r_*SPP(9) + OP_l_11_c_16_r_*SPP(23) + OP_l_14_c_16_r_*SPP(18)); -nextP(3,4) = OP_l_1_c_4_r_*SPP(15) - OP_l_2_c_4_r_*SPP(4) + OP_l_3_c_4_r_*SPP(14) + OP_l_12_c_4_r_*SPP(23) + OP_l_15_c_4_r_*SPP(17) + SPP(2)*(OP_l_1_c_1_r_*SPP(15) - OP_l_2_c_1_r_*SPP(4) + OP_l_3_c_1_r_*SPP(14) + OP_l_12_c_1_r_*SPP(23) + OP_l_15_c_1_r_*SPP(17)) + SPP(20)*(OP_l_1_c_2_r_*SPP(15) - OP_l_2_c_2_r_*SPP(4) + OP_l_3_c_2_r_*SPP(14) + OP_l_12_c_2_r_*SPP(23) + OP_l_15_c_2_r_*SPP(17)) + SPP(16)*(OP_l_1_c_3_r_*SPP(15) - OP_l_2_c_3_r_*SPP(4) + OP_l_3_c_3_r_*SPP(14) + OP_l_12_c_3_r_*SPP(23) + OP_l_15_c_3_r_*SPP(17)) - SPP(22)*(OP_l_1_c_16_r_*SPP(15) - OP_l_2_c_16_r_*SPP(4) + OP_l_3_c_16_r_*SPP(14) + OP_l_12_c_16_r_*SPP(23) + OP_l_15_c_16_r_*SPP(17)); -nextP(4,4) = OP_l_4_c_4_r_ + OP_l_1_c_4_r_*SPP(2) + OP_l_2_c_4_r_*SPP(20) + OP_l_3_c_4_r_*SPP(16) - OP_l_16_c_4_r_*SPP(22) + SQ(6)*(SQ(9) + 2*q0*q2)^2 + SQ(5)*(SQ(10) - 2*q0*q3)^2 + SPP(2)*(OP_l_4_c_1_r_ + OP_l_1_c_1_r_*SPP(2) + OP_l_2_c_1_r_*SPP(20) + OP_l_3_c_1_r_*SPP(16) - OP_l_16_c_1_r_*SPP(22)) + SPP(20)*(OP_l_4_c_2_r_ + OP_l_1_c_2_r_*SPP(2) + OP_l_2_c_2_r_*SPP(20) + OP_l_3_c_2_r_*SPP(16) - OP_l_16_c_2_r_*SPP(22)) + SPP(16)*(OP_l_4_c_3_r_ + OP_l_1_c_3_r_*SPP(2) + OP_l_2_c_3_r_*SPP(20) + OP_l_3_c_3_r_*SPP(16) - OP_l_16_c_3_r_*SPP(22)) - SPP(22)*(OP_l_4_c_16_r_ + OP_l_1_c_16_r_*SPP(2) + OP_l_2_c_16_r_*SPP(20) + OP_l_3_c_16_r_*SPP(16) - OP_l_16_c_16_r_*SPP(22)) + SQ(7)*(SG(2) + SG(3) - SG(4) - SG(5))^2; -nextP(1,5) = OP_l_1_c_5_r_*SPP(6) - OP_l_2_c_5_r_*SPP(5) + OP_l_3_c_5_r_*SPP(8) + OP_l_10_c_5_r_*SPP(23) + OP_l_13_c_5_r_*SPP(19) + SF(23)*(OP_l_1_c_16_r_*SPP(6) - OP_l_2_c_16_r_*SPP(5) + OP_l_3_c_16_r_*SPP(8) + OP_l_10_c_16_r_*SPP(23) + OP_l_13_c_16_r_*SPP(19)) + SPP(13)*(OP_l_1_c_2_r_*SPP(6) - OP_l_2_c_2_r_*SPP(5) + OP_l_3_c_2_r_*SPP(8) + OP_l_10_c_2_r_*SPP(23) + OP_l_13_c_2_r_*SPP(19)) + SPP(21)*(OP_l_1_c_1_r_*SPP(6) - OP_l_2_c_1_r_*SPP(5) + OP_l_3_c_1_r_*SPP(8) + OP_l_10_c_1_r_*SPP(23) + OP_l_13_c_1_r_*SPP(19)) + SPP(12)*(OP_l_1_c_3_r_*SPP(6) - OP_l_2_c_3_r_*SPP(5) + OP_l_3_c_3_r_*SPP(8) + OP_l_10_c_3_r_*SPP(23) + OP_l_13_c_3_r_*SPP(19)); -nextP(2,5) = OP_l_2_c_5_r_*SPP(7) - OP_l_1_c_5_r_*SPP(3) - OP_l_3_c_5_r_*SPP(9) + OP_l_11_c_5_r_*SPP(23) + OP_l_14_c_5_r_*SPP(18) + SF(23)*(OP_l_2_c_16_r_*SPP(7) - OP_l_1_c_16_r_*SPP(3) - OP_l_3_c_16_r_*SPP(9) + OP_l_11_c_16_r_*SPP(23) + OP_l_14_c_16_r_*SPP(18)) + SPP(13)*(OP_l_2_c_2_r_*SPP(7) - OP_l_1_c_2_r_*SPP(3) - OP_l_3_c_2_r_*SPP(9) + OP_l_11_c_2_r_*SPP(23) + OP_l_14_c_2_r_*SPP(18)) + SPP(21)*(OP_l_2_c_1_r_*SPP(7) - OP_l_1_c_1_r_*SPP(3) - OP_l_3_c_1_r_*SPP(9) + OP_l_11_c_1_r_*SPP(23) + OP_l_14_c_1_r_*SPP(18)) + SPP(12)*(OP_l_2_c_3_r_*SPP(7) - OP_l_1_c_3_r_*SPP(3) - OP_l_3_c_3_r_*SPP(9) + OP_l_11_c_3_r_*SPP(23) + OP_l_14_c_3_r_*SPP(18)); -nextP(3,5) = OP_l_1_c_5_r_*SPP(15) - OP_l_2_c_5_r_*SPP(4) + OP_l_3_c_5_r_*SPP(14) + OP_l_12_c_5_r_*SPP(23) + OP_l_15_c_5_r_*SPP(17) + SF(23)*(OP_l_1_c_16_r_*SPP(15) - OP_l_2_c_16_r_*SPP(4) + OP_l_3_c_16_r_*SPP(14) + OP_l_12_c_16_r_*SPP(23) + OP_l_15_c_16_r_*SPP(17)) + SPP(13)*(OP_l_1_c_2_r_*SPP(15) - OP_l_2_c_2_r_*SPP(4) + OP_l_3_c_2_r_*SPP(14) + OP_l_12_c_2_r_*SPP(23) + OP_l_15_c_2_r_*SPP(17)) + SPP(21)*(OP_l_1_c_1_r_*SPP(15) - OP_l_2_c_1_r_*SPP(4) + OP_l_3_c_1_r_*SPP(14) + OP_l_12_c_1_r_*SPP(23) + OP_l_15_c_1_r_*SPP(17)) + SPP(12)*(OP_l_1_c_3_r_*SPP(15) - OP_l_2_c_3_r_*SPP(4) + OP_l_3_c_3_r_*SPP(14) + OP_l_12_c_3_r_*SPP(23) + OP_l_15_c_3_r_*SPP(17)); -nextP(4,5) = OP_l_4_c_5_r_ + SQ(3) + OP_l_1_c_5_r_*SPP(2) + OP_l_2_c_5_r_*SPP(20) + OP_l_3_c_5_r_*SPP(16) - OP_l_16_c_5_r_*SPP(22) + SF(23)*(OP_l_4_c_16_r_ + OP_l_1_c_16_r_*SPP(2) + OP_l_2_c_16_r_*SPP(20) + OP_l_3_c_16_r_*SPP(16) - OP_l_16_c_16_r_*SPP(22)) + SPP(13)*(OP_l_4_c_2_r_ + OP_l_1_c_2_r_*SPP(2) + OP_l_2_c_2_r_*SPP(20) + OP_l_3_c_2_r_*SPP(16) - OP_l_16_c_2_r_*SPP(22)) + SPP(21)*(OP_l_4_c_1_r_ + OP_l_1_c_1_r_*SPP(2) + OP_l_2_c_1_r_*SPP(20) + OP_l_3_c_1_r_*SPP(16) - OP_l_16_c_1_r_*SPP(22)) + SPP(12)*(OP_l_4_c_3_r_ + OP_l_1_c_3_r_*SPP(2) + OP_l_2_c_3_r_*SPP(20) + OP_l_3_c_3_r_*SPP(16) - OP_l_16_c_3_r_*SPP(22)); -nextP(5,5) = OP_l_5_c_5_r_ + OP_l_16_c_5_r_*SF(23) + OP_l_1_c_5_r_*SPP(21) + OP_l_2_c_5_r_*SPP(13) + OP_l_3_c_5_r_*SPP(12) + SQ(6)*(SQ(8) - 2*q0*q1)^2 + SQ(7)*(SQ(10) + 2*q0*q3)^2 + SF(23)*(OP_l_5_c_16_r_ + OP_l_16_c_16_r_*SF(23) + OP_l_1_c_16_r_*SPP(21) + OP_l_2_c_16_r_*SPP(13) + OP_l_3_c_16_r_*SPP(12)) + SPP(13)*(OP_l_5_c_2_r_ + OP_l_16_c_2_r_*SF(23) + OP_l_1_c_2_r_*SPP(21) + OP_l_2_c_2_r_*SPP(13) + OP_l_3_c_2_r_*SPP(12)) + SPP(21)*(OP_l_5_c_1_r_ + OP_l_16_c_1_r_*SF(23) + OP_l_1_c_1_r_*SPP(21) + OP_l_2_c_1_r_*SPP(13) + OP_l_3_c_1_r_*SPP(12)) + SPP(12)*(OP_l_5_c_3_r_ + OP_l_16_c_3_r_*SF(23) + OP_l_1_c_3_r_*SPP(21) + OP_l_2_c_3_r_*SPP(13) + OP_l_3_c_3_r_*SPP(12)) + SQ(5)*(SG(2) - SG(3) + SG(4) - SG(5))^2; -nextP(1,6) = OP_l_1_c_6_r_*SPP(6) - OP_l_2_c_6_r_*SPP(5) + OP_l_3_c_6_r_*SPP(8) + OP_l_10_c_6_r_*SPP(23) + OP_l_13_c_6_r_*SPP(19) + SF(21)*(OP_l_1_c_16_r_*SPP(6) - OP_l_2_c_16_r_*SPP(5) + OP_l_3_c_16_r_*SPP(8) + OP_l_10_c_16_r_*SPP(23) + OP_l_13_c_16_r_*SPP(19)) - SPP(10)*(OP_l_1_c_1_r_*SPP(6) - OP_l_2_c_1_r_*SPP(5) + OP_l_3_c_1_r_*SPP(8) + OP_l_10_c_1_r_*SPP(23) + OP_l_13_c_1_r_*SPP(19)) + SPP(1)*(OP_l_1_c_3_r_*SPP(6) - OP_l_2_c_3_r_*SPP(5) + OP_l_3_c_3_r_*SPP(8) + OP_l_10_c_3_r_*SPP(23) + OP_l_13_c_3_r_*SPP(19)) + SPP(11)*(OP_l_1_c_2_r_*SPP(6) - OP_l_2_c_2_r_*SPP(5) + OP_l_3_c_2_r_*SPP(8) + OP_l_10_c_2_r_*SPP(23) + OP_l_13_c_2_r_*SPP(19)); -nextP(2,6) = OP_l_2_c_6_r_*SPP(7) - OP_l_1_c_6_r_*SPP(3) - OP_l_3_c_6_r_*SPP(9) + OP_l_11_c_6_r_*SPP(23) + OP_l_14_c_6_r_*SPP(18) + SF(21)*(OP_l_2_c_16_r_*SPP(7) - OP_l_1_c_16_r_*SPP(3) - OP_l_3_c_16_r_*SPP(9) + OP_l_11_c_16_r_*SPP(23) + OP_l_14_c_16_r_*SPP(18)) - SPP(10)*(OP_l_2_c_1_r_*SPP(7) - OP_l_1_c_1_r_*SPP(3) - OP_l_3_c_1_r_*SPP(9) + OP_l_11_c_1_r_*SPP(23) + OP_l_14_c_1_r_*SPP(18)) + SPP(1)*(OP_l_2_c_3_r_*SPP(7) - OP_l_1_c_3_r_*SPP(3) - OP_l_3_c_3_r_*SPP(9) + OP_l_11_c_3_r_*SPP(23) + OP_l_14_c_3_r_*SPP(18)) + SPP(11)*(OP_l_2_c_2_r_*SPP(7) - OP_l_1_c_2_r_*SPP(3) - OP_l_3_c_2_r_*SPP(9) + OP_l_11_c_2_r_*SPP(23) + OP_l_14_c_2_r_*SPP(18)); -nextP(3,6) = OP_l_1_c_6_r_*SPP(15) - OP_l_2_c_6_r_*SPP(4) + OP_l_3_c_6_r_*SPP(14) + OP_l_12_c_6_r_*SPP(23) + OP_l_15_c_6_r_*SPP(17) + SF(21)*(OP_l_1_c_16_r_*SPP(15) - OP_l_2_c_16_r_*SPP(4) + OP_l_3_c_16_r_*SPP(14) + OP_l_12_c_16_r_*SPP(23) + OP_l_15_c_16_r_*SPP(17)) - SPP(10)*(OP_l_1_c_1_r_*SPP(15) - OP_l_2_c_1_r_*SPP(4) + OP_l_3_c_1_r_*SPP(14) + OP_l_12_c_1_r_*SPP(23) + OP_l_15_c_1_r_*SPP(17)) + SPP(1)*(OP_l_1_c_3_r_*SPP(15) - OP_l_2_c_3_r_*SPP(4) + OP_l_3_c_3_r_*SPP(14) + OP_l_12_c_3_r_*SPP(23) + OP_l_15_c_3_r_*SPP(17)) + SPP(11)*(OP_l_1_c_2_r_*SPP(15) - OP_l_2_c_2_r_*SPP(4) + OP_l_3_c_2_r_*SPP(14) + OP_l_12_c_2_r_*SPP(23) + OP_l_15_c_2_r_*SPP(17)); -nextP(4,6) = OP_l_4_c_6_r_ + SQ(2) + OP_l_1_c_6_r_*SPP(2) + OP_l_2_c_6_r_*SPP(20) + OP_l_3_c_6_r_*SPP(16) - OP_l_16_c_6_r_*SPP(22) + SF(21)*(OP_l_4_c_16_r_ + OP_l_1_c_16_r_*SPP(2) + OP_l_2_c_16_r_*SPP(20) + OP_l_3_c_16_r_*SPP(16) - OP_l_16_c_16_r_*SPP(22)) - SPP(10)*(OP_l_4_c_1_r_ + OP_l_1_c_1_r_*SPP(2) + OP_l_2_c_1_r_*SPP(20) + OP_l_3_c_1_r_*SPP(16) - OP_l_16_c_1_r_*SPP(22)) + SPP(1)*(OP_l_4_c_3_r_ + OP_l_1_c_3_r_*SPP(2) + OP_l_2_c_3_r_*SPP(20) + OP_l_3_c_3_r_*SPP(16) - OP_l_16_c_3_r_*SPP(22)) + SPP(11)*(OP_l_4_c_2_r_ + OP_l_1_c_2_r_*SPP(2) + OP_l_2_c_2_r_*SPP(20) + OP_l_3_c_2_r_*SPP(16) - OP_l_16_c_2_r_*SPP(22)); -nextP(5,6) = OP_l_5_c_6_r_ + SQ(1) + OP_l_16_c_6_r_*SF(23) + OP_l_1_c_6_r_*SPP(21) + OP_l_2_c_6_r_*SPP(13) + OP_l_3_c_6_r_*SPP(12) + SF(21)*(OP_l_5_c_16_r_ + OP_l_16_c_16_r_*SF(23) + OP_l_1_c_16_r_*SPP(21) + OP_l_2_c_16_r_*SPP(13) + OP_l_3_c_16_r_*SPP(12)) - SPP(10)*(OP_l_5_c_1_r_ + OP_l_16_c_1_r_*SF(23) + OP_l_1_c_1_r_*SPP(21) + OP_l_2_c_1_r_*SPP(13) + OP_l_3_c_1_r_*SPP(12)) + SPP(1)*(OP_l_5_c_3_r_ + OP_l_16_c_3_r_*SF(23) + OP_l_1_c_3_r_*SPP(21) + OP_l_2_c_3_r_*SPP(13) + OP_l_3_c_3_r_*SPP(12)) + SPP(11)*(OP_l_5_c_2_r_ + OP_l_16_c_2_r_*SF(23) + OP_l_1_c_2_r_*SPP(21) + OP_l_2_c_2_r_*SPP(13) + OP_l_3_c_2_r_*SPP(12)); -nextP(6,6) = OP_l_6_c_6_r_ + OP_l_16_c_6_r_*SF(21) - OP_l_1_c_6_r_*SPP(10) + OP_l_2_c_6_r_*SPP(11) + OP_l_3_c_6_r_*SPP(1) + SQ(5)*(SQ(8) + 2*q0*q1)^2 + SQ(7)*(SQ(9) - 2*q0*q2)^2 + SF(21)*(OP_l_6_c_16_r_ + OP_l_16_c_16_r_*SF(21) - OP_l_1_c_16_r_*SPP(10) + OP_l_2_c_16_r_*SPP(11) + OP_l_3_c_16_r_*SPP(1)) - SPP(10)*(OP_l_6_c_1_r_ + OP_l_16_c_1_r_*SF(21) - OP_l_1_c_1_r_*SPP(10) + OP_l_2_c_1_r_*SPP(11) + OP_l_3_c_1_r_*SPP(1)) + SPP(1)*(OP_l_6_c_3_r_ + OP_l_16_c_3_r_*SF(21) - OP_l_1_c_3_r_*SPP(10) + OP_l_2_c_3_r_*SPP(11) + OP_l_3_c_3_r_*SPP(1)) + SPP(11)*(OP_l_6_c_2_r_ + OP_l_16_c_2_r_*SF(21) - OP_l_1_c_2_r_*SPP(10) + OP_l_2_c_2_r_*SPP(11) + OP_l_3_c_2_r_*SPP(1)) + SQ(6)*(SG(2) - SG(3) - SG(4) + SG(5))^2; -nextP(1,7) = OP_l_1_c_7_r_*SPP(6) - OP_l_2_c_7_r_*SPP(5) + OP_l_3_c_7_r_*SPP(8) + OP_l_10_c_7_r_*SPP(23) + OP_l_13_c_7_r_*SPP(19) + dt*(OP_l_1_c_4_r_*SPP(6) - OP_l_2_c_4_r_*SPP(5) + OP_l_3_c_4_r_*SPP(8) + OP_l_10_c_4_r_*SPP(23) + OP_l_13_c_4_r_*SPP(19)); -nextP(2,7) = OP_l_2_c_7_r_*SPP(7) - OP_l_1_c_7_r_*SPP(3) - OP_l_3_c_7_r_*SPP(9) + OP_l_11_c_7_r_*SPP(23) + OP_l_14_c_7_r_*SPP(18) + dt*(OP_l_2_c_4_r_*SPP(7) - OP_l_1_c_4_r_*SPP(3) - OP_l_3_c_4_r_*SPP(9) + OP_l_11_c_4_r_*SPP(23) + OP_l_14_c_4_r_*SPP(18)); -nextP(3,7) = OP_l_1_c_7_r_*SPP(15) - OP_l_2_c_7_r_*SPP(4) + OP_l_3_c_7_r_*SPP(14) + OP_l_12_c_7_r_*SPP(23) + OP_l_15_c_7_r_*SPP(17) + dt*(OP_l_1_c_4_r_*SPP(15) - OP_l_2_c_4_r_*SPP(4) + OP_l_3_c_4_r_*SPP(14) + OP_l_12_c_4_r_*SPP(23) + OP_l_15_c_4_r_*SPP(17)); -nextP(4,7) = OP_l_4_c_7_r_ + OP_l_1_c_7_r_*SPP(2) + OP_l_2_c_7_r_*SPP(20) + OP_l_3_c_7_r_*SPP(16) - OP_l_16_c_7_r_*SPP(22) + dt*(OP_l_4_c_4_r_ + OP_l_1_c_4_r_*SPP(2) + OP_l_2_c_4_r_*SPP(20) + OP_l_3_c_4_r_*SPP(16) - OP_l_16_c_4_r_*SPP(22)); -nextP(5,7) = OP_l_5_c_7_r_ + OP_l_16_c_7_r_*SF(23) + OP_l_1_c_7_r_*SPP(21) + OP_l_2_c_7_r_*SPP(13) + OP_l_3_c_7_r_*SPP(12) + dt*(OP_l_5_c_4_r_ + OP_l_16_c_4_r_*SF(23) + OP_l_1_c_4_r_*SPP(21) + OP_l_2_c_4_r_*SPP(13) + OP_l_3_c_4_r_*SPP(12)); -nextP(6,7) = OP_l_6_c_7_r_ + OP_l_16_c_7_r_*SF(21) - OP_l_1_c_7_r_*SPP(10) + OP_l_2_c_7_r_*SPP(11) + OP_l_3_c_7_r_*SPP(1) + dt*(OP_l_6_c_4_r_ + OP_l_16_c_4_r_*SF(21) - OP_l_1_c_4_r_*SPP(10) + OP_l_2_c_4_r_*SPP(11) + OP_l_3_c_4_r_*SPP(1)); -nextP(7,7) = OP_l_7_c_7_r_ + OP_l_4_c_7_r_*dt + dt*(OP_l_7_c_4_r_ + OP_l_4_c_4_r_*dt); -nextP(1,8) = OP_l_1_c_8_r_*SPP(6) - OP_l_2_c_8_r_*SPP(5) + OP_l_3_c_8_r_*SPP(8) + OP_l_10_c_8_r_*SPP(23) + OP_l_13_c_8_r_*SPP(19) + dt*(OP_l_1_c_5_r_*SPP(6) - OP_l_2_c_5_r_*SPP(5) + OP_l_3_c_5_r_*SPP(8) + OP_l_10_c_5_r_*SPP(23) + OP_l_13_c_5_r_*SPP(19)); -nextP(2,8) = OP_l_2_c_8_r_*SPP(7) - OP_l_1_c_8_r_*SPP(3) - OP_l_3_c_8_r_*SPP(9) + OP_l_11_c_8_r_*SPP(23) + OP_l_14_c_8_r_*SPP(18) + dt*(OP_l_2_c_5_r_*SPP(7) - OP_l_1_c_5_r_*SPP(3) - OP_l_3_c_5_r_*SPP(9) + OP_l_11_c_5_r_*SPP(23) + OP_l_14_c_5_r_*SPP(18)); -nextP(3,8) = OP_l_1_c_8_r_*SPP(15) - OP_l_2_c_8_r_*SPP(4) + OP_l_3_c_8_r_*SPP(14) + OP_l_12_c_8_r_*SPP(23) + OP_l_15_c_8_r_*SPP(17) + dt*(OP_l_1_c_5_r_*SPP(15) - OP_l_2_c_5_r_*SPP(4) + OP_l_3_c_5_r_*SPP(14) + OP_l_12_c_5_r_*SPP(23) + OP_l_15_c_5_r_*SPP(17)); -nextP(4,8) = OP_l_4_c_8_r_ + OP_l_1_c_8_r_*SPP(2) + OP_l_2_c_8_r_*SPP(20) + OP_l_3_c_8_r_*SPP(16) - OP_l_16_c_8_r_*SPP(22) + dt*(OP_l_4_c_5_r_ + OP_l_1_c_5_r_*SPP(2) + OP_l_2_c_5_r_*SPP(20) + OP_l_3_c_5_r_*SPP(16) - OP_l_16_c_5_r_*SPP(22)); -nextP(5,8) = OP_l_5_c_8_r_ + OP_l_16_c_8_r_*SF(23) + OP_l_1_c_8_r_*SPP(21) + OP_l_2_c_8_r_*SPP(13) + OP_l_3_c_8_r_*SPP(12) + dt*(OP_l_5_c_5_r_ + OP_l_16_c_5_r_*SF(23) + OP_l_1_c_5_r_*SPP(21) + OP_l_2_c_5_r_*SPP(13) + OP_l_3_c_5_r_*SPP(12)); -nextP(6,8) = OP_l_6_c_8_r_ + OP_l_16_c_8_r_*SF(21) - OP_l_1_c_8_r_*SPP(10) + OP_l_2_c_8_r_*SPP(11) + OP_l_3_c_8_r_*SPP(1) + dt*(OP_l_6_c_5_r_ + OP_l_16_c_5_r_*SF(21) - OP_l_1_c_5_r_*SPP(10) + OP_l_2_c_5_r_*SPP(11) + OP_l_3_c_5_r_*SPP(1)); -nextP(7,8) = OP_l_7_c_8_r_ + OP_l_4_c_8_r_*dt + dt*(OP_l_7_c_5_r_ + OP_l_4_c_5_r_*dt); +nextP(1,1) = OP_l_1_c_1_r_ + OP_l_2_c_1_r_*SF(10) + OP_l_3_c_1_r_*SF(12) + OP_l_4_c_1_r_*SF(11) + OP_l_11_c_1_r_*SF(15) + OP_l_12_c_1_r_*SF(16) + OP_l_13_c_1_r_*SPP(11) + (daxVar*SQ(11))/4 + SF(10)*(OP_l_1_c_2_r_ + OP_l_2_c_2_r_*SF(10) + OP_l_3_c_2_r_*SF(12) + OP_l_4_c_2_r_*SF(11) + OP_l_11_c_2_r_*SF(15) + OP_l_12_c_2_r_*SF(16) + OP_l_13_c_2_r_*SPP(11)) + SF(12)*(OP_l_1_c_3_r_ + OP_l_2_c_3_r_*SF(10) + OP_l_3_c_3_r_*SF(12) + OP_l_4_c_3_r_*SF(11) + OP_l_11_c_3_r_*SF(15) + OP_l_12_c_3_r_*SF(16) + OP_l_13_c_3_r_*SPP(11)) + SF(11)*(OP_l_1_c_4_r_ + OP_l_2_c_4_r_*SF(10) + OP_l_3_c_4_r_*SF(12) + OP_l_4_c_4_r_*SF(11) + OP_l_11_c_4_r_*SF(15) + OP_l_12_c_4_r_*SF(16) + OP_l_13_c_4_r_*SPP(11)) + SF(15)*(OP_l_1_c_11_r_ + OP_l_2_c_11_r_*SF(10) + OP_l_3_c_11_r_*SF(12) + OP_l_4_c_11_r_*SF(11) + OP_l_11_c_11_r_*SF(15) + OP_l_12_c_11_r_*SF(16) + OP_l_13_c_11_r_*SPP(11)) + SF(16)*(OP_l_1_c_12_r_ + OP_l_2_c_12_r_*SF(10) + OP_l_3_c_12_r_*SF(12) + OP_l_4_c_12_r_*SF(11) + OP_l_11_c_12_r_*SF(15) + OP_l_12_c_12_r_*SF(16) + OP_l_13_c_12_r_*SPP(11)) + SPP(11)*(OP_l_1_c_13_r_ + OP_l_2_c_13_r_*SF(10) + OP_l_3_c_13_r_*SF(12) + OP_l_4_c_13_r_*SF(11) + OP_l_11_c_13_r_*SF(15) + OP_l_12_c_13_r_*SF(16) + OP_l_13_c_13_r_*SPP(11)) + (dayVar*q2^2)/4 + (dazVar*q3^2)/4; +nextP(1,2) = OP_l_1_c_2_r_ + SQ(9) + OP_l_2_c_2_r_*SF(10) + OP_l_3_c_2_r_*SF(12) + OP_l_4_c_2_r_*SF(11) + OP_l_11_c_2_r_*SF(15) + OP_l_12_c_2_r_*SF(16) + OP_l_13_c_2_r_*SPP(11) + SF(9)*(OP_l_1_c_1_r_ + OP_l_2_c_1_r_*SF(10) + OP_l_3_c_1_r_*SF(12) + OP_l_4_c_1_r_*SF(11) + OP_l_11_c_1_r_*SF(15) + OP_l_12_c_1_r_*SF(16) + OP_l_13_c_1_r_*SPP(11)) + SF(8)*(OP_l_1_c_3_r_ + OP_l_2_c_3_r_*SF(10) + OP_l_3_c_3_r_*SF(12) + OP_l_4_c_3_r_*SF(11) + OP_l_11_c_3_r_*SF(15) + OP_l_12_c_3_r_*SF(16) + OP_l_13_c_3_r_*SPP(11)) + SF(12)*(OP_l_1_c_4_r_ + OP_l_2_c_4_r_*SF(10) + OP_l_3_c_4_r_*SF(12) + OP_l_4_c_4_r_*SF(11) + OP_l_11_c_4_r_*SF(15) + OP_l_12_c_4_r_*SF(16) + OP_l_13_c_4_r_*SPP(11)) - SF(16)*(OP_l_1_c_13_r_ + OP_l_2_c_13_r_*SF(10) + OP_l_3_c_13_r_*SF(12) + OP_l_4_c_13_r_*SF(11) + OP_l_11_c_13_r_*SF(15) + OP_l_12_c_13_r_*SF(16) + OP_l_13_c_13_r_*SPP(11)) + SPP(11)*(OP_l_1_c_12_r_ + OP_l_2_c_12_r_*SF(10) + OP_l_3_c_12_r_*SF(12) + OP_l_4_c_12_r_*SF(11) + OP_l_11_c_12_r_*SF(15) + OP_l_12_c_12_r_*SF(16) + OP_l_13_c_12_r_*SPP(11)) - (q0*(OP_l_1_c_11_r_ + OP_l_2_c_11_r_*SF(10) + OP_l_3_c_11_r_*SF(12) + OP_l_4_c_11_r_*SF(11) + OP_l_11_c_11_r_*SF(15) + OP_l_12_c_11_r_*SF(16) + OP_l_13_c_11_r_*SPP(11)))/2; +nextP(2,2) = OP_l_2_c_2_r_ + OP_l_1_c_2_r_*SF(9) + OP_l_3_c_2_r_*SF(8) + OP_l_4_c_2_r_*SF(12) - OP_l_13_c_2_r_*SF(16) + OP_l_12_c_2_r_*SPP(11) + daxVar*SQ(10) - (OP_l_11_c_2_r_*q0)/2 + SF(9)*(OP_l_2_c_1_r_ + OP_l_1_c_1_r_*SF(9) + OP_l_3_c_1_r_*SF(8) + OP_l_4_c_1_r_*SF(12) - OP_l_13_c_1_r_*SF(16) + OP_l_12_c_1_r_*SPP(11) - (OP_l_11_c_1_r_*q0)/2) + SF(8)*(OP_l_2_c_3_r_ + OP_l_1_c_3_r_*SF(9) + OP_l_3_c_3_r_*SF(8) + OP_l_4_c_3_r_*SF(12) - OP_l_13_c_3_r_*SF(16) + OP_l_12_c_3_r_*SPP(11) - (OP_l_11_c_3_r_*q0)/2) + SF(12)*(OP_l_2_c_4_r_ + OP_l_1_c_4_r_*SF(9) + OP_l_3_c_4_r_*SF(8) + OP_l_4_c_4_r_*SF(12) - OP_l_13_c_4_r_*SF(16) + OP_l_12_c_4_r_*SPP(11) - (OP_l_11_c_4_r_*q0)/2) - SF(16)*(OP_l_2_c_13_r_ + OP_l_1_c_13_r_*SF(9) + OP_l_3_c_13_r_*SF(8) + OP_l_4_c_13_r_*SF(12) - OP_l_13_c_13_r_*SF(16) + OP_l_12_c_13_r_*SPP(11) - (OP_l_11_c_13_r_*q0)/2) + SPP(11)*(OP_l_2_c_12_r_ + OP_l_1_c_12_r_*SF(9) + OP_l_3_c_12_r_*SF(8) + OP_l_4_c_12_r_*SF(12) - OP_l_13_c_12_r_*SF(16) + OP_l_12_c_12_r_*SPP(11) - (OP_l_11_c_12_r_*q0)/2) + (dayVar*q3^2)/4 + (dazVar*q2^2)/4 - (q0*(OP_l_2_c_11_r_ + OP_l_1_c_11_r_*SF(9) + OP_l_3_c_11_r_*SF(8) + OP_l_4_c_11_r_*SF(12) - OP_l_13_c_11_r_*SF(16) + OP_l_12_c_11_r_*SPP(11) - (OP_l_11_c_11_r_*q0)/2))/2; +nextP(1,3) = OP_l_1_c_3_r_ + SQ(8) + OP_l_2_c_3_r_*SF(10) + OP_l_3_c_3_r_*SF(12) + OP_l_4_c_3_r_*SF(11) + OP_l_11_c_3_r_*SF(15) + OP_l_12_c_3_r_*SF(16) + OP_l_13_c_3_r_*SPP(11) + SF(7)*(OP_l_1_c_1_r_ + OP_l_2_c_1_r_*SF(10) + OP_l_3_c_1_r_*SF(12) + OP_l_4_c_1_r_*SF(11) + OP_l_11_c_1_r_*SF(15) + OP_l_12_c_1_r_*SF(16) + OP_l_13_c_1_r_*SPP(11)) + SF(11)*(OP_l_1_c_2_r_ + OP_l_2_c_2_r_*SF(10) + OP_l_3_c_2_r_*SF(12) + OP_l_4_c_2_r_*SF(11) + OP_l_11_c_2_r_*SF(15) + OP_l_12_c_2_r_*SF(16) + OP_l_13_c_2_r_*SPP(11)) + SF(9)*(OP_l_1_c_4_r_ + OP_l_2_c_4_r_*SF(10) + OP_l_3_c_4_r_*SF(12) + OP_l_4_c_4_r_*SF(11) + OP_l_11_c_4_r_*SF(15) + OP_l_12_c_4_r_*SF(16) + OP_l_13_c_4_r_*SPP(11)) + SF(15)*(OP_l_1_c_13_r_ + OP_l_2_c_13_r_*SF(10) + OP_l_3_c_13_r_*SF(12) + OP_l_4_c_13_r_*SF(11) + OP_l_11_c_13_r_*SF(15) + OP_l_12_c_13_r_*SF(16) + OP_l_13_c_13_r_*SPP(11)) - SPP(11)*(OP_l_1_c_11_r_ + OP_l_2_c_11_r_*SF(10) + OP_l_3_c_11_r_*SF(12) + OP_l_4_c_11_r_*SF(11) + OP_l_11_c_11_r_*SF(15) + OP_l_12_c_11_r_*SF(16) + OP_l_13_c_11_r_*SPP(11)) - (q0*(OP_l_1_c_12_r_ + OP_l_2_c_12_r_*SF(10) + OP_l_3_c_12_r_*SF(12) + OP_l_4_c_12_r_*SF(11) + OP_l_11_c_12_r_*SF(15) + OP_l_12_c_12_r_*SF(16) + OP_l_13_c_12_r_*SPP(11)))/2; +nextP(2,3) = OP_l_2_c_3_r_ + SQ(6) + OP_l_1_c_3_r_*SF(9) + OP_l_3_c_3_r_*SF(8) + OP_l_4_c_3_r_*SF(12) - OP_l_13_c_3_r_*SF(16) + OP_l_12_c_3_r_*SPP(11) - (OP_l_11_c_3_r_*q0)/2 + SF(7)*(OP_l_2_c_1_r_ + OP_l_1_c_1_r_*SF(9) + OP_l_3_c_1_r_*SF(8) + OP_l_4_c_1_r_*SF(12) - OP_l_13_c_1_r_*SF(16) + OP_l_12_c_1_r_*SPP(11) - (OP_l_11_c_1_r_*q0)/2) + SF(11)*(OP_l_2_c_2_r_ + OP_l_1_c_2_r_*SF(9) + OP_l_3_c_2_r_*SF(8) + OP_l_4_c_2_r_*SF(12) - OP_l_13_c_2_r_*SF(16) + OP_l_12_c_2_r_*SPP(11) - (OP_l_11_c_2_r_*q0)/2) + SF(9)*(OP_l_2_c_4_r_ + OP_l_1_c_4_r_*SF(9) + OP_l_3_c_4_r_*SF(8) + OP_l_4_c_4_r_*SF(12) - OP_l_13_c_4_r_*SF(16) + OP_l_12_c_4_r_*SPP(11) - (OP_l_11_c_4_r_*q0)/2) + SF(15)*(OP_l_2_c_13_r_ + OP_l_1_c_13_r_*SF(9) + OP_l_3_c_13_r_*SF(8) + OP_l_4_c_13_r_*SF(12) - OP_l_13_c_13_r_*SF(16) + OP_l_12_c_13_r_*SPP(11) - (OP_l_11_c_13_r_*q0)/2) - SPP(11)*(OP_l_2_c_11_r_ + OP_l_1_c_11_r_*SF(9) + OP_l_3_c_11_r_*SF(8) + OP_l_4_c_11_r_*SF(12) - OP_l_13_c_11_r_*SF(16) + OP_l_12_c_11_r_*SPP(11) - (OP_l_11_c_11_r_*q0)/2) - (q0*(OP_l_2_c_12_r_ + OP_l_1_c_12_r_*SF(9) + OP_l_3_c_12_r_*SF(8) + OP_l_4_c_12_r_*SF(12) - OP_l_13_c_12_r_*SF(16) + OP_l_12_c_12_r_*SPP(11) - (OP_l_11_c_12_r_*q0)/2))/2; +nextP(3,3) = OP_l_3_c_3_r_ + OP_l_1_c_3_r_*SF(7) + OP_l_2_c_3_r_*SF(11) + OP_l_4_c_3_r_*SF(9) + OP_l_13_c_3_r_*SF(15) - OP_l_11_c_3_r_*SPP(11) + dayVar*SQ(10) + (dazVar*SQ(11))/4 - (OP_l_12_c_3_r_*q0)/2 + SF(7)*(OP_l_3_c_1_r_ + OP_l_1_c_1_r_*SF(7) + OP_l_2_c_1_r_*SF(11) + OP_l_4_c_1_r_*SF(9) + OP_l_13_c_1_r_*SF(15) - OP_l_11_c_1_r_*SPP(11) - (OP_l_12_c_1_r_*q0)/2) + SF(11)*(OP_l_3_c_2_r_ + OP_l_1_c_2_r_*SF(7) + OP_l_2_c_2_r_*SF(11) + OP_l_4_c_2_r_*SF(9) + OP_l_13_c_2_r_*SF(15) - OP_l_11_c_2_r_*SPP(11) - (OP_l_12_c_2_r_*q0)/2) + SF(9)*(OP_l_3_c_4_r_ + OP_l_1_c_4_r_*SF(7) + OP_l_2_c_4_r_*SF(11) + OP_l_4_c_4_r_*SF(9) + OP_l_13_c_4_r_*SF(15) - OP_l_11_c_4_r_*SPP(11) - (OP_l_12_c_4_r_*q0)/2) + SF(15)*(OP_l_3_c_13_r_ + OP_l_1_c_13_r_*SF(7) + OP_l_2_c_13_r_*SF(11) + OP_l_4_c_13_r_*SF(9) + OP_l_13_c_13_r_*SF(15) - OP_l_11_c_13_r_*SPP(11) - (OP_l_12_c_13_r_*q0)/2) - SPP(11)*(OP_l_3_c_11_r_ + OP_l_1_c_11_r_*SF(7) + OP_l_2_c_11_r_*SF(11) + OP_l_4_c_11_r_*SF(9) + OP_l_13_c_11_r_*SF(15) - OP_l_11_c_11_r_*SPP(11) - (OP_l_12_c_11_r_*q0)/2) + (daxVar*q3^2)/4 - (q0*(OP_l_3_c_12_r_ + OP_l_1_c_12_r_*SF(7) + OP_l_2_c_12_r_*SF(11) + OP_l_4_c_12_r_*SF(9) + OP_l_13_c_12_r_*SF(15) - OP_l_11_c_12_r_*SPP(11) - (OP_l_12_c_12_r_*q0)/2))/2; +nextP(1,4) = OP_l_1_c_4_r_ + SQ(7) + OP_l_2_c_4_r_*SF(10) + OP_l_3_c_4_r_*SF(12) + OP_l_4_c_4_r_*SF(11) + OP_l_11_c_4_r_*SF(15) + OP_l_12_c_4_r_*SF(16) + OP_l_13_c_4_r_*SPP(11) + SF(8)*(OP_l_1_c_1_r_ + OP_l_2_c_1_r_*SF(10) + OP_l_3_c_1_r_*SF(12) + OP_l_4_c_1_r_*SF(11) + OP_l_11_c_1_r_*SF(15) + OP_l_12_c_1_r_*SF(16) + OP_l_13_c_1_r_*SPP(11)) + SF(7)*(OP_l_1_c_2_r_ + OP_l_2_c_2_r_*SF(10) + OP_l_3_c_2_r_*SF(12) + OP_l_4_c_2_r_*SF(11) + OP_l_11_c_2_r_*SF(15) + OP_l_12_c_2_r_*SF(16) + OP_l_13_c_2_r_*SPP(11)) + SF(10)*(OP_l_1_c_3_r_ + OP_l_2_c_3_r_*SF(10) + OP_l_3_c_3_r_*SF(12) + OP_l_4_c_3_r_*SF(11) + OP_l_11_c_3_r_*SF(15) + OP_l_12_c_3_r_*SF(16) + OP_l_13_c_3_r_*SPP(11)) + SF(16)*(OP_l_1_c_11_r_ + OP_l_2_c_11_r_*SF(10) + OP_l_3_c_11_r_*SF(12) + OP_l_4_c_11_r_*SF(11) + OP_l_11_c_11_r_*SF(15) + OP_l_12_c_11_r_*SF(16) + OP_l_13_c_11_r_*SPP(11)) - SF(15)*(OP_l_1_c_12_r_ + OP_l_2_c_12_r_*SF(10) + OP_l_3_c_12_r_*SF(12) + OP_l_4_c_12_r_*SF(11) + OP_l_11_c_12_r_*SF(15) + OP_l_12_c_12_r_*SF(16) + OP_l_13_c_12_r_*SPP(11)) - (q0*(OP_l_1_c_13_r_ + OP_l_2_c_13_r_*SF(10) + OP_l_3_c_13_r_*SF(12) + OP_l_4_c_13_r_*SF(11) + OP_l_11_c_13_r_*SF(15) + OP_l_12_c_13_r_*SF(16) + OP_l_13_c_13_r_*SPP(11)))/2; +nextP(2,4) = OP_l_2_c_4_r_ + SQ(5) + OP_l_1_c_4_r_*SF(9) + OP_l_3_c_4_r_*SF(8) + OP_l_4_c_4_r_*SF(12) - OP_l_13_c_4_r_*SF(16) + OP_l_12_c_4_r_*SPP(11) - (OP_l_11_c_4_r_*q0)/2 + SF(8)*(OP_l_2_c_1_r_ + OP_l_1_c_1_r_*SF(9) + OP_l_3_c_1_r_*SF(8) + OP_l_4_c_1_r_*SF(12) - OP_l_13_c_1_r_*SF(16) + OP_l_12_c_1_r_*SPP(11) - (OP_l_11_c_1_r_*q0)/2) + SF(7)*(OP_l_2_c_2_r_ + OP_l_1_c_2_r_*SF(9) + OP_l_3_c_2_r_*SF(8) + OP_l_4_c_2_r_*SF(12) - OP_l_13_c_2_r_*SF(16) + OP_l_12_c_2_r_*SPP(11) - (OP_l_11_c_2_r_*q0)/2) + SF(10)*(OP_l_2_c_3_r_ + OP_l_1_c_3_r_*SF(9) + OP_l_3_c_3_r_*SF(8) + OP_l_4_c_3_r_*SF(12) - OP_l_13_c_3_r_*SF(16) + OP_l_12_c_3_r_*SPP(11) - (OP_l_11_c_3_r_*q0)/2) + SF(16)*(OP_l_2_c_11_r_ + OP_l_1_c_11_r_*SF(9) + OP_l_3_c_11_r_*SF(8) + OP_l_4_c_11_r_*SF(12) - OP_l_13_c_11_r_*SF(16) + OP_l_12_c_11_r_*SPP(11) - (OP_l_11_c_11_r_*q0)/2) - SF(15)*(OP_l_2_c_12_r_ + OP_l_1_c_12_r_*SF(9) + OP_l_3_c_12_r_*SF(8) + OP_l_4_c_12_r_*SF(12) - OP_l_13_c_12_r_*SF(16) + OP_l_12_c_12_r_*SPP(11) - (OP_l_11_c_12_r_*q0)/2) - (q0*(OP_l_2_c_13_r_ + OP_l_1_c_13_r_*SF(9) + OP_l_3_c_13_r_*SF(8) + OP_l_4_c_13_r_*SF(12) - OP_l_13_c_13_r_*SF(16) + OP_l_12_c_13_r_*SPP(11) - (OP_l_11_c_13_r_*q0)/2))/2; +nextP(3,4) = OP_l_3_c_4_r_ + SQ(4) + OP_l_1_c_4_r_*SF(7) + OP_l_2_c_4_r_*SF(11) + OP_l_4_c_4_r_*SF(9) + OP_l_13_c_4_r_*SF(15) - OP_l_11_c_4_r_*SPP(11) - (OP_l_12_c_4_r_*q0)/2 + SF(8)*(OP_l_3_c_1_r_ + OP_l_1_c_1_r_*SF(7) + OP_l_2_c_1_r_*SF(11) + OP_l_4_c_1_r_*SF(9) + OP_l_13_c_1_r_*SF(15) - OP_l_11_c_1_r_*SPP(11) - (OP_l_12_c_1_r_*q0)/2) + SF(7)*(OP_l_3_c_2_r_ + OP_l_1_c_2_r_*SF(7) + OP_l_2_c_2_r_*SF(11) + OP_l_4_c_2_r_*SF(9) + OP_l_13_c_2_r_*SF(15) - OP_l_11_c_2_r_*SPP(11) - (OP_l_12_c_2_r_*q0)/2) + SF(10)*(OP_l_3_c_3_r_ + OP_l_1_c_3_r_*SF(7) + OP_l_2_c_3_r_*SF(11) + OP_l_4_c_3_r_*SF(9) + OP_l_13_c_3_r_*SF(15) - OP_l_11_c_3_r_*SPP(11) - (OP_l_12_c_3_r_*q0)/2) + SF(16)*(OP_l_3_c_11_r_ + OP_l_1_c_11_r_*SF(7) + OP_l_2_c_11_r_*SF(11) + OP_l_4_c_11_r_*SF(9) + OP_l_13_c_11_r_*SF(15) - OP_l_11_c_11_r_*SPP(11) - (OP_l_12_c_11_r_*q0)/2) - SF(15)*(OP_l_3_c_12_r_ + OP_l_1_c_12_r_*SF(7) + OP_l_2_c_12_r_*SF(11) + OP_l_4_c_12_r_*SF(9) + OP_l_13_c_12_r_*SF(15) - OP_l_11_c_12_r_*SPP(11) - (OP_l_12_c_12_r_*q0)/2) - (q0*(OP_l_3_c_13_r_ + OP_l_1_c_13_r_*SF(7) + OP_l_2_c_13_r_*SF(11) + OP_l_4_c_13_r_*SF(9) + OP_l_13_c_13_r_*SF(15) - OP_l_11_c_13_r_*SPP(11) - (OP_l_12_c_13_r_*q0)/2))/2; +nextP(4,4) = OP_l_4_c_4_r_ + OP_l_1_c_4_r_*SF(8) + OP_l_2_c_4_r_*SF(7) + OP_l_3_c_4_r_*SF(10) + OP_l_11_c_4_r_*SF(16) - OP_l_12_c_4_r_*SF(15) + (dayVar*SQ(11))/4 + dazVar*SQ(10) - (OP_l_13_c_4_r_*q0)/2 + SF(8)*(OP_l_4_c_1_r_ + OP_l_1_c_1_r_*SF(8) + OP_l_2_c_1_r_*SF(7) + OP_l_3_c_1_r_*SF(10) + OP_l_11_c_1_r_*SF(16) - OP_l_12_c_1_r_*SF(15) - (OP_l_13_c_1_r_*q0)/2) + SF(7)*(OP_l_4_c_2_r_ + OP_l_1_c_2_r_*SF(8) + OP_l_2_c_2_r_*SF(7) + OP_l_3_c_2_r_*SF(10) + OP_l_11_c_2_r_*SF(16) - OP_l_12_c_2_r_*SF(15) - (OP_l_13_c_2_r_*q0)/2) + SF(10)*(OP_l_4_c_3_r_ + OP_l_1_c_3_r_*SF(8) + OP_l_2_c_3_r_*SF(7) + OP_l_3_c_3_r_*SF(10) + OP_l_11_c_3_r_*SF(16) - OP_l_12_c_3_r_*SF(15) - (OP_l_13_c_3_r_*q0)/2) + SF(16)*(OP_l_4_c_11_r_ + OP_l_1_c_11_r_*SF(8) + OP_l_2_c_11_r_*SF(7) + OP_l_3_c_11_r_*SF(10) + OP_l_11_c_11_r_*SF(16) - OP_l_12_c_11_r_*SF(15) - (OP_l_13_c_11_r_*q0)/2) - SF(15)*(OP_l_4_c_12_r_ + OP_l_1_c_12_r_*SF(8) + OP_l_2_c_12_r_*SF(7) + OP_l_3_c_12_r_*SF(10) + OP_l_11_c_12_r_*SF(16) - OP_l_12_c_12_r_*SF(15) - (OP_l_13_c_12_r_*q0)/2) + (daxVar*q2^2)/4 - (q0*(OP_l_4_c_13_r_ + OP_l_1_c_13_r_*SF(8) + OP_l_2_c_13_r_*SF(7) + OP_l_3_c_13_r_*SF(10) + OP_l_11_c_13_r_*SF(16) - OP_l_12_c_13_r_*SF(15) - (OP_l_13_c_13_r_*q0)/2))/2; +nextP(1,5) = OP_l_1_c_5_r_ + OP_l_2_c_5_r_*SF(10) + OP_l_3_c_5_r_*SF(12) + OP_l_4_c_5_r_*SF(11) + OP_l_11_c_5_r_*SF(15) + OP_l_12_c_5_r_*SF(16) + OP_l_13_c_5_r_*SPP(11) + SF(6)*(OP_l_1_c_1_r_ + OP_l_2_c_1_r_*SF(10) + OP_l_3_c_1_r_*SF(12) + OP_l_4_c_1_r_*SF(11) + OP_l_11_c_1_r_*SF(15) + OP_l_12_c_1_r_*SF(16) + OP_l_13_c_1_r_*SPP(11)) + SF(4)*(OP_l_1_c_2_r_ + OP_l_2_c_2_r_*SF(10) + OP_l_3_c_2_r_*SF(12) + OP_l_4_c_2_r_*SF(11) + OP_l_11_c_2_r_*SF(15) + OP_l_12_c_2_r_*SF(16) + OP_l_13_c_2_r_*SPP(11)) - SF(5)*(OP_l_1_c_4_r_ + OP_l_2_c_4_r_*SF(10) + OP_l_3_c_4_r_*SF(12) + OP_l_4_c_4_r_*SF(11) + OP_l_11_c_4_r_*SF(15) + OP_l_12_c_4_r_*SF(16) + OP_l_13_c_4_r_*SPP(11)) + SPP(1)*(OP_l_1_c_3_r_ + OP_l_2_c_3_r_*SF(10) + OP_l_3_c_3_r_*SF(12) + OP_l_4_c_3_r_*SF(11) + OP_l_11_c_3_r_*SF(15) + OP_l_12_c_3_r_*SF(16) + OP_l_13_c_3_r_*SPP(11)) + SPP(4)*(OP_l_1_c_14_r_ + OP_l_2_c_14_r_*SF(10) + OP_l_3_c_14_r_*SF(12) + OP_l_4_c_14_r_*SF(11) + OP_l_11_c_14_r_*SF(15) + OP_l_12_c_14_r_*SF(16) + OP_l_13_c_14_r_*SPP(11)) + SPP(7)*(OP_l_1_c_15_r_ + OP_l_2_c_15_r_*SF(10) + OP_l_3_c_15_r_*SF(12) + OP_l_4_c_15_r_*SF(11) + OP_l_11_c_15_r_*SF(15) + OP_l_12_c_15_r_*SF(16) + OP_l_13_c_15_r_*SPP(11)) - SPP(10)*(OP_l_1_c_16_r_ + OP_l_2_c_16_r_*SF(10) + OP_l_3_c_16_r_*SF(12) + OP_l_4_c_16_r_*SF(11) + OP_l_11_c_16_r_*SF(15) + OP_l_12_c_16_r_*SF(16) + OP_l_13_c_16_r_*SPP(11)); +nextP(2,5) = OP_l_2_c_5_r_ + OP_l_1_c_5_r_*SF(9) + OP_l_3_c_5_r_*SF(8) + OP_l_4_c_5_r_*SF(12) - OP_l_13_c_5_r_*SF(16) + OP_l_12_c_5_r_*SPP(11) - (OP_l_11_c_5_r_*q0)/2 + SF(6)*(OP_l_2_c_1_r_ + OP_l_1_c_1_r_*SF(9) + OP_l_3_c_1_r_*SF(8) + OP_l_4_c_1_r_*SF(12) - OP_l_13_c_1_r_*SF(16) + OP_l_12_c_1_r_*SPP(11) - (OP_l_11_c_1_r_*q0)/2) + SF(4)*(OP_l_2_c_2_r_ + OP_l_1_c_2_r_*SF(9) + OP_l_3_c_2_r_*SF(8) + OP_l_4_c_2_r_*SF(12) - OP_l_13_c_2_r_*SF(16) + OP_l_12_c_2_r_*SPP(11) - (OP_l_11_c_2_r_*q0)/2) - SF(5)*(OP_l_2_c_4_r_ + OP_l_1_c_4_r_*SF(9) + OP_l_3_c_4_r_*SF(8) + OP_l_4_c_4_r_*SF(12) - OP_l_13_c_4_r_*SF(16) + OP_l_12_c_4_r_*SPP(11) - (OP_l_11_c_4_r_*q0)/2) + SPP(1)*(OP_l_2_c_3_r_ + OP_l_1_c_3_r_*SF(9) + OP_l_3_c_3_r_*SF(8) + OP_l_4_c_3_r_*SF(12) - OP_l_13_c_3_r_*SF(16) + OP_l_12_c_3_r_*SPP(11) - (OP_l_11_c_3_r_*q0)/2) + SPP(4)*(OP_l_2_c_14_r_ + OP_l_1_c_14_r_*SF(9) + OP_l_3_c_14_r_*SF(8) + OP_l_4_c_14_r_*SF(12) - OP_l_13_c_14_r_*SF(16) + OP_l_12_c_14_r_*SPP(11) - (OP_l_11_c_14_r_*q0)/2) + SPP(7)*(OP_l_2_c_15_r_ + OP_l_1_c_15_r_*SF(9) + OP_l_3_c_15_r_*SF(8) + OP_l_4_c_15_r_*SF(12) - OP_l_13_c_15_r_*SF(16) + OP_l_12_c_15_r_*SPP(11) - (OP_l_11_c_15_r_*q0)/2) - SPP(10)*(OP_l_2_c_16_r_ + OP_l_1_c_16_r_*SF(9) + OP_l_3_c_16_r_*SF(8) + OP_l_4_c_16_r_*SF(12) - OP_l_13_c_16_r_*SF(16) + OP_l_12_c_16_r_*SPP(11) - (OP_l_11_c_16_r_*q0)/2); +nextP(3,5) = OP_l_3_c_5_r_ + OP_l_1_c_5_r_*SF(7) + OP_l_2_c_5_r_*SF(11) + OP_l_4_c_5_r_*SF(9) + OP_l_13_c_5_r_*SF(15) - OP_l_11_c_5_r_*SPP(11) - (OP_l_12_c_5_r_*q0)/2 + SF(6)*(OP_l_3_c_1_r_ + OP_l_1_c_1_r_*SF(7) + OP_l_2_c_1_r_*SF(11) + OP_l_4_c_1_r_*SF(9) + OP_l_13_c_1_r_*SF(15) - OP_l_11_c_1_r_*SPP(11) - (OP_l_12_c_1_r_*q0)/2) + SF(4)*(OP_l_3_c_2_r_ + OP_l_1_c_2_r_*SF(7) + OP_l_2_c_2_r_*SF(11) + OP_l_4_c_2_r_*SF(9) + OP_l_13_c_2_r_*SF(15) - OP_l_11_c_2_r_*SPP(11) - (OP_l_12_c_2_r_*q0)/2) - SF(5)*(OP_l_3_c_4_r_ + OP_l_1_c_4_r_*SF(7) + OP_l_2_c_4_r_*SF(11) + OP_l_4_c_4_r_*SF(9) + OP_l_13_c_4_r_*SF(15) - OP_l_11_c_4_r_*SPP(11) - (OP_l_12_c_4_r_*q0)/2) + SPP(1)*(OP_l_3_c_3_r_ + OP_l_1_c_3_r_*SF(7) + OP_l_2_c_3_r_*SF(11) + OP_l_4_c_3_r_*SF(9) + OP_l_13_c_3_r_*SF(15) - OP_l_11_c_3_r_*SPP(11) - (OP_l_12_c_3_r_*q0)/2) + SPP(4)*(OP_l_3_c_14_r_ + OP_l_1_c_14_r_*SF(7) + OP_l_2_c_14_r_*SF(11) + OP_l_4_c_14_r_*SF(9) + OP_l_13_c_14_r_*SF(15) - OP_l_11_c_14_r_*SPP(11) - (OP_l_12_c_14_r_*q0)/2) + SPP(7)*(OP_l_3_c_15_r_ + OP_l_1_c_15_r_*SF(7) + OP_l_2_c_15_r_*SF(11) + OP_l_4_c_15_r_*SF(9) + OP_l_13_c_15_r_*SF(15) - OP_l_11_c_15_r_*SPP(11) - (OP_l_12_c_15_r_*q0)/2) - SPP(10)*(OP_l_3_c_16_r_ + OP_l_1_c_16_r_*SF(7) + OP_l_2_c_16_r_*SF(11) + OP_l_4_c_16_r_*SF(9) + OP_l_13_c_16_r_*SF(15) - OP_l_11_c_16_r_*SPP(11) - (OP_l_12_c_16_r_*q0)/2); +nextP(4,5) = OP_l_4_c_5_r_ + OP_l_1_c_5_r_*SF(8) + OP_l_2_c_5_r_*SF(7) + OP_l_3_c_5_r_*SF(10) + OP_l_11_c_5_r_*SF(16) - OP_l_12_c_5_r_*SF(15) - (OP_l_13_c_5_r_*q0)/2 + SF(6)*(OP_l_4_c_1_r_ + OP_l_1_c_1_r_*SF(8) + OP_l_2_c_1_r_*SF(7) + OP_l_3_c_1_r_*SF(10) + OP_l_11_c_1_r_*SF(16) - OP_l_12_c_1_r_*SF(15) - (OP_l_13_c_1_r_*q0)/2) + SF(4)*(OP_l_4_c_2_r_ + OP_l_1_c_2_r_*SF(8) + OP_l_2_c_2_r_*SF(7) + OP_l_3_c_2_r_*SF(10) + OP_l_11_c_2_r_*SF(16) - OP_l_12_c_2_r_*SF(15) - (OP_l_13_c_2_r_*q0)/2) - SF(5)*(OP_l_4_c_4_r_ + OP_l_1_c_4_r_*SF(8) + OP_l_2_c_4_r_*SF(7) + OP_l_3_c_4_r_*SF(10) + OP_l_11_c_4_r_*SF(16) - OP_l_12_c_4_r_*SF(15) - (OP_l_13_c_4_r_*q0)/2) + SPP(1)*(OP_l_4_c_3_r_ + OP_l_1_c_3_r_*SF(8) + OP_l_2_c_3_r_*SF(7) + OP_l_3_c_3_r_*SF(10) + OP_l_11_c_3_r_*SF(16) - OP_l_12_c_3_r_*SF(15) - (OP_l_13_c_3_r_*q0)/2) + SPP(4)*(OP_l_4_c_14_r_ + OP_l_1_c_14_r_*SF(8) + OP_l_2_c_14_r_*SF(7) + OP_l_3_c_14_r_*SF(10) + OP_l_11_c_14_r_*SF(16) - OP_l_12_c_14_r_*SF(15) - (OP_l_13_c_14_r_*q0)/2) + SPP(7)*(OP_l_4_c_15_r_ + OP_l_1_c_15_r_*SF(8) + OP_l_2_c_15_r_*SF(7) + OP_l_3_c_15_r_*SF(10) + OP_l_11_c_15_r_*SF(16) - OP_l_12_c_15_r_*SF(15) - (OP_l_13_c_15_r_*q0)/2) - SPP(10)*(OP_l_4_c_16_r_ + OP_l_1_c_16_r_*SF(8) + OP_l_2_c_16_r_*SF(7) + OP_l_3_c_16_r_*SF(10) + OP_l_11_c_16_r_*SF(16) - OP_l_12_c_16_r_*SF(15) - (OP_l_13_c_16_r_*q0)/2); +nextP(5,5) = OP_l_5_c_5_r_ + OP_l_1_c_5_r_*SF(6) + OP_l_2_c_5_r_*SF(4) - OP_l_4_c_5_r_*SF(5) + OP_l_3_c_5_r_*SPP(1) + OP_l_14_c_5_r_*SPP(4) + OP_l_15_c_5_r_*SPP(7) - OP_l_16_c_5_r_*SPP(10) + dvyVar*(SG(8) - 2*q0*q3)^2 + dvzVar*(SG(7) + 2*q0*q2)^2 + SF(6)*(OP_l_5_c_1_r_ + OP_l_1_c_1_r_*SF(6) + OP_l_2_c_1_r_*SF(4) - OP_l_4_c_1_r_*SF(5) + OP_l_3_c_1_r_*SPP(1) + OP_l_14_c_1_r_*SPP(4) + OP_l_15_c_1_r_*SPP(7) - OP_l_16_c_1_r_*SPP(10)) + SF(4)*(OP_l_5_c_2_r_ + OP_l_1_c_2_r_*SF(6) + OP_l_2_c_2_r_*SF(4) - OP_l_4_c_2_r_*SF(5) + OP_l_3_c_2_r_*SPP(1) + OP_l_14_c_2_r_*SPP(4) + OP_l_15_c_2_r_*SPP(7) - OP_l_16_c_2_r_*SPP(10)) - SF(5)*(OP_l_5_c_4_r_ + OP_l_1_c_4_r_*SF(6) + OP_l_2_c_4_r_*SF(4) - OP_l_4_c_4_r_*SF(5) + OP_l_3_c_4_r_*SPP(1) + OP_l_14_c_4_r_*SPP(4) + OP_l_15_c_4_r_*SPP(7) - OP_l_16_c_4_r_*SPP(10)) + SPP(1)*(OP_l_5_c_3_r_ + OP_l_1_c_3_r_*SF(6) + OP_l_2_c_3_r_*SF(4) - OP_l_4_c_3_r_*SF(5) + OP_l_3_c_3_r_*SPP(1) + OP_l_14_c_3_r_*SPP(4) + OP_l_15_c_3_r_*SPP(7) - OP_l_16_c_3_r_*SPP(10)) + SPP(4)*(OP_l_5_c_14_r_ + OP_l_1_c_14_r_*SF(6) + OP_l_2_c_14_r_*SF(4) - OP_l_4_c_14_r_*SF(5) + OP_l_3_c_14_r_*SPP(1) + OP_l_14_c_14_r_*SPP(4) + OP_l_15_c_14_r_*SPP(7) - OP_l_16_c_14_r_*SPP(10)) + SPP(7)*(OP_l_5_c_15_r_ + OP_l_1_c_15_r_*SF(6) + OP_l_2_c_15_r_*SF(4) - OP_l_4_c_15_r_*SF(5) + OP_l_3_c_15_r_*SPP(1) + OP_l_14_c_15_r_*SPP(4) + OP_l_15_c_15_r_*SPP(7) - OP_l_16_c_15_r_*SPP(10)) - SPP(10)*(OP_l_5_c_16_r_ + OP_l_1_c_16_r_*SF(6) + OP_l_2_c_16_r_*SF(4) - OP_l_4_c_16_r_*SF(5) + OP_l_3_c_16_r_*SPP(1) + OP_l_14_c_16_r_*SPP(4) + OP_l_15_c_16_r_*SPP(7) - OP_l_16_c_16_r_*SPP(10)) + dvxVar*(SG(2) + SG(3) - SG(4) - SG(5))^2; +nextP(1,6) = OP_l_1_c_6_r_ + OP_l_2_c_6_r_*SF(10) + OP_l_3_c_6_r_*SF(12) + OP_l_4_c_6_r_*SF(11) + OP_l_11_c_6_r_*SF(15) + OP_l_12_c_6_r_*SF(16) + OP_l_13_c_6_r_*SPP(11) + SF(5)*(OP_l_1_c_1_r_ + OP_l_2_c_1_r_*SF(10) + OP_l_3_c_1_r_*SF(12) + OP_l_4_c_1_r_*SF(11) + OP_l_11_c_1_r_*SF(15) + OP_l_12_c_1_r_*SF(16) + OP_l_13_c_1_r_*SPP(11)) + SF(4)*(OP_l_1_c_3_r_ + OP_l_2_c_3_r_*SF(10) + OP_l_3_c_3_r_*SF(12) + OP_l_4_c_3_r_*SF(11) + OP_l_11_c_3_r_*SF(15) + OP_l_12_c_3_r_*SF(16) + OP_l_13_c_3_r_*SPP(11)) + SF(6)*(OP_l_1_c_4_r_ + OP_l_2_c_4_r_*SF(10) + OP_l_3_c_4_r_*SF(12) + OP_l_4_c_4_r_*SF(11) + OP_l_11_c_4_r_*SF(15) + OP_l_12_c_4_r_*SF(16) + OP_l_13_c_4_r_*SPP(11)) - SPP(1)*(OP_l_1_c_2_r_ + OP_l_2_c_2_r_*SF(10) + OP_l_3_c_2_r_*SF(12) + OP_l_4_c_2_r_*SF(11) + OP_l_11_c_2_r_*SF(15) + OP_l_12_c_2_r_*SF(16) + OP_l_13_c_2_r_*SPP(11)) - SPP(9)*(OP_l_1_c_14_r_ + OP_l_2_c_14_r_*SF(10) + OP_l_3_c_14_r_*SF(12) + OP_l_4_c_14_r_*SF(11) + OP_l_11_c_14_r_*SF(15) + OP_l_12_c_14_r_*SF(16) + OP_l_13_c_14_r_*SPP(11)) + SPP(3)*(OP_l_1_c_15_r_ + OP_l_2_c_15_r_*SF(10) + OP_l_3_c_15_r_*SF(12) + OP_l_4_c_15_r_*SF(11) + OP_l_11_c_15_r_*SF(15) + OP_l_12_c_15_r_*SF(16) + OP_l_13_c_15_r_*SPP(11)) + SPP(6)*(OP_l_1_c_16_r_ + OP_l_2_c_16_r_*SF(10) + OP_l_3_c_16_r_*SF(12) + OP_l_4_c_16_r_*SF(11) + OP_l_11_c_16_r_*SF(15) + OP_l_12_c_16_r_*SF(16) + OP_l_13_c_16_r_*SPP(11)); +nextP(2,6) = OP_l_2_c_6_r_ + OP_l_1_c_6_r_*SF(9) + OP_l_3_c_6_r_*SF(8) + OP_l_4_c_6_r_*SF(12) - OP_l_13_c_6_r_*SF(16) + OP_l_12_c_6_r_*SPP(11) - (OP_l_11_c_6_r_*q0)/2 + SF(5)*(OP_l_2_c_1_r_ + OP_l_1_c_1_r_*SF(9) + OP_l_3_c_1_r_*SF(8) + OP_l_4_c_1_r_*SF(12) - OP_l_13_c_1_r_*SF(16) + OP_l_12_c_1_r_*SPP(11) - (OP_l_11_c_1_r_*q0)/2) + SF(4)*(OP_l_2_c_3_r_ + OP_l_1_c_3_r_*SF(9) + OP_l_3_c_3_r_*SF(8) + OP_l_4_c_3_r_*SF(12) - OP_l_13_c_3_r_*SF(16) + OP_l_12_c_3_r_*SPP(11) - (OP_l_11_c_3_r_*q0)/2) + SF(6)*(OP_l_2_c_4_r_ + OP_l_1_c_4_r_*SF(9) + OP_l_3_c_4_r_*SF(8) + OP_l_4_c_4_r_*SF(12) - OP_l_13_c_4_r_*SF(16) + OP_l_12_c_4_r_*SPP(11) - (OP_l_11_c_4_r_*q0)/2) - SPP(1)*(OP_l_2_c_2_r_ + OP_l_1_c_2_r_*SF(9) + OP_l_3_c_2_r_*SF(8) + OP_l_4_c_2_r_*SF(12) - OP_l_13_c_2_r_*SF(16) + OP_l_12_c_2_r_*SPP(11) - (OP_l_11_c_2_r_*q0)/2) - SPP(9)*(OP_l_2_c_14_r_ + OP_l_1_c_14_r_*SF(9) + OP_l_3_c_14_r_*SF(8) + OP_l_4_c_14_r_*SF(12) - OP_l_13_c_14_r_*SF(16) + OP_l_12_c_14_r_*SPP(11) - (OP_l_11_c_14_r_*q0)/2) + SPP(3)*(OP_l_2_c_15_r_ + OP_l_1_c_15_r_*SF(9) + OP_l_3_c_15_r_*SF(8) + OP_l_4_c_15_r_*SF(12) - OP_l_13_c_15_r_*SF(16) + OP_l_12_c_15_r_*SPP(11) - (OP_l_11_c_15_r_*q0)/2) + SPP(6)*(OP_l_2_c_16_r_ + OP_l_1_c_16_r_*SF(9) + OP_l_3_c_16_r_*SF(8) + OP_l_4_c_16_r_*SF(12) - OP_l_13_c_16_r_*SF(16) + OP_l_12_c_16_r_*SPP(11) - (OP_l_11_c_16_r_*q0)/2); +nextP(3,6) = OP_l_3_c_6_r_ + OP_l_1_c_6_r_*SF(7) + OP_l_2_c_6_r_*SF(11) + OP_l_4_c_6_r_*SF(9) + OP_l_13_c_6_r_*SF(15) - OP_l_11_c_6_r_*SPP(11) - (OP_l_12_c_6_r_*q0)/2 + SF(5)*(OP_l_3_c_1_r_ + OP_l_1_c_1_r_*SF(7) + OP_l_2_c_1_r_*SF(11) + OP_l_4_c_1_r_*SF(9) + OP_l_13_c_1_r_*SF(15) - OP_l_11_c_1_r_*SPP(11) - (OP_l_12_c_1_r_*q0)/2) + SF(4)*(OP_l_3_c_3_r_ + OP_l_1_c_3_r_*SF(7) + OP_l_2_c_3_r_*SF(11) + OP_l_4_c_3_r_*SF(9) + OP_l_13_c_3_r_*SF(15) - OP_l_11_c_3_r_*SPP(11) - (OP_l_12_c_3_r_*q0)/2) + SF(6)*(OP_l_3_c_4_r_ + OP_l_1_c_4_r_*SF(7) + OP_l_2_c_4_r_*SF(11) + OP_l_4_c_4_r_*SF(9) + OP_l_13_c_4_r_*SF(15) - OP_l_11_c_4_r_*SPP(11) - (OP_l_12_c_4_r_*q0)/2) - SPP(1)*(OP_l_3_c_2_r_ + OP_l_1_c_2_r_*SF(7) + OP_l_2_c_2_r_*SF(11) + OP_l_4_c_2_r_*SF(9) + OP_l_13_c_2_r_*SF(15) - OP_l_11_c_2_r_*SPP(11) - (OP_l_12_c_2_r_*q0)/2) - SPP(9)*(OP_l_3_c_14_r_ + OP_l_1_c_14_r_*SF(7) + OP_l_2_c_14_r_*SF(11) + OP_l_4_c_14_r_*SF(9) + OP_l_13_c_14_r_*SF(15) - OP_l_11_c_14_r_*SPP(11) - (OP_l_12_c_14_r_*q0)/2) + SPP(3)*(OP_l_3_c_15_r_ + OP_l_1_c_15_r_*SF(7) + OP_l_2_c_15_r_*SF(11) + OP_l_4_c_15_r_*SF(9) + OP_l_13_c_15_r_*SF(15) - OP_l_11_c_15_r_*SPP(11) - (OP_l_12_c_15_r_*q0)/2) + SPP(6)*(OP_l_3_c_16_r_ + OP_l_1_c_16_r_*SF(7) + OP_l_2_c_16_r_*SF(11) + OP_l_4_c_16_r_*SF(9) + OP_l_13_c_16_r_*SF(15) - OP_l_11_c_16_r_*SPP(11) - (OP_l_12_c_16_r_*q0)/2); +nextP(4,6) = OP_l_4_c_6_r_ + OP_l_1_c_6_r_*SF(8) + OP_l_2_c_6_r_*SF(7) + OP_l_3_c_6_r_*SF(10) + OP_l_11_c_6_r_*SF(16) - OP_l_12_c_6_r_*SF(15) - (OP_l_13_c_6_r_*q0)/2 + SF(5)*(OP_l_4_c_1_r_ + OP_l_1_c_1_r_*SF(8) + OP_l_2_c_1_r_*SF(7) + OP_l_3_c_1_r_*SF(10) + OP_l_11_c_1_r_*SF(16) - OP_l_12_c_1_r_*SF(15) - (OP_l_13_c_1_r_*q0)/2) + SF(4)*(OP_l_4_c_3_r_ + OP_l_1_c_3_r_*SF(8) + OP_l_2_c_3_r_*SF(7) + OP_l_3_c_3_r_*SF(10) + OP_l_11_c_3_r_*SF(16) - OP_l_12_c_3_r_*SF(15) - (OP_l_13_c_3_r_*q0)/2) + SF(6)*(OP_l_4_c_4_r_ + OP_l_1_c_4_r_*SF(8) + OP_l_2_c_4_r_*SF(7) + OP_l_3_c_4_r_*SF(10) + OP_l_11_c_4_r_*SF(16) - OP_l_12_c_4_r_*SF(15) - (OP_l_13_c_4_r_*q0)/2) - SPP(1)*(OP_l_4_c_2_r_ + OP_l_1_c_2_r_*SF(8) + OP_l_2_c_2_r_*SF(7) + OP_l_3_c_2_r_*SF(10) + OP_l_11_c_2_r_*SF(16) - OP_l_12_c_2_r_*SF(15) - (OP_l_13_c_2_r_*q0)/2) - SPP(9)*(OP_l_4_c_14_r_ + OP_l_1_c_14_r_*SF(8) + OP_l_2_c_14_r_*SF(7) + OP_l_3_c_14_r_*SF(10) + OP_l_11_c_14_r_*SF(16) - OP_l_12_c_14_r_*SF(15) - (OP_l_13_c_14_r_*q0)/2) + SPP(3)*(OP_l_4_c_15_r_ + OP_l_1_c_15_r_*SF(8) + OP_l_2_c_15_r_*SF(7) + OP_l_3_c_15_r_*SF(10) + OP_l_11_c_15_r_*SF(16) - OP_l_12_c_15_r_*SF(15) - (OP_l_13_c_15_r_*q0)/2) + SPP(6)*(OP_l_4_c_16_r_ + OP_l_1_c_16_r_*SF(8) + OP_l_2_c_16_r_*SF(7) + OP_l_3_c_16_r_*SF(10) + OP_l_11_c_16_r_*SF(16) - OP_l_12_c_16_r_*SF(15) - (OP_l_13_c_16_r_*q0)/2); +nextP(5,6) = OP_l_5_c_6_r_ + SQ(3) + OP_l_1_c_6_r_*SF(6) + OP_l_2_c_6_r_*SF(4) - OP_l_4_c_6_r_*SF(5) + OP_l_3_c_6_r_*SPP(1) + OP_l_14_c_6_r_*SPP(4) + OP_l_15_c_6_r_*SPP(7) - OP_l_16_c_6_r_*SPP(10) + SF(5)*(OP_l_5_c_1_r_ + OP_l_1_c_1_r_*SF(6) + OP_l_2_c_1_r_*SF(4) - OP_l_4_c_1_r_*SF(5) + OP_l_3_c_1_r_*SPP(1) + OP_l_14_c_1_r_*SPP(4) + OP_l_15_c_1_r_*SPP(7) - OP_l_16_c_1_r_*SPP(10)) + SF(4)*(OP_l_5_c_3_r_ + OP_l_1_c_3_r_*SF(6) + OP_l_2_c_3_r_*SF(4) - OP_l_4_c_3_r_*SF(5) + OP_l_3_c_3_r_*SPP(1) + OP_l_14_c_3_r_*SPP(4) + OP_l_15_c_3_r_*SPP(7) - OP_l_16_c_3_r_*SPP(10)) + SF(6)*(OP_l_5_c_4_r_ + OP_l_1_c_4_r_*SF(6) + OP_l_2_c_4_r_*SF(4) - OP_l_4_c_4_r_*SF(5) + OP_l_3_c_4_r_*SPP(1) + OP_l_14_c_4_r_*SPP(4) + OP_l_15_c_4_r_*SPP(7) - OP_l_16_c_4_r_*SPP(10)) - SPP(1)*(OP_l_5_c_2_r_ + OP_l_1_c_2_r_*SF(6) + OP_l_2_c_2_r_*SF(4) - OP_l_4_c_2_r_*SF(5) + OP_l_3_c_2_r_*SPP(1) + OP_l_14_c_2_r_*SPP(4) + OP_l_15_c_2_r_*SPP(7) - OP_l_16_c_2_r_*SPP(10)) - SPP(9)*(OP_l_5_c_14_r_ + OP_l_1_c_14_r_*SF(6) + OP_l_2_c_14_r_*SF(4) - OP_l_4_c_14_r_*SF(5) + OP_l_3_c_14_r_*SPP(1) + OP_l_14_c_14_r_*SPP(4) + OP_l_15_c_14_r_*SPP(7) - OP_l_16_c_14_r_*SPP(10)) + SPP(3)*(OP_l_5_c_15_r_ + OP_l_1_c_15_r_*SF(6) + OP_l_2_c_15_r_*SF(4) - OP_l_4_c_15_r_*SF(5) + OP_l_3_c_15_r_*SPP(1) + OP_l_14_c_15_r_*SPP(4) + OP_l_15_c_15_r_*SPP(7) - OP_l_16_c_15_r_*SPP(10)) + SPP(6)*(OP_l_5_c_16_r_ + OP_l_1_c_16_r_*SF(6) + OP_l_2_c_16_r_*SF(4) - OP_l_4_c_16_r_*SF(5) + OP_l_3_c_16_r_*SPP(1) + OP_l_14_c_16_r_*SPP(4) + OP_l_15_c_16_r_*SPP(7) - OP_l_16_c_16_r_*SPP(10)); +nextP(6,6) = OP_l_6_c_6_r_ + OP_l_1_c_6_r_*SF(5) + OP_l_3_c_6_r_*SF(4) + OP_l_4_c_6_r_*SF(6) - OP_l_2_c_6_r_*SPP(1) - OP_l_14_c_6_r_*SPP(9) + OP_l_15_c_6_r_*SPP(3) + OP_l_16_c_6_r_*SPP(6) + dvxVar*(SG(8) + 2*q0*q3)^2 + dvzVar*(SG(6) - 2*q0*q1)^2 + SF(5)*(OP_l_6_c_1_r_ + OP_l_1_c_1_r_*SF(5) + OP_l_3_c_1_r_*SF(4) + OP_l_4_c_1_r_*SF(6) - OP_l_2_c_1_r_*SPP(1) - OP_l_14_c_1_r_*SPP(9) + OP_l_15_c_1_r_*SPP(3) + OP_l_16_c_1_r_*SPP(6)) + SF(4)*(OP_l_6_c_3_r_ + OP_l_1_c_3_r_*SF(5) + OP_l_3_c_3_r_*SF(4) + OP_l_4_c_3_r_*SF(6) - OP_l_2_c_3_r_*SPP(1) - OP_l_14_c_3_r_*SPP(9) + OP_l_15_c_3_r_*SPP(3) + OP_l_16_c_3_r_*SPP(6)) + SF(6)*(OP_l_6_c_4_r_ + OP_l_1_c_4_r_*SF(5) + OP_l_3_c_4_r_*SF(4) + OP_l_4_c_4_r_*SF(6) - OP_l_2_c_4_r_*SPP(1) - OP_l_14_c_4_r_*SPP(9) + OP_l_15_c_4_r_*SPP(3) + OP_l_16_c_4_r_*SPP(6)) - SPP(1)*(OP_l_6_c_2_r_ + OP_l_1_c_2_r_*SF(5) + OP_l_3_c_2_r_*SF(4) + OP_l_4_c_2_r_*SF(6) - OP_l_2_c_2_r_*SPP(1) - OP_l_14_c_2_r_*SPP(9) + OP_l_15_c_2_r_*SPP(3) + OP_l_16_c_2_r_*SPP(6)) - SPP(9)*(OP_l_6_c_14_r_ + OP_l_1_c_14_r_*SF(5) + OP_l_3_c_14_r_*SF(4) + OP_l_4_c_14_r_*SF(6) - OP_l_2_c_14_r_*SPP(1) - OP_l_14_c_14_r_*SPP(9) + OP_l_15_c_14_r_*SPP(3) + OP_l_16_c_14_r_*SPP(6)) + SPP(3)*(OP_l_6_c_15_r_ + OP_l_1_c_15_r_*SF(5) + OP_l_3_c_15_r_*SF(4) + OP_l_4_c_15_r_*SF(6) - OP_l_2_c_15_r_*SPP(1) - OP_l_14_c_15_r_*SPP(9) + OP_l_15_c_15_r_*SPP(3) + OP_l_16_c_15_r_*SPP(6)) + SPP(6)*(OP_l_6_c_16_r_ + OP_l_1_c_16_r_*SF(5) + OP_l_3_c_16_r_*SF(4) + OP_l_4_c_16_r_*SF(6) - OP_l_2_c_16_r_*SPP(1) - OP_l_14_c_16_r_*SPP(9) + OP_l_15_c_16_r_*SPP(3) + OP_l_16_c_16_r_*SPP(6)) + dvyVar*(SG(2) - SG(3) + SG(4) - SG(5))^2; +nextP(1,7) = OP_l_1_c_7_r_ + OP_l_2_c_7_r_*SF(10) + OP_l_3_c_7_r_*SF(12) + OP_l_4_c_7_r_*SF(11) + OP_l_11_c_7_r_*SF(15) + OP_l_12_c_7_r_*SF(16) + OP_l_13_c_7_r_*SPP(11) + SF(5)*(OP_l_1_c_2_r_ + OP_l_2_c_2_r_*SF(10) + OP_l_3_c_2_r_*SF(12) + OP_l_4_c_2_r_*SF(11) + OP_l_11_c_2_r_*SF(15) + OP_l_12_c_2_r_*SF(16) + OP_l_13_c_2_r_*SPP(11)) - SF(6)*(OP_l_1_c_3_r_ + OP_l_2_c_3_r_*SF(10) + OP_l_3_c_3_r_*SF(12) + OP_l_4_c_3_r_*SF(11) + OP_l_11_c_3_r_*SF(15) + OP_l_12_c_3_r_*SF(16) + OP_l_13_c_3_r_*SPP(11)) + SF(4)*(OP_l_1_c_4_r_ + OP_l_2_c_4_r_*SF(10) + OP_l_3_c_4_r_*SF(12) + OP_l_4_c_4_r_*SF(11) + OP_l_11_c_4_r_*SF(15) + OP_l_12_c_4_r_*SF(16) + OP_l_13_c_4_r_*SPP(11)) + SPP(1)*(OP_l_1_c_1_r_ + OP_l_2_c_1_r_*SF(10) + OP_l_3_c_1_r_*SF(12) + OP_l_4_c_1_r_*SF(11) + OP_l_11_c_1_r_*SF(15) + OP_l_12_c_1_r_*SF(16) + OP_l_13_c_1_r_*SPP(11)) + SPP(5)*(OP_l_1_c_14_r_ + OP_l_2_c_14_r_*SF(10) + OP_l_3_c_14_r_*SF(12) + OP_l_4_c_14_r_*SF(11) + OP_l_11_c_14_r_*SF(15) + OP_l_12_c_14_r_*SF(16) + OP_l_13_c_14_r_*SPP(11)) - SPP(8)*(OP_l_1_c_15_r_ + OP_l_2_c_15_r_*SF(10) + OP_l_3_c_15_r_*SF(12) + OP_l_4_c_15_r_*SF(11) + OP_l_11_c_15_r_*SF(15) + OP_l_12_c_15_r_*SF(16) + OP_l_13_c_15_r_*SPP(11)) - SPP(2)*(OP_l_1_c_16_r_ + OP_l_2_c_16_r_*SF(10) + OP_l_3_c_16_r_*SF(12) + OP_l_4_c_16_r_*SF(11) + OP_l_11_c_16_r_*SF(15) + OP_l_12_c_16_r_*SF(16) + OP_l_13_c_16_r_*SPP(11)); +nextP(2,7) = OP_l_2_c_7_r_ + OP_l_1_c_7_r_*SF(9) + OP_l_3_c_7_r_*SF(8) + OP_l_4_c_7_r_*SF(12) - OP_l_13_c_7_r_*SF(16) + OP_l_12_c_7_r_*SPP(11) - (OP_l_11_c_7_r_*q0)/2 + SF(5)*(OP_l_2_c_2_r_ + OP_l_1_c_2_r_*SF(9) + OP_l_3_c_2_r_*SF(8) + OP_l_4_c_2_r_*SF(12) - OP_l_13_c_2_r_*SF(16) + OP_l_12_c_2_r_*SPP(11) - (OP_l_11_c_2_r_*q0)/2) - SF(6)*(OP_l_2_c_3_r_ + OP_l_1_c_3_r_*SF(9) + OP_l_3_c_3_r_*SF(8) + OP_l_4_c_3_r_*SF(12) - OP_l_13_c_3_r_*SF(16) + OP_l_12_c_3_r_*SPP(11) - (OP_l_11_c_3_r_*q0)/2) + SF(4)*(OP_l_2_c_4_r_ + OP_l_1_c_4_r_*SF(9) + OP_l_3_c_4_r_*SF(8) + OP_l_4_c_4_r_*SF(12) - OP_l_13_c_4_r_*SF(16) + OP_l_12_c_4_r_*SPP(11) - (OP_l_11_c_4_r_*q0)/2) + SPP(1)*(OP_l_2_c_1_r_ + OP_l_1_c_1_r_*SF(9) + OP_l_3_c_1_r_*SF(8) + OP_l_4_c_1_r_*SF(12) - OP_l_13_c_1_r_*SF(16) + OP_l_12_c_1_r_*SPP(11) - (OP_l_11_c_1_r_*q0)/2) + SPP(5)*(OP_l_2_c_14_r_ + OP_l_1_c_14_r_*SF(9) + OP_l_3_c_14_r_*SF(8) + OP_l_4_c_14_r_*SF(12) - OP_l_13_c_14_r_*SF(16) + OP_l_12_c_14_r_*SPP(11) - (OP_l_11_c_14_r_*q0)/2) - SPP(8)*(OP_l_2_c_15_r_ + OP_l_1_c_15_r_*SF(9) + OP_l_3_c_15_r_*SF(8) + OP_l_4_c_15_r_*SF(12) - OP_l_13_c_15_r_*SF(16) + OP_l_12_c_15_r_*SPP(11) - (OP_l_11_c_15_r_*q0)/2) - SPP(2)*(OP_l_2_c_16_r_ + OP_l_1_c_16_r_*SF(9) + OP_l_3_c_16_r_*SF(8) + OP_l_4_c_16_r_*SF(12) - OP_l_13_c_16_r_*SF(16) + OP_l_12_c_16_r_*SPP(11) - (OP_l_11_c_16_r_*q0)/2); +nextP(3,7) = OP_l_3_c_7_r_ + OP_l_1_c_7_r_*SF(7) + OP_l_2_c_7_r_*SF(11) + OP_l_4_c_7_r_*SF(9) + OP_l_13_c_7_r_*SF(15) - OP_l_11_c_7_r_*SPP(11) - (OP_l_12_c_7_r_*q0)/2 + SF(5)*(OP_l_3_c_2_r_ + OP_l_1_c_2_r_*SF(7) + OP_l_2_c_2_r_*SF(11) + OP_l_4_c_2_r_*SF(9) + OP_l_13_c_2_r_*SF(15) - OP_l_11_c_2_r_*SPP(11) - (OP_l_12_c_2_r_*q0)/2) - SF(6)*(OP_l_3_c_3_r_ + OP_l_1_c_3_r_*SF(7) + OP_l_2_c_3_r_*SF(11) + OP_l_4_c_3_r_*SF(9) + OP_l_13_c_3_r_*SF(15) - OP_l_11_c_3_r_*SPP(11) - (OP_l_12_c_3_r_*q0)/2) + SF(4)*(OP_l_3_c_4_r_ + OP_l_1_c_4_r_*SF(7) + OP_l_2_c_4_r_*SF(11) + OP_l_4_c_4_r_*SF(9) + OP_l_13_c_4_r_*SF(15) - OP_l_11_c_4_r_*SPP(11) - (OP_l_12_c_4_r_*q0)/2) + SPP(1)*(OP_l_3_c_1_r_ + OP_l_1_c_1_r_*SF(7) + OP_l_2_c_1_r_*SF(11) + OP_l_4_c_1_r_*SF(9) + OP_l_13_c_1_r_*SF(15) - OP_l_11_c_1_r_*SPP(11) - (OP_l_12_c_1_r_*q0)/2) + SPP(5)*(OP_l_3_c_14_r_ + OP_l_1_c_14_r_*SF(7) + OP_l_2_c_14_r_*SF(11) + OP_l_4_c_14_r_*SF(9) + OP_l_13_c_14_r_*SF(15) - OP_l_11_c_14_r_*SPP(11) - (OP_l_12_c_14_r_*q0)/2) - SPP(8)*(OP_l_3_c_15_r_ + OP_l_1_c_15_r_*SF(7) + OP_l_2_c_15_r_*SF(11) + OP_l_4_c_15_r_*SF(9) + OP_l_13_c_15_r_*SF(15) - OP_l_11_c_15_r_*SPP(11) - (OP_l_12_c_15_r_*q0)/2) - SPP(2)*(OP_l_3_c_16_r_ + OP_l_1_c_16_r_*SF(7) + OP_l_2_c_16_r_*SF(11) + OP_l_4_c_16_r_*SF(9) + OP_l_13_c_16_r_*SF(15) - OP_l_11_c_16_r_*SPP(11) - (OP_l_12_c_16_r_*q0)/2); +nextP(4,7) = OP_l_4_c_7_r_ + OP_l_1_c_7_r_*SF(8) + OP_l_2_c_7_r_*SF(7) + OP_l_3_c_7_r_*SF(10) + OP_l_11_c_7_r_*SF(16) - OP_l_12_c_7_r_*SF(15) - (OP_l_13_c_7_r_*q0)/2 + SF(5)*(OP_l_4_c_2_r_ + OP_l_1_c_2_r_*SF(8) + OP_l_2_c_2_r_*SF(7) + OP_l_3_c_2_r_*SF(10) + OP_l_11_c_2_r_*SF(16) - OP_l_12_c_2_r_*SF(15) - (OP_l_13_c_2_r_*q0)/2) - SF(6)*(OP_l_4_c_3_r_ + OP_l_1_c_3_r_*SF(8) + OP_l_2_c_3_r_*SF(7) + OP_l_3_c_3_r_*SF(10) + OP_l_11_c_3_r_*SF(16) - OP_l_12_c_3_r_*SF(15) - (OP_l_13_c_3_r_*q0)/2) + SF(4)*(OP_l_4_c_4_r_ + OP_l_1_c_4_r_*SF(8) + OP_l_2_c_4_r_*SF(7) + OP_l_3_c_4_r_*SF(10) + OP_l_11_c_4_r_*SF(16) - OP_l_12_c_4_r_*SF(15) - (OP_l_13_c_4_r_*q0)/2) + SPP(1)*(OP_l_4_c_1_r_ + OP_l_1_c_1_r_*SF(8) + OP_l_2_c_1_r_*SF(7) + OP_l_3_c_1_r_*SF(10) + OP_l_11_c_1_r_*SF(16) - OP_l_12_c_1_r_*SF(15) - (OP_l_13_c_1_r_*q0)/2) + SPP(5)*(OP_l_4_c_14_r_ + OP_l_1_c_14_r_*SF(8) + OP_l_2_c_14_r_*SF(7) + OP_l_3_c_14_r_*SF(10) + OP_l_11_c_14_r_*SF(16) - OP_l_12_c_14_r_*SF(15) - (OP_l_13_c_14_r_*q0)/2) - SPP(8)*(OP_l_4_c_15_r_ + OP_l_1_c_15_r_*SF(8) + OP_l_2_c_15_r_*SF(7) + OP_l_3_c_15_r_*SF(10) + OP_l_11_c_15_r_*SF(16) - OP_l_12_c_15_r_*SF(15) - (OP_l_13_c_15_r_*q0)/2) - SPP(2)*(OP_l_4_c_16_r_ + OP_l_1_c_16_r_*SF(8) + OP_l_2_c_16_r_*SF(7) + OP_l_3_c_16_r_*SF(10) + OP_l_11_c_16_r_*SF(16) - OP_l_12_c_16_r_*SF(15) - (OP_l_13_c_16_r_*q0)/2); +nextP(5,7) = OP_l_5_c_7_r_ + SQ(2) + OP_l_1_c_7_r_*SF(6) + OP_l_2_c_7_r_*SF(4) - OP_l_4_c_7_r_*SF(5) + OP_l_3_c_7_r_*SPP(1) + OP_l_14_c_7_r_*SPP(4) + OP_l_15_c_7_r_*SPP(7) - OP_l_16_c_7_r_*SPP(10) + SF(5)*(OP_l_5_c_2_r_ + OP_l_1_c_2_r_*SF(6) + OP_l_2_c_2_r_*SF(4) - OP_l_4_c_2_r_*SF(5) + OP_l_3_c_2_r_*SPP(1) + OP_l_14_c_2_r_*SPP(4) + OP_l_15_c_2_r_*SPP(7) - OP_l_16_c_2_r_*SPP(10)) - SF(6)*(OP_l_5_c_3_r_ + OP_l_1_c_3_r_*SF(6) + OP_l_2_c_3_r_*SF(4) - OP_l_4_c_3_r_*SF(5) + OP_l_3_c_3_r_*SPP(1) + OP_l_14_c_3_r_*SPP(4) + OP_l_15_c_3_r_*SPP(7) - OP_l_16_c_3_r_*SPP(10)) + SF(4)*(OP_l_5_c_4_r_ + OP_l_1_c_4_r_*SF(6) + OP_l_2_c_4_r_*SF(4) - OP_l_4_c_4_r_*SF(5) + OP_l_3_c_4_r_*SPP(1) + OP_l_14_c_4_r_*SPP(4) + OP_l_15_c_4_r_*SPP(7) - OP_l_16_c_4_r_*SPP(10)) + SPP(1)*(OP_l_5_c_1_r_ + OP_l_1_c_1_r_*SF(6) + OP_l_2_c_1_r_*SF(4) - OP_l_4_c_1_r_*SF(5) + OP_l_3_c_1_r_*SPP(1) + OP_l_14_c_1_r_*SPP(4) + OP_l_15_c_1_r_*SPP(7) - OP_l_16_c_1_r_*SPP(10)) + SPP(5)*(OP_l_5_c_14_r_ + OP_l_1_c_14_r_*SF(6) + OP_l_2_c_14_r_*SF(4) - OP_l_4_c_14_r_*SF(5) + OP_l_3_c_14_r_*SPP(1) + OP_l_14_c_14_r_*SPP(4) + OP_l_15_c_14_r_*SPP(7) - OP_l_16_c_14_r_*SPP(10)) - SPP(8)*(OP_l_5_c_15_r_ + OP_l_1_c_15_r_*SF(6) + OP_l_2_c_15_r_*SF(4) - OP_l_4_c_15_r_*SF(5) + OP_l_3_c_15_r_*SPP(1) + OP_l_14_c_15_r_*SPP(4) + OP_l_15_c_15_r_*SPP(7) - OP_l_16_c_15_r_*SPP(10)) - SPP(2)*(OP_l_5_c_16_r_ + OP_l_1_c_16_r_*SF(6) + OP_l_2_c_16_r_*SF(4) - OP_l_4_c_16_r_*SF(5) + OP_l_3_c_16_r_*SPP(1) + OP_l_14_c_16_r_*SPP(4) + OP_l_15_c_16_r_*SPP(7) - OP_l_16_c_16_r_*SPP(10)); +nextP(6,7) = OP_l_6_c_7_r_ + SQ(1) + OP_l_1_c_7_r_*SF(5) + OP_l_3_c_7_r_*SF(4) + OP_l_4_c_7_r_*SF(6) - OP_l_2_c_7_r_*SPP(1) - OP_l_14_c_7_r_*SPP(9) + OP_l_15_c_7_r_*SPP(3) + OP_l_16_c_7_r_*SPP(6) + SF(5)*(OP_l_6_c_2_r_ + OP_l_1_c_2_r_*SF(5) + OP_l_3_c_2_r_*SF(4) + OP_l_4_c_2_r_*SF(6) - OP_l_2_c_2_r_*SPP(1) - OP_l_14_c_2_r_*SPP(9) + OP_l_15_c_2_r_*SPP(3) + OP_l_16_c_2_r_*SPP(6)) - SF(6)*(OP_l_6_c_3_r_ + OP_l_1_c_3_r_*SF(5) + OP_l_3_c_3_r_*SF(4) + OP_l_4_c_3_r_*SF(6) - OP_l_2_c_3_r_*SPP(1) - OP_l_14_c_3_r_*SPP(9) + OP_l_15_c_3_r_*SPP(3) + OP_l_16_c_3_r_*SPP(6)) + SF(4)*(OP_l_6_c_4_r_ + OP_l_1_c_4_r_*SF(5) + OP_l_3_c_4_r_*SF(4) + OP_l_4_c_4_r_*SF(6) - OP_l_2_c_4_r_*SPP(1) - OP_l_14_c_4_r_*SPP(9) + OP_l_15_c_4_r_*SPP(3) + OP_l_16_c_4_r_*SPP(6)) + SPP(1)*(OP_l_6_c_1_r_ + OP_l_1_c_1_r_*SF(5) + OP_l_3_c_1_r_*SF(4) + OP_l_4_c_1_r_*SF(6) - OP_l_2_c_1_r_*SPP(1) - OP_l_14_c_1_r_*SPP(9) + OP_l_15_c_1_r_*SPP(3) + OP_l_16_c_1_r_*SPP(6)) + SPP(5)*(OP_l_6_c_14_r_ + OP_l_1_c_14_r_*SF(5) + OP_l_3_c_14_r_*SF(4) + OP_l_4_c_14_r_*SF(6) - OP_l_2_c_14_r_*SPP(1) - OP_l_14_c_14_r_*SPP(9) + OP_l_15_c_14_r_*SPP(3) + OP_l_16_c_14_r_*SPP(6)) - SPP(8)*(OP_l_6_c_15_r_ + OP_l_1_c_15_r_*SF(5) + OP_l_3_c_15_r_*SF(4) + OP_l_4_c_15_r_*SF(6) - OP_l_2_c_15_r_*SPP(1) - OP_l_14_c_15_r_*SPP(9) + OP_l_15_c_15_r_*SPP(3) + OP_l_16_c_15_r_*SPP(6)) - SPP(2)*(OP_l_6_c_16_r_ + OP_l_1_c_16_r_*SF(5) + OP_l_3_c_16_r_*SF(4) + OP_l_4_c_16_r_*SF(6) - OP_l_2_c_16_r_*SPP(1) - OP_l_14_c_16_r_*SPP(9) + OP_l_15_c_16_r_*SPP(3) + OP_l_16_c_16_r_*SPP(6)); +nextP(7,7) = OP_l_7_c_7_r_ + OP_l_2_c_7_r_*SF(5) - OP_l_3_c_7_r_*SF(6) + OP_l_4_c_7_r_*SF(4) + OP_l_1_c_7_r_*SPP(1) + OP_l_14_c_7_r_*SPP(5) - OP_l_15_c_7_r_*SPP(8) - OP_l_16_c_7_r_*SPP(2) + dvxVar*(SG(7) - 2*q0*q2)^2 + dvyVar*(SG(6) + 2*q0*q1)^2 + SF(5)*(OP_l_7_c_2_r_ + OP_l_2_c_2_r_*SF(5) - OP_l_3_c_2_r_*SF(6) + OP_l_4_c_2_r_*SF(4) + OP_l_1_c_2_r_*SPP(1) + OP_l_14_c_2_r_*SPP(5) - OP_l_15_c_2_r_*SPP(8) - OP_l_16_c_2_r_*SPP(2)) - SF(6)*(OP_l_7_c_3_r_ + OP_l_2_c_3_r_*SF(5) - OP_l_3_c_3_r_*SF(6) + OP_l_4_c_3_r_*SF(4) + OP_l_1_c_3_r_*SPP(1) + OP_l_14_c_3_r_*SPP(5) - OP_l_15_c_3_r_*SPP(8) - OP_l_16_c_3_r_*SPP(2)) + SF(4)*(OP_l_7_c_4_r_ + OP_l_2_c_4_r_*SF(5) - OP_l_3_c_4_r_*SF(6) + OP_l_4_c_4_r_*SF(4) + OP_l_1_c_4_r_*SPP(1) + OP_l_14_c_4_r_*SPP(5) - OP_l_15_c_4_r_*SPP(8) - OP_l_16_c_4_r_*SPP(2)) + SPP(1)*(OP_l_7_c_1_r_ + OP_l_2_c_1_r_*SF(5) - OP_l_3_c_1_r_*SF(6) + OP_l_4_c_1_r_*SF(4) + OP_l_1_c_1_r_*SPP(1) + OP_l_14_c_1_r_*SPP(5) - OP_l_15_c_1_r_*SPP(8) - OP_l_16_c_1_r_*SPP(2)) + SPP(5)*(OP_l_7_c_14_r_ + OP_l_2_c_14_r_*SF(5) - OP_l_3_c_14_r_*SF(6) + OP_l_4_c_14_r_*SF(4) + OP_l_1_c_14_r_*SPP(1) + OP_l_14_c_14_r_*SPP(5) - OP_l_15_c_14_r_*SPP(8) - OP_l_16_c_14_r_*SPP(2)) - SPP(8)*(OP_l_7_c_15_r_ + OP_l_2_c_15_r_*SF(5) - OP_l_3_c_15_r_*SF(6) + OP_l_4_c_15_r_*SF(4) + OP_l_1_c_15_r_*SPP(1) + OP_l_14_c_15_r_*SPP(5) - OP_l_15_c_15_r_*SPP(8) - OP_l_16_c_15_r_*SPP(2)) - SPP(2)*(OP_l_7_c_16_r_ + OP_l_2_c_16_r_*SF(5) - OP_l_3_c_16_r_*SF(6) + OP_l_4_c_16_r_*SF(4) + OP_l_1_c_16_r_*SPP(1) + OP_l_14_c_16_r_*SPP(5) - OP_l_15_c_16_r_*SPP(8) - OP_l_16_c_16_r_*SPP(2)) + dvzVar*(SG(2) - SG(3) - SG(4) + SG(5))^2; +nextP(1,8) = OP_l_1_c_8_r_ + OP_l_2_c_8_r_*SF(10) + OP_l_3_c_8_r_*SF(12) + OP_l_4_c_8_r_*SF(11) + OP_l_11_c_8_r_*SF(15) + OP_l_12_c_8_r_*SF(16) + OP_l_13_c_8_r_*SPP(11) + dt*(OP_l_1_c_5_r_ + OP_l_2_c_5_r_*SF(10) + OP_l_3_c_5_r_*SF(12) + OP_l_4_c_5_r_*SF(11) + OP_l_11_c_5_r_*SF(15) + OP_l_12_c_5_r_*SF(16) + OP_l_13_c_5_r_*SPP(11)); +nextP(2,8) = OP_l_2_c_8_r_ + OP_l_1_c_8_r_*SF(9) + OP_l_3_c_8_r_*SF(8) + OP_l_4_c_8_r_*SF(12) - OP_l_13_c_8_r_*SF(16) + OP_l_12_c_8_r_*SPP(11) - (OP_l_11_c_8_r_*q0)/2 + dt*(OP_l_2_c_5_r_ + OP_l_1_c_5_r_*SF(9) + OP_l_3_c_5_r_*SF(8) + OP_l_4_c_5_r_*SF(12) - OP_l_13_c_5_r_*SF(16) + OP_l_12_c_5_r_*SPP(11) - (OP_l_11_c_5_r_*q0)/2); +nextP(3,8) = OP_l_3_c_8_r_ + OP_l_1_c_8_r_*SF(7) + OP_l_2_c_8_r_*SF(11) + OP_l_4_c_8_r_*SF(9) + OP_l_13_c_8_r_*SF(15) - OP_l_11_c_8_r_*SPP(11) - (OP_l_12_c_8_r_*q0)/2 + dt*(OP_l_3_c_5_r_ + OP_l_1_c_5_r_*SF(7) + OP_l_2_c_5_r_*SF(11) + OP_l_4_c_5_r_*SF(9) + OP_l_13_c_5_r_*SF(15) - OP_l_11_c_5_r_*SPP(11) - (OP_l_12_c_5_r_*q0)/2); +nextP(4,8) = OP_l_4_c_8_r_ + OP_l_1_c_8_r_*SF(8) + OP_l_2_c_8_r_*SF(7) + OP_l_3_c_8_r_*SF(10) + OP_l_11_c_8_r_*SF(16) - OP_l_12_c_8_r_*SF(15) - (OP_l_13_c_8_r_*q0)/2 + dt*(OP_l_4_c_5_r_ + OP_l_1_c_5_r_*SF(8) + OP_l_2_c_5_r_*SF(7) + OP_l_3_c_5_r_*SF(10) + OP_l_11_c_5_r_*SF(16) - OP_l_12_c_5_r_*SF(15) - (OP_l_13_c_5_r_*q0)/2); +nextP(5,8) = OP_l_5_c_8_r_ + OP_l_1_c_8_r_*SF(6) + OP_l_2_c_8_r_*SF(4) - OP_l_4_c_8_r_*SF(5) + OP_l_3_c_8_r_*SPP(1) + OP_l_14_c_8_r_*SPP(4) + OP_l_15_c_8_r_*SPP(7) - OP_l_16_c_8_r_*SPP(10) + dt*(OP_l_5_c_5_r_ + OP_l_1_c_5_r_*SF(6) + OP_l_2_c_5_r_*SF(4) - OP_l_4_c_5_r_*SF(5) + OP_l_3_c_5_r_*SPP(1) + OP_l_14_c_5_r_*SPP(4) + OP_l_15_c_5_r_*SPP(7) - OP_l_16_c_5_r_*SPP(10)); +nextP(6,8) = OP_l_6_c_8_r_ + OP_l_1_c_8_r_*SF(5) + OP_l_3_c_8_r_*SF(4) + OP_l_4_c_8_r_*SF(6) - OP_l_2_c_8_r_*SPP(1) - OP_l_14_c_8_r_*SPP(9) + OP_l_15_c_8_r_*SPP(3) + OP_l_16_c_8_r_*SPP(6) + dt*(OP_l_6_c_5_r_ + OP_l_1_c_5_r_*SF(5) + OP_l_3_c_5_r_*SF(4) + OP_l_4_c_5_r_*SF(6) - OP_l_2_c_5_r_*SPP(1) - OP_l_14_c_5_r_*SPP(9) + OP_l_15_c_5_r_*SPP(3) + OP_l_16_c_5_r_*SPP(6)); +nextP(7,8) = OP_l_7_c_8_r_ + OP_l_2_c_8_r_*SF(5) - OP_l_3_c_8_r_*SF(6) + OP_l_4_c_8_r_*SF(4) + OP_l_1_c_8_r_*SPP(1) + OP_l_14_c_8_r_*SPP(5) - OP_l_15_c_8_r_*SPP(8) - OP_l_16_c_8_r_*SPP(2) + dt*(OP_l_7_c_5_r_ + OP_l_2_c_5_r_*SF(5) - OP_l_3_c_5_r_*SF(6) + OP_l_4_c_5_r_*SF(4) + OP_l_1_c_5_r_*SPP(1) + OP_l_14_c_5_r_*SPP(5) - OP_l_15_c_5_r_*SPP(8) - OP_l_16_c_5_r_*SPP(2)); nextP(8,8) = OP_l_8_c_8_r_ + OP_l_5_c_8_r_*dt + dt*(OP_l_8_c_5_r_ + OP_l_5_c_5_r_*dt); -nextP(1,9) = OP_l_1_c_9_r_*SPP(6) - OP_l_2_c_9_r_*SPP(5) + OP_l_3_c_9_r_*SPP(8) + OP_l_10_c_9_r_*SPP(23) + OP_l_13_c_9_r_*SPP(19) + dt*(OP_l_1_c_6_r_*SPP(6) - OP_l_2_c_6_r_*SPP(5) + OP_l_3_c_6_r_*SPP(8) + OP_l_10_c_6_r_*SPP(23) + OP_l_13_c_6_r_*SPP(19)); -nextP(2,9) = OP_l_2_c_9_r_*SPP(7) - OP_l_1_c_9_r_*SPP(3) - OP_l_3_c_9_r_*SPP(9) + OP_l_11_c_9_r_*SPP(23) + OP_l_14_c_9_r_*SPP(18) + dt*(OP_l_2_c_6_r_*SPP(7) - OP_l_1_c_6_r_*SPP(3) - OP_l_3_c_6_r_*SPP(9) + OP_l_11_c_6_r_*SPP(23) + OP_l_14_c_6_r_*SPP(18)); -nextP(3,9) = OP_l_1_c_9_r_*SPP(15) - OP_l_2_c_9_r_*SPP(4) + OP_l_3_c_9_r_*SPP(14) + OP_l_12_c_9_r_*SPP(23) + OP_l_15_c_9_r_*SPP(17) + dt*(OP_l_1_c_6_r_*SPP(15) - OP_l_2_c_6_r_*SPP(4) + OP_l_3_c_6_r_*SPP(14) + OP_l_12_c_6_r_*SPP(23) + OP_l_15_c_6_r_*SPP(17)); -nextP(4,9) = OP_l_4_c_9_r_ + OP_l_1_c_9_r_*SPP(2) + OP_l_2_c_9_r_*SPP(20) + OP_l_3_c_9_r_*SPP(16) - OP_l_16_c_9_r_*SPP(22) + dt*(OP_l_4_c_6_r_ + OP_l_1_c_6_r_*SPP(2) + OP_l_2_c_6_r_*SPP(20) + OP_l_3_c_6_r_*SPP(16) - OP_l_16_c_6_r_*SPP(22)); -nextP(5,9) = OP_l_5_c_9_r_ + OP_l_16_c_9_r_*SF(23) + OP_l_1_c_9_r_*SPP(21) + OP_l_2_c_9_r_*SPP(13) + OP_l_3_c_9_r_*SPP(12) + dt*(OP_l_5_c_6_r_ + OP_l_16_c_6_r_*SF(23) + OP_l_1_c_6_r_*SPP(21) + OP_l_2_c_6_r_*SPP(13) + OP_l_3_c_6_r_*SPP(12)); -nextP(6,9) = OP_l_6_c_9_r_ + OP_l_16_c_9_r_*SF(21) - OP_l_1_c_9_r_*SPP(10) + OP_l_2_c_9_r_*SPP(11) + OP_l_3_c_9_r_*SPP(1) + dt*(OP_l_6_c_6_r_ + OP_l_16_c_6_r_*SF(21) - OP_l_1_c_6_r_*SPP(10) + OP_l_2_c_6_r_*SPP(11) + OP_l_3_c_6_r_*SPP(1)); -nextP(7,9) = OP_l_7_c_9_r_ + OP_l_4_c_9_r_*dt + dt*(OP_l_7_c_6_r_ + OP_l_4_c_6_r_*dt); +nextP(1,9) = OP_l_1_c_9_r_ + OP_l_2_c_9_r_*SF(10) + OP_l_3_c_9_r_*SF(12) + OP_l_4_c_9_r_*SF(11) + OP_l_11_c_9_r_*SF(15) + OP_l_12_c_9_r_*SF(16) + OP_l_13_c_9_r_*SPP(11) + dt*(OP_l_1_c_6_r_ + OP_l_2_c_6_r_*SF(10) + OP_l_3_c_6_r_*SF(12) + OP_l_4_c_6_r_*SF(11) + OP_l_11_c_6_r_*SF(15) + OP_l_12_c_6_r_*SF(16) + OP_l_13_c_6_r_*SPP(11)); +nextP(2,9) = OP_l_2_c_9_r_ + OP_l_1_c_9_r_*SF(9) + OP_l_3_c_9_r_*SF(8) + OP_l_4_c_9_r_*SF(12) - OP_l_13_c_9_r_*SF(16) + OP_l_12_c_9_r_*SPP(11) - (OP_l_11_c_9_r_*q0)/2 + dt*(OP_l_2_c_6_r_ + OP_l_1_c_6_r_*SF(9) + OP_l_3_c_6_r_*SF(8) + OP_l_4_c_6_r_*SF(12) - OP_l_13_c_6_r_*SF(16) + OP_l_12_c_6_r_*SPP(11) - (OP_l_11_c_6_r_*q0)/2); +nextP(3,9) = OP_l_3_c_9_r_ + OP_l_1_c_9_r_*SF(7) + OP_l_2_c_9_r_*SF(11) + OP_l_4_c_9_r_*SF(9) + OP_l_13_c_9_r_*SF(15) - OP_l_11_c_9_r_*SPP(11) - (OP_l_12_c_9_r_*q0)/2 + dt*(OP_l_3_c_6_r_ + OP_l_1_c_6_r_*SF(7) + OP_l_2_c_6_r_*SF(11) + OP_l_4_c_6_r_*SF(9) + OP_l_13_c_6_r_*SF(15) - OP_l_11_c_6_r_*SPP(11) - (OP_l_12_c_6_r_*q0)/2); +nextP(4,9) = OP_l_4_c_9_r_ + OP_l_1_c_9_r_*SF(8) + OP_l_2_c_9_r_*SF(7) + OP_l_3_c_9_r_*SF(10) + OP_l_11_c_9_r_*SF(16) - OP_l_12_c_9_r_*SF(15) - (OP_l_13_c_9_r_*q0)/2 + dt*(OP_l_4_c_6_r_ + OP_l_1_c_6_r_*SF(8) + OP_l_2_c_6_r_*SF(7) + OP_l_3_c_6_r_*SF(10) + OP_l_11_c_6_r_*SF(16) - OP_l_12_c_6_r_*SF(15) - (OP_l_13_c_6_r_*q0)/2); +nextP(5,9) = OP_l_5_c_9_r_ + OP_l_1_c_9_r_*SF(6) + OP_l_2_c_9_r_*SF(4) - OP_l_4_c_9_r_*SF(5) + OP_l_3_c_9_r_*SPP(1) + OP_l_14_c_9_r_*SPP(4) + OP_l_15_c_9_r_*SPP(7) - OP_l_16_c_9_r_*SPP(10) + dt*(OP_l_5_c_6_r_ + OP_l_1_c_6_r_*SF(6) + OP_l_2_c_6_r_*SF(4) - OP_l_4_c_6_r_*SF(5) + OP_l_3_c_6_r_*SPP(1) + OP_l_14_c_6_r_*SPP(4) + OP_l_15_c_6_r_*SPP(7) - OP_l_16_c_6_r_*SPP(10)); +nextP(6,9) = OP_l_6_c_9_r_ + OP_l_1_c_9_r_*SF(5) + OP_l_3_c_9_r_*SF(4) + OP_l_4_c_9_r_*SF(6) - OP_l_2_c_9_r_*SPP(1) - OP_l_14_c_9_r_*SPP(9) + OP_l_15_c_9_r_*SPP(3) + OP_l_16_c_9_r_*SPP(6) + dt*(OP_l_6_c_6_r_ + OP_l_1_c_6_r_*SF(5) + OP_l_3_c_6_r_*SF(4) + OP_l_4_c_6_r_*SF(6) - OP_l_2_c_6_r_*SPP(1) - OP_l_14_c_6_r_*SPP(9) + OP_l_15_c_6_r_*SPP(3) + OP_l_16_c_6_r_*SPP(6)); +nextP(7,9) = OP_l_7_c_9_r_ + OP_l_2_c_9_r_*SF(5) - OP_l_3_c_9_r_*SF(6) + OP_l_4_c_9_r_*SF(4) + OP_l_1_c_9_r_*SPP(1) + OP_l_14_c_9_r_*SPP(5) - OP_l_15_c_9_r_*SPP(8) - OP_l_16_c_9_r_*SPP(2) + dt*(OP_l_7_c_6_r_ + OP_l_2_c_6_r_*SF(5) - OP_l_3_c_6_r_*SF(6) + OP_l_4_c_6_r_*SF(4) + OP_l_1_c_6_r_*SPP(1) + OP_l_14_c_6_r_*SPP(5) - OP_l_15_c_6_r_*SPP(8) - OP_l_16_c_6_r_*SPP(2)); nextP(8,9) = OP_l_8_c_9_r_ + OP_l_5_c_9_r_*dt + dt*(OP_l_8_c_6_r_ + OP_l_5_c_6_r_*dt); nextP(9,9) = OP_l_9_c_9_r_ + OP_l_6_c_9_r_*dt + dt*(OP_l_9_c_6_r_ + OP_l_6_c_6_r_*dt); -nextP(1,10) = OP_l_1_c_10_r_*SPP(6) - OP_l_2_c_10_r_*SPP(5) + OP_l_3_c_10_r_*SPP(8) + OP_l_10_c_10_r_*SPP(23) + OP_l_13_c_10_r_*SPP(19); -nextP(2,10) = OP_l_2_c_10_r_*SPP(7) - OP_l_1_c_10_r_*SPP(3) - OP_l_3_c_10_r_*SPP(9) + OP_l_11_c_10_r_*SPP(23) + OP_l_14_c_10_r_*SPP(18); -nextP(3,10) = OP_l_1_c_10_r_*SPP(15) - OP_l_2_c_10_r_*SPP(4) + OP_l_3_c_10_r_*SPP(14) + OP_l_12_c_10_r_*SPP(23) + OP_l_15_c_10_r_*SPP(17); -nextP(4,10) = OP_l_4_c_10_r_ + OP_l_1_c_10_r_*SPP(2) + OP_l_2_c_10_r_*SPP(20) + OP_l_3_c_10_r_*SPP(16) - OP_l_16_c_10_r_*SPP(22); -nextP(5,10) = OP_l_5_c_10_r_ + OP_l_16_c_10_r_*SF(23) + OP_l_1_c_10_r_*SPP(21) + OP_l_2_c_10_r_*SPP(13) + OP_l_3_c_10_r_*SPP(12); -nextP(6,10) = OP_l_6_c_10_r_ + OP_l_16_c_10_r_*SF(21) - OP_l_1_c_10_r_*SPP(10) + OP_l_2_c_10_r_*SPP(11) + OP_l_3_c_10_r_*SPP(1); -nextP(7,10) = OP_l_7_c_10_r_ + OP_l_4_c_10_r_*dt; -nextP(8,10) = OP_l_8_c_10_r_ + OP_l_5_c_10_r_*dt; -nextP(9,10) = OP_l_9_c_10_r_ + OP_l_6_c_10_r_*dt; -nextP(10,10) = OP_l_10_c_10_r_; -nextP(1,11) = OP_l_1_c_11_r_*SPP(6) - OP_l_2_c_11_r_*SPP(5) + OP_l_3_c_11_r_*SPP(8) + OP_l_10_c_11_r_*SPP(23) + OP_l_13_c_11_r_*SPP(19); -nextP(2,11) = OP_l_2_c_11_r_*SPP(7) - OP_l_1_c_11_r_*SPP(3) - OP_l_3_c_11_r_*SPP(9) + OP_l_11_c_11_r_*SPP(23) + OP_l_14_c_11_r_*SPP(18); -nextP(3,11) = OP_l_1_c_11_r_*SPP(15) - OP_l_2_c_11_r_*SPP(4) + OP_l_3_c_11_r_*SPP(14) + OP_l_12_c_11_r_*SPP(23) + OP_l_15_c_11_r_*SPP(17); -nextP(4,11) = OP_l_4_c_11_r_ + OP_l_1_c_11_r_*SPP(2) + OP_l_2_c_11_r_*SPP(20) + OP_l_3_c_11_r_*SPP(16) - OP_l_16_c_11_r_*SPP(22); -nextP(5,11) = OP_l_5_c_11_r_ + OP_l_16_c_11_r_*SF(23) + OP_l_1_c_11_r_*SPP(21) + OP_l_2_c_11_r_*SPP(13) + OP_l_3_c_11_r_*SPP(12); -nextP(6,11) = OP_l_6_c_11_r_ + OP_l_16_c_11_r_*SF(21) - OP_l_1_c_11_r_*SPP(10) + OP_l_2_c_11_r_*SPP(11) + OP_l_3_c_11_r_*SPP(1); -nextP(7,11) = OP_l_7_c_11_r_ + OP_l_4_c_11_r_*dt; +nextP(1,10) = OP_l_1_c_10_r_ + OP_l_2_c_10_r_*SF(10) + OP_l_3_c_10_r_*SF(12) + OP_l_4_c_10_r_*SF(11) + OP_l_11_c_10_r_*SF(15) + OP_l_12_c_10_r_*SF(16) + OP_l_13_c_10_r_*SPP(11) + dt*(OP_l_1_c_7_r_ + OP_l_2_c_7_r_*SF(10) + OP_l_3_c_7_r_*SF(12) + OP_l_4_c_7_r_*SF(11) + OP_l_11_c_7_r_*SF(15) + OP_l_12_c_7_r_*SF(16) + OP_l_13_c_7_r_*SPP(11)); +nextP(2,10) = OP_l_2_c_10_r_ + OP_l_1_c_10_r_*SF(9) + OP_l_3_c_10_r_*SF(8) + OP_l_4_c_10_r_*SF(12) - OP_l_13_c_10_r_*SF(16) + OP_l_12_c_10_r_*SPP(11) - (OP_l_11_c_10_r_*q0)/2 + dt*(OP_l_2_c_7_r_ + OP_l_1_c_7_r_*SF(9) + OP_l_3_c_7_r_*SF(8) + OP_l_4_c_7_r_*SF(12) - OP_l_13_c_7_r_*SF(16) + OP_l_12_c_7_r_*SPP(11) - (OP_l_11_c_7_r_*q0)/2); +nextP(3,10) = OP_l_3_c_10_r_ + OP_l_1_c_10_r_*SF(7) + OP_l_2_c_10_r_*SF(11) + OP_l_4_c_10_r_*SF(9) + OP_l_13_c_10_r_*SF(15) - OP_l_11_c_10_r_*SPP(11) - (OP_l_12_c_10_r_*q0)/2 + dt*(OP_l_3_c_7_r_ + OP_l_1_c_7_r_*SF(7) + OP_l_2_c_7_r_*SF(11) + OP_l_4_c_7_r_*SF(9) + OP_l_13_c_7_r_*SF(15) - OP_l_11_c_7_r_*SPP(11) - (OP_l_12_c_7_r_*q0)/2); +nextP(4,10) = OP_l_4_c_10_r_ + OP_l_1_c_10_r_*SF(8) + OP_l_2_c_10_r_*SF(7) + OP_l_3_c_10_r_*SF(10) + OP_l_11_c_10_r_*SF(16) - OP_l_12_c_10_r_*SF(15) - (OP_l_13_c_10_r_*q0)/2 + dt*(OP_l_4_c_7_r_ + OP_l_1_c_7_r_*SF(8) + OP_l_2_c_7_r_*SF(7) + OP_l_3_c_7_r_*SF(10) + OP_l_11_c_7_r_*SF(16) - OP_l_12_c_7_r_*SF(15) - (OP_l_13_c_7_r_*q0)/2); +nextP(5,10) = OP_l_5_c_10_r_ + OP_l_1_c_10_r_*SF(6) + OP_l_2_c_10_r_*SF(4) - OP_l_4_c_10_r_*SF(5) + OP_l_3_c_10_r_*SPP(1) + OP_l_14_c_10_r_*SPP(4) + OP_l_15_c_10_r_*SPP(7) - OP_l_16_c_10_r_*SPP(10) + dt*(OP_l_5_c_7_r_ + OP_l_1_c_7_r_*SF(6) + OP_l_2_c_7_r_*SF(4) - OP_l_4_c_7_r_*SF(5) + OP_l_3_c_7_r_*SPP(1) + OP_l_14_c_7_r_*SPP(4) + OP_l_15_c_7_r_*SPP(7) - OP_l_16_c_7_r_*SPP(10)); +nextP(6,10) = OP_l_6_c_10_r_ + OP_l_1_c_10_r_*SF(5) + OP_l_3_c_10_r_*SF(4) + OP_l_4_c_10_r_*SF(6) - OP_l_2_c_10_r_*SPP(1) - OP_l_14_c_10_r_*SPP(9) + OP_l_15_c_10_r_*SPP(3) + OP_l_16_c_10_r_*SPP(6) + dt*(OP_l_6_c_7_r_ + OP_l_1_c_7_r_*SF(5) + OP_l_3_c_7_r_*SF(4) + OP_l_4_c_7_r_*SF(6) - OP_l_2_c_7_r_*SPP(1) - OP_l_14_c_7_r_*SPP(9) + OP_l_15_c_7_r_*SPP(3) + OP_l_16_c_7_r_*SPP(6)); +nextP(7,10) = OP_l_7_c_10_r_ + OP_l_2_c_10_r_*SF(5) - OP_l_3_c_10_r_*SF(6) + OP_l_4_c_10_r_*SF(4) + OP_l_1_c_10_r_*SPP(1) + OP_l_14_c_10_r_*SPP(5) - OP_l_15_c_10_r_*SPP(8) - OP_l_16_c_10_r_*SPP(2) + dt*(OP_l_7_c_7_r_ + OP_l_2_c_7_r_*SF(5) - OP_l_3_c_7_r_*SF(6) + OP_l_4_c_7_r_*SF(4) + OP_l_1_c_7_r_*SPP(1) + OP_l_14_c_7_r_*SPP(5) - OP_l_15_c_7_r_*SPP(8) - OP_l_16_c_7_r_*SPP(2)); +nextP(8,10) = OP_l_8_c_10_r_ + OP_l_5_c_10_r_*dt + dt*(OP_l_8_c_7_r_ + OP_l_5_c_7_r_*dt); +nextP(9,10) = OP_l_9_c_10_r_ + OP_l_6_c_10_r_*dt + dt*(OP_l_9_c_7_r_ + OP_l_6_c_7_r_*dt); +nextP(10,10) = OP_l_10_c_10_r_ + OP_l_7_c_10_r_*dt + dt*(OP_l_10_c_7_r_ + OP_l_7_c_7_r_*dt); +nextP(1,11) = OP_l_1_c_11_r_ + OP_l_2_c_11_r_*SF(10) + OP_l_3_c_11_r_*SF(12) + OP_l_4_c_11_r_*SF(11) + OP_l_11_c_11_r_*SF(15) + OP_l_12_c_11_r_*SF(16) + OP_l_13_c_11_r_*SPP(11); +nextP(2,11) = OP_l_2_c_11_r_ + OP_l_1_c_11_r_*SF(9) + OP_l_3_c_11_r_*SF(8) + OP_l_4_c_11_r_*SF(12) - OP_l_13_c_11_r_*SF(16) + OP_l_12_c_11_r_*SPP(11) - (OP_l_11_c_11_r_*q0)/2; +nextP(3,11) = OP_l_3_c_11_r_ + OP_l_1_c_11_r_*SF(7) + OP_l_2_c_11_r_*SF(11) + OP_l_4_c_11_r_*SF(9) + OP_l_13_c_11_r_*SF(15) - OP_l_11_c_11_r_*SPP(11) - (OP_l_12_c_11_r_*q0)/2; +nextP(4,11) = OP_l_4_c_11_r_ + OP_l_1_c_11_r_*SF(8) + OP_l_2_c_11_r_*SF(7) + OP_l_3_c_11_r_*SF(10) + OP_l_11_c_11_r_*SF(16) - OP_l_12_c_11_r_*SF(15) - (OP_l_13_c_11_r_*q0)/2; +nextP(5,11) = OP_l_5_c_11_r_ + OP_l_1_c_11_r_*SF(6) + OP_l_2_c_11_r_*SF(4) - OP_l_4_c_11_r_*SF(5) + OP_l_3_c_11_r_*SPP(1) + OP_l_14_c_11_r_*SPP(4) + OP_l_15_c_11_r_*SPP(7) - OP_l_16_c_11_r_*SPP(10); +nextP(6,11) = OP_l_6_c_11_r_ + OP_l_1_c_11_r_*SF(5) + OP_l_3_c_11_r_*SF(4) + OP_l_4_c_11_r_*SF(6) - OP_l_2_c_11_r_*SPP(1) - OP_l_14_c_11_r_*SPP(9) + OP_l_15_c_11_r_*SPP(3) + OP_l_16_c_11_r_*SPP(6); +nextP(7,11) = OP_l_7_c_11_r_ + OP_l_2_c_11_r_*SF(5) - OP_l_3_c_11_r_*SF(6) + OP_l_4_c_11_r_*SF(4) + OP_l_1_c_11_r_*SPP(1) + OP_l_14_c_11_r_*SPP(5) - OP_l_15_c_11_r_*SPP(8) - OP_l_16_c_11_r_*SPP(2); nextP(8,11) = OP_l_8_c_11_r_ + OP_l_5_c_11_r_*dt; nextP(9,11) = OP_l_9_c_11_r_ + OP_l_6_c_11_r_*dt; -nextP(10,11) = OP_l_10_c_11_r_; +nextP(10,11) = OP_l_10_c_11_r_ + OP_l_7_c_11_r_*dt; nextP(11,11) = OP_l_11_c_11_r_; -nextP(1,12) = OP_l_1_c_12_r_*SPP(6) - OP_l_2_c_12_r_*SPP(5) + OP_l_3_c_12_r_*SPP(8) + OP_l_10_c_12_r_*SPP(23) + OP_l_13_c_12_r_*SPP(19); -nextP(2,12) = OP_l_2_c_12_r_*SPP(7) - OP_l_1_c_12_r_*SPP(3) - OP_l_3_c_12_r_*SPP(9) + OP_l_11_c_12_r_*SPP(23) + OP_l_14_c_12_r_*SPP(18); -nextP(3,12) = OP_l_1_c_12_r_*SPP(15) - OP_l_2_c_12_r_*SPP(4) + OP_l_3_c_12_r_*SPP(14) + OP_l_12_c_12_r_*SPP(23) + OP_l_15_c_12_r_*SPP(17); -nextP(4,12) = OP_l_4_c_12_r_ + OP_l_1_c_12_r_*SPP(2) + OP_l_2_c_12_r_*SPP(20) + OP_l_3_c_12_r_*SPP(16) - OP_l_16_c_12_r_*SPP(22); -nextP(5,12) = OP_l_5_c_12_r_ + OP_l_16_c_12_r_*SF(23) + OP_l_1_c_12_r_*SPP(21) + OP_l_2_c_12_r_*SPP(13) + OP_l_3_c_12_r_*SPP(12); -nextP(6,12) = OP_l_6_c_12_r_ + OP_l_16_c_12_r_*SF(21) - OP_l_1_c_12_r_*SPP(10) + OP_l_2_c_12_r_*SPP(11) + OP_l_3_c_12_r_*SPP(1); -nextP(7,12) = OP_l_7_c_12_r_ + OP_l_4_c_12_r_*dt; +nextP(1,12) = OP_l_1_c_12_r_ + OP_l_2_c_12_r_*SF(10) + OP_l_3_c_12_r_*SF(12) + OP_l_4_c_12_r_*SF(11) + OP_l_11_c_12_r_*SF(15) + OP_l_12_c_12_r_*SF(16) + OP_l_13_c_12_r_*SPP(11); +nextP(2,12) = OP_l_2_c_12_r_ + OP_l_1_c_12_r_*SF(9) + OP_l_3_c_12_r_*SF(8) + OP_l_4_c_12_r_*SF(12) - OP_l_13_c_12_r_*SF(16) + OP_l_12_c_12_r_*SPP(11) - (OP_l_11_c_12_r_*q0)/2; +nextP(3,12) = OP_l_3_c_12_r_ + OP_l_1_c_12_r_*SF(7) + OP_l_2_c_12_r_*SF(11) + OP_l_4_c_12_r_*SF(9) + OP_l_13_c_12_r_*SF(15) - OP_l_11_c_12_r_*SPP(11) - (OP_l_12_c_12_r_*q0)/2; +nextP(4,12) = OP_l_4_c_12_r_ + OP_l_1_c_12_r_*SF(8) + OP_l_2_c_12_r_*SF(7) + OP_l_3_c_12_r_*SF(10) + OP_l_11_c_12_r_*SF(16) - OP_l_12_c_12_r_*SF(15) - (OP_l_13_c_12_r_*q0)/2; +nextP(5,12) = OP_l_5_c_12_r_ + OP_l_1_c_12_r_*SF(6) + OP_l_2_c_12_r_*SF(4) - OP_l_4_c_12_r_*SF(5) + OP_l_3_c_12_r_*SPP(1) + OP_l_14_c_12_r_*SPP(4) + OP_l_15_c_12_r_*SPP(7) - OP_l_16_c_12_r_*SPP(10); +nextP(6,12) = OP_l_6_c_12_r_ + OP_l_1_c_12_r_*SF(5) + OP_l_3_c_12_r_*SF(4) + OP_l_4_c_12_r_*SF(6) - OP_l_2_c_12_r_*SPP(1) - OP_l_14_c_12_r_*SPP(9) + OP_l_15_c_12_r_*SPP(3) + OP_l_16_c_12_r_*SPP(6); +nextP(7,12) = OP_l_7_c_12_r_ + OP_l_2_c_12_r_*SF(5) - OP_l_3_c_12_r_*SF(6) + OP_l_4_c_12_r_*SF(4) + OP_l_1_c_12_r_*SPP(1) + OP_l_14_c_12_r_*SPP(5) - OP_l_15_c_12_r_*SPP(8) - OP_l_16_c_12_r_*SPP(2); nextP(8,12) = OP_l_8_c_12_r_ + OP_l_5_c_12_r_*dt; nextP(9,12) = OP_l_9_c_12_r_ + OP_l_6_c_12_r_*dt; -nextP(10,12) = OP_l_10_c_12_r_; +nextP(10,12) = OP_l_10_c_12_r_ + OP_l_7_c_12_r_*dt; nextP(11,12) = OP_l_11_c_12_r_; nextP(12,12) = OP_l_12_c_12_r_; -nextP(1,13) = OP_l_1_c_13_r_*SPP(6) - OP_l_2_c_13_r_*SPP(5) + OP_l_3_c_13_r_*SPP(8) + OP_l_10_c_13_r_*SPP(23) + OP_l_13_c_13_r_*SPP(19); -nextP(2,13) = OP_l_2_c_13_r_*SPP(7) - OP_l_1_c_13_r_*SPP(3) - OP_l_3_c_13_r_*SPP(9) + OP_l_11_c_13_r_*SPP(23) + OP_l_14_c_13_r_*SPP(18); -nextP(3,13) = OP_l_1_c_13_r_*SPP(15) - OP_l_2_c_13_r_*SPP(4) + OP_l_3_c_13_r_*SPP(14) + OP_l_12_c_13_r_*SPP(23) + OP_l_15_c_13_r_*SPP(17); -nextP(4,13) = OP_l_4_c_13_r_ + OP_l_1_c_13_r_*SPP(2) + OP_l_2_c_13_r_*SPP(20) + OP_l_3_c_13_r_*SPP(16) - OP_l_16_c_13_r_*SPP(22); -nextP(5,13) = OP_l_5_c_13_r_ + OP_l_16_c_13_r_*SF(23) + OP_l_1_c_13_r_*SPP(21) + OP_l_2_c_13_r_*SPP(13) + OP_l_3_c_13_r_*SPP(12); -nextP(6,13) = OP_l_6_c_13_r_ + OP_l_16_c_13_r_*SF(21) - OP_l_1_c_13_r_*SPP(10) + OP_l_2_c_13_r_*SPP(11) + OP_l_3_c_13_r_*SPP(1); -nextP(7,13) = OP_l_7_c_13_r_ + OP_l_4_c_13_r_*dt; +nextP(1,13) = OP_l_1_c_13_r_ + OP_l_2_c_13_r_*SF(10) + OP_l_3_c_13_r_*SF(12) + OP_l_4_c_13_r_*SF(11) + OP_l_11_c_13_r_*SF(15) + OP_l_12_c_13_r_*SF(16) + OP_l_13_c_13_r_*SPP(11); +nextP(2,13) = OP_l_2_c_13_r_ + OP_l_1_c_13_r_*SF(9) + OP_l_3_c_13_r_*SF(8) + OP_l_4_c_13_r_*SF(12) - OP_l_13_c_13_r_*SF(16) + OP_l_12_c_13_r_*SPP(11) - (OP_l_11_c_13_r_*q0)/2; +nextP(3,13) = OP_l_3_c_13_r_ + OP_l_1_c_13_r_*SF(7) + OP_l_2_c_13_r_*SF(11) + OP_l_4_c_13_r_*SF(9) + OP_l_13_c_13_r_*SF(15) - OP_l_11_c_13_r_*SPP(11) - (OP_l_12_c_13_r_*q0)/2; +nextP(4,13) = OP_l_4_c_13_r_ + OP_l_1_c_13_r_*SF(8) + OP_l_2_c_13_r_*SF(7) + OP_l_3_c_13_r_*SF(10) + OP_l_11_c_13_r_*SF(16) - OP_l_12_c_13_r_*SF(15) - (OP_l_13_c_13_r_*q0)/2; +nextP(5,13) = OP_l_5_c_13_r_ + OP_l_1_c_13_r_*SF(6) + OP_l_2_c_13_r_*SF(4) - OP_l_4_c_13_r_*SF(5) + OP_l_3_c_13_r_*SPP(1) + OP_l_14_c_13_r_*SPP(4) + OP_l_15_c_13_r_*SPP(7) - OP_l_16_c_13_r_*SPP(10); +nextP(6,13) = OP_l_6_c_13_r_ + OP_l_1_c_13_r_*SF(5) + OP_l_3_c_13_r_*SF(4) + OP_l_4_c_13_r_*SF(6) - OP_l_2_c_13_r_*SPP(1) - OP_l_14_c_13_r_*SPP(9) + OP_l_15_c_13_r_*SPP(3) + OP_l_16_c_13_r_*SPP(6); +nextP(7,13) = OP_l_7_c_13_r_ + OP_l_2_c_13_r_*SF(5) - OP_l_3_c_13_r_*SF(6) + OP_l_4_c_13_r_*SF(4) + OP_l_1_c_13_r_*SPP(1) + OP_l_14_c_13_r_*SPP(5) - OP_l_15_c_13_r_*SPP(8) - OP_l_16_c_13_r_*SPP(2); nextP(8,13) = OP_l_8_c_13_r_ + OP_l_5_c_13_r_*dt; nextP(9,13) = OP_l_9_c_13_r_ + OP_l_6_c_13_r_*dt; -nextP(10,13) = OP_l_10_c_13_r_; +nextP(10,13) = OP_l_10_c_13_r_ + OP_l_7_c_13_r_*dt; nextP(11,13) = OP_l_11_c_13_r_; nextP(12,13) = OP_l_12_c_13_r_; nextP(13,13) = OP_l_13_c_13_r_; -nextP(1,14) = OP_l_1_c_14_r_*SPP(6) - OP_l_2_c_14_r_*SPP(5) + OP_l_3_c_14_r_*SPP(8) + OP_l_10_c_14_r_*SPP(23) + OP_l_13_c_14_r_*SPP(19); -nextP(2,14) = OP_l_2_c_14_r_*SPP(7) - OP_l_1_c_14_r_*SPP(3) - OP_l_3_c_14_r_*SPP(9) + OP_l_11_c_14_r_*SPP(23) + OP_l_14_c_14_r_*SPP(18); -nextP(3,14) = OP_l_1_c_14_r_*SPP(15) - OP_l_2_c_14_r_*SPP(4) + OP_l_3_c_14_r_*SPP(14) + OP_l_12_c_14_r_*SPP(23) + OP_l_15_c_14_r_*SPP(17); -nextP(4,14) = OP_l_4_c_14_r_ + OP_l_1_c_14_r_*SPP(2) + OP_l_2_c_14_r_*SPP(20) + OP_l_3_c_14_r_*SPP(16) - OP_l_16_c_14_r_*SPP(22); -nextP(5,14) = OP_l_5_c_14_r_ + OP_l_16_c_14_r_*SF(23) + OP_l_1_c_14_r_*SPP(21) + OP_l_2_c_14_r_*SPP(13) + OP_l_3_c_14_r_*SPP(12); -nextP(6,14) = OP_l_6_c_14_r_ + OP_l_16_c_14_r_*SF(21) - OP_l_1_c_14_r_*SPP(10) + OP_l_2_c_14_r_*SPP(11) + OP_l_3_c_14_r_*SPP(1); -nextP(7,14) = OP_l_7_c_14_r_ + OP_l_4_c_14_r_*dt; +nextP(1,14) = OP_l_1_c_14_r_ + OP_l_2_c_14_r_*SF(10) + OP_l_3_c_14_r_*SF(12) + OP_l_4_c_14_r_*SF(11) + OP_l_11_c_14_r_*SF(15) + OP_l_12_c_14_r_*SF(16) + OP_l_13_c_14_r_*SPP(11); +nextP(2,14) = OP_l_2_c_14_r_ + OP_l_1_c_14_r_*SF(9) + OP_l_3_c_14_r_*SF(8) + OP_l_4_c_14_r_*SF(12) - OP_l_13_c_14_r_*SF(16) + OP_l_12_c_14_r_*SPP(11) - (OP_l_11_c_14_r_*q0)/2; +nextP(3,14) = OP_l_3_c_14_r_ + OP_l_1_c_14_r_*SF(7) + OP_l_2_c_14_r_*SF(11) + OP_l_4_c_14_r_*SF(9) + OP_l_13_c_14_r_*SF(15) - OP_l_11_c_14_r_*SPP(11) - (OP_l_12_c_14_r_*q0)/2; +nextP(4,14) = OP_l_4_c_14_r_ + OP_l_1_c_14_r_*SF(8) + OP_l_2_c_14_r_*SF(7) + OP_l_3_c_14_r_*SF(10) + OP_l_11_c_14_r_*SF(16) - OP_l_12_c_14_r_*SF(15) - (OP_l_13_c_14_r_*q0)/2; +nextP(5,14) = OP_l_5_c_14_r_ + OP_l_1_c_14_r_*SF(6) + OP_l_2_c_14_r_*SF(4) - OP_l_4_c_14_r_*SF(5) + OP_l_3_c_14_r_*SPP(1) + OP_l_14_c_14_r_*SPP(4) + OP_l_15_c_14_r_*SPP(7) - OP_l_16_c_14_r_*SPP(10); +nextP(6,14) = OP_l_6_c_14_r_ + OP_l_1_c_14_r_*SF(5) + OP_l_3_c_14_r_*SF(4) + OP_l_4_c_14_r_*SF(6) - OP_l_2_c_14_r_*SPP(1) - OP_l_14_c_14_r_*SPP(9) + OP_l_15_c_14_r_*SPP(3) + OP_l_16_c_14_r_*SPP(6); +nextP(7,14) = OP_l_7_c_14_r_ + OP_l_2_c_14_r_*SF(5) - OP_l_3_c_14_r_*SF(6) + OP_l_4_c_14_r_*SF(4) + OP_l_1_c_14_r_*SPP(1) + OP_l_14_c_14_r_*SPP(5) - OP_l_15_c_14_r_*SPP(8) - OP_l_16_c_14_r_*SPP(2); nextP(8,14) = OP_l_8_c_14_r_ + OP_l_5_c_14_r_*dt; nextP(9,14) = OP_l_9_c_14_r_ + OP_l_6_c_14_r_*dt; -nextP(10,14) = OP_l_10_c_14_r_; +nextP(10,14) = OP_l_10_c_14_r_ + OP_l_7_c_14_r_*dt; nextP(11,14) = OP_l_11_c_14_r_; nextP(12,14) = OP_l_12_c_14_r_; nextP(13,14) = OP_l_13_c_14_r_; nextP(14,14) = OP_l_14_c_14_r_; -nextP(1,15) = OP_l_1_c_15_r_*SPP(6) - OP_l_2_c_15_r_*SPP(5) + OP_l_3_c_15_r_*SPP(8) + OP_l_10_c_15_r_*SPP(23) + OP_l_13_c_15_r_*SPP(19); -nextP(2,15) = OP_l_2_c_15_r_*SPP(7) - OP_l_1_c_15_r_*SPP(3) - OP_l_3_c_15_r_*SPP(9) + OP_l_11_c_15_r_*SPP(23) + OP_l_14_c_15_r_*SPP(18); -nextP(3,15) = OP_l_1_c_15_r_*SPP(15) - OP_l_2_c_15_r_*SPP(4) + OP_l_3_c_15_r_*SPP(14) + OP_l_12_c_15_r_*SPP(23) + OP_l_15_c_15_r_*SPP(17); -nextP(4,15) = OP_l_4_c_15_r_ + OP_l_1_c_15_r_*SPP(2) + OP_l_2_c_15_r_*SPP(20) + OP_l_3_c_15_r_*SPP(16) - OP_l_16_c_15_r_*SPP(22); -nextP(5,15) = OP_l_5_c_15_r_ + OP_l_16_c_15_r_*SF(23) + OP_l_1_c_15_r_*SPP(21) + OP_l_2_c_15_r_*SPP(13) + OP_l_3_c_15_r_*SPP(12); -nextP(6,15) = OP_l_6_c_15_r_ + OP_l_16_c_15_r_*SF(21) - OP_l_1_c_15_r_*SPP(10) + OP_l_2_c_15_r_*SPP(11) + OP_l_3_c_15_r_*SPP(1); -nextP(7,15) = OP_l_7_c_15_r_ + OP_l_4_c_15_r_*dt; +nextP(1,15) = OP_l_1_c_15_r_ + OP_l_2_c_15_r_*SF(10) + OP_l_3_c_15_r_*SF(12) + OP_l_4_c_15_r_*SF(11) + OP_l_11_c_15_r_*SF(15) + OP_l_12_c_15_r_*SF(16) + OP_l_13_c_15_r_*SPP(11); +nextP(2,15) = OP_l_2_c_15_r_ + OP_l_1_c_15_r_*SF(9) + OP_l_3_c_15_r_*SF(8) + OP_l_4_c_15_r_*SF(12) - OP_l_13_c_15_r_*SF(16) + OP_l_12_c_15_r_*SPP(11) - (OP_l_11_c_15_r_*q0)/2; +nextP(3,15) = OP_l_3_c_15_r_ + OP_l_1_c_15_r_*SF(7) + OP_l_2_c_15_r_*SF(11) + OP_l_4_c_15_r_*SF(9) + OP_l_13_c_15_r_*SF(15) - OP_l_11_c_15_r_*SPP(11) - (OP_l_12_c_15_r_*q0)/2; +nextP(4,15) = OP_l_4_c_15_r_ + OP_l_1_c_15_r_*SF(8) + OP_l_2_c_15_r_*SF(7) + OP_l_3_c_15_r_*SF(10) + OP_l_11_c_15_r_*SF(16) - OP_l_12_c_15_r_*SF(15) - (OP_l_13_c_15_r_*q0)/2; +nextP(5,15) = OP_l_5_c_15_r_ + OP_l_1_c_15_r_*SF(6) + OP_l_2_c_15_r_*SF(4) - OP_l_4_c_15_r_*SF(5) + OP_l_3_c_15_r_*SPP(1) + OP_l_14_c_15_r_*SPP(4) + OP_l_15_c_15_r_*SPP(7) - OP_l_16_c_15_r_*SPP(10); +nextP(6,15) = OP_l_6_c_15_r_ + OP_l_1_c_15_r_*SF(5) + OP_l_3_c_15_r_*SF(4) + OP_l_4_c_15_r_*SF(6) - OP_l_2_c_15_r_*SPP(1) - OP_l_14_c_15_r_*SPP(9) + OP_l_15_c_15_r_*SPP(3) + OP_l_16_c_15_r_*SPP(6); +nextP(7,15) = OP_l_7_c_15_r_ + OP_l_2_c_15_r_*SF(5) - OP_l_3_c_15_r_*SF(6) + OP_l_4_c_15_r_*SF(4) + OP_l_1_c_15_r_*SPP(1) + OP_l_14_c_15_r_*SPP(5) - OP_l_15_c_15_r_*SPP(8) - OP_l_16_c_15_r_*SPP(2); nextP(8,15) = OP_l_8_c_15_r_ + OP_l_5_c_15_r_*dt; nextP(9,15) = OP_l_9_c_15_r_ + OP_l_6_c_15_r_*dt; -nextP(10,15) = OP_l_10_c_15_r_; +nextP(10,15) = OP_l_10_c_15_r_ + OP_l_7_c_15_r_*dt; nextP(11,15) = OP_l_11_c_15_r_; nextP(12,15) = OP_l_12_c_15_r_; nextP(13,15) = OP_l_13_c_15_r_; nextP(14,15) = OP_l_14_c_15_r_; nextP(15,15) = OP_l_15_c_15_r_; -nextP(1,16) = OP_l_1_c_16_r_*SPP(6) - OP_l_2_c_16_r_*SPP(5) + OP_l_3_c_16_r_*SPP(8) + OP_l_10_c_16_r_*SPP(23) + OP_l_13_c_16_r_*SPP(19); -nextP(2,16) = OP_l_2_c_16_r_*SPP(7) - OP_l_1_c_16_r_*SPP(3) - OP_l_3_c_16_r_*SPP(9) + OP_l_11_c_16_r_*SPP(23) + OP_l_14_c_16_r_*SPP(18); -nextP(3,16) = OP_l_1_c_16_r_*SPP(15) - OP_l_2_c_16_r_*SPP(4) + OP_l_3_c_16_r_*SPP(14) + OP_l_12_c_16_r_*SPP(23) + OP_l_15_c_16_r_*SPP(17); -nextP(4,16) = OP_l_4_c_16_r_ + OP_l_1_c_16_r_*SPP(2) + OP_l_2_c_16_r_*SPP(20) + OP_l_3_c_16_r_*SPP(16) - OP_l_16_c_16_r_*SPP(22); -nextP(5,16) = OP_l_5_c_16_r_ + OP_l_16_c_16_r_*SF(23) + OP_l_1_c_16_r_*SPP(21) + OP_l_2_c_16_r_*SPP(13) + OP_l_3_c_16_r_*SPP(12); -nextP(6,16) = OP_l_6_c_16_r_ + OP_l_16_c_16_r_*SF(21) - OP_l_1_c_16_r_*SPP(10) + OP_l_2_c_16_r_*SPP(11) + OP_l_3_c_16_r_*SPP(1); -nextP(7,16) = OP_l_7_c_16_r_ + OP_l_4_c_16_r_*dt; +nextP(1,16) = OP_l_1_c_16_r_ + OP_l_2_c_16_r_*SF(10) + OP_l_3_c_16_r_*SF(12) + OP_l_4_c_16_r_*SF(11) + OP_l_11_c_16_r_*SF(15) + OP_l_12_c_16_r_*SF(16) + OP_l_13_c_16_r_*SPP(11); +nextP(2,16) = OP_l_2_c_16_r_ + OP_l_1_c_16_r_*SF(9) + OP_l_3_c_16_r_*SF(8) + OP_l_4_c_16_r_*SF(12) - OP_l_13_c_16_r_*SF(16) + OP_l_12_c_16_r_*SPP(11) - (OP_l_11_c_16_r_*q0)/2; +nextP(3,16) = OP_l_3_c_16_r_ + OP_l_1_c_16_r_*SF(7) + OP_l_2_c_16_r_*SF(11) + OP_l_4_c_16_r_*SF(9) + OP_l_13_c_16_r_*SF(15) - OP_l_11_c_16_r_*SPP(11) - (OP_l_12_c_16_r_*q0)/2; +nextP(4,16) = OP_l_4_c_16_r_ + OP_l_1_c_16_r_*SF(8) + OP_l_2_c_16_r_*SF(7) + OP_l_3_c_16_r_*SF(10) + OP_l_11_c_16_r_*SF(16) - OP_l_12_c_16_r_*SF(15) - (OP_l_13_c_16_r_*q0)/2; +nextP(5,16) = OP_l_5_c_16_r_ + OP_l_1_c_16_r_*SF(6) + OP_l_2_c_16_r_*SF(4) - OP_l_4_c_16_r_*SF(5) + OP_l_3_c_16_r_*SPP(1) + OP_l_14_c_16_r_*SPP(4) + OP_l_15_c_16_r_*SPP(7) - OP_l_16_c_16_r_*SPP(10); +nextP(6,16) = OP_l_6_c_16_r_ + OP_l_1_c_16_r_*SF(5) + OP_l_3_c_16_r_*SF(4) + OP_l_4_c_16_r_*SF(6) - OP_l_2_c_16_r_*SPP(1) - OP_l_14_c_16_r_*SPP(9) + OP_l_15_c_16_r_*SPP(3) + OP_l_16_c_16_r_*SPP(6); +nextP(7,16) = OP_l_7_c_16_r_ + OP_l_2_c_16_r_*SF(5) - OP_l_3_c_16_r_*SF(6) + OP_l_4_c_16_r_*SF(4) + OP_l_1_c_16_r_*SPP(1) + OP_l_14_c_16_r_*SPP(5) - OP_l_15_c_16_r_*SPP(8) - OP_l_16_c_16_r_*SPP(2); nextP(8,16) = OP_l_8_c_16_r_ + OP_l_5_c_16_r_*dt; nextP(9,16) = OP_l_9_c_16_r_ + OP_l_6_c_16_r_*dt; -nextP(10,16) = OP_l_10_c_16_r_; +nextP(10,16) = OP_l_10_c_16_r_ + OP_l_7_c_16_r_*dt; nextP(11,16) = OP_l_11_c_16_r_; nextP(12,16) = OP_l_12_c_16_r_; nextP(13,16) = OP_l_13_c_16_r_; nextP(14,16) = OP_l_14_c_16_r_; nextP(15,16) = OP_l_15_c_16_r_; nextP(16,16) = OP_l_16_c_16_r_; -nextP(1,17) = OP_l_1_c_17_r_*SPP(6) - OP_l_2_c_17_r_*SPP(5) + OP_l_3_c_17_r_*SPP(8) + OP_l_10_c_17_r_*SPP(23) + OP_l_13_c_17_r_*SPP(19); -nextP(2,17) = OP_l_2_c_17_r_*SPP(7) - OP_l_1_c_17_r_*SPP(3) - OP_l_3_c_17_r_*SPP(9) + OP_l_11_c_17_r_*SPP(23) + OP_l_14_c_17_r_*SPP(18); -nextP(3,17) = OP_l_1_c_17_r_*SPP(15) - OP_l_2_c_17_r_*SPP(4) + OP_l_3_c_17_r_*SPP(14) + OP_l_12_c_17_r_*SPP(23) + OP_l_15_c_17_r_*SPP(17); -nextP(4,17) = OP_l_4_c_17_r_ + OP_l_1_c_17_r_*SPP(2) + OP_l_2_c_17_r_*SPP(20) + OP_l_3_c_17_r_*SPP(16) - OP_l_16_c_17_r_*SPP(22); -nextP(5,17) = OP_l_5_c_17_r_ + OP_l_16_c_17_r_*SF(23) + OP_l_1_c_17_r_*SPP(21) + OP_l_2_c_17_r_*SPP(13) + OP_l_3_c_17_r_*SPP(12); -nextP(6,17) = OP_l_6_c_17_r_ + OP_l_16_c_17_r_*SF(21) - OP_l_1_c_17_r_*SPP(10) + OP_l_2_c_17_r_*SPP(11) + OP_l_3_c_17_r_*SPP(1); -nextP(7,17) = OP_l_7_c_17_r_ + OP_l_4_c_17_r_*dt; +nextP(1,17) = OP_l_1_c_17_r_ + OP_l_2_c_17_r_*SF(10) + OP_l_3_c_17_r_*SF(12) + OP_l_4_c_17_r_*SF(11) + OP_l_11_c_17_r_*SF(15) + OP_l_12_c_17_r_*SF(16) + OP_l_13_c_17_r_*SPP(11); +nextP(2,17) = OP_l_2_c_17_r_ + OP_l_1_c_17_r_*SF(9) + OP_l_3_c_17_r_*SF(8) + OP_l_4_c_17_r_*SF(12) - OP_l_13_c_17_r_*SF(16) + OP_l_12_c_17_r_*SPP(11) - (OP_l_11_c_17_r_*q0)/2; +nextP(3,17) = OP_l_3_c_17_r_ + OP_l_1_c_17_r_*SF(7) + OP_l_2_c_17_r_*SF(11) + OP_l_4_c_17_r_*SF(9) + OP_l_13_c_17_r_*SF(15) - OP_l_11_c_17_r_*SPP(11) - (OP_l_12_c_17_r_*q0)/2; +nextP(4,17) = OP_l_4_c_17_r_ + OP_l_1_c_17_r_*SF(8) + OP_l_2_c_17_r_*SF(7) + OP_l_3_c_17_r_*SF(10) + OP_l_11_c_17_r_*SF(16) - OP_l_12_c_17_r_*SF(15) - (OP_l_13_c_17_r_*q0)/2; +nextP(5,17) = OP_l_5_c_17_r_ + OP_l_1_c_17_r_*SF(6) + OP_l_2_c_17_r_*SF(4) - OP_l_4_c_17_r_*SF(5) + OP_l_3_c_17_r_*SPP(1) + OP_l_14_c_17_r_*SPP(4) + OP_l_15_c_17_r_*SPP(7) - OP_l_16_c_17_r_*SPP(10); +nextP(6,17) = OP_l_6_c_17_r_ + OP_l_1_c_17_r_*SF(5) + OP_l_3_c_17_r_*SF(4) + OP_l_4_c_17_r_*SF(6) - OP_l_2_c_17_r_*SPP(1) - OP_l_14_c_17_r_*SPP(9) + OP_l_15_c_17_r_*SPP(3) + OP_l_16_c_17_r_*SPP(6); +nextP(7,17) = OP_l_7_c_17_r_ + OP_l_2_c_17_r_*SF(5) - OP_l_3_c_17_r_*SF(6) + OP_l_4_c_17_r_*SF(4) + OP_l_1_c_17_r_*SPP(1) + OP_l_14_c_17_r_*SPP(5) - OP_l_15_c_17_r_*SPP(8) - OP_l_16_c_17_r_*SPP(2); nextP(8,17) = OP_l_8_c_17_r_ + OP_l_5_c_17_r_*dt; nextP(9,17) = OP_l_9_c_17_r_ + OP_l_6_c_17_r_*dt; -nextP(10,17) = OP_l_10_c_17_r_; +nextP(10,17) = OP_l_10_c_17_r_ + OP_l_7_c_17_r_*dt; nextP(11,17) = OP_l_11_c_17_r_; nextP(12,17) = OP_l_12_c_17_r_; nextP(13,17) = OP_l_13_c_17_r_; @@ -226,16 +214,16 @@ nextP(14,17) = OP_l_14_c_17_r_; nextP(15,17) = OP_l_15_c_17_r_; nextP(16,17) = OP_l_16_c_17_r_; nextP(17,17) = OP_l_17_c_17_r_; -nextP(1,18) = OP_l_1_c_18_r_*SPP(6) - OP_l_2_c_18_r_*SPP(5) + OP_l_3_c_18_r_*SPP(8) + OP_l_10_c_18_r_*SPP(23) + OP_l_13_c_18_r_*SPP(19); -nextP(2,18) = OP_l_2_c_18_r_*SPP(7) - OP_l_1_c_18_r_*SPP(3) - OP_l_3_c_18_r_*SPP(9) + OP_l_11_c_18_r_*SPP(23) + OP_l_14_c_18_r_*SPP(18); -nextP(3,18) = OP_l_1_c_18_r_*SPP(15) - OP_l_2_c_18_r_*SPP(4) + OP_l_3_c_18_r_*SPP(14) + OP_l_12_c_18_r_*SPP(23) + OP_l_15_c_18_r_*SPP(17); -nextP(4,18) = OP_l_4_c_18_r_ + OP_l_1_c_18_r_*SPP(2) + OP_l_2_c_18_r_*SPP(20) + OP_l_3_c_18_r_*SPP(16) - OP_l_16_c_18_r_*SPP(22); -nextP(5,18) = OP_l_5_c_18_r_ + OP_l_16_c_18_r_*SF(23) + OP_l_1_c_18_r_*SPP(21) + OP_l_2_c_18_r_*SPP(13) + OP_l_3_c_18_r_*SPP(12); -nextP(6,18) = OP_l_6_c_18_r_ + OP_l_16_c_18_r_*SF(21) - OP_l_1_c_18_r_*SPP(10) + OP_l_2_c_18_r_*SPP(11) + OP_l_3_c_18_r_*SPP(1); -nextP(7,18) = OP_l_7_c_18_r_ + OP_l_4_c_18_r_*dt; +nextP(1,18) = OP_l_1_c_18_r_ + OP_l_2_c_18_r_*SF(10) + OP_l_3_c_18_r_*SF(12) + OP_l_4_c_18_r_*SF(11) + OP_l_11_c_18_r_*SF(15) + OP_l_12_c_18_r_*SF(16) + OP_l_13_c_18_r_*SPP(11); +nextP(2,18) = OP_l_2_c_18_r_ + OP_l_1_c_18_r_*SF(9) + OP_l_3_c_18_r_*SF(8) + OP_l_4_c_18_r_*SF(12) - OP_l_13_c_18_r_*SF(16) + OP_l_12_c_18_r_*SPP(11) - (OP_l_11_c_18_r_*q0)/2; +nextP(3,18) = OP_l_3_c_18_r_ + OP_l_1_c_18_r_*SF(7) + OP_l_2_c_18_r_*SF(11) + OP_l_4_c_18_r_*SF(9) + OP_l_13_c_18_r_*SF(15) - OP_l_11_c_18_r_*SPP(11) - (OP_l_12_c_18_r_*q0)/2; +nextP(4,18) = OP_l_4_c_18_r_ + OP_l_1_c_18_r_*SF(8) + OP_l_2_c_18_r_*SF(7) + OP_l_3_c_18_r_*SF(10) + OP_l_11_c_18_r_*SF(16) - OP_l_12_c_18_r_*SF(15) - (OP_l_13_c_18_r_*q0)/2; +nextP(5,18) = OP_l_5_c_18_r_ + OP_l_1_c_18_r_*SF(6) + OP_l_2_c_18_r_*SF(4) - OP_l_4_c_18_r_*SF(5) + OP_l_3_c_18_r_*SPP(1) + OP_l_14_c_18_r_*SPP(4) + OP_l_15_c_18_r_*SPP(7) - OP_l_16_c_18_r_*SPP(10); +nextP(6,18) = OP_l_6_c_18_r_ + OP_l_1_c_18_r_*SF(5) + OP_l_3_c_18_r_*SF(4) + OP_l_4_c_18_r_*SF(6) - OP_l_2_c_18_r_*SPP(1) - OP_l_14_c_18_r_*SPP(9) + OP_l_15_c_18_r_*SPP(3) + OP_l_16_c_18_r_*SPP(6); +nextP(7,18) = OP_l_7_c_18_r_ + OP_l_2_c_18_r_*SF(5) - OP_l_3_c_18_r_*SF(6) + OP_l_4_c_18_r_*SF(4) + OP_l_1_c_18_r_*SPP(1) + OP_l_14_c_18_r_*SPP(5) - OP_l_15_c_18_r_*SPP(8) - OP_l_16_c_18_r_*SPP(2); nextP(8,18) = OP_l_8_c_18_r_ + OP_l_5_c_18_r_*dt; nextP(9,18) = OP_l_9_c_18_r_ + OP_l_6_c_18_r_*dt; -nextP(10,18) = OP_l_10_c_18_r_; +nextP(10,18) = OP_l_10_c_18_r_ + OP_l_7_c_18_r_*dt; nextP(11,18) = OP_l_11_c_18_r_; nextP(12,18) = OP_l_12_c_18_r_; nextP(13,18) = OP_l_13_c_18_r_; @@ -244,16 +232,16 @@ nextP(15,18) = OP_l_15_c_18_r_; nextP(16,18) = OP_l_16_c_18_r_; nextP(17,18) = OP_l_17_c_18_r_; nextP(18,18) = OP_l_18_c_18_r_; -nextP(1,19) = OP_l_1_c_19_r_*SPP(6) - OP_l_2_c_19_r_*SPP(5) + OP_l_3_c_19_r_*SPP(8) + OP_l_10_c_19_r_*SPP(23) + OP_l_13_c_19_r_*SPP(19); -nextP(2,19) = OP_l_2_c_19_r_*SPP(7) - OP_l_1_c_19_r_*SPP(3) - OP_l_3_c_19_r_*SPP(9) + OP_l_11_c_19_r_*SPP(23) + OP_l_14_c_19_r_*SPP(18); -nextP(3,19) = OP_l_1_c_19_r_*SPP(15) - OP_l_2_c_19_r_*SPP(4) + OP_l_3_c_19_r_*SPP(14) + OP_l_12_c_19_r_*SPP(23) + OP_l_15_c_19_r_*SPP(17); -nextP(4,19) = OP_l_4_c_19_r_ + OP_l_1_c_19_r_*SPP(2) + OP_l_2_c_19_r_*SPP(20) + OP_l_3_c_19_r_*SPP(16) - OP_l_16_c_19_r_*SPP(22); -nextP(5,19) = OP_l_5_c_19_r_ + OP_l_16_c_19_r_*SF(23) + OP_l_1_c_19_r_*SPP(21) + OP_l_2_c_19_r_*SPP(13) + OP_l_3_c_19_r_*SPP(12); -nextP(6,19) = OP_l_6_c_19_r_ + OP_l_16_c_19_r_*SF(21) - OP_l_1_c_19_r_*SPP(10) + OP_l_2_c_19_r_*SPP(11) + OP_l_3_c_19_r_*SPP(1); -nextP(7,19) = OP_l_7_c_19_r_ + OP_l_4_c_19_r_*dt; +nextP(1,19) = OP_l_1_c_19_r_ + OP_l_2_c_19_r_*SF(10) + OP_l_3_c_19_r_*SF(12) + OP_l_4_c_19_r_*SF(11) + OP_l_11_c_19_r_*SF(15) + OP_l_12_c_19_r_*SF(16) + OP_l_13_c_19_r_*SPP(11); +nextP(2,19) = OP_l_2_c_19_r_ + OP_l_1_c_19_r_*SF(9) + OP_l_3_c_19_r_*SF(8) + OP_l_4_c_19_r_*SF(12) - OP_l_13_c_19_r_*SF(16) + OP_l_12_c_19_r_*SPP(11) - (OP_l_11_c_19_r_*q0)/2; +nextP(3,19) = OP_l_3_c_19_r_ + OP_l_1_c_19_r_*SF(7) + OP_l_2_c_19_r_*SF(11) + OP_l_4_c_19_r_*SF(9) + OP_l_13_c_19_r_*SF(15) - OP_l_11_c_19_r_*SPP(11) - (OP_l_12_c_19_r_*q0)/2; +nextP(4,19) = OP_l_4_c_19_r_ + OP_l_1_c_19_r_*SF(8) + OP_l_2_c_19_r_*SF(7) + OP_l_3_c_19_r_*SF(10) + OP_l_11_c_19_r_*SF(16) - OP_l_12_c_19_r_*SF(15) - (OP_l_13_c_19_r_*q0)/2; +nextP(5,19) = OP_l_5_c_19_r_ + OP_l_1_c_19_r_*SF(6) + OP_l_2_c_19_r_*SF(4) - OP_l_4_c_19_r_*SF(5) + OP_l_3_c_19_r_*SPP(1) + OP_l_14_c_19_r_*SPP(4) + OP_l_15_c_19_r_*SPP(7) - OP_l_16_c_19_r_*SPP(10); +nextP(6,19) = OP_l_6_c_19_r_ + OP_l_1_c_19_r_*SF(5) + OP_l_3_c_19_r_*SF(4) + OP_l_4_c_19_r_*SF(6) - OP_l_2_c_19_r_*SPP(1) - OP_l_14_c_19_r_*SPP(9) + OP_l_15_c_19_r_*SPP(3) + OP_l_16_c_19_r_*SPP(6); +nextP(7,19) = OP_l_7_c_19_r_ + OP_l_2_c_19_r_*SF(5) - OP_l_3_c_19_r_*SF(6) + OP_l_4_c_19_r_*SF(4) + OP_l_1_c_19_r_*SPP(1) + OP_l_14_c_19_r_*SPP(5) - OP_l_15_c_19_r_*SPP(8) - OP_l_16_c_19_r_*SPP(2); nextP(8,19) = OP_l_8_c_19_r_ + OP_l_5_c_19_r_*dt; nextP(9,19) = OP_l_9_c_19_r_ + OP_l_6_c_19_r_*dt; -nextP(10,19) = OP_l_10_c_19_r_; +nextP(10,19) = OP_l_10_c_19_r_ + OP_l_7_c_19_r_*dt; nextP(11,19) = OP_l_11_c_19_r_; nextP(12,19) = OP_l_12_c_19_r_; nextP(13,19) = OP_l_13_c_19_r_; @@ -263,16 +251,16 @@ nextP(16,19) = OP_l_16_c_19_r_; nextP(17,19) = OP_l_17_c_19_r_; nextP(18,19) = OP_l_18_c_19_r_; nextP(19,19) = OP_l_19_c_19_r_; -nextP(1,20) = OP_l_1_c_20_r_*SPP(6) - OP_l_2_c_20_r_*SPP(5) + OP_l_3_c_20_r_*SPP(8) + OP_l_10_c_20_r_*SPP(23) + OP_l_13_c_20_r_*SPP(19); -nextP(2,20) = OP_l_2_c_20_r_*SPP(7) - OP_l_1_c_20_r_*SPP(3) - OP_l_3_c_20_r_*SPP(9) + OP_l_11_c_20_r_*SPP(23) + OP_l_14_c_20_r_*SPP(18); -nextP(3,20) = OP_l_1_c_20_r_*SPP(15) - OP_l_2_c_20_r_*SPP(4) + OP_l_3_c_20_r_*SPP(14) + OP_l_12_c_20_r_*SPP(23) + OP_l_15_c_20_r_*SPP(17); -nextP(4,20) = OP_l_4_c_20_r_ + OP_l_1_c_20_r_*SPP(2) + OP_l_2_c_20_r_*SPP(20) + OP_l_3_c_20_r_*SPP(16) - OP_l_16_c_20_r_*SPP(22); -nextP(5,20) = OP_l_5_c_20_r_ + OP_l_16_c_20_r_*SF(23) + OP_l_1_c_20_r_*SPP(21) + OP_l_2_c_20_r_*SPP(13) + OP_l_3_c_20_r_*SPP(12); -nextP(6,20) = OP_l_6_c_20_r_ + OP_l_16_c_20_r_*SF(21) - OP_l_1_c_20_r_*SPP(10) + OP_l_2_c_20_r_*SPP(11) + OP_l_3_c_20_r_*SPP(1); -nextP(7,20) = OP_l_7_c_20_r_ + OP_l_4_c_20_r_*dt; +nextP(1,20) = OP_l_1_c_20_r_ + OP_l_2_c_20_r_*SF(10) + OP_l_3_c_20_r_*SF(12) + OP_l_4_c_20_r_*SF(11) + OP_l_11_c_20_r_*SF(15) + OP_l_12_c_20_r_*SF(16) + OP_l_13_c_20_r_*SPP(11); +nextP(2,20) = OP_l_2_c_20_r_ + OP_l_1_c_20_r_*SF(9) + OP_l_3_c_20_r_*SF(8) + OP_l_4_c_20_r_*SF(12) - OP_l_13_c_20_r_*SF(16) + OP_l_12_c_20_r_*SPP(11) - (OP_l_11_c_20_r_*q0)/2; +nextP(3,20) = OP_l_3_c_20_r_ + OP_l_1_c_20_r_*SF(7) + OP_l_2_c_20_r_*SF(11) + OP_l_4_c_20_r_*SF(9) + OP_l_13_c_20_r_*SF(15) - OP_l_11_c_20_r_*SPP(11) - (OP_l_12_c_20_r_*q0)/2; +nextP(4,20) = OP_l_4_c_20_r_ + OP_l_1_c_20_r_*SF(8) + OP_l_2_c_20_r_*SF(7) + OP_l_3_c_20_r_*SF(10) + OP_l_11_c_20_r_*SF(16) - OP_l_12_c_20_r_*SF(15) - (OP_l_13_c_20_r_*q0)/2; +nextP(5,20) = OP_l_5_c_20_r_ + OP_l_1_c_20_r_*SF(6) + OP_l_2_c_20_r_*SF(4) - OP_l_4_c_20_r_*SF(5) + OP_l_3_c_20_r_*SPP(1) + OP_l_14_c_20_r_*SPP(4) + OP_l_15_c_20_r_*SPP(7) - OP_l_16_c_20_r_*SPP(10); +nextP(6,20) = OP_l_6_c_20_r_ + OP_l_1_c_20_r_*SF(5) + OP_l_3_c_20_r_*SF(4) + OP_l_4_c_20_r_*SF(6) - OP_l_2_c_20_r_*SPP(1) - OP_l_14_c_20_r_*SPP(9) + OP_l_15_c_20_r_*SPP(3) + OP_l_16_c_20_r_*SPP(6); +nextP(7,20) = OP_l_7_c_20_r_ + OP_l_2_c_20_r_*SF(5) - OP_l_3_c_20_r_*SF(6) + OP_l_4_c_20_r_*SF(4) + OP_l_1_c_20_r_*SPP(1) + OP_l_14_c_20_r_*SPP(5) - OP_l_15_c_20_r_*SPP(8) - OP_l_16_c_20_r_*SPP(2); nextP(8,20) = OP_l_8_c_20_r_ + OP_l_5_c_20_r_*dt; nextP(9,20) = OP_l_9_c_20_r_ + OP_l_6_c_20_r_*dt; -nextP(10,20) = OP_l_10_c_20_r_; +nextP(10,20) = OP_l_10_c_20_r_ + OP_l_7_c_20_r_*dt; nextP(11,20) = OP_l_11_c_20_r_; nextP(12,20) = OP_l_12_c_20_r_; nextP(13,20) = OP_l_13_c_20_r_; @@ -283,16 +271,16 @@ nextP(17,20) = OP_l_17_c_20_r_; nextP(18,20) = OP_l_18_c_20_r_; nextP(19,20) = OP_l_19_c_20_r_; nextP(20,20) = OP_l_20_c_20_r_; -nextP(1,21) = OP_l_1_c_21_r_*SPP(6) - OP_l_2_c_21_r_*SPP(5) + OP_l_3_c_21_r_*SPP(8) + OP_l_10_c_21_r_*SPP(23) + OP_l_13_c_21_r_*SPP(19); -nextP(2,21) = OP_l_2_c_21_r_*SPP(7) - OP_l_1_c_21_r_*SPP(3) - OP_l_3_c_21_r_*SPP(9) + OP_l_11_c_21_r_*SPP(23) + OP_l_14_c_21_r_*SPP(18); -nextP(3,21) = OP_l_1_c_21_r_*SPP(15) - OP_l_2_c_21_r_*SPP(4) + OP_l_3_c_21_r_*SPP(14) + OP_l_12_c_21_r_*SPP(23) + OP_l_15_c_21_r_*SPP(17); -nextP(4,21) = OP_l_4_c_21_r_ + OP_l_1_c_21_r_*SPP(2) + OP_l_2_c_21_r_*SPP(20) + OP_l_3_c_21_r_*SPP(16) - OP_l_16_c_21_r_*SPP(22); -nextP(5,21) = OP_l_5_c_21_r_ + OP_l_16_c_21_r_*SF(23) + OP_l_1_c_21_r_*SPP(21) + OP_l_2_c_21_r_*SPP(13) + OP_l_3_c_21_r_*SPP(12); -nextP(6,21) = OP_l_6_c_21_r_ + OP_l_16_c_21_r_*SF(21) - OP_l_1_c_21_r_*SPP(10) + OP_l_2_c_21_r_*SPP(11) + OP_l_3_c_21_r_*SPP(1); -nextP(7,21) = OP_l_7_c_21_r_ + OP_l_4_c_21_r_*dt; +nextP(1,21) = OP_l_1_c_21_r_ + OP_l_2_c_21_r_*SF(10) + OP_l_3_c_21_r_*SF(12) + OP_l_4_c_21_r_*SF(11) + OP_l_11_c_21_r_*SF(15) + OP_l_12_c_21_r_*SF(16) + OP_l_13_c_21_r_*SPP(11); +nextP(2,21) = OP_l_2_c_21_r_ + OP_l_1_c_21_r_*SF(9) + OP_l_3_c_21_r_*SF(8) + OP_l_4_c_21_r_*SF(12) - OP_l_13_c_21_r_*SF(16) + OP_l_12_c_21_r_*SPP(11) - (OP_l_11_c_21_r_*q0)/2; +nextP(3,21) = OP_l_3_c_21_r_ + OP_l_1_c_21_r_*SF(7) + OP_l_2_c_21_r_*SF(11) + OP_l_4_c_21_r_*SF(9) + OP_l_13_c_21_r_*SF(15) - OP_l_11_c_21_r_*SPP(11) - (OP_l_12_c_21_r_*q0)/2; +nextP(4,21) = OP_l_4_c_21_r_ + OP_l_1_c_21_r_*SF(8) + OP_l_2_c_21_r_*SF(7) + OP_l_3_c_21_r_*SF(10) + OP_l_11_c_21_r_*SF(16) - OP_l_12_c_21_r_*SF(15) - (OP_l_13_c_21_r_*q0)/2; +nextP(5,21) = OP_l_5_c_21_r_ + OP_l_1_c_21_r_*SF(6) + OP_l_2_c_21_r_*SF(4) - OP_l_4_c_21_r_*SF(5) + OP_l_3_c_21_r_*SPP(1) + OP_l_14_c_21_r_*SPP(4) + OP_l_15_c_21_r_*SPP(7) - OP_l_16_c_21_r_*SPP(10); +nextP(6,21) = OP_l_6_c_21_r_ + OP_l_1_c_21_r_*SF(5) + OP_l_3_c_21_r_*SF(4) + OP_l_4_c_21_r_*SF(6) - OP_l_2_c_21_r_*SPP(1) - OP_l_14_c_21_r_*SPP(9) + OP_l_15_c_21_r_*SPP(3) + OP_l_16_c_21_r_*SPP(6); +nextP(7,21) = OP_l_7_c_21_r_ + OP_l_2_c_21_r_*SF(5) - OP_l_3_c_21_r_*SF(6) + OP_l_4_c_21_r_*SF(4) + OP_l_1_c_21_r_*SPP(1) + OP_l_14_c_21_r_*SPP(5) - OP_l_15_c_21_r_*SPP(8) - OP_l_16_c_21_r_*SPP(2); nextP(8,21) = OP_l_8_c_21_r_ + OP_l_5_c_21_r_*dt; nextP(9,21) = OP_l_9_c_21_r_ + OP_l_6_c_21_r_*dt; -nextP(10,21) = OP_l_10_c_21_r_; +nextP(10,21) = OP_l_10_c_21_r_ + OP_l_7_c_21_r_*dt; nextP(11,21) = OP_l_11_c_21_r_; nextP(12,21) = OP_l_12_c_21_r_; nextP(13,21) = OP_l_13_c_21_r_; @@ -304,16 +292,16 @@ nextP(18,21) = OP_l_18_c_21_r_; nextP(19,21) = OP_l_19_c_21_r_; nextP(20,21) = OP_l_20_c_21_r_; nextP(21,21) = OP_l_21_c_21_r_; -nextP(1,22) = OP_l_1_c_22_r_*SPP(6) - OP_l_2_c_22_r_*SPP(5) + OP_l_3_c_22_r_*SPP(8) + OP_l_10_c_22_r_*SPP(23) + OP_l_13_c_22_r_*SPP(19); -nextP(2,22) = OP_l_2_c_22_r_*SPP(7) - OP_l_1_c_22_r_*SPP(3) - OP_l_3_c_22_r_*SPP(9) + OP_l_11_c_22_r_*SPP(23) + OP_l_14_c_22_r_*SPP(18); -nextP(3,22) = OP_l_1_c_22_r_*SPP(15) - OP_l_2_c_22_r_*SPP(4) + OP_l_3_c_22_r_*SPP(14) + OP_l_12_c_22_r_*SPP(23) + OP_l_15_c_22_r_*SPP(17); -nextP(4,22) = OP_l_4_c_22_r_ + OP_l_1_c_22_r_*SPP(2) + OP_l_2_c_22_r_*SPP(20) + OP_l_3_c_22_r_*SPP(16) - OP_l_16_c_22_r_*SPP(22); -nextP(5,22) = OP_l_5_c_22_r_ + OP_l_16_c_22_r_*SF(23) + OP_l_1_c_22_r_*SPP(21) + OP_l_2_c_22_r_*SPP(13) + OP_l_3_c_22_r_*SPP(12); -nextP(6,22) = OP_l_6_c_22_r_ + OP_l_16_c_22_r_*SF(21) - OP_l_1_c_22_r_*SPP(10) + OP_l_2_c_22_r_*SPP(11) + OP_l_3_c_22_r_*SPP(1); -nextP(7,22) = OP_l_7_c_22_r_ + OP_l_4_c_22_r_*dt; +nextP(1,22) = OP_l_1_c_22_r_ + OP_l_2_c_22_r_*SF(10) + OP_l_3_c_22_r_*SF(12) + OP_l_4_c_22_r_*SF(11) + OP_l_11_c_22_r_*SF(15) + OP_l_12_c_22_r_*SF(16) + OP_l_13_c_22_r_*SPP(11); +nextP(2,22) = OP_l_2_c_22_r_ + OP_l_1_c_22_r_*SF(9) + OP_l_3_c_22_r_*SF(8) + OP_l_4_c_22_r_*SF(12) - OP_l_13_c_22_r_*SF(16) + OP_l_12_c_22_r_*SPP(11) - (OP_l_11_c_22_r_*q0)/2; +nextP(3,22) = OP_l_3_c_22_r_ + OP_l_1_c_22_r_*SF(7) + OP_l_2_c_22_r_*SF(11) + OP_l_4_c_22_r_*SF(9) + OP_l_13_c_22_r_*SF(15) - OP_l_11_c_22_r_*SPP(11) - (OP_l_12_c_22_r_*q0)/2; +nextP(4,22) = OP_l_4_c_22_r_ + OP_l_1_c_22_r_*SF(8) + OP_l_2_c_22_r_*SF(7) + OP_l_3_c_22_r_*SF(10) + OP_l_11_c_22_r_*SF(16) - OP_l_12_c_22_r_*SF(15) - (OP_l_13_c_22_r_*q0)/2; +nextP(5,22) = OP_l_5_c_22_r_ + OP_l_1_c_22_r_*SF(6) + OP_l_2_c_22_r_*SF(4) - OP_l_4_c_22_r_*SF(5) + OP_l_3_c_22_r_*SPP(1) + OP_l_14_c_22_r_*SPP(4) + OP_l_15_c_22_r_*SPP(7) - OP_l_16_c_22_r_*SPP(10); +nextP(6,22) = OP_l_6_c_22_r_ + OP_l_1_c_22_r_*SF(5) + OP_l_3_c_22_r_*SF(4) + OP_l_4_c_22_r_*SF(6) - OP_l_2_c_22_r_*SPP(1) - OP_l_14_c_22_r_*SPP(9) + OP_l_15_c_22_r_*SPP(3) + OP_l_16_c_22_r_*SPP(6); +nextP(7,22) = OP_l_7_c_22_r_ + OP_l_2_c_22_r_*SF(5) - OP_l_3_c_22_r_*SF(6) + OP_l_4_c_22_r_*SF(4) + OP_l_1_c_22_r_*SPP(1) + OP_l_14_c_22_r_*SPP(5) - OP_l_15_c_22_r_*SPP(8) - OP_l_16_c_22_r_*SPP(2); nextP(8,22) = OP_l_8_c_22_r_ + OP_l_5_c_22_r_*dt; nextP(9,22) = OP_l_9_c_22_r_ + OP_l_6_c_22_r_*dt; -nextP(10,22) = OP_l_10_c_22_r_; +nextP(10,22) = OP_l_10_c_22_r_ + OP_l_7_c_22_r_*dt; nextP(11,22) = OP_l_11_c_22_r_; nextP(12,22) = OP_l_12_c_22_r_; nextP(13,22) = OP_l_13_c_22_r_; @@ -326,16 +314,16 @@ nextP(19,22) = OP_l_19_c_22_r_; nextP(20,22) = OP_l_20_c_22_r_; nextP(21,22) = OP_l_21_c_22_r_; nextP(22,22) = OP_l_22_c_22_r_; -nextP(1,23) = OP_l_1_c_23_r_*SPP(6) - OP_l_2_c_23_r_*SPP(5) + OP_l_3_c_23_r_*SPP(8) + OP_l_10_c_23_r_*SPP(23) + OP_l_13_c_23_r_*SPP(19); -nextP(2,23) = OP_l_2_c_23_r_*SPP(7) - OP_l_1_c_23_r_*SPP(3) - OP_l_3_c_23_r_*SPP(9) + OP_l_11_c_23_r_*SPP(23) + OP_l_14_c_23_r_*SPP(18); -nextP(3,23) = OP_l_1_c_23_r_*SPP(15) - OP_l_2_c_23_r_*SPP(4) + OP_l_3_c_23_r_*SPP(14) + OP_l_12_c_23_r_*SPP(23) + OP_l_15_c_23_r_*SPP(17); -nextP(4,23) = OP_l_4_c_23_r_ + OP_l_1_c_23_r_*SPP(2) + OP_l_2_c_23_r_*SPP(20) + OP_l_3_c_23_r_*SPP(16) - OP_l_16_c_23_r_*SPP(22); -nextP(5,23) = OP_l_5_c_23_r_ + OP_l_16_c_23_r_*SF(23) + OP_l_1_c_23_r_*SPP(21) + OP_l_2_c_23_r_*SPP(13) + OP_l_3_c_23_r_*SPP(12); -nextP(6,23) = OP_l_6_c_23_r_ + OP_l_16_c_23_r_*SF(21) - OP_l_1_c_23_r_*SPP(10) + OP_l_2_c_23_r_*SPP(11) + OP_l_3_c_23_r_*SPP(1); -nextP(7,23) = OP_l_7_c_23_r_ + OP_l_4_c_23_r_*dt; +nextP(1,23) = OP_l_1_c_23_r_ + OP_l_2_c_23_r_*SF(10) + OP_l_3_c_23_r_*SF(12) + OP_l_4_c_23_r_*SF(11) + OP_l_11_c_23_r_*SF(15) + OP_l_12_c_23_r_*SF(16) + OP_l_13_c_23_r_*SPP(11); +nextP(2,23) = OP_l_2_c_23_r_ + OP_l_1_c_23_r_*SF(9) + OP_l_3_c_23_r_*SF(8) + OP_l_4_c_23_r_*SF(12) - OP_l_13_c_23_r_*SF(16) + OP_l_12_c_23_r_*SPP(11) - (OP_l_11_c_23_r_*q0)/2; +nextP(3,23) = OP_l_3_c_23_r_ + OP_l_1_c_23_r_*SF(7) + OP_l_2_c_23_r_*SF(11) + OP_l_4_c_23_r_*SF(9) + OP_l_13_c_23_r_*SF(15) - OP_l_11_c_23_r_*SPP(11) - (OP_l_12_c_23_r_*q0)/2; +nextP(4,23) = OP_l_4_c_23_r_ + OP_l_1_c_23_r_*SF(8) + OP_l_2_c_23_r_*SF(7) + OP_l_3_c_23_r_*SF(10) + OP_l_11_c_23_r_*SF(16) - OP_l_12_c_23_r_*SF(15) - (OP_l_13_c_23_r_*q0)/2; +nextP(5,23) = OP_l_5_c_23_r_ + OP_l_1_c_23_r_*SF(6) + OP_l_2_c_23_r_*SF(4) - OP_l_4_c_23_r_*SF(5) + OP_l_3_c_23_r_*SPP(1) + OP_l_14_c_23_r_*SPP(4) + OP_l_15_c_23_r_*SPP(7) - OP_l_16_c_23_r_*SPP(10); +nextP(6,23) = OP_l_6_c_23_r_ + OP_l_1_c_23_r_*SF(5) + OP_l_3_c_23_r_*SF(4) + OP_l_4_c_23_r_*SF(6) - OP_l_2_c_23_r_*SPP(1) - OP_l_14_c_23_r_*SPP(9) + OP_l_15_c_23_r_*SPP(3) + OP_l_16_c_23_r_*SPP(6); +nextP(7,23) = OP_l_7_c_23_r_ + OP_l_2_c_23_r_*SF(5) - OP_l_3_c_23_r_*SF(6) + OP_l_4_c_23_r_*SF(4) + OP_l_1_c_23_r_*SPP(1) + OP_l_14_c_23_r_*SPP(5) - OP_l_15_c_23_r_*SPP(8) - OP_l_16_c_23_r_*SPP(2); nextP(8,23) = OP_l_8_c_23_r_ + OP_l_5_c_23_r_*dt; nextP(9,23) = OP_l_9_c_23_r_ + OP_l_6_c_23_r_*dt; -nextP(10,23) = OP_l_10_c_23_r_; +nextP(10,23) = OP_l_10_c_23_r_ + OP_l_7_c_23_r_*dt; nextP(11,23) = OP_l_11_c_23_r_; nextP(12,23) = OP_l_12_c_23_r_; nextP(13,23) = OP_l_13_c_23_r_; @@ -349,16 +337,16 @@ nextP(20,23) = OP_l_20_c_23_r_; nextP(21,23) = OP_l_21_c_23_r_; nextP(22,23) = OP_l_22_c_23_r_; nextP(23,23) = OP_l_23_c_23_r_; -nextP(1,24) = OP_l_1_c_24_r_*SPP(6) - OP_l_2_c_24_r_*SPP(5) + OP_l_3_c_24_r_*SPP(8) + OP_l_10_c_24_r_*SPP(23) + OP_l_13_c_24_r_*SPP(19); -nextP(2,24) = OP_l_2_c_24_r_*SPP(7) - OP_l_1_c_24_r_*SPP(3) - OP_l_3_c_24_r_*SPP(9) + OP_l_11_c_24_r_*SPP(23) + OP_l_14_c_24_r_*SPP(18); -nextP(3,24) = OP_l_1_c_24_r_*SPP(15) - OP_l_2_c_24_r_*SPP(4) + OP_l_3_c_24_r_*SPP(14) + OP_l_12_c_24_r_*SPP(23) + OP_l_15_c_24_r_*SPP(17); -nextP(4,24) = OP_l_4_c_24_r_ + OP_l_1_c_24_r_*SPP(2) + OP_l_2_c_24_r_*SPP(20) + OP_l_3_c_24_r_*SPP(16) - OP_l_16_c_24_r_*SPP(22); -nextP(5,24) = OP_l_5_c_24_r_ + OP_l_16_c_24_r_*SF(23) + OP_l_1_c_24_r_*SPP(21) + OP_l_2_c_24_r_*SPP(13) + OP_l_3_c_24_r_*SPP(12); -nextP(6,24) = OP_l_6_c_24_r_ + OP_l_16_c_24_r_*SF(21) - OP_l_1_c_24_r_*SPP(10) + OP_l_2_c_24_r_*SPP(11) + OP_l_3_c_24_r_*SPP(1); -nextP(7,24) = OP_l_7_c_24_r_ + OP_l_4_c_24_r_*dt; +nextP(1,24) = OP_l_1_c_24_r_ + OP_l_2_c_24_r_*SF(10) + OP_l_3_c_24_r_*SF(12) + OP_l_4_c_24_r_*SF(11) + OP_l_11_c_24_r_*SF(15) + OP_l_12_c_24_r_*SF(16) + OP_l_13_c_24_r_*SPP(11); +nextP(2,24) = OP_l_2_c_24_r_ + OP_l_1_c_24_r_*SF(9) + OP_l_3_c_24_r_*SF(8) + OP_l_4_c_24_r_*SF(12) - OP_l_13_c_24_r_*SF(16) + OP_l_12_c_24_r_*SPP(11) - (OP_l_11_c_24_r_*q0)/2; +nextP(3,24) = OP_l_3_c_24_r_ + OP_l_1_c_24_r_*SF(7) + OP_l_2_c_24_r_*SF(11) + OP_l_4_c_24_r_*SF(9) + OP_l_13_c_24_r_*SF(15) - OP_l_11_c_24_r_*SPP(11) - (OP_l_12_c_24_r_*q0)/2; +nextP(4,24) = OP_l_4_c_24_r_ + OP_l_1_c_24_r_*SF(8) + OP_l_2_c_24_r_*SF(7) + OP_l_3_c_24_r_*SF(10) + OP_l_11_c_24_r_*SF(16) - OP_l_12_c_24_r_*SF(15) - (OP_l_13_c_24_r_*q0)/2; +nextP(5,24) = OP_l_5_c_24_r_ + OP_l_1_c_24_r_*SF(6) + OP_l_2_c_24_r_*SF(4) - OP_l_4_c_24_r_*SF(5) + OP_l_3_c_24_r_*SPP(1) + OP_l_14_c_24_r_*SPP(4) + OP_l_15_c_24_r_*SPP(7) - OP_l_16_c_24_r_*SPP(10); +nextP(6,24) = OP_l_6_c_24_r_ + OP_l_1_c_24_r_*SF(5) + OP_l_3_c_24_r_*SF(4) + OP_l_4_c_24_r_*SF(6) - OP_l_2_c_24_r_*SPP(1) - OP_l_14_c_24_r_*SPP(9) + OP_l_15_c_24_r_*SPP(3) + OP_l_16_c_24_r_*SPP(6); +nextP(7,24) = OP_l_7_c_24_r_ + OP_l_2_c_24_r_*SF(5) - OP_l_3_c_24_r_*SF(6) + OP_l_4_c_24_r_*SF(4) + OP_l_1_c_24_r_*SPP(1) + OP_l_14_c_24_r_*SPP(5) - OP_l_15_c_24_r_*SPP(8) - OP_l_16_c_24_r_*SPP(2); nextP(8,24) = OP_l_8_c_24_r_ + OP_l_5_c_24_r_*dt; nextP(9,24) = OP_l_9_c_24_r_ + OP_l_6_c_24_r_*dt; -nextP(10,24) = OP_l_10_c_24_r_; +nextP(10,24) = OP_l_10_c_24_r_ + OP_l_7_c_24_r_*dt; nextP(11,24) = OP_l_11_c_24_r_; nextP(12,24) = OP_l_12_c_24_r_; nextP(13,24) = OP_l_13_c_24_r_; @@ -381,357 +369,374 @@ SH_TAS(2) = (SH_TAS(1)*(2*ve - 2*vwe))/2; SH_TAS(3) = (SH_TAS(1)*(2*vn - 2*vwn))/2; H_TAS = zeros(1,24); -H_TAS(1,4) = SH_TAS(3); -H_TAS(1,5) = SH_TAS(2); -H_TAS(1,6) = vd*SH_TAS(1); +H_TAS(1,5) = SH_TAS(3); +H_TAS(1,6) = SH_TAS(2); +H_TAS(1,7) = vd*SH_TAS(1); H_TAS(1,23) = -SH_TAS(3); H_TAS(1,24) = -SH_TAS(2); SK_TAS = zeros(2,1); -SK_TAS(1) = 1/(R_TAS + SH_TAS(3)*(OP_l_4_c_4_r_*SH_TAS(3) + OP_l_5_c_4_r_*SH_TAS(2) - OP_l_23_c_4_r_*SH_TAS(3) - OP_l_24_c_4_r_*SH_TAS(2) + OP_l_6_c_4_r_*vd*SH_TAS(1)) + SH_TAS(2)*(OP_l_4_c_5_r_*SH_TAS(3) + OP_l_5_c_5_r_*SH_TAS(2) - OP_l_23_c_5_r_*SH_TAS(3) - OP_l_24_c_5_r_*SH_TAS(2) + OP_l_6_c_5_r_*vd*SH_TAS(1)) - SH_TAS(3)*(OP_l_4_c_23_r_*SH_TAS(3) + OP_l_5_c_23_r_*SH_TAS(2) - OP_l_23_c_23_r_*SH_TAS(3) - OP_l_24_c_23_r_*SH_TAS(2) + OP_l_6_c_23_r_*vd*SH_TAS(1)) - SH_TAS(2)*(OP_l_4_c_24_r_*SH_TAS(3) + OP_l_5_c_24_r_*SH_TAS(2) - OP_l_23_c_24_r_*SH_TAS(3) - OP_l_24_c_24_r_*SH_TAS(2) + OP_l_6_c_24_r_*vd*SH_TAS(1)) + vd*SH_TAS(1)*(OP_l_4_c_6_r_*SH_TAS(3) + OP_l_5_c_6_r_*SH_TAS(2) - OP_l_23_c_6_r_*SH_TAS(3) - OP_l_24_c_6_r_*SH_TAS(2) + OP_l_6_c_6_r_*vd*SH_TAS(1))); +SK_TAS(1) = 1/(R_TAS + SH_TAS(3)*(OP_l_5_c_5_r_*SH_TAS(3) + OP_l_6_c_5_r_*SH_TAS(2) - OP_l_23_c_5_r_*SH_TAS(3) - OP_l_24_c_5_r_*SH_TAS(2) + OP_l_7_c_5_r_*vd*SH_TAS(1)) + SH_TAS(2)*(OP_l_5_c_6_r_*SH_TAS(3) + OP_l_6_c_6_r_*SH_TAS(2) - OP_l_23_c_6_r_*SH_TAS(3) - OP_l_24_c_6_r_*SH_TAS(2) + OP_l_7_c_6_r_*vd*SH_TAS(1)) - SH_TAS(3)*(OP_l_5_c_23_r_*SH_TAS(3) + OP_l_6_c_23_r_*SH_TAS(2) - OP_l_23_c_23_r_*SH_TAS(3) - OP_l_24_c_23_r_*SH_TAS(2) + OP_l_7_c_23_r_*vd*SH_TAS(1)) - SH_TAS(2)*(OP_l_5_c_24_r_*SH_TAS(3) + OP_l_6_c_24_r_*SH_TAS(2) - OP_l_23_c_24_r_*SH_TAS(3) - OP_l_24_c_24_r_*SH_TAS(2) + OP_l_7_c_24_r_*vd*SH_TAS(1)) + vd*SH_TAS(1)*(OP_l_5_c_7_r_*SH_TAS(3) + OP_l_6_c_7_r_*SH_TAS(2) - OP_l_23_c_7_r_*SH_TAS(3) - OP_l_24_c_7_r_*SH_TAS(2) + OP_l_7_c_7_r_*vd*SH_TAS(1))); SK_TAS(2) = SH_TAS(2); Kfusion = zeros(24,1); Kfusion = zeros(1,1); -Kfusion(1) = SK_TAS(1)*(OP_l_1_c_4_r_*SH_TAS(3) - OP_l_1_c_23_r_*SH_TAS(3) + OP_l_1_c_5_r_*SK_TAS(2) - OP_l_1_c_24_r_*SK_TAS(2) + OP_l_1_c_6_r_*vd*SH_TAS(1)); -Kfusion(2) = SK_TAS(1)*(OP_l_2_c_4_r_*SH_TAS(3) - OP_l_2_c_23_r_*SH_TAS(3) + OP_l_2_c_5_r_*SK_TAS(2) - OP_l_2_c_24_r_*SK_TAS(2) + OP_l_2_c_6_r_*vd*SH_TAS(1)); -Kfusion(3) = SK_TAS(1)*(OP_l_3_c_4_r_*SH_TAS(3) - OP_l_3_c_23_r_*SH_TAS(3) + OP_l_3_c_5_r_*SK_TAS(2) - OP_l_3_c_24_r_*SK_TAS(2) + OP_l_3_c_6_r_*vd*SH_TAS(1)); -Kfusion(4) = SK_TAS(1)*(OP_l_4_c_4_r_*SH_TAS(3) - OP_l_4_c_23_r_*SH_TAS(3) + OP_l_4_c_5_r_*SK_TAS(2) - OP_l_4_c_24_r_*SK_TAS(2) + OP_l_4_c_6_r_*vd*SH_TAS(1)); -Kfusion(5) = SK_TAS(1)*(OP_l_5_c_4_r_*SH_TAS(3) - OP_l_5_c_23_r_*SH_TAS(3) + OP_l_5_c_5_r_*SK_TAS(2) - OP_l_5_c_24_r_*SK_TAS(2) + OP_l_5_c_6_r_*vd*SH_TAS(1)); -Kfusion(6) = SK_TAS(1)*(OP_l_6_c_4_r_*SH_TAS(3) - OP_l_6_c_23_r_*SH_TAS(3) + OP_l_6_c_5_r_*SK_TAS(2) - OP_l_6_c_24_r_*SK_TAS(2) + OP_l_6_c_6_r_*vd*SH_TAS(1)); -Kfusion(7) = SK_TAS(1)*(OP_l_7_c_4_r_*SH_TAS(3) - OP_l_7_c_23_r_*SH_TAS(3) + OP_l_7_c_5_r_*SK_TAS(2) - OP_l_7_c_24_r_*SK_TAS(2) + OP_l_7_c_6_r_*vd*SH_TAS(1)); -Kfusion(8) = SK_TAS(1)*(OP_l_8_c_4_r_*SH_TAS(3) - OP_l_8_c_23_r_*SH_TAS(3) + OP_l_8_c_5_r_*SK_TAS(2) - OP_l_8_c_24_r_*SK_TAS(2) + OP_l_8_c_6_r_*vd*SH_TAS(1)); -Kfusion(9) = SK_TAS(1)*(OP_l_9_c_4_r_*SH_TAS(3) - OP_l_9_c_23_r_*SH_TAS(3) + OP_l_9_c_5_r_*SK_TAS(2) - OP_l_9_c_24_r_*SK_TAS(2) + OP_l_9_c_6_r_*vd*SH_TAS(1)); -Kfusion(10) = SK_TAS(1)*(OP_l_10_c_4_r_*SH_TAS(3) - OP_l_10_c_23_r_*SH_TAS(3) + OP_l_10_c_5_r_*SK_TAS(2) - OP_l_10_c_24_r_*SK_TAS(2) + OP_l_10_c_6_r_*vd*SH_TAS(1)); -Kfusion(11) = SK_TAS(1)*(OP_l_11_c_4_r_*SH_TAS(3) - OP_l_11_c_23_r_*SH_TAS(3) + OP_l_11_c_5_r_*SK_TAS(2) - OP_l_11_c_24_r_*SK_TAS(2) + OP_l_11_c_6_r_*vd*SH_TAS(1)); -Kfusion(12) = SK_TAS(1)*(OP_l_12_c_4_r_*SH_TAS(3) - OP_l_12_c_23_r_*SH_TAS(3) + OP_l_12_c_5_r_*SK_TAS(2) - OP_l_12_c_24_r_*SK_TAS(2) + OP_l_12_c_6_r_*vd*SH_TAS(1)); -Kfusion(13) = SK_TAS(1)*(OP_l_13_c_4_r_*SH_TAS(3) - OP_l_13_c_23_r_*SH_TAS(3) + OP_l_13_c_5_r_*SK_TAS(2) - OP_l_13_c_24_r_*SK_TAS(2) + OP_l_13_c_6_r_*vd*SH_TAS(1)); -Kfusion(14) = SK_TAS(1)*(OP_l_14_c_4_r_*SH_TAS(3) - OP_l_14_c_23_r_*SH_TAS(3) + OP_l_14_c_5_r_*SK_TAS(2) - OP_l_14_c_24_r_*SK_TAS(2) + OP_l_14_c_6_r_*vd*SH_TAS(1)); -Kfusion(15) = SK_TAS(1)*(OP_l_15_c_4_r_*SH_TAS(3) - OP_l_15_c_23_r_*SH_TAS(3) + OP_l_15_c_5_r_*SK_TAS(2) - OP_l_15_c_24_r_*SK_TAS(2) + OP_l_15_c_6_r_*vd*SH_TAS(1)); -Kfusion(16) = SK_TAS(1)*(OP_l_16_c_4_r_*SH_TAS(3) - OP_l_16_c_23_r_*SH_TAS(3) + OP_l_16_c_5_r_*SK_TAS(2) - OP_l_16_c_24_r_*SK_TAS(2) + OP_l_16_c_6_r_*vd*SH_TAS(1)); -Kfusion(17) = SK_TAS(1)*(OP_l_17_c_4_r_*SH_TAS(3) - OP_l_17_c_23_r_*SH_TAS(3) + OP_l_17_c_5_r_*SK_TAS(2) - OP_l_17_c_24_r_*SK_TAS(2) + OP_l_17_c_6_r_*vd*SH_TAS(1)); -Kfusion(18) = SK_TAS(1)*(OP_l_18_c_4_r_*SH_TAS(3) - OP_l_18_c_23_r_*SH_TAS(3) + OP_l_18_c_5_r_*SK_TAS(2) - OP_l_18_c_24_r_*SK_TAS(2) + OP_l_18_c_6_r_*vd*SH_TAS(1)); -Kfusion(19) = SK_TAS(1)*(OP_l_19_c_4_r_*SH_TAS(3) - OP_l_19_c_23_r_*SH_TAS(3) + OP_l_19_c_5_r_*SK_TAS(2) - OP_l_19_c_24_r_*SK_TAS(2) + OP_l_19_c_6_r_*vd*SH_TAS(1)); -Kfusion(20) = SK_TAS(1)*(OP_l_20_c_4_r_*SH_TAS(3) - OP_l_20_c_23_r_*SH_TAS(3) + OP_l_20_c_5_r_*SK_TAS(2) - OP_l_20_c_24_r_*SK_TAS(2) + OP_l_20_c_6_r_*vd*SH_TAS(1)); -Kfusion(21) = SK_TAS(1)*(OP_l_21_c_4_r_*SH_TAS(3) - OP_l_21_c_23_r_*SH_TAS(3) + OP_l_21_c_5_r_*SK_TAS(2) - OP_l_21_c_24_r_*SK_TAS(2) + OP_l_21_c_6_r_*vd*SH_TAS(1)); -Kfusion(22) = SK_TAS(1)*(OP_l_22_c_4_r_*SH_TAS(3) - OP_l_22_c_23_r_*SH_TAS(3) + OP_l_22_c_5_r_*SK_TAS(2) - OP_l_22_c_24_r_*SK_TAS(2) + OP_l_22_c_6_r_*vd*SH_TAS(1)); -Kfusion(23) = SK_TAS(1)*(OP_l_23_c_4_r_*SH_TAS(3) - OP_l_23_c_23_r_*SH_TAS(3) + OP_l_23_c_5_r_*SK_TAS(2) - OP_l_23_c_24_r_*SK_TAS(2) + OP_l_23_c_6_r_*vd*SH_TAS(1)); -Kfusion(24) = SK_TAS(1)*(OP_l_24_c_4_r_*SH_TAS(3) - OP_l_24_c_23_r_*SH_TAS(3) + OP_l_24_c_5_r_*SK_TAS(2) - OP_l_24_c_24_r_*SK_TAS(2) + OP_l_24_c_6_r_*vd*SH_TAS(1)); +Kfusion(1) = SK_TAS(1)*(OP_l_1_c_5_r_*SH_TAS(3) - OP_l_1_c_23_r_*SH_TAS(3) + OP_l_1_c_6_r_*SK_TAS(2) - OP_l_1_c_24_r_*SK_TAS(2) + OP_l_1_c_7_r_*vd*SH_TAS(1)); +Kfusion(2) = SK_TAS(1)*(OP_l_2_c_5_r_*SH_TAS(3) - OP_l_2_c_23_r_*SH_TAS(3) + OP_l_2_c_6_r_*SK_TAS(2) - OP_l_2_c_24_r_*SK_TAS(2) + OP_l_2_c_7_r_*vd*SH_TAS(1)); +Kfusion(3) = SK_TAS(1)*(OP_l_3_c_5_r_*SH_TAS(3) - OP_l_3_c_23_r_*SH_TAS(3) + OP_l_3_c_6_r_*SK_TAS(2) - OP_l_3_c_24_r_*SK_TAS(2) + OP_l_3_c_7_r_*vd*SH_TAS(1)); +Kfusion(4) = SK_TAS(1)*(OP_l_4_c_5_r_*SH_TAS(3) - OP_l_4_c_23_r_*SH_TAS(3) + OP_l_4_c_6_r_*SK_TAS(2) - OP_l_4_c_24_r_*SK_TAS(2) + OP_l_4_c_7_r_*vd*SH_TAS(1)); +Kfusion(5) = SK_TAS(1)*(OP_l_5_c_5_r_*SH_TAS(3) - OP_l_5_c_23_r_*SH_TAS(3) + OP_l_5_c_6_r_*SK_TAS(2) - OP_l_5_c_24_r_*SK_TAS(2) + OP_l_5_c_7_r_*vd*SH_TAS(1)); +Kfusion(6) = SK_TAS(1)*(OP_l_6_c_5_r_*SH_TAS(3) - OP_l_6_c_23_r_*SH_TAS(3) + OP_l_6_c_6_r_*SK_TAS(2) - OP_l_6_c_24_r_*SK_TAS(2) + OP_l_6_c_7_r_*vd*SH_TAS(1)); +Kfusion(7) = SK_TAS(1)*(OP_l_7_c_5_r_*SH_TAS(3) - OP_l_7_c_23_r_*SH_TAS(3) + OP_l_7_c_6_r_*SK_TAS(2) - OP_l_7_c_24_r_*SK_TAS(2) + OP_l_7_c_7_r_*vd*SH_TAS(1)); +Kfusion(8) = SK_TAS(1)*(OP_l_8_c_5_r_*SH_TAS(3) - OP_l_8_c_23_r_*SH_TAS(3) + OP_l_8_c_6_r_*SK_TAS(2) - OP_l_8_c_24_r_*SK_TAS(2) + OP_l_8_c_7_r_*vd*SH_TAS(1)); +Kfusion(9) = SK_TAS(1)*(OP_l_9_c_5_r_*SH_TAS(3) - OP_l_9_c_23_r_*SH_TAS(3) + OP_l_9_c_6_r_*SK_TAS(2) - OP_l_9_c_24_r_*SK_TAS(2) + OP_l_9_c_7_r_*vd*SH_TAS(1)); +Kfusion(10) = SK_TAS(1)*(OP_l_10_c_5_r_*SH_TAS(3) - OP_l_10_c_23_r_*SH_TAS(3) + OP_l_10_c_6_r_*SK_TAS(2) - OP_l_10_c_24_r_*SK_TAS(2) + OP_l_10_c_7_r_*vd*SH_TAS(1)); +Kfusion(11) = SK_TAS(1)*(OP_l_11_c_5_r_*SH_TAS(3) - OP_l_11_c_23_r_*SH_TAS(3) + OP_l_11_c_6_r_*SK_TAS(2) - OP_l_11_c_24_r_*SK_TAS(2) + OP_l_11_c_7_r_*vd*SH_TAS(1)); +Kfusion(12) = SK_TAS(1)*(OP_l_12_c_5_r_*SH_TAS(3) - OP_l_12_c_23_r_*SH_TAS(3) + OP_l_12_c_6_r_*SK_TAS(2) - OP_l_12_c_24_r_*SK_TAS(2) + OP_l_12_c_7_r_*vd*SH_TAS(1)); +Kfusion(13) = SK_TAS(1)*(OP_l_13_c_5_r_*SH_TAS(3) - OP_l_13_c_23_r_*SH_TAS(3) + OP_l_13_c_6_r_*SK_TAS(2) - OP_l_13_c_24_r_*SK_TAS(2) + OP_l_13_c_7_r_*vd*SH_TAS(1)); +Kfusion(14) = SK_TAS(1)*(OP_l_14_c_5_r_*SH_TAS(3) - OP_l_14_c_23_r_*SH_TAS(3) + OP_l_14_c_6_r_*SK_TAS(2) - OP_l_14_c_24_r_*SK_TAS(2) + OP_l_14_c_7_r_*vd*SH_TAS(1)); +Kfusion(15) = SK_TAS(1)*(OP_l_15_c_5_r_*SH_TAS(3) - OP_l_15_c_23_r_*SH_TAS(3) + OP_l_15_c_6_r_*SK_TAS(2) - OP_l_15_c_24_r_*SK_TAS(2) + OP_l_15_c_7_r_*vd*SH_TAS(1)); +Kfusion(16) = SK_TAS(1)*(OP_l_16_c_5_r_*SH_TAS(3) - OP_l_16_c_23_r_*SH_TAS(3) + OP_l_16_c_6_r_*SK_TAS(2) - OP_l_16_c_24_r_*SK_TAS(2) + OP_l_16_c_7_r_*vd*SH_TAS(1)); +Kfusion(17) = SK_TAS(1)*(OP_l_17_c_5_r_*SH_TAS(3) - OP_l_17_c_23_r_*SH_TAS(3) + OP_l_17_c_6_r_*SK_TAS(2) - OP_l_17_c_24_r_*SK_TAS(2) + OP_l_17_c_7_r_*vd*SH_TAS(1)); +Kfusion(18) = SK_TAS(1)*(OP_l_18_c_5_r_*SH_TAS(3) - OP_l_18_c_23_r_*SH_TAS(3) + OP_l_18_c_6_r_*SK_TAS(2) - OP_l_18_c_24_r_*SK_TAS(2) + OP_l_18_c_7_r_*vd*SH_TAS(1)); +Kfusion(19) = SK_TAS(1)*(OP_l_19_c_5_r_*SH_TAS(3) - OP_l_19_c_23_r_*SH_TAS(3) + OP_l_19_c_6_r_*SK_TAS(2) - OP_l_19_c_24_r_*SK_TAS(2) + OP_l_19_c_7_r_*vd*SH_TAS(1)); +Kfusion(20) = SK_TAS(1)*(OP_l_20_c_5_r_*SH_TAS(3) - OP_l_20_c_23_r_*SH_TAS(3) + OP_l_20_c_6_r_*SK_TAS(2) - OP_l_20_c_24_r_*SK_TAS(2) + OP_l_20_c_7_r_*vd*SH_TAS(1)); +Kfusion(21) = SK_TAS(1)*(OP_l_21_c_5_r_*SH_TAS(3) - OP_l_21_c_23_r_*SH_TAS(3) + OP_l_21_c_6_r_*SK_TAS(2) - OP_l_21_c_24_r_*SK_TAS(2) + OP_l_21_c_7_r_*vd*SH_TAS(1)); +Kfusion(22) = SK_TAS(1)*(OP_l_22_c_5_r_*SH_TAS(3) - OP_l_22_c_23_r_*SH_TAS(3) + OP_l_22_c_6_r_*SK_TAS(2) - OP_l_22_c_24_r_*SK_TAS(2) + OP_l_22_c_7_r_*vd*SH_TAS(1)); +Kfusion(23) = SK_TAS(1)*(OP_l_23_c_5_r_*SH_TAS(3) - OP_l_23_c_23_r_*SH_TAS(3) + OP_l_23_c_6_r_*SK_TAS(2) - OP_l_23_c_24_r_*SK_TAS(2) + OP_l_23_c_7_r_*vd*SH_TAS(1)); +Kfusion(24) = SK_TAS(1)*(OP_l_24_c_5_r_*SH_TAS(3) - OP_l_24_c_23_r_*SH_TAS(3) + OP_l_24_c_6_r_*SK_TAS(2) - OP_l_24_c_24_r_*SK_TAS(2) + OP_l_24_c_7_r_*vd*SH_TAS(1)); -SH_BETA = zeros(10,1); -SH_BETA(1) = (2*conj(q0)*conj(q3) + 2*conj(q1)*conj(q2))*(ve - vwe) - vd*(2*conj(q0)*conj(q2) - 2*conj(q1)*conj(q3)) + (vn - vwn)*(conj(q0)^2 + conj(q1)^2 - conj(q2)^2 - conj(q3)^2); -SH_BETA(2) = vd*(2*conj(q0)*conj(q1) + 2*conj(q2)*conj(q3)) - (2*conj(q0)*conj(q3) - 2*conj(q1)*conj(q2))*(vn - vwn) + (ve - vwe)*(conj(q0)^2 - conj(q1)^2 + conj(q2)^2 - conj(q3)^2); -SH_BETA(3) = (2*conj(q0)*conj(q2) + 2*conj(q1)*conj(q3))*(vn - vwn) - (2*conj(q0)*conj(q1) - 2*conj(q2)*conj(q3))*(ve - vwe) + vd*(conj(q0)^2 - conj(q1)^2 - conj(q2)^2 + conj(q3)^2); -SH_BETA(4) = (conj(q0)^2 - conj(q1)^2 + conj(q2)^2 - conj(q3)^2)/SH_BETA(1); +SH_BETA = zeros(13,1); +SH_BETA(1) = (vn - vwn)*(q0^2 + q1^2 - q2^2 - q3^2) - vd*(2*q0*q2 - 2*q1*q3) + (ve - vwe)*(2*q0*q3 + 2*q1*q2); +SH_BETA(2) = (ve - vwe)*(q0^2 - q1^2 + q2^2 - q3^2) + vd*(2*q0*q1 + 2*q2*q3) - (vn - vwn)*(2*q0*q3 - 2*q1*q2); +SH_BETA(3) = vn - vwn; +SH_BETA(4) = ve - vwe; SH_BETA(5) = 1/SH_BETA(1)^2; -SH_BETA(6) = conj(q0)^2 + conj(q1)^2 - conj(q2)^2 - conj(q3)^2; -SH_BETA(7) = 2*conj(q0)*conj(q3); -SH_BETA(8) = 1/SH_BETA(1); -SH_BETA(9) = SH_BETA(7) + 2*conj(q1)*conj(q2); -SH_BETA(10) = SH_BETA(7) - 2*conj(q1)*conj(q2); +SH_BETA(6) = 1/SH_BETA(1); +SH_BETA(7) = SH_BETA(6)*(q0^2 - q1^2 + q2^2 - q3^2); +SH_BETA(8) = q0^2 + q1^2 - q2^2 - q3^2; +SH_BETA(9) = 2*q0*SH_BETA(4) - 2*q3*SH_BETA(3) + 2*q1*vd; +SH_BETA(10) = 2*q0*SH_BETA(3) + 2*q3*SH_BETA(4) - 2*q2*vd; +SH_BETA(11) = 2*q2*SH_BETA(3) - 2*q1*SH_BETA(4) + 2*q0*vd; +SH_BETA(12) = 2*q1*SH_BETA(3) + 2*q2*SH_BETA(4) + 2*q3*vd; +SH_BETA(13) = 2*q0*q3; H_BETA = zeros(1,24); -H_BETA(1,1) = SH_BETA(3)*SH_BETA(8); -H_BETA(1,2) = SH_BETA(2)*SH_BETA(3)*SH_BETA(5); -H_BETA(1,3) = - SH_BETA(2)^2*SH_BETA(5) - 1; -H_BETA(1,4) = - SH_BETA(8)*SH_BETA(10) - SH_BETA(2)*SH_BETA(5)*SH_BETA(6); -H_BETA(1,5) = SH_BETA(4) - SH_BETA(2)*SH_BETA(5)*SH_BETA(9); -H_BETA(1,6) = SH_BETA(8)*(2*conj(q0)*conj(q1) + 2*conj(q2)*conj(q3)) + SH_BETA(2)*SH_BETA(5)*(2*conj(q0)*conj(q2) - 2*conj(q1)*conj(q3)); -H_BETA(1,23) = SH_BETA(8)*SH_BETA(10) + SH_BETA(2)*SH_BETA(5)*SH_BETA(6); -H_BETA(1,24) = SH_BETA(2)*SH_BETA(5)*SH_BETA(9) - SH_BETA(4); +H_BETA(1,1) = SH_BETA(6)*SH_BETA(9) - SH_BETA(2)*SH_BETA(5)*SH_BETA(10); +H_BETA(1,2) = SH_BETA(6)*SH_BETA(11) - SH_BETA(2)*SH_BETA(5)*SH_BETA(12); +H_BETA(1,3) = SH_BETA(6)*SH_BETA(12) + SH_BETA(2)*SH_BETA(5)*SH_BETA(11); +H_BETA(1,4) = - SH_BETA(6)*SH_BETA(10) - SH_BETA(2)*SH_BETA(5)*SH_BETA(9); +H_BETA(1,5) = - SH_BETA(6)*(SH_BETA(13) - 2*q1*q2) - SH_BETA(2)*SH_BETA(5)*SH_BETA(8); +H_BETA(1,6) = SH_BETA(7) - SH_BETA(2)*SH_BETA(5)*(SH_BETA(13) + 2*q1*q2); +H_BETA(1,7) = SH_BETA(6)*(2*q0*q1 + 2*q2*q3) + SH_BETA(2)*SH_BETA(5)*(2*q0*q2 - 2*q1*q3); +H_BETA(1,23) = SH_BETA(6)*(SH_BETA(13) - 2*q1*q2) + SH_BETA(2)*SH_BETA(5)*SH_BETA(8); +H_BETA(1,24) = SH_BETA(2)*SH_BETA(5)*(SH_BETA(13) + 2*q1*q2) - SH_BETA(7); -SK_BETA = zeros(6,1); -SK_BETA(1) = 1/(R_BETA + (SH_BETA(8)*(2*conj(q0)*conj(q1) + 2*conj(q2)*conj(q3)) + SH_BETA(2)*SH_BETA(5)*(2*conj(q0)*conj(q2) - 2*conj(q1)*conj(q3)))*(OP_l_23_c_6_r_*(SH_BETA(8)*SH_BETA(10) + SH_BETA(2)*SH_BETA(5)*SH_BETA(6)) - OP_l_4_c_6_r_*(SH_BETA(8)*SH_BETA(10) + SH_BETA(2)*SH_BETA(5)*SH_BETA(6)) - OP_l_3_c_6_r_*(SH_BETA(2)^2*SH_BETA(5) + 1) + OP_l_6_c_6_r_*(SH_BETA(8)*(2*conj(q0)*conj(q1) + 2*conj(q2)*conj(q3)) + SH_BETA(2)*SH_BETA(5)*(2*conj(q0)*conj(q2) - 2*conj(q1)*conj(q3))) + OP_l_5_c_6_r_*(SH_BETA(4) - SH_BETA(2)*SH_BETA(5)*SH_BETA(9)) - OP_l_24_c_6_r_*(SH_BETA(4) - SH_BETA(2)*SH_BETA(5)*SH_BETA(9)) + OP_l_1_c_6_r_*SH_BETA(3)*SH_BETA(8) + OP_l_2_c_6_r_*SH_BETA(2)*SH_BETA(3)*SH_BETA(5)) + (SH_BETA(4) - SH_BETA(2)*SH_BETA(5)*SH_BETA(9))*(OP_l_23_c_5_r_*(SH_BETA(8)*SH_BETA(10) + SH_BETA(2)*SH_BETA(5)*SH_BETA(6)) - OP_l_4_c_5_r_*(SH_BETA(8)*SH_BETA(10) + SH_BETA(2)*SH_BETA(5)*SH_BETA(6)) - OP_l_3_c_5_r_*(SH_BETA(2)^2*SH_BETA(5) + 1) + OP_l_6_c_5_r_*(SH_BETA(8)*(2*conj(q0)*conj(q1) + 2*conj(q2)*conj(q3)) + SH_BETA(2)*SH_BETA(5)*(2*conj(q0)*conj(q2) - 2*conj(q1)*conj(q3))) + OP_l_5_c_5_r_*(SH_BETA(4) - SH_BETA(2)*SH_BETA(5)*SH_BETA(9)) - OP_l_24_c_5_r_*(SH_BETA(4) - SH_BETA(2)*SH_BETA(5)*SH_BETA(9)) + OP_l_1_c_5_r_*SH_BETA(3)*SH_BETA(8) + OP_l_2_c_5_r_*SH_BETA(2)*SH_BETA(3)*SH_BETA(5)) - (SH_BETA(4) - SH_BETA(2)*SH_BETA(5)*SH_BETA(9))*(OP_l_23_c_24_r_*(SH_BETA(8)*SH_BETA(10) + SH_BETA(2)*SH_BETA(5)*SH_BETA(6)) - OP_l_4_c_24_r_*(SH_BETA(8)*SH_BETA(10) + SH_BETA(2)*SH_BETA(5)*SH_BETA(6)) - OP_l_3_c_24_r_*(SH_BETA(2)^2*SH_BETA(5) + 1) + OP_l_6_c_24_r_*(SH_BETA(8)*(2*conj(q0)*conj(q1) + 2*conj(q2)*conj(q3)) + SH_BETA(2)*SH_BETA(5)*(2*conj(q0)*conj(q2) - 2*conj(q1)*conj(q3))) + OP_l_5_c_24_r_*(SH_BETA(4) - SH_BETA(2)*SH_BETA(5)*SH_BETA(9)) - OP_l_24_c_24_r_*(SH_BETA(4) - SH_BETA(2)*SH_BETA(5)*SH_BETA(9)) + OP_l_1_c_24_r_*SH_BETA(3)*SH_BETA(8) + OP_l_2_c_24_r_*SH_BETA(2)*SH_BETA(3)*SH_BETA(5)) - (SH_BETA(8)*SH_BETA(10) + SH_BETA(2)*SH_BETA(5)*SH_BETA(6))*(OP_l_23_c_4_r_*(SH_BETA(8)*SH_BETA(10) + SH_BETA(2)*SH_BETA(5)*SH_BETA(6)) - OP_l_4_c_4_r_*(SH_BETA(8)*SH_BETA(10) + SH_BETA(2)*SH_BETA(5)*SH_BETA(6)) - OP_l_3_c_4_r_*(SH_BETA(2)^2*SH_BETA(5) + 1) + OP_l_6_c_4_r_*(SH_BETA(8)*(2*conj(q0)*conj(q1) + 2*conj(q2)*conj(q3)) + SH_BETA(2)*SH_BETA(5)*(2*conj(q0)*conj(q2) - 2*conj(q1)*conj(q3))) + OP_l_5_c_4_r_*(SH_BETA(4) - SH_BETA(2)*SH_BETA(5)*SH_BETA(9)) - OP_l_24_c_4_r_*(SH_BETA(4) - SH_BETA(2)*SH_BETA(5)*SH_BETA(9)) + OP_l_1_c_4_r_*SH_BETA(3)*SH_BETA(8) + OP_l_2_c_4_r_*SH_BETA(2)*SH_BETA(3)*SH_BETA(5)) + (SH_BETA(8)*SH_BETA(10) + SH_BETA(2)*SH_BETA(5)*SH_BETA(6))*(OP_l_23_c_23_r_*(SH_BETA(8)*SH_BETA(10) + SH_BETA(2)*SH_BETA(5)*SH_BETA(6)) - OP_l_4_c_23_r_*(SH_BETA(8)*SH_BETA(10) + SH_BETA(2)*SH_BETA(5)*SH_BETA(6)) - OP_l_3_c_23_r_*(SH_BETA(2)^2*SH_BETA(5) + 1) + OP_l_6_c_23_r_*(SH_BETA(8)*(2*conj(q0)*conj(q1) + 2*conj(q2)*conj(q3)) + SH_BETA(2)*SH_BETA(5)*(2*conj(q0)*conj(q2) - 2*conj(q1)*conj(q3))) + OP_l_5_c_23_r_*(SH_BETA(4) - SH_BETA(2)*SH_BETA(5)*SH_BETA(9)) - OP_l_24_c_23_r_*(SH_BETA(4) - SH_BETA(2)*SH_BETA(5)*SH_BETA(9)) + OP_l_1_c_23_r_*SH_BETA(3)*SH_BETA(8) + OP_l_2_c_23_r_*SH_BETA(2)*SH_BETA(3)*SH_BETA(5)) - (SH_BETA(2)^2*SH_BETA(5) + 1)*(OP_l_23_c_3_r_*(SH_BETA(8)*SH_BETA(10) + SH_BETA(2)*SH_BETA(5)*SH_BETA(6)) - OP_l_4_c_3_r_*(SH_BETA(8)*SH_BETA(10) + SH_BETA(2)*SH_BETA(5)*SH_BETA(6)) - OP_l_3_c_3_r_*(SH_BETA(2)^2*SH_BETA(5) + 1) + OP_l_6_c_3_r_*(SH_BETA(8)*(2*conj(q0)*conj(q1) + 2*conj(q2)*conj(q3)) + SH_BETA(2)*SH_BETA(5)*(2*conj(q0)*conj(q2) - 2*conj(q1)*conj(q3))) + OP_l_5_c_3_r_*(SH_BETA(4) - SH_BETA(2)*SH_BETA(5)*SH_BETA(9)) - OP_l_24_c_3_r_*(SH_BETA(4) - SH_BETA(2)*SH_BETA(5)*SH_BETA(9)) + OP_l_1_c_3_r_*SH_BETA(3)*SH_BETA(8) + OP_l_2_c_3_r_*SH_BETA(2)*SH_BETA(3)*SH_BETA(5)) + SH_BETA(3)*SH_BETA(8)*(OP_l_23_c_1_r_*(SH_BETA(8)*SH_BETA(10) + SH_BETA(2)*SH_BETA(5)*SH_BETA(6)) - OP_l_4_c_1_r_*(SH_BETA(8)*SH_BETA(10) + SH_BETA(2)*SH_BETA(5)*SH_BETA(6)) - OP_l_3_c_1_r_*(SH_BETA(2)^2*SH_BETA(5) + 1) + OP_l_6_c_1_r_*(SH_BETA(8)*(2*conj(q0)*conj(q1) + 2*conj(q2)*conj(q3)) + SH_BETA(2)*SH_BETA(5)*(2*conj(q0)*conj(q2) - 2*conj(q1)*conj(q3))) + OP_l_5_c_1_r_*(SH_BETA(4) - SH_BETA(2)*SH_BETA(5)*SH_BETA(9)) - OP_l_24_c_1_r_*(SH_BETA(4) - SH_BETA(2)*SH_BETA(5)*SH_BETA(9)) + OP_l_1_c_1_r_*SH_BETA(3)*SH_BETA(8) + OP_l_2_c_1_r_*SH_BETA(2)*SH_BETA(3)*SH_BETA(5)) + SH_BETA(2)*SH_BETA(3)*SH_BETA(5)*(OP_l_23_c_2_r_*(SH_BETA(8)*SH_BETA(10) + SH_BETA(2)*SH_BETA(5)*SH_BETA(6)) - OP_l_4_c_2_r_*(SH_BETA(8)*SH_BETA(10) + SH_BETA(2)*SH_BETA(5)*SH_BETA(6)) - OP_l_3_c_2_r_*(SH_BETA(2)^2*SH_BETA(5) + 1) + OP_l_6_c_2_r_*(SH_BETA(8)*(2*conj(q0)*conj(q1) + 2*conj(q2)*conj(q3)) + SH_BETA(2)*SH_BETA(5)*(2*conj(q0)*conj(q2) - 2*conj(q1)*conj(q3))) + OP_l_5_c_2_r_*(SH_BETA(4) - SH_BETA(2)*SH_BETA(5)*SH_BETA(9)) - OP_l_24_c_2_r_*(SH_BETA(4) - SH_BETA(2)*SH_BETA(5)*SH_BETA(9)) + OP_l_1_c_2_r_*SH_BETA(3)*SH_BETA(8) + OP_l_2_c_2_r_*SH_BETA(2)*SH_BETA(3)*SH_BETA(5))); -SK_BETA(2) = SH_BETA(8)*(2*conj(q0)*conj(q1) + 2*conj(q2)*conj(q3)) + SH_BETA(2)*SH_BETA(5)*(2*conj(q0)*conj(q2) - 2*conj(q1)*conj(q3)); -SK_BETA(3) = SH_BETA(8)*SH_BETA(10) + SH_BETA(2)*SH_BETA(5)*SH_BETA(6); -SK_BETA(4) = SH_BETA(4) - SH_BETA(2)*SH_BETA(5)*SH_BETA(9); -SK_BETA(5) = SH_BETA(2)^2*SH_BETA(5) + 1; -SK_BETA(6) = SH_BETA(3); +SK_BETA = zeros(8,1); +SK_BETA(1) = 1/(R_BETA - (SH_BETA(6)*(SH_BETA(13) - 2*q1*q2) + SH_BETA(2)*SH_BETA(5)*SH_BETA(8))*(OP_l_23_c_5_r_*(SH_BETA(6)*(SH_BETA(13) - 2*q1*q2) + SH_BETA(2)*SH_BETA(5)*SH_BETA(8)) - OP_l_5_c_5_r_*(SH_BETA(6)*(SH_BETA(13) - 2*q1*q2) + SH_BETA(2)*SH_BETA(5)*SH_BETA(8)) + OP_l_6_c_5_r_*(SH_BETA(7) - SH_BETA(2)*SH_BETA(5)*(SH_BETA(13) + 2*q1*q2)) - OP_l_24_c_5_r_*(SH_BETA(7) - SH_BETA(2)*SH_BETA(5)*(SH_BETA(13) + 2*q1*q2)) + OP_l_1_c_5_r_*(SH_BETA(6)*SH_BETA(9) - SH_BETA(2)*SH_BETA(5)*SH_BETA(10)) + OP_l_2_c_5_r_*(SH_BETA(6)*SH_BETA(11) - SH_BETA(2)*SH_BETA(5)*SH_BETA(12)) + OP_l_3_c_5_r_*(SH_BETA(6)*SH_BETA(12) + SH_BETA(2)*SH_BETA(5)*SH_BETA(11)) - OP_l_4_c_5_r_*(SH_BETA(6)*SH_BETA(10) + SH_BETA(2)*SH_BETA(5)*SH_BETA(9)) + OP_l_7_c_5_r_*(SH_BETA(6)*(2*q0*q1 + 2*q2*q3) + SH_BETA(2)*SH_BETA(5)*(2*q0*q2 - 2*q1*q3))) + (SH_BETA(6)*(SH_BETA(13) - 2*q1*q2) + SH_BETA(2)*SH_BETA(5)*SH_BETA(8))*(OP_l_23_c_23_r_*(SH_BETA(6)*(SH_BETA(13) - 2*q1*q2) + SH_BETA(2)*SH_BETA(5)*SH_BETA(8)) - OP_l_5_c_23_r_*(SH_BETA(6)*(SH_BETA(13) - 2*q1*q2) + SH_BETA(2)*SH_BETA(5)*SH_BETA(8)) + OP_l_6_c_23_r_*(SH_BETA(7) - SH_BETA(2)*SH_BETA(5)*(SH_BETA(13) + 2*q1*q2)) - OP_l_24_c_23_r_*(SH_BETA(7) - SH_BETA(2)*SH_BETA(5)*(SH_BETA(13) + 2*q1*q2)) + OP_l_1_c_23_r_*(SH_BETA(6)*SH_BETA(9) - SH_BETA(2)*SH_BETA(5)*SH_BETA(10)) + OP_l_2_c_23_r_*(SH_BETA(6)*SH_BETA(11) - SH_BETA(2)*SH_BETA(5)*SH_BETA(12)) + OP_l_3_c_23_r_*(SH_BETA(6)*SH_BETA(12) + SH_BETA(2)*SH_BETA(5)*SH_BETA(11)) - OP_l_4_c_23_r_*(SH_BETA(6)*SH_BETA(10) + SH_BETA(2)*SH_BETA(5)*SH_BETA(9)) + OP_l_7_c_23_r_*(SH_BETA(6)*(2*q0*q1 + 2*q2*q3) + SH_BETA(2)*SH_BETA(5)*(2*q0*q2 - 2*q1*q3))) + (SH_BETA(7) - SH_BETA(2)*SH_BETA(5)*(SH_BETA(13) + 2*q1*q2))*(OP_l_23_c_6_r_*(SH_BETA(6)*(SH_BETA(13) - 2*q1*q2) + SH_BETA(2)*SH_BETA(5)*SH_BETA(8)) - OP_l_5_c_6_r_*(SH_BETA(6)*(SH_BETA(13) - 2*q1*q2) + SH_BETA(2)*SH_BETA(5)*SH_BETA(8)) + OP_l_6_c_6_r_*(SH_BETA(7) - SH_BETA(2)*SH_BETA(5)*(SH_BETA(13) + 2*q1*q2)) - OP_l_24_c_6_r_*(SH_BETA(7) - SH_BETA(2)*SH_BETA(5)*(SH_BETA(13) + 2*q1*q2)) + OP_l_1_c_6_r_*(SH_BETA(6)*SH_BETA(9) - SH_BETA(2)*SH_BETA(5)*SH_BETA(10)) + OP_l_2_c_6_r_*(SH_BETA(6)*SH_BETA(11) - SH_BETA(2)*SH_BETA(5)*SH_BETA(12)) + OP_l_3_c_6_r_*(SH_BETA(6)*SH_BETA(12) + SH_BETA(2)*SH_BETA(5)*SH_BETA(11)) - OP_l_4_c_6_r_*(SH_BETA(6)*SH_BETA(10) + SH_BETA(2)*SH_BETA(5)*SH_BETA(9)) + OP_l_7_c_6_r_*(SH_BETA(6)*(2*q0*q1 + 2*q2*q3) + SH_BETA(2)*SH_BETA(5)*(2*q0*q2 - 2*q1*q3))) - (SH_BETA(7) - SH_BETA(2)*SH_BETA(5)*(SH_BETA(13) + 2*q1*q2))*(OP_l_23_c_24_r_*(SH_BETA(6)*(SH_BETA(13) - 2*q1*q2) + SH_BETA(2)*SH_BETA(5)*SH_BETA(8)) - OP_l_5_c_24_r_*(SH_BETA(6)*(SH_BETA(13) - 2*q1*q2) + SH_BETA(2)*SH_BETA(5)*SH_BETA(8)) + OP_l_6_c_24_r_*(SH_BETA(7) - SH_BETA(2)*SH_BETA(5)*(SH_BETA(13) + 2*q1*q2)) - OP_l_24_c_24_r_*(SH_BETA(7) - SH_BETA(2)*SH_BETA(5)*(SH_BETA(13) + 2*q1*q2)) + OP_l_1_c_24_r_*(SH_BETA(6)*SH_BETA(9) - SH_BETA(2)*SH_BETA(5)*SH_BETA(10)) + OP_l_2_c_24_r_*(SH_BETA(6)*SH_BETA(11) - SH_BETA(2)*SH_BETA(5)*SH_BETA(12)) + OP_l_3_c_24_r_*(SH_BETA(6)*SH_BETA(12) + SH_BETA(2)*SH_BETA(5)*SH_BETA(11)) - OP_l_4_c_24_r_*(SH_BETA(6)*SH_BETA(10) + SH_BETA(2)*SH_BETA(5)*SH_BETA(9)) + OP_l_7_c_24_r_*(SH_BETA(6)*(2*q0*q1 + 2*q2*q3) + SH_BETA(2)*SH_BETA(5)*(2*q0*q2 - 2*q1*q3))) + (SH_BETA(6)*SH_BETA(9) - SH_BETA(2)*SH_BETA(5)*SH_BETA(10))*(OP_l_23_c_1_r_*(SH_BETA(6)*(SH_BETA(13) - 2*q1*q2) + SH_BETA(2)*SH_BETA(5)*SH_BETA(8)) - OP_l_5_c_1_r_*(SH_BETA(6)*(SH_BETA(13) - 2*q1*q2) + SH_BETA(2)*SH_BETA(5)*SH_BETA(8)) + OP_l_6_c_1_r_*(SH_BETA(7) - SH_BETA(2)*SH_BETA(5)*(SH_BETA(13) + 2*q1*q2)) - OP_l_24_c_1_r_*(SH_BETA(7) - SH_BETA(2)*SH_BETA(5)*(SH_BETA(13) + 2*q1*q2)) + OP_l_1_c_1_r_*(SH_BETA(6)*SH_BETA(9) - SH_BETA(2)*SH_BETA(5)*SH_BETA(10)) + OP_l_2_c_1_r_*(SH_BETA(6)*SH_BETA(11) - SH_BETA(2)*SH_BETA(5)*SH_BETA(12)) + OP_l_3_c_1_r_*(SH_BETA(6)*SH_BETA(12) + SH_BETA(2)*SH_BETA(5)*SH_BETA(11)) - OP_l_4_c_1_r_*(SH_BETA(6)*SH_BETA(10) + SH_BETA(2)*SH_BETA(5)*SH_BETA(9)) + OP_l_7_c_1_r_*(SH_BETA(6)*(2*q0*q1 + 2*q2*q3) + SH_BETA(2)*SH_BETA(5)*(2*q0*q2 - 2*q1*q3))) + (SH_BETA(6)*SH_BETA(11) - SH_BETA(2)*SH_BETA(5)*SH_BETA(12))*(OP_l_23_c_2_r_*(SH_BETA(6)*(SH_BETA(13) - 2*q1*q2) + SH_BETA(2)*SH_BETA(5)*SH_BETA(8)) - OP_l_5_c_2_r_*(SH_BETA(6)*(SH_BETA(13) - 2*q1*q2) + SH_BETA(2)*SH_BETA(5)*SH_BETA(8)) + OP_l_6_c_2_r_*(SH_BETA(7) - SH_BETA(2)*SH_BETA(5)*(SH_BETA(13) + 2*q1*q2)) - OP_l_24_c_2_r_*(SH_BETA(7) - SH_BETA(2)*SH_BETA(5)*(SH_BETA(13) + 2*q1*q2)) + OP_l_1_c_2_r_*(SH_BETA(6)*SH_BETA(9) - SH_BETA(2)*SH_BETA(5)*SH_BETA(10)) + OP_l_2_c_2_r_*(SH_BETA(6)*SH_BETA(11) - SH_BETA(2)*SH_BETA(5)*SH_BETA(12)) + OP_l_3_c_2_r_*(SH_BETA(6)*SH_BETA(12) + SH_BETA(2)*SH_BETA(5)*SH_BETA(11)) - OP_l_4_c_2_r_*(SH_BETA(6)*SH_BETA(10) + SH_BETA(2)*SH_BETA(5)*SH_BETA(9)) + OP_l_7_c_2_r_*(SH_BETA(6)*(2*q0*q1 + 2*q2*q3) + SH_BETA(2)*SH_BETA(5)*(2*q0*q2 - 2*q1*q3))) + (SH_BETA(6)*SH_BETA(12) + SH_BETA(2)*SH_BETA(5)*SH_BETA(11))*(OP_l_23_c_3_r_*(SH_BETA(6)*(SH_BETA(13) - 2*q1*q2) + SH_BETA(2)*SH_BETA(5)*SH_BETA(8)) - OP_l_5_c_3_r_*(SH_BETA(6)*(SH_BETA(13) - 2*q1*q2) + SH_BETA(2)*SH_BETA(5)*SH_BETA(8)) + OP_l_6_c_3_r_*(SH_BETA(7) - SH_BETA(2)*SH_BETA(5)*(SH_BETA(13) + 2*q1*q2)) - OP_l_24_c_3_r_*(SH_BETA(7) - SH_BETA(2)*SH_BETA(5)*(SH_BETA(13) + 2*q1*q2)) + OP_l_1_c_3_r_*(SH_BETA(6)*SH_BETA(9) - SH_BETA(2)*SH_BETA(5)*SH_BETA(10)) + OP_l_2_c_3_r_*(SH_BETA(6)*SH_BETA(11) - SH_BETA(2)*SH_BETA(5)*SH_BETA(12)) + OP_l_3_c_3_r_*(SH_BETA(6)*SH_BETA(12) + SH_BETA(2)*SH_BETA(5)*SH_BETA(11)) - OP_l_4_c_3_r_*(SH_BETA(6)*SH_BETA(10) + SH_BETA(2)*SH_BETA(5)*SH_BETA(9)) + OP_l_7_c_3_r_*(SH_BETA(6)*(2*q0*q1 + 2*q2*q3) + SH_BETA(2)*SH_BETA(5)*(2*q0*q2 - 2*q1*q3))) - (SH_BETA(6)*SH_BETA(10) + SH_BETA(2)*SH_BETA(5)*SH_BETA(9))*(OP_l_23_c_4_r_*(SH_BETA(6)*(SH_BETA(13) - 2*q1*q2) + SH_BETA(2)*SH_BETA(5)*SH_BETA(8)) - OP_l_5_c_4_r_*(SH_BETA(6)*(SH_BETA(13) - 2*q1*q2) + SH_BETA(2)*SH_BETA(5)*SH_BETA(8)) + OP_l_6_c_4_r_*(SH_BETA(7) - SH_BETA(2)*SH_BETA(5)*(SH_BETA(13) + 2*q1*q2)) - OP_l_24_c_4_r_*(SH_BETA(7) - SH_BETA(2)*SH_BETA(5)*(SH_BETA(13) + 2*q1*q2)) + OP_l_1_c_4_r_*(SH_BETA(6)*SH_BETA(9) - SH_BETA(2)*SH_BETA(5)*SH_BETA(10)) + OP_l_2_c_4_r_*(SH_BETA(6)*SH_BETA(11) - SH_BETA(2)*SH_BETA(5)*SH_BETA(12)) + OP_l_3_c_4_r_*(SH_BETA(6)*SH_BETA(12) + SH_BETA(2)*SH_BETA(5)*SH_BETA(11)) - OP_l_4_c_4_r_*(SH_BETA(6)*SH_BETA(10) + SH_BETA(2)*SH_BETA(5)*SH_BETA(9)) + OP_l_7_c_4_r_*(SH_BETA(6)*(2*q0*q1 + 2*q2*q3) + SH_BETA(2)*SH_BETA(5)*(2*q0*q2 - 2*q1*q3))) + (SH_BETA(6)*(2*q0*q1 + 2*q2*q3) + SH_BETA(2)*SH_BETA(5)*(2*q0*q2 - 2*q1*q3))*(OP_l_23_c_7_r_*(SH_BETA(6)*(SH_BETA(13) - 2*q1*q2) + SH_BETA(2)*SH_BETA(5)*SH_BETA(8)) - OP_l_5_c_7_r_*(SH_BETA(6)*(SH_BETA(13) - 2*q1*q2) + SH_BETA(2)*SH_BETA(5)*SH_BETA(8)) + OP_l_6_c_7_r_*(SH_BETA(7) - SH_BETA(2)*SH_BETA(5)*(SH_BETA(13) + 2*q1*q2)) - OP_l_24_c_7_r_*(SH_BETA(7) - SH_BETA(2)*SH_BETA(5)*(SH_BETA(13) + 2*q1*q2)) + OP_l_1_c_7_r_*(SH_BETA(6)*SH_BETA(9) - SH_BETA(2)*SH_BETA(5)*SH_BETA(10)) + OP_l_2_c_7_r_*(SH_BETA(6)*SH_BETA(11) - SH_BETA(2)*SH_BETA(5)*SH_BETA(12)) + OP_l_3_c_7_r_*(SH_BETA(6)*SH_BETA(12) + SH_BETA(2)*SH_BETA(5)*SH_BETA(11)) - OP_l_4_c_7_r_*(SH_BETA(6)*SH_BETA(10) + SH_BETA(2)*SH_BETA(5)*SH_BETA(9)) + OP_l_7_c_7_r_*(SH_BETA(6)*(2*q0*q1 + 2*q2*q3) + SH_BETA(2)*SH_BETA(5)*(2*q0*q2 - 2*q1*q3)))); +SK_BETA(2) = SH_BETA(6)*(SH_BETA(13) - 2*q1*q2) + SH_BETA(2)*SH_BETA(5)*SH_BETA(8); +SK_BETA(3) = SH_BETA(7) - SH_BETA(2)*SH_BETA(5)*(SH_BETA(13) + 2*q1*q2); +SK_BETA(4) = SH_BETA(6)*(2*q0*q1 + 2*q2*q3) + SH_BETA(2)*SH_BETA(5)*(2*q0*q2 - 2*q1*q3); +SK_BETA(5) = SH_BETA(6)*SH_BETA(11) - SH_BETA(2)*SH_BETA(5)*SH_BETA(12); +SK_BETA(6) = SH_BETA(6)*SH_BETA(9) - SH_BETA(2)*SH_BETA(5)*SH_BETA(10); +SK_BETA(7) = SH_BETA(6)*SH_BETA(12) + SH_BETA(2)*SH_BETA(5)*SH_BETA(11); +SK_BETA(8) = SH_BETA(6)*SH_BETA(10) + SH_BETA(2)*SH_BETA(5)*SH_BETA(9); Kfusion = zeros(24,1); Kfusion = zeros(1,1); -Kfusion(1) = SK_BETA(1)*(OP_l_1_c_6_r_*SK_BETA(2) - OP_l_1_c_3_r_*SK_BETA(5) - OP_l_1_c_4_r_*SK_BETA(3) + OP_l_1_c_5_r_*SK_BETA(4) + OP_l_1_c_23_r_*SK_BETA(3) - OP_l_1_c_24_r_*SK_BETA(4) + OP_l_1_c_1_r_*SH_BETA(8)*SK_BETA(6) + OP_l_1_c_2_r_*SH_BETA(2)*SH_BETA(5)*SK_BETA(6)); -Kfusion(2) = SK_BETA(1)*(OP_l_2_c_6_r_*SK_BETA(2) - OP_l_2_c_3_r_*SK_BETA(5) - OP_l_2_c_4_r_*SK_BETA(3) + OP_l_2_c_5_r_*SK_BETA(4) + OP_l_2_c_23_r_*SK_BETA(3) - OP_l_2_c_24_r_*SK_BETA(4) + OP_l_2_c_1_r_*SH_BETA(8)*SK_BETA(6) + OP_l_2_c_2_r_*SH_BETA(2)*SH_BETA(5)*SK_BETA(6)); -Kfusion(3) = SK_BETA(1)*(OP_l_3_c_6_r_*SK_BETA(2) - OP_l_3_c_3_r_*SK_BETA(5) - OP_l_3_c_4_r_*SK_BETA(3) + OP_l_3_c_5_r_*SK_BETA(4) + OP_l_3_c_23_r_*SK_BETA(3) - OP_l_3_c_24_r_*SK_BETA(4) + OP_l_3_c_1_r_*SH_BETA(8)*SK_BETA(6) + OP_l_3_c_2_r_*SH_BETA(2)*SH_BETA(5)*SK_BETA(6)); -Kfusion(4) = SK_BETA(1)*(OP_l_4_c_6_r_*SK_BETA(2) - OP_l_4_c_3_r_*SK_BETA(5) - OP_l_4_c_4_r_*SK_BETA(3) + OP_l_4_c_5_r_*SK_BETA(4) + OP_l_4_c_23_r_*SK_BETA(3) - OP_l_4_c_24_r_*SK_BETA(4) + OP_l_4_c_1_r_*SH_BETA(8)*SK_BETA(6) + OP_l_4_c_2_r_*SH_BETA(2)*SH_BETA(5)*SK_BETA(6)); -Kfusion(5) = SK_BETA(1)*(OP_l_5_c_6_r_*SK_BETA(2) - OP_l_5_c_3_r_*SK_BETA(5) - OP_l_5_c_4_r_*SK_BETA(3) + OP_l_5_c_5_r_*SK_BETA(4) + OP_l_5_c_23_r_*SK_BETA(3) - OP_l_5_c_24_r_*SK_BETA(4) + OP_l_5_c_1_r_*SH_BETA(8)*SK_BETA(6) + OP_l_5_c_2_r_*SH_BETA(2)*SH_BETA(5)*SK_BETA(6)); -Kfusion(6) = SK_BETA(1)*(OP_l_6_c_6_r_*SK_BETA(2) - OP_l_6_c_3_r_*SK_BETA(5) - OP_l_6_c_4_r_*SK_BETA(3) + OP_l_6_c_5_r_*SK_BETA(4) + OP_l_6_c_23_r_*SK_BETA(3) - OP_l_6_c_24_r_*SK_BETA(4) + OP_l_6_c_1_r_*SH_BETA(8)*SK_BETA(6) + OP_l_6_c_2_r_*SH_BETA(2)*SH_BETA(5)*SK_BETA(6)); -Kfusion(7) = SK_BETA(1)*(OP_l_7_c_6_r_*SK_BETA(2) - OP_l_7_c_3_r_*SK_BETA(5) - OP_l_7_c_4_r_*SK_BETA(3) + OP_l_7_c_5_r_*SK_BETA(4) + OP_l_7_c_23_r_*SK_BETA(3) - OP_l_7_c_24_r_*SK_BETA(4) + OP_l_7_c_1_r_*SH_BETA(8)*SK_BETA(6) + OP_l_7_c_2_r_*SH_BETA(2)*SH_BETA(5)*SK_BETA(6)); -Kfusion(8) = SK_BETA(1)*(OP_l_8_c_6_r_*SK_BETA(2) - OP_l_8_c_3_r_*SK_BETA(5) - OP_l_8_c_4_r_*SK_BETA(3) + OP_l_8_c_5_r_*SK_BETA(4) + OP_l_8_c_23_r_*SK_BETA(3) - OP_l_8_c_24_r_*SK_BETA(4) + OP_l_8_c_1_r_*SH_BETA(8)*SK_BETA(6) + OP_l_8_c_2_r_*SH_BETA(2)*SH_BETA(5)*SK_BETA(6)); -Kfusion(9) = SK_BETA(1)*(OP_l_9_c_6_r_*SK_BETA(2) - OP_l_9_c_3_r_*SK_BETA(5) - OP_l_9_c_4_r_*SK_BETA(3) + OP_l_9_c_5_r_*SK_BETA(4) + OP_l_9_c_23_r_*SK_BETA(3) - OP_l_9_c_24_r_*SK_BETA(4) + OP_l_9_c_1_r_*SH_BETA(8)*SK_BETA(6) + OP_l_9_c_2_r_*SH_BETA(2)*SH_BETA(5)*SK_BETA(6)); -Kfusion(10) = SK_BETA(1)*(OP_l_10_c_6_r_*SK_BETA(2) - OP_l_10_c_3_r_*SK_BETA(5) - OP_l_10_c_4_r_*SK_BETA(3) + OP_l_10_c_5_r_*SK_BETA(4) + OP_l_10_c_23_r_*SK_BETA(3) - OP_l_10_c_24_r_*SK_BETA(4) + OP_l_10_c_1_r_*SH_BETA(8)*SK_BETA(6) + OP_l_10_c_2_r_*SH_BETA(2)*SH_BETA(5)*SK_BETA(6)); -Kfusion(11) = SK_BETA(1)*(OP_l_11_c_6_r_*SK_BETA(2) - OP_l_11_c_3_r_*SK_BETA(5) - OP_l_11_c_4_r_*SK_BETA(3) + OP_l_11_c_5_r_*SK_BETA(4) + OP_l_11_c_23_r_*SK_BETA(3) - OP_l_11_c_24_r_*SK_BETA(4) + OP_l_11_c_1_r_*SH_BETA(8)*SK_BETA(6) + OP_l_11_c_2_r_*SH_BETA(2)*SH_BETA(5)*SK_BETA(6)); -Kfusion(12) = SK_BETA(1)*(OP_l_12_c_6_r_*SK_BETA(2) - OP_l_12_c_3_r_*SK_BETA(5) - OP_l_12_c_4_r_*SK_BETA(3) + OP_l_12_c_5_r_*SK_BETA(4) + OP_l_12_c_23_r_*SK_BETA(3) - OP_l_12_c_24_r_*SK_BETA(4) + OP_l_12_c_1_r_*SH_BETA(8)*SK_BETA(6) + OP_l_12_c_2_r_*SH_BETA(2)*SH_BETA(5)*SK_BETA(6)); -Kfusion(13) = SK_BETA(1)*(OP_l_13_c_6_r_*SK_BETA(2) - OP_l_13_c_3_r_*SK_BETA(5) - OP_l_13_c_4_r_*SK_BETA(3) + OP_l_13_c_5_r_*SK_BETA(4) + OP_l_13_c_23_r_*SK_BETA(3) - OP_l_13_c_24_r_*SK_BETA(4) + OP_l_13_c_1_r_*SH_BETA(8)*SK_BETA(6) + OP_l_13_c_2_r_*SH_BETA(2)*SH_BETA(5)*SK_BETA(6)); -Kfusion(14) = SK_BETA(1)*(OP_l_14_c_6_r_*SK_BETA(2) - OP_l_14_c_3_r_*SK_BETA(5) - OP_l_14_c_4_r_*SK_BETA(3) + OP_l_14_c_5_r_*SK_BETA(4) + OP_l_14_c_23_r_*SK_BETA(3) - OP_l_14_c_24_r_*SK_BETA(4) + OP_l_14_c_1_r_*SH_BETA(8)*SK_BETA(6) + OP_l_14_c_2_r_*SH_BETA(2)*SH_BETA(5)*SK_BETA(6)); -Kfusion(15) = SK_BETA(1)*(OP_l_15_c_6_r_*SK_BETA(2) - OP_l_15_c_3_r_*SK_BETA(5) - OP_l_15_c_4_r_*SK_BETA(3) + OP_l_15_c_5_r_*SK_BETA(4) + OP_l_15_c_23_r_*SK_BETA(3) - OP_l_15_c_24_r_*SK_BETA(4) + OP_l_15_c_1_r_*SH_BETA(8)*SK_BETA(6) + OP_l_15_c_2_r_*SH_BETA(2)*SH_BETA(5)*SK_BETA(6)); -Kfusion(16) = SK_BETA(1)*(OP_l_16_c_6_r_*SK_BETA(2) - OP_l_16_c_3_r_*SK_BETA(5) - OP_l_16_c_4_r_*SK_BETA(3) + OP_l_16_c_5_r_*SK_BETA(4) + OP_l_16_c_23_r_*SK_BETA(3) - OP_l_16_c_24_r_*SK_BETA(4) + OP_l_16_c_1_r_*SH_BETA(8)*SK_BETA(6) + OP_l_16_c_2_r_*SH_BETA(2)*SH_BETA(5)*SK_BETA(6)); -Kfusion(17) = SK_BETA(1)*(OP_l_17_c_6_r_*SK_BETA(2) - OP_l_17_c_3_r_*SK_BETA(5) - OP_l_17_c_4_r_*SK_BETA(3) + OP_l_17_c_5_r_*SK_BETA(4) + OP_l_17_c_23_r_*SK_BETA(3) - OP_l_17_c_24_r_*SK_BETA(4) + OP_l_17_c_1_r_*SH_BETA(8)*SK_BETA(6) + OP_l_17_c_2_r_*SH_BETA(2)*SH_BETA(5)*SK_BETA(6)); -Kfusion(18) = SK_BETA(1)*(OP_l_18_c_6_r_*SK_BETA(2) - OP_l_18_c_3_r_*SK_BETA(5) - OP_l_18_c_4_r_*SK_BETA(3) + OP_l_18_c_5_r_*SK_BETA(4) + OP_l_18_c_23_r_*SK_BETA(3) - OP_l_18_c_24_r_*SK_BETA(4) + OP_l_18_c_1_r_*SH_BETA(8)*SK_BETA(6) + OP_l_18_c_2_r_*SH_BETA(2)*SH_BETA(5)*SK_BETA(6)); -Kfusion(19) = SK_BETA(1)*(OP_l_19_c_6_r_*SK_BETA(2) - OP_l_19_c_3_r_*SK_BETA(5) - OP_l_19_c_4_r_*SK_BETA(3) + OP_l_19_c_5_r_*SK_BETA(4) + OP_l_19_c_23_r_*SK_BETA(3) - OP_l_19_c_24_r_*SK_BETA(4) + OP_l_19_c_1_r_*SH_BETA(8)*SK_BETA(6) + OP_l_19_c_2_r_*SH_BETA(2)*SH_BETA(5)*SK_BETA(6)); -Kfusion(20) = SK_BETA(1)*(OP_l_20_c_6_r_*SK_BETA(2) - OP_l_20_c_3_r_*SK_BETA(5) - OP_l_20_c_4_r_*SK_BETA(3) + OP_l_20_c_5_r_*SK_BETA(4) + OP_l_20_c_23_r_*SK_BETA(3) - OP_l_20_c_24_r_*SK_BETA(4) + OP_l_20_c_1_r_*SH_BETA(8)*SK_BETA(6) + OP_l_20_c_2_r_*SH_BETA(2)*SH_BETA(5)*SK_BETA(6)); -Kfusion(21) = SK_BETA(1)*(OP_l_21_c_6_r_*SK_BETA(2) - OP_l_21_c_3_r_*SK_BETA(5) - OP_l_21_c_4_r_*SK_BETA(3) + OP_l_21_c_5_r_*SK_BETA(4) + OP_l_21_c_23_r_*SK_BETA(3) - OP_l_21_c_24_r_*SK_BETA(4) + OP_l_21_c_1_r_*SH_BETA(8)*SK_BETA(6) + OP_l_21_c_2_r_*SH_BETA(2)*SH_BETA(5)*SK_BETA(6)); -Kfusion(22) = SK_BETA(1)*(OP_l_22_c_6_r_*SK_BETA(2) - OP_l_22_c_3_r_*SK_BETA(5) - OP_l_22_c_4_r_*SK_BETA(3) + OP_l_22_c_5_r_*SK_BETA(4) + OP_l_22_c_23_r_*SK_BETA(3) - OP_l_22_c_24_r_*SK_BETA(4) + OP_l_22_c_1_r_*SH_BETA(8)*SK_BETA(6) + OP_l_22_c_2_r_*SH_BETA(2)*SH_BETA(5)*SK_BETA(6)); -Kfusion(23) = SK_BETA(1)*(OP_l_23_c_6_r_*SK_BETA(2) - OP_l_23_c_3_r_*SK_BETA(5) - OP_l_23_c_4_r_*SK_BETA(3) + OP_l_23_c_5_r_*SK_BETA(4) + OP_l_23_c_23_r_*SK_BETA(3) - OP_l_23_c_24_r_*SK_BETA(4) + OP_l_23_c_1_r_*SH_BETA(8)*SK_BETA(6) + OP_l_23_c_2_r_*SH_BETA(2)*SH_BETA(5)*SK_BETA(6)); -Kfusion(24) = SK_BETA(1)*(OP_l_24_c_6_r_*SK_BETA(2) - OP_l_24_c_3_r_*SK_BETA(5) - OP_l_24_c_4_r_*SK_BETA(3) + OP_l_24_c_5_r_*SK_BETA(4) + OP_l_24_c_23_r_*SK_BETA(3) - OP_l_24_c_24_r_*SK_BETA(4) + OP_l_24_c_1_r_*SH_BETA(8)*SK_BETA(6) + OP_l_24_c_2_r_*SH_BETA(2)*SH_BETA(5)*SK_BETA(6)); +Kfusion(1) = SK_BETA(1)*(OP_l_1_c_1_r_*SK_BETA(6) + OP_l_1_c_2_r_*SK_BETA(5) - OP_l_1_c_5_r_*SK_BETA(2) + OP_l_1_c_6_r_*SK_BETA(3) + OP_l_1_c_3_r_*SK_BETA(7) + OP_l_1_c_7_r_*SK_BETA(4) - OP_l_1_c_4_r_*SK_BETA(8) + OP_l_1_c_23_r_*SK_BETA(2) - OP_l_1_c_24_r_*SK_BETA(3)); +Kfusion(2) = SK_BETA(1)*(OP_l_2_c_1_r_*SK_BETA(6) + OP_l_2_c_2_r_*SK_BETA(5) - OP_l_2_c_5_r_*SK_BETA(2) + OP_l_2_c_6_r_*SK_BETA(3) + OP_l_2_c_3_r_*SK_BETA(7) + OP_l_2_c_7_r_*SK_BETA(4) - OP_l_2_c_4_r_*SK_BETA(8) + OP_l_2_c_23_r_*SK_BETA(2) - OP_l_2_c_24_r_*SK_BETA(3)); +Kfusion(3) = SK_BETA(1)*(OP_l_3_c_1_r_*SK_BETA(6) + OP_l_3_c_2_r_*SK_BETA(5) - OP_l_3_c_5_r_*SK_BETA(2) + OP_l_3_c_6_r_*SK_BETA(3) + OP_l_3_c_3_r_*SK_BETA(7) + OP_l_3_c_7_r_*SK_BETA(4) - OP_l_3_c_4_r_*SK_BETA(8) + OP_l_3_c_23_r_*SK_BETA(2) - OP_l_3_c_24_r_*SK_BETA(3)); +Kfusion(4) = SK_BETA(1)*(OP_l_4_c_1_r_*SK_BETA(6) + OP_l_4_c_2_r_*SK_BETA(5) - OP_l_4_c_5_r_*SK_BETA(2) + OP_l_4_c_6_r_*SK_BETA(3) + OP_l_4_c_3_r_*SK_BETA(7) + OP_l_4_c_7_r_*SK_BETA(4) - OP_l_4_c_4_r_*SK_BETA(8) + OP_l_4_c_23_r_*SK_BETA(2) - OP_l_4_c_24_r_*SK_BETA(3)); +Kfusion(5) = SK_BETA(1)*(OP_l_5_c_1_r_*SK_BETA(6) + OP_l_5_c_2_r_*SK_BETA(5) - OP_l_5_c_5_r_*SK_BETA(2) + OP_l_5_c_6_r_*SK_BETA(3) + OP_l_5_c_3_r_*SK_BETA(7) + OP_l_5_c_7_r_*SK_BETA(4) - OP_l_5_c_4_r_*SK_BETA(8) + OP_l_5_c_23_r_*SK_BETA(2) - OP_l_5_c_24_r_*SK_BETA(3)); +Kfusion(6) = SK_BETA(1)*(OP_l_6_c_1_r_*SK_BETA(6) + OP_l_6_c_2_r_*SK_BETA(5) - OP_l_6_c_5_r_*SK_BETA(2) + OP_l_6_c_6_r_*SK_BETA(3) + OP_l_6_c_3_r_*SK_BETA(7) + OP_l_6_c_7_r_*SK_BETA(4) - OP_l_6_c_4_r_*SK_BETA(8) + OP_l_6_c_23_r_*SK_BETA(2) - OP_l_6_c_24_r_*SK_BETA(3)); +Kfusion(7) = SK_BETA(1)*(OP_l_7_c_1_r_*SK_BETA(6) + OP_l_7_c_2_r_*SK_BETA(5) - OP_l_7_c_5_r_*SK_BETA(2) + OP_l_7_c_6_r_*SK_BETA(3) + OP_l_7_c_3_r_*SK_BETA(7) + OP_l_7_c_7_r_*SK_BETA(4) - OP_l_7_c_4_r_*SK_BETA(8) + OP_l_7_c_23_r_*SK_BETA(2) - OP_l_7_c_24_r_*SK_BETA(3)); +Kfusion(8) = SK_BETA(1)*(OP_l_8_c_1_r_*SK_BETA(6) + OP_l_8_c_2_r_*SK_BETA(5) - OP_l_8_c_5_r_*SK_BETA(2) + OP_l_8_c_6_r_*SK_BETA(3) + OP_l_8_c_3_r_*SK_BETA(7) + OP_l_8_c_7_r_*SK_BETA(4) - OP_l_8_c_4_r_*SK_BETA(8) + OP_l_8_c_23_r_*SK_BETA(2) - OP_l_8_c_24_r_*SK_BETA(3)); +Kfusion(9) = SK_BETA(1)*(OP_l_9_c_1_r_*SK_BETA(6) + OP_l_9_c_2_r_*SK_BETA(5) - OP_l_9_c_5_r_*SK_BETA(2) + OP_l_9_c_6_r_*SK_BETA(3) + OP_l_9_c_3_r_*SK_BETA(7) + OP_l_9_c_7_r_*SK_BETA(4) - OP_l_9_c_4_r_*SK_BETA(8) + OP_l_9_c_23_r_*SK_BETA(2) - OP_l_9_c_24_r_*SK_BETA(3)); +Kfusion(10) = SK_BETA(1)*(OP_l_10_c_1_r_*SK_BETA(6) + OP_l_10_c_2_r_*SK_BETA(5) - OP_l_10_c_5_r_*SK_BETA(2) + OP_l_10_c_6_r_*SK_BETA(3) + OP_l_10_c_3_r_*SK_BETA(7) + OP_l_10_c_7_r_*SK_BETA(4) - OP_l_10_c_4_r_*SK_BETA(8) + OP_l_10_c_23_r_*SK_BETA(2) - OP_l_10_c_24_r_*SK_BETA(3)); +Kfusion(11) = SK_BETA(1)*(OP_l_11_c_1_r_*SK_BETA(6) + OP_l_11_c_2_r_*SK_BETA(5) - OP_l_11_c_5_r_*SK_BETA(2) + OP_l_11_c_6_r_*SK_BETA(3) + OP_l_11_c_3_r_*SK_BETA(7) + OP_l_11_c_7_r_*SK_BETA(4) - OP_l_11_c_4_r_*SK_BETA(8) + OP_l_11_c_23_r_*SK_BETA(2) - OP_l_11_c_24_r_*SK_BETA(3)); +Kfusion(12) = SK_BETA(1)*(OP_l_12_c_1_r_*SK_BETA(6) + OP_l_12_c_2_r_*SK_BETA(5) - OP_l_12_c_5_r_*SK_BETA(2) + OP_l_12_c_6_r_*SK_BETA(3) + OP_l_12_c_3_r_*SK_BETA(7) + OP_l_12_c_7_r_*SK_BETA(4) - OP_l_12_c_4_r_*SK_BETA(8) + OP_l_12_c_23_r_*SK_BETA(2) - OP_l_12_c_24_r_*SK_BETA(3)); +Kfusion(13) = SK_BETA(1)*(OP_l_13_c_1_r_*SK_BETA(6) + OP_l_13_c_2_r_*SK_BETA(5) - OP_l_13_c_5_r_*SK_BETA(2) + OP_l_13_c_6_r_*SK_BETA(3) + OP_l_13_c_3_r_*SK_BETA(7) + OP_l_13_c_7_r_*SK_BETA(4) - OP_l_13_c_4_r_*SK_BETA(8) + OP_l_13_c_23_r_*SK_BETA(2) - OP_l_13_c_24_r_*SK_BETA(3)); +Kfusion(14) = SK_BETA(1)*(OP_l_14_c_1_r_*SK_BETA(6) + OP_l_14_c_2_r_*SK_BETA(5) - OP_l_14_c_5_r_*SK_BETA(2) + OP_l_14_c_6_r_*SK_BETA(3) + OP_l_14_c_3_r_*SK_BETA(7) + OP_l_14_c_7_r_*SK_BETA(4) - OP_l_14_c_4_r_*SK_BETA(8) + OP_l_14_c_23_r_*SK_BETA(2) - OP_l_14_c_24_r_*SK_BETA(3)); +Kfusion(15) = SK_BETA(1)*(OP_l_15_c_1_r_*SK_BETA(6) + OP_l_15_c_2_r_*SK_BETA(5) - OP_l_15_c_5_r_*SK_BETA(2) + OP_l_15_c_6_r_*SK_BETA(3) + OP_l_15_c_3_r_*SK_BETA(7) + OP_l_15_c_7_r_*SK_BETA(4) - OP_l_15_c_4_r_*SK_BETA(8) + OP_l_15_c_23_r_*SK_BETA(2) - OP_l_15_c_24_r_*SK_BETA(3)); +Kfusion(16) = SK_BETA(1)*(OP_l_16_c_1_r_*SK_BETA(6) + OP_l_16_c_2_r_*SK_BETA(5) - OP_l_16_c_5_r_*SK_BETA(2) + OP_l_16_c_6_r_*SK_BETA(3) + OP_l_16_c_3_r_*SK_BETA(7) + OP_l_16_c_7_r_*SK_BETA(4) - OP_l_16_c_4_r_*SK_BETA(8) + OP_l_16_c_23_r_*SK_BETA(2) - OP_l_16_c_24_r_*SK_BETA(3)); +Kfusion(17) = SK_BETA(1)*(OP_l_17_c_1_r_*SK_BETA(6) + OP_l_17_c_2_r_*SK_BETA(5) - OP_l_17_c_5_r_*SK_BETA(2) + OP_l_17_c_6_r_*SK_BETA(3) + OP_l_17_c_3_r_*SK_BETA(7) + OP_l_17_c_7_r_*SK_BETA(4) - OP_l_17_c_4_r_*SK_BETA(8) + OP_l_17_c_23_r_*SK_BETA(2) - OP_l_17_c_24_r_*SK_BETA(3)); +Kfusion(18) = SK_BETA(1)*(OP_l_18_c_1_r_*SK_BETA(6) + OP_l_18_c_2_r_*SK_BETA(5) - OP_l_18_c_5_r_*SK_BETA(2) + OP_l_18_c_6_r_*SK_BETA(3) + OP_l_18_c_3_r_*SK_BETA(7) + OP_l_18_c_7_r_*SK_BETA(4) - OP_l_18_c_4_r_*SK_BETA(8) + OP_l_18_c_23_r_*SK_BETA(2) - OP_l_18_c_24_r_*SK_BETA(3)); +Kfusion(19) = SK_BETA(1)*(OP_l_19_c_1_r_*SK_BETA(6) + OP_l_19_c_2_r_*SK_BETA(5) - OP_l_19_c_5_r_*SK_BETA(2) + OP_l_19_c_6_r_*SK_BETA(3) + OP_l_19_c_3_r_*SK_BETA(7) + OP_l_19_c_7_r_*SK_BETA(4) - OP_l_19_c_4_r_*SK_BETA(8) + OP_l_19_c_23_r_*SK_BETA(2) - OP_l_19_c_24_r_*SK_BETA(3)); +Kfusion(20) = SK_BETA(1)*(OP_l_20_c_1_r_*SK_BETA(6) + OP_l_20_c_2_r_*SK_BETA(5) - OP_l_20_c_5_r_*SK_BETA(2) + OP_l_20_c_6_r_*SK_BETA(3) + OP_l_20_c_3_r_*SK_BETA(7) + OP_l_20_c_7_r_*SK_BETA(4) - OP_l_20_c_4_r_*SK_BETA(8) + OP_l_20_c_23_r_*SK_BETA(2) - OP_l_20_c_24_r_*SK_BETA(3)); +Kfusion(21) = SK_BETA(1)*(OP_l_21_c_1_r_*SK_BETA(6) + OP_l_21_c_2_r_*SK_BETA(5) - OP_l_21_c_5_r_*SK_BETA(2) + OP_l_21_c_6_r_*SK_BETA(3) + OP_l_21_c_3_r_*SK_BETA(7) + OP_l_21_c_7_r_*SK_BETA(4) - OP_l_21_c_4_r_*SK_BETA(8) + OP_l_21_c_23_r_*SK_BETA(2) - OP_l_21_c_24_r_*SK_BETA(3)); +Kfusion(22) = SK_BETA(1)*(OP_l_22_c_1_r_*SK_BETA(6) + OP_l_22_c_2_r_*SK_BETA(5) - OP_l_22_c_5_r_*SK_BETA(2) + OP_l_22_c_6_r_*SK_BETA(3) + OP_l_22_c_3_r_*SK_BETA(7) + OP_l_22_c_7_r_*SK_BETA(4) - OP_l_22_c_4_r_*SK_BETA(8) + OP_l_22_c_23_r_*SK_BETA(2) - OP_l_22_c_24_r_*SK_BETA(3)); +Kfusion(23) = SK_BETA(1)*(OP_l_23_c_1_r_*SK_BETA(6) + OP_l_23_c_2_r_*SK_BETA(5) - OP_l_23_c_5_r_*SK_BETA(2) + OP_l_23_c_6_r_*SK_BETA(3) + OP_l_23_c_3_r_*SK_BETA(7) + OP_l_23_c_7_r_*SK_BETA(4) - OP_l_23_c_4_r_*SK_BETA(8) + OP_l_23_c_23_r_*SK_BETA(2) - OP_l_23_c_24_r_*SK_BETA(3)); +Kfusion(24) = SK_BETA(1)*(OP_l_24_c_1_r_*SK_BETA(6) + OP_l_24_c_2_r_*SK_BETA(5) - OP_l_24_c_5_r_*SK_BETA(2) + OP_l_24_c_6_r_*SK_BETA(3) + OP_l_24_c_3_r_*SK_BETA(7) + OP_l_24_c_7_r_*SK_BETA(4) - OP_l_24_c_4_r_*SK_BETA(8) + OP_l_24_c_23_r_*SK_BETA(2) - OP_l_24_c_24_r_*SK_BETA(3)); SH_MAG = zeros(9,1); -SH_MAG(1) = q0^2 - q1^2 + q2^2 - q3^2; -SH_MAG(2) = q0^2 + q1^2 - q2^2 - q3^2; -SH_MAG(3) = q0^2 - q1^2 - q2^2 + q3^2; -SH_MAG(4) = 2*q0*q1 + 2*q2*q3; -SH_MAG(5) = 2*q0*q3 + 2*q1*q2; -SH_MAG(6) = 2*q0*q2 + 2*q1*q3; -SH_MAG(7) = magE*(2*q0*q1 - 2*q2*q3); -SH_MAG(8) = 2*q1*q3 - 2*q0*q2; -SH_MAG(9) = 2*q0*q3; +SH_MAG(1) = 2*magD*q3 + 2*magE*q2 + 2*magN*q1; +SH_MAG(2) = 2*magD*q0 - 2*magE*q1 + 2*magN*q2; +SH_MAG(3) = 2*magD*q1 + 2*magE*q0 - 2*magN*q3; +SH_MAG(4) = q3^2; +SH_MAG(5) = q2^2; +SH_MAG(6) = q1^2; +SH_MAG(7) = q0^2; +SH_MAG(8) = 2*magN*q0; +SH_MAG(9) = 2*magE*q3; H_MAG = zeros(1,24); -H_MAG(2) = SH_MAG(7) - magD*SH_MAG(3) - magN*SH_MAG(6); -H_MAG(3) = magE*SH_MAG(1) + magD*SH_MAG(4) - magN*(SH_MAG(9) - 2*q1*q2); -H_MAG(17) = SH_MAG(2); -H_MAG(18) = SH_MAG(5); -H_MAG(19) = SH_MAG(8); +H_MAG(1) = SH_MAG(8) + SH_MAG(9) - 2*magD*q2; +H_MAG(2) = SH_MAG(1); +H_MAG(3) = -SH_MAG(2); +H_MAG(4) = SH_MAG(3); +H_MAG(17) = SH_MAG(6) - SH_MAG(5) - SH_MAG(4) + SH_MAG(7); +H_MAG(18) = 2*q0*q3 + 2*q1*q2; +H_MAG(19) = 2*q1*q3 - 2*q0*q2; H_MAG(20) = 1; -SK_MX = zeros(4,1); -SK_MX(1) = 1/(OP_l_20_c_20_r_ + R_MAG - OP_l_2_c_20_r_*(magD*SH_MAG(3) - SH_MAG(7) + magN*SH_MAG(6)) + OP_l_17_c_20_r_*SH_MAG(2) + OP_l_18_c_20_r_*SH_MAG(5) + OP_l_19_c_20_r_*SH_MAG(8) + OP_l_3_c_20_r_*(magE*SH_MAG(1) + magD*SH_MAG(4) - magN*(SH_MAG(9) - 2*q1*q2)) - (magD*SH_MAG(3) - SH_MAG(7) + magN*SH_MAG(6))*(OP_l_20_c_2_r_ - OP_l_2_c_2_r_*(magD*SH_MAG(3) - SH_MAG(7) + magN*SH_MAG(6)) + OP_l_17_c_2_r_*SH_MAG(2) + OP_l_18_c_2_r_*SH_MAG(5) + OP_l_19_c_2_r_*SH_MAG(8) + OP_l_3_c_2_r_*(magE*SH_MAG(1) + magD*SH_MAG(4) - magN*(SH_MAG(9) - 2*q1*q2))) + SH_MAG(2)*(OP_l_20_c_17_r_ - OP_l_2_c_17_r_*(magD*SH_MAG(3) - SH_MAG(7) + magN*SH_MAG(6)) + OP_l_17_c_17_r_*SH_MAG(2) + OP_l_18_c_17_r_*SH_MAG(5) + OP_l_19_c_17_r_*SH_MAG(8) + OP_l_3_c_17_r_*(magE*SH_MAG(1) + magD*SH_MAG(4) - magN*(SH_MAG(9) - 2*q1*q2))) + SH_MAG(5)*(OP_l_20_c_18_r_ - OP_l_2_c_18_r_*(magD*SH_MAG(3) - SH_MAG(7) + magN*SH_MAG(6)) + OP_l_17_c_18_r_*SH_MAG(2) + OP_l_18_c_18_r_*SH_MAG(5) + OP_l_19_c_18_r_*SH_MAG(8) + OP_l_3_c_18_r_*(magE*SH_MAG(1) + magD*SH_MAG(4) - magN*(SH_MAG(9) - 2*q1*q2))) + SH_MAG(8)*(OP_l_20_c_19_r_ - OP_l_2_c_19_r_*(magD*SH_MAG(3) - SH_MAG(7) + magN*SH_MAG(6)) + OP_l_17_c_19_r_*SH_MAG(2) + OP_l_18_c_19_r_*SH_MAG(5) + OP_l_19_c_19_r_*SH_MAG(8) + OP_l_3_c_19_r_*(magE*SH_MAG(1) + magD*SH_MAG(4) - magN*(SH_MAG(9) - 2*q1*q2))) + (magE*SH_MAG(1) + magD*SH_MAG(4) - magN*(SH_MAG(9) - 2*q1*q2))*(OP_l_20_c_3_r_ - OP_l_2_c_3_r_*(magD*SH_MAG(3) - SH_MAG(7) + magN*SH_MAG(6)) + OP_l_17_c_3_r_*SH_MAG(2) + OP_l_18_c_3_r_*SH_MAG(5) + OP_l_19_c_3_r_*SH_MAG(8) + OP_l_3_c_3_r_*(magE*SH_MAG(1) + magD*SH_MAG(4) - magN*(SH_MAG(9) - 2*q1*q2)))); -SK_MX(2) = magE*SH_MAG(1) + magD*SH_MAG(4) - magN*(SH_MAG(9) - 2*q1*q2); -SK_MX(3) = magD*SH_MAG(3) - SH_MAG(7) + magN*SH_MAG(6); -SK_MX(4) = SH_MAG(8); +SK_MX = zeros(5,1); +SK_MX(1) = 1/(OP_l_20_c_20_r_ + R_MAG + OP_l_2_c_20_r_*SH_MAG(1) - OP_l_3_c_20_r_*SH_MAG(2) + OP_l_4_c_20_r_*SH_MAG(3) - OP_l_17_c_20_r_*(SH_MAG(4) + SH_MAG(5) - SH_MAG(6) - SH_MAG(7)) + (2*q0*q3 + 2*q1*q2)*(OP_l_20_c_18_r_ + OP_l_2_c_18_r_*SH_MAG(1) - OP_l_3_c_18_r_*SH_MAG(2) + OP_l_4_c_18_r_*SH_MAG(3) - OP_l_17_c_18_r_*(SH_MAG(4) + SH_MAG(5) - SH_MAG(6) - SH_MAG(7)) + OP_l_18_c_18_r_*(2*q0*q3 + 2*q1*q2) - OP_l_19_c_18_r_*(2*q0*q2 - 2*q1*q3) + OP_l_1_c_18_r_*(SH_MAG(8) + SH_MAG(9) - 2*magD*q2)) - (2*q0*q2 - 2*q1*q3)*(OP_l_20_c_19_r_ + OP_l_2_c_19_r_*SH_MAG(1) - OP_l_3_c_19_r_*SH_MAG(2) + OP_l_4_c_19_r_*SH_MAG(3) - OP_l_17_c_19_r_*(SH_MAG(4) + SH_MAG(5) - SH_MAG(6) - SH_MAG(7)) + OP_l_18_c_19_r_*(2*q0*q3 + 2*q1*q2) - OP_l_19_c_19_r_*(2*q0*q2 - 2*q1*q3) + OP_l_1_c_19_r_*(SH_MAG(8) + SH_MAG(9) - 2*magD*q2)) + (SH_MAG(8) + SH_MAG(9) - 2*magD*q2)*(OP_l_20_c_1_r_ + OP_l_2_c_1_r_*SH_MAG(1) - OP_l_3_c_1_r_*SH_MAG(2) + OP_l_4_c_1_r_*SH_MAG(3) - OP_l_17_c_1_r_*(SH_MAG(4) + SH_MAG(5) - SH_MAG(6) - SH_MAG(7)) + OP_l_18_c_1_r_*(2*q0*q3 + 2*q1*q2) - OP_l_19_c_1_r_*(2*q0*q2 - 2*q1*q3) + OP_l_1_c_1_r_*(SH_MAG(8) + SH_MAG(9) - 2*magD*q2)) + OP_l_18_c_20_r_*(2*q0*q3 + 2*q1*q2) - OP_l_19_c_20_r_*(2*q0*q2 - 2*q1*q3) + SH_MAG(1)*(OP_l_20_c_2_r_ + OP_l_2_c_2_r_*SH_MAG(1) - OP_l_3_c_2_r_*SH_MAG(2) + OP_l_4_c_2_r_*SH_MAG(3) - OP_l_17_c_2_r_*(SH_MAG(4) + SH_MAG(5) - SH_MAG(6) - SH_MAG(7)) + OP_l_18_c_2_r_*(2*q0*q3 + 2*q1*q2) - OP_l_19_c_2_r_*(2*q0*q2 - 2*q1*q3) + OP_l_1_c_2_r_*(SH_MAG(8) + SH_MAG(9) - 2*magD*q2)) - SH_MAG(2)*(OP_l_20_c_3_r_ + OP_l_2_c_3_r_*SH_MAG(1) - OP_l_3_c_3_r_*SH_MAG(2) + OP_l_4_c_3_r_*SH_MAG(3) - OP_l_17_c_3_r_*(SH_MAG(4) + SH_MAG(5) - SH_MAG(6) - SH_MAG(7)) + OP_l_18_c_3_r_*(2*q0*q3 + 2*q1*q2) - OP_l_19_c_3_r_*(2*q0*q2 - 2*q1*q3) + OP_l_1_c_3_r_*(SH_MAG(8) + SH_MAG(9) - 2*magD*q2)) + SH_MAG(3)*(OP_l_20_c_4_r_ + OP_l_2_c_4_r_*SH_MAG(1) - OP_l_3_c_4_r_*SH_MAG(2) + OP_l_4_c_4_r_*SH_MAG(3) - OP_l_17_c_4_r_*(SH_MAG(4) + SH_MAG(5) - SH_MAG(6) - SH_MAG(7)) + OP_l_18_c_4_r_*(2*q0*q3 + 2*q1*q2) - OP_l_19_c_4_r_*(2*q0*q2 - 2*q1*q3) + OP_l_1_c_4_r_*(SH_MAG(8) + SH_MAG(9) - 2*magD*q2)) - (SH_MAG(4) + SH_MAG(5) - SH_MAG(6) - SH_MAG(7))*(OP_l_20_c_17_r_ + OP_l_2_c_17_r_*SH_MAG(1) - OP_l_3_c_17_r_*SH_MAG(2) + OP_l_4_c_17_r_*SH_MAG(3) - OP_l_17_c_17_r_*(SH_MAG(4) + SH_MAG(5) - SH_MAG(6) - SH_MAG(7)) + OP_l_18_c_17_r_*(2*q0*q3 + 2*q1*q2) - OP_l_19_c_17_r_*(2*q0*q2 - 2*q1*q3) + OP_l_1_c_17_r_*(SH_MAG(8) + SH_MAG(9) - 2*magD*q2)) + OP_l_1_c_20_r_*(SH_MAG(8) + SH_MAG(9) - 2*magD*q2)); +SK_MX(2) = SH_MAG(4) + SH_MAG(5) - SH_MAG(6) - SH_MAG(7); +SK_MX(3) = SH_MAG(8) + SH_MAG(9) - 2*magD*q2; +SK_MX(4) = 2*q0*q2 - 2*q1*q3; +SK_MX(5) = 2*q0*q3 + 2*q1*q2; Kfusion = zeros(24,1); Kfusion = zeros(1,1); -Kfusion(1) = SK_MX(1)*(OP_l_1_c_20_r_ + OP_l_1_c_17_r_*SH_MAG(2) + OP_l_1_c_18_r_*SH_MAG(5) - OP_l_1_c_2_r_*SK_MX(3) + OP_l_1_c_3_r_*SK_MX(2) + OP_l_1_c_19_r_*SK_MX(4)); -Kfusion(2) = SK_MX(1)*(OP_l_2_c_20_r_ + OP_l_2_c_17_r_*SH_MAG(2) + OP_l_2_c_18_r_*SH_MAG(5) - OP_l_2_c_2_r_*SK_MX(3) + OP_l_2_c_3_r_*SK_MX(2) + OP_l_2_c_19_r_*SK_MX(4)); -Kfusion(3) = SK_MX(1)*(OP_l_3_c_20_r_ + OP_l_3_c_17_r_*SH_MAG(2) + OP_l_3_c_18_r_*SH_MAG(5) - OP_l_3_c_2_r_*SK_MX(3) + OP_l_3_c_3_r_*SK_MX(2) + OP_l_3_c_19_r_*SK_MX(4)); -Kfusion(4) = SK_MX(1)*(OP_l_4_c_20_r_ + OP_l_4_c_17_r_*SH_MAG(2) + OP_l_4_c_18_r_*SH_MAG(5) - OP_l_4_c_2_r_*SK_MX(3) + OP_l_4_c_3_r_*SK_MX(2) + OP_l_4_c_19_r_*SK_MX(4)); -Kfusion(5) = SK_MX(1)*(OP_l_5_c_20_r_ + OP_l_5_c_17_r_*SH_MAG(2) + OP_l_5_c_18_r_*SH_MAG(5) - OP_l_5_c_2_r_*SK_MX(3) + OP_l_5_c_3_r_*SK_MX(2) + OP_l_5_c_19_r_*SK_MX(4)); -Kfusion(6) = SK_MX(1)*(OP_l_6_c_20_r_ + OP_l_6_c_17_r_*SH_MAG(2) + OP_l_6_c_18_r_*SH_MAG(5) - OP_l_6_c_2_r_*SK_MX(3) + OP_l_6_c_3_r_*SK_MX(2) + OP_l_6_c_19_r_*SK_MX(4)); -Kfusion(7) = SK_MX(1)*(OP_l_7_c_20_r_ + OP_l_7_c_17_r_*SH_MAG(2) + OP_l_7_c_18_r_*SH_MAG(5) - OP_l_7_c_2_r_*SK_MX(3) + OP_l_7_c_3_r_*SK_MX(2) + OP_l_7_c_19_r_*SK_MX(4)); -Kfusion(8) = SK_MX(1)*(OP_l_8_c_20_r_ + OP_l_8_c_17_r_*SH_MAG(2) + OP_l_8_c_18_r_*SH_MAG(5) - OP_l_8_c_2_r_*SK_MX(3) + OP_l_8_c_3_r_*SK_MX(2) + OP_l_8_c_19_r_*SK_MX(4)); -Kfusion(9) = SK_MX(1)*(OP_l_9_c_20_r_ + OP_l_9_c_17_r_*SH_MAG(2) + OP_l_9_c_18_r_*SH_MAG(5) - OP_l_9_c_2_r_*SK_MX(3) + OP_l_9_c_3_r_*SK_MX(2) + OP_l_9_c_19_r_*SK_MX(4)); -Kfusion(10) = SK_MX(1)*(OP_l_10_c_20_r_ + OP_l_10_c_17_r_*SH_MAG(2) + OP_l_10_c_18_r_*SH_MAG(5) - OP_l_10_c_2_r_*SK_MX(3) + OP_l_10_c_3_r_*SK_MX(2) + OP_l_10_c_19_r_*SK_MX(4)); -Kfusion(11) = SK_MX(1)*(OP_l_11_c_20_r_ + OP_l_11_c_17_r_*SH_MAG(2) + OP_l_11_c_18_r_*SH_MAG(5) - OP_l_11_c_2_r_*SK_MX(3) + OP_l_11_c_3_r_*SK_MX(2) + OP_l_11_c_19_r_*SK_MX(4)); -Kfusion(12) = SK_MX(1)*(OP_l_12_c_20_r_ + OP_l_12_c_17_r_*SH_MAG(2) + OP_l_12_c_18_r_*SH_MAG(5) - OP_l_12_c_2_r_*SK_MX(3) + OP_l_12_c_3_r_*SK_MX(2) + OP_l_12_c_19_r_*SK_MX(4)); -Kfusion(13) = SK_MX(1)*(OP_l_13_c_20_r_ + OP_l_13_c_17_r_*SH_MAG(2) + OP_l_13_c_18_r_*SH_MAG(5) - OP_l_13_c_2_r_*SK_MX(3) + OP_l_13_c_3_r_*SK_MX(2) + OP_l_13_c_19_r_*SK_MX(4)); -Kfusion(14) = SK_MX(1)*(OP_l_14_c_20_r_ + OP_l_14_c_17_r_*SH_MAG(2) + OP_l_14_c_18_r_*SH_MAG(5) - OP_l_14_c_2_r_*SK_MX(3) + OP_l_14_c_3_r_*SK_MX(2) + OP_l_14_c_19_r_*SK_MX(4)); -Kfusion(15) = SK_MX(1)*(OP_l_15_c_20_r_ + OP_l_15_c_17_r_*SH_MAG(2) + OP_l_15_c_18_r_*SH_MAG(5) - OP_l_15_c_2_r_*SK_MX(3) + OP_l_15_c_3_r_*SK_MX(2) + OP_l_15_c_19_r_*SK_MX(4)); -Kfusion(16) = SK_MX(1)*(OP_l_16_c_20_r_ + OP_l_16_c_17_r_*SH_MAG(2) + OP_l_16_c_18_r_*SH_MAG(5) - OP_l_16_c_2_r_*SK_MX(3) + OP_l_16_c_3_r_*SK_MX(2) + OP_l_16_c_19_r_*SK_MX(4)); -Kfusion(17) = SK_MX(1)*(OP_l_17_c_20_r_ + OP_l_17_c_17_r_*SH_MAG(2) + OP_l_17_c_18_r_*SH_MAG(5) - OP_l_17_c_2_r_*SK_MX(3) + OP_l_17_c_3_r_*SK_MX(2) + OP_l_17_c_19_r_*SK_MX(4)); -Kfusion(18) = SK_MX(1)*(OP_l_18_c_20_r_ + OP_l_18_c_17_r_*SH_MAG(2) + OP_l_18_c_18_r_*SH_MAG(5) - OP_l_18_c_2_r_*SK_MX(3) + OP_l_18_c_3_r_*SK_MX(2) + OP_l_18_c_19_r_*SK_MX(4)); -Kfusion(19) = SK_MX(1)*(OP_l_19_c_20_r_ + OP_l_19_c_17_r_*SH_MAG(2) + OP_l_19_c_18_r_*SH_MAG(5) - OP_l_19_c_2_r_*SK_MX(3) + OP_l_19_c_3_r_*SK_MX(2) + OP_l_19_c_19_r_*SK_MX(4)); -Kfusion(20) = SK_MX(1)*(OP_l_20_c_20_r_ + OP_l_20_c_17_r_*SH_MAG(2) + OP_l_20_c_18_r_*SH_MAG(5) - OP_l_20_c_2_r_*SK_MX(3) + OP_l_20_c_3_r_*SK_MX(2) + OP_l_20_c_19_r_*SK_MX(4)); -Kfusion(21) = SK_MX(1)*(OP_l_21_c_20_r_ + OP_l_21_c_17_r_*SH_MAG(2) + OP_l_21_c_18_r_*SH_MAG(5) - OP_l_21_c_2_r_*SK_MX(3) + OP_l_21_c_3_r_*SK_MX(2) + OP_l_21_c_19_r_*SK_MX(4)); -Kfusion(22) = SK_MX(1)*(OP_l_22_c_20_r_ + OP_l_22_c_17_r_*SH_MAG(2) + OP_l_22_c_18_r_*SH_MAG(5) - OP_l_22_c_2_r_*SK_MX(3) + OP_l_22_c_3_r_*SK_MX(2) + OP_l_22_c_19_r_*SK_MX(4)); -Kfusion(23) = SK_MX(1)*(OP_l_23_c_20_r_ + OP_l_23_c_17_r_*SH_MAG(2) + OP_l_23_c_18_r_*SH_MAG(5) - OP_l_23_c_2_r_*SK_MX(3) + OP_l_23_c_3_r_*SK_MX(2) + OP_l_23_c_19_r_*SK_MX(4)); -Kfusion(24) = SK_MX(1)*(OP_l_24_c_20_r_ + OP_l_24_c_17_r_*SH_MAG(2) + OP_l_24_c_18_r_*SH_MAG(5) - OP_l_24_c_2_r_*SK_MX(3) + OP_l_24_c_3_r_*SK_MX(2) + OP_l_24_c_19_r_*SK_MX(4)); +Kfusion(1) = SK_MX(1)*(OP_l_1_c_20_r_ + OP_l_1_c_2_r_*SH_MAG(1) - OP_l_1_c_3_r_*SH_MAG(2) + OP_l_1_c_4_r_*SH_MAG(3) + OP_l_1_c_1_r_*SK_MX(3) - OP_l_1_c_17_r_*SK_MX(2) + OP_l_1_c_18_r_*SK_MX(5) - OP_l_1_c_19_r_*SK_MX(4)); +Kfusion(2) = SK_MX(1)*(OP_l_2_c_20_r_ + OP_l_2_c_2_r_*SH_MAG(1) - OP_l_2_c_3_r_*SH_MAG(2) + OP_l_2_c_4_r_*SH_MAG(3) + OP_l_2_c_1_r_*SK_MX(3) - OP_l_2_c_17_r_*SK_MX(2) + OP_l_2_c_18_r_*SK_MX(5) - OP_l_2_c_19_r_*SK_MX(4)); +Kfusion(3) = SK_MX(1)*(OP_l_3_c_20_r_ + OP_l_3_c_2_r_*SH_MAG(1) - OP_l_3_c_3_r_*SH_MAG(2) + OP_l_3_c_4_r_*SH_MAG(3) + OP_l_3_c_1_r_*SK_MX(3) - OP_l_3_c_17_r_*SK_MX(2) + OP_l_3_c_18_r_*SK_MX(5) - OP_l_3_c_19_r_*SK_MX(4)); +Kfusion(4) = SK_MX(1)*(OP_l_4_c_20_r_ + OP_l_4_c_2_r_*SH_MAG(1) - OP_l_4_c_3_r_*SH_MAG(2) + OP_l_4_c_4_r_*SH_MAG(3) + OP_l_4_c_1_r_*SK_MX(3) - OP_l_4_c_17_r_*SK_MX(2) + OP_l_4_c_18_r_*SK_MX(5) - OP_l_4_c_19_r_*SK_MX(4)); +Kfusion(5) = SK_MX(1)*(OP_l_5_c_20_r_ + OP_l_5_c_2_r_*SH_MAG(1) - OP_l_5_c_3_r_*SH_MAG(2) + OP_l_5_c_4_r_*SH_MAG(3) + OP_l_5_c_1_r_*SK_MX(3) - OP_l_5_c_17_r_*SK_MX(2) + OP_l_5_c_18_r_*SK_MX(5) - OP_l_5_c_19_r_*SK_MX(4)); +Kfusion(6) = SK_MX(1)*(OP_l_6_c_20_r_ + OP_l_6_c_2_r_*SH_MAG(1) - OP_l_6_c_3_r_*SH_MAG(2) + OP_l_6_c_4_r_*SH_MAG(3) + OP_l_6_c_1_r_*SK_MX(3) - OP_l_6_c_17_r_*SK_MX(2) + OP_l_6_c_18_r_*SK_MX(5) - OP_l_6_c_19_r_*SK_MX(4)); +Kfusion(7) = SK_MX(1)*(OP_l_7_c_20_r_ + OP_l_7_c_2_r_*SH_MAG(1) - OP_l_7_c_3_r_*SH_MAG(2) + OP_l_7_c_4_r_*SH_MAG(3) + OP_l_7_c_1_r_*SK_MX(3) - OP_l_7_c_17_r_*SK_MX(2) + OP_l_7_c_18_r_*SK_MX(5) - OP_l_7_c_19_r_*SK_MX(4)); +Kfusion(8) = SK_MX(1)*(OP_l_8_c_20_r_ + OP_l_8_c_2_r_*SH_MAG(1) - OP_l_8_c_3_r_*SH_MAG(2) + OP_l_8_c_4_r_*SH_MAG(3) + OP_l_8_c_1_r_*SK_MX(3) - OP_l_8_c_17_r_*SK_MX(2) + OP_l_8_c_18_r_*SK_MX(5) - OP_l_8_c_19_r_*SK_MX(4)); +Kfusion(9) = SK_MX(1)*(OP_l_9_c_20_r_ + OP_l_9_c_2_r_*SH_MAG(1) - OP_l_9_c_3_r_*SH_MAG(2) + OP_l_9_c_4_r_*SH_MAG(3) + OP_l_9_c_1_r_*SK_MX(3) - OP_l_9_c_17_r_*SK_MX(2) + OP_l_9_c_18_r_*SK_MX(5) - OP_l_9_c_19_r_*SK_MX(4)); +Kfusion(10) = SK_MX(1)*(OP_l_10_c_20_r_ + OP_l_10_c_2_r_*SH_MAG(1) - OP_l_10_c_3_r_*SH_MAG(2) + OP_l_10_c_4_r_*SH_MAG(3) + OP_l_10_c_1_r_*SK_MX(3) - OP_l_10_c_17_r_*SK_MX(2) + OP_l_10_c_18_r_*SK_MX(5) - OP_l_10_c_19_r_*SK_MX(4)); +Kfusion(11) = SK_MX(1)*(OP_l_11_c_20_r_ + OP_l_11_c_2_r_*SH_MAG(1) - OP_l_11_c_3_r_*SH_MAG(2) + OP_l_11_c_4_r_*SH_MAG(3) + OP_l_11_c_1_r_*SK_MX(3) - OP_l_11_c_17_r_*SK_MX(2) + OP_l_11_c_18_r_*SK_MX(5) - OP_l_11_c_19_r_*SK_MX(4)); +Kfusion(12) = SK_MX(1)*(OP_l_12_c_20_r_ + OP_l_12_c_2_r_*SH_MAG(1) - OP_l_12_c_3_r_*SH_MAG(2) + OP_l_12_c_4_r_*SH_MAG(3) + OP_l_12_c_1_r_*SK_MX(3) - OP_l_12_c_17_r_*SK_MX(2) + OP_l_12_c_18_r_*SK_MX(5) - OP_l_12_c_19_r_*SK_MX(4)); +Kfusion(13) = SK_MX(1)*(OP_l_13_c_20_r_ + OP_l_13_c_2_r_*SH_MAG(1) - OP_l_13_c_3_r_*SH_MAG(2) + OP_l_13_c_4_r_*SH_MAG(3) + OP_l_13_c_1_r_*SK_MX(3) - OP_l_13_c_17_r_*SK_MX(2) + OP_l_13_c_18_r_*SK_MX(5) - OP_l_13_c_19_r_*SK_MX(4)); +Kfusion(14) = SK_MX(1)*(OP_l_14_c_20_r_ + OP_l_14_c_2_r_*SH_MAG(1) - OP_l_14_c_3_r_*SH_MAG(2) + OP_l_14_c_4_r_*SH_MAG(3) + OP_l_14_c_1_r_*SK_MX(3) - OP_l_14_c_17_r_*SK_MX(2) + OP_l_14_c_18_r_*SK_MX(5) - OP_l_14_c_19_r_*SK_MX(4)); +Kfusion(15) = SK_MX(1)*(OP_l_15_c_20_r_ + OP_l_15_c_2_r_*SH_MAG(1) - OP_l_15_c_3_r_*SH_MAG(2) + OP_l_15_c_4_r_*SH_MAG(3) + OP_l_15_c_1_r_*SK_MX(3) - OP_l_15_c_17_r_*SK_MX(2) + OP_l_15_c_18_r_*SK_MX(5) - OP_l_15_c_19_r_*SK_MX(4)); +Kfusion(16) = SK_MX(1)*(OP_l_16_c_20_r_ + OP_l_16_c_2_r_*SH_MAG(1) - OP_l_16_c_3_r_*SH_MAG(2) + OP_l_16_c_4_r_*SH_MAG(3) + OP_l_16_c_1_r_*SK_MX(3) - OP_l_16_c_17_r_*SK_MX(2) + OP_l_16_c_18_r_*SK_MX(5) - OP_l_16_c_19_r_*SK_MX(4)); +Kfusion(17) = SK_MX(1)*(OP_l_17_c_20_r_ + OP_l_17_c_2_r_*SH_MAG(1) - OP_l_17_c_3_r_*SH_MAG(2) + OP_l_17_c_4_r_*SH_MAG(3) + OP_l_17_c_1_r_*SK_MX(3) - OP_l_17_c_17_r_*SK_MX(2) + OP_l_17_c_18_r_*SK_MX(5) - OP_l_17_c_19_r_*SK_MX(4)); +Kfusion(18) = SK_MX(1)*(OP_l_18_c_20_r_ + OP_l_18_c_2_r_*SH_MAG(1) - OP_l_18_c_3_r_*SH_MAG(2) + OP_l_18_c_4_r_*SH_MAG(3) + OP_l_18_c_1_r_*SK_MX(3) - OP_l_18_c_17_r_*SK_MX(2) + OP_l_18_c_18_r_*SK_MX(5) - OP_l_18_c_19_r_*SK_MX(4)); +Kfusion(19) = SK_MX(1)*(OP_l_19_c_20_r_ + OP_l_19_c_2_r_*SH_MAG(1) - OP_l_19_c_3_r_*SH_MAG(2) + OP_l_19_c_4_r_*SH_MAG(3) + OP_l_19_c_1_r_*SK_MX(3) - OP_l_19_c_17_r_*SK_MX(2) + OP_l_19_c_18_r_*SK_MX(5) - OP_l_19_c_19_r_*SK_MX(4)); +Kfusion(20) = SK_MX(1)*(OP_l_20_c_20_r_ + OP_l_20_c_2_r_*SH_MAG(1) - OP_l_20_c_3_r_*SH_MAG(2) + OP_l_20_c_4_r_*SH_MAG(3) + OP_l_20_c_1_r_*SK_MX(3) - OP_l_20_c_17_r_*SK_MX(2) + OP_l_20_c_18_r_*SK_MX(5) - OP_l_20_c_19_r_*SK_MX(4)); +Kfusion(21) = SK_MX(1)*(OP_l_21_c_20_r_ + OP_l_21_c_2_r_*SH_MAG(1) - OP_l_21_c_3_r_*SH_MAG(2) + OP_l_21_c_4_r_*SH_MAG(3) + OP_l_21_c_1_r_*SK_MX(3) - OP_l_21_c_17_r_*SK_MX(2) + OP_l_21_c_18_r_*SK_MX(5) - OP_l_21_c_19_r_*SK_MX(4)); +Kfusion(22) = SK_MX(1)*(OP_l_22_c_20_r_ + OP_l_22_c_2_r_*SH_MAG(1) - OP_l_22_c_3_r_*SH_MAG(2) + OP_l_22_c_4_r_*SH_MAG(3) + OP_l_22_c_1_r_*SK_MX(3) - OP_l_22_c_17_r_*SK_MX(2) + OP_l_22_c_18_r_*SK_MX(5) - OP_l_22_c_19_r_*SK_MX(4)); +Kfusion(23) = SK_MX(1)*(OP_l_23_c_20_r_ + OP_l_23_c_2_r_*SH_MAG(1) - OP_l_23_c_3_r_*SH_MAG(2) + OP_l_23_c_4_r_*SH_MAG(3) + OP_l_23_c_1_r_*SK_MX(3) - OP_l_23_c_17_r_*SK_MX(2) + OP_l_23_c_18_r_*SK_MX(5) - OP_l_23_c_19_r_*SK_MX(4)); +Kfusion(24) = SK_MX(1)*(OP_l_24_c_20_r_ + OP_l_24_c_2_r_*SH_MAG(1) - OP_l_24_c_3_r_*SH_MAG(2) + OP_l_24_c_4_r_*SH_MAG(3) + OP_l_24_c_1_r_*SK_MX(3) - OP_l_24_c_17_r_*SK_MX(2) + OP_l_24_c_18_r_*SK_MX(5) - OP_l_24_c_19_r_*SK_MX(4)); H_MAG = zeros(1,24); -H_MAG(1) = magD*SH_MAG(3) - SH_MAG(7) + magN*SH_MAG(6); -H_MAG(3) = - magE*SH_MAG(5) - magD*SH_MAG(8) - magN*SH_MAG(2); -H_MAG(17) = 2*q1*q2 - SH_MAG(9); -H_MAG(18) = SH_MAG(1); -H_MAG(19) = SH_MAG(4); +H_MAG(1) = SH_MAG(3); +H_MAG(2) = SH_MAG(2); +H_MAG(3) = SH_MAG(1); +H_MAG(4) = 2*magD*q2 - SH_MAG(9) - SH_MAG(8); +H_MAG(17) = 2*q1*q2 - 2*q0*q3; +H_MAG(18) = SH_MAG(5) - SH_MAG(4) - SH_MAG(6) + SH_MAG(7); +H_MAG(19) = 2*q0*q1 + 2*q2*q3; H_MAG(21) = 1; -SK_MY = zeros(4,1); -SK_MY(1) = 1/(OP_l_21_c_21_r_ + R_MAG + OP_l_1_c_21_r_*(magD*SH_MAG(3) - SH_MAG(7) + magN*SH_MAG(6)) + OP_l_18_c_21_r_*SH_MAG(1) + OP_l_19_c_21_r_*SH_MAG(4) - (SH_MAG(9) - 2*q1*q2)*(OP_l_21_c_17_r_ + OP_l_1_c_17_r_*(magD*SH_MAG(3) - SH_MAG(7) + magN*SH_MAG(6)) + OP_l_18_c_17_r_*SH_MAG(1) + OP_l_19_c_17_r_*SH_MAG(4) - OP_l_3_c_17_r_*(magE*SH_MAG(5) + magD*SH_MAG(8) + magN*SH_MAG(2)) - OP_l_17_c_17_r_*(SH_MAG(9) - 2*q1*q2)) - OP_l_3_c_21_r_*(magE*SH_MAG(5) + magD*SH_MAG(8) + magN*SH_MAG(2)) + (magD*SH_MAG(3) - SH_MAG(7) + magN*SH_MAG(6))*(OP_l_21_c_1_r_ + OP_l_1_c_1_r_*(magD*SH_MAG(3) - SH_MAG(7) + magN*SH_MAG(6)) + OP_l_18_c_1_r_*SH_MAG(1) + OP_l_19_c_1_r_*SH_MAG(4) - OP_l_3_c_1_r_*(magE*SH_MAG(5) + magD*SH_MAG(8) + magN*SH_MAG(2)) - OP_l_17_c_1_r_*(SH_MAG(9) - 2*q1*q2)) + SH_MAG(1)*(OP_l_21_c_18_r_ + OP_l_1_c_18_r_*(magD*SH_MAG(3) - SH_MAG(7) + magN*SH_MAG(6)) + OP_l_18_c_18_r_*SH_MAG(1) + OP_l_19_c_18_r_*SH_MAG(4) - OP_l_3_c_18_r_*(magE*SH_MAG(5) + magD*SH_MAG(8) + magN*SH_MAG(2)) - OP_l_17_c_18_r_*(SH_MAG(9) - 2*q1*q2)) + SH_MAG(4)*(OP_l_21_c_19_r_ + OP_l_1_c_19_r_*(magD*SH_MAG(3) - SH_MAG(7) + magN*SH_MAG(6)) + OP_l_18_c_19_r_*SH_MAG(1) + OP_l_19_c_19_r_*SH_MAG(4) - OP_l_3_c_19_r_*(magE*SH_MAG(5) + magD*SH_MAG(8) + magN*SH_MAG(2)) - OP_l_17_c_19_r_*(SH_MAG(9) - 2*q1*q2)) - OP_l_17_c_21_r_*(SH_MAG(9) - 2*q1*q2) - (magE*SH_MAG(5) + magD*SH_MAG(8) + magN*SH_MAG(2))*(OP_l_21_c_3_r_ + OP_l_1_c_3_r_*(magD*SH_MAG(3) - SH_MAG(7) + magN*SH_MAG(6)) + OP_l_18_c_3_r_*SH_MAG(1) + OP_l_19_c_3_r_*SH_MAG(4) - OP_l_3_c_3_r_*(magE*SH_MAG(5) + magD*SH_MAG(8) + magN*SH_MAG(2)) - OP_l_17_c_3_r_*(SH_MAG(9) - 2*q1*q2))); -SK_MY(2) = magE*SH_MAG(5) + magD*SH_MAG(8) + magN*SH_MAG(2); -SK_MY(3) = magD*SH_MAG(3) - SH_MAG(7) + magN*SH_MAG(6); -SK_MY(4) = SH_MAG(9) - 2*q1*q2; +SK_MY = zeros(5,1); +SK_MY(1) = 1/(OP_l_21_c_21_r_ + R_MAG + OP_l_1_c_21_r_*SH_MAG(3) + OP_l_2_c_21_r_*SH_MAG(2) + OP_l_3_c_21_r_*SH_MAG(1) - OP_l_18_c_21_r_*(SH_MAG(4) - SH_MAG(5) + SH_MAG(6) - SH_MAG(7)) - (2*q0*q3 - 2*q1*q2)*(OP_l_21_c_17_r_ + OP_l_1_c_17_r_*SH_MAG(3) + OP_l_2_c_17_r_*SH_MAG(2) + OP_l_3_c_17_r_*SH_MAG(1) - OP_l_18_c_17_r_*(SH_MAG(4) - SH_MAG(5) + SH_MAG(6) - SH_MAG(7)) - OP_l_17_c_17_r_*(2*q0*q3 - 2*q1*q2) + OP_l_19_c_17_r_*(2*q0*q1 + 2*q2*q3) - OP_l_4_c_17_r_*(SH_MAG(8) + SH_MAG(9) - 2*magD*q2)) + (2*q0*q1 + 2*q2*q3)*(OP_l_21_c_19_r_ + OP_l_1_c_19_r_*SH_MAG(3) + OP_l_2_c_19_r_*SH_MAG(2) + OP_l_3_c_19_r_*SH_MAG(1) - OP_l_18_c_19_r_*(SH_MAG(4) - SH_MAG(5) + SH_MAG(6) - SH_MAG(7)) - OP_l_17_c_19_r_*(2*q0*q3 - 2*q1*q2) + OP_l_19_c_19_r_*(2*q0*q1 + 2*q2*q3) - OP_l_4_c_19_r_*(SH_MAG(8) + SH_MAG(9) - 2*magD*q2)) - (SH_MAG(8) + SH_MAG(9) - 2*magD*q2)*(OP_l_21_c_4_r_ + OP_l_1_c_4_r_*SH_MAG(3) + OP_l_2_c_4_r_*SH_MAG(2) + OP_l_3_c_4_r_*SH_MAG(1) - OP_l_18_c_4_r_*(SH_MAG(4) - SH_MAG(5) + SH_MAG(6) - SH_MAG(7)) - OP_l_17_c_4_r_*(2*q0*q3 - 2*q1*q2) + OP_l_19_c_4_r_*(2*q0*q1 + 2*q2*q3) - OP_l_4_c_4_r_*(SH_MAG(8) + SH_MAG(9) - 2*magD*q2)) - OP_l_17_c_21_r_*(2*q0*q3 - 2*q1*q2) + OP_l_19_c_21_r_*(2*q0*q1 + 2*q2*q3) + SH_MAG(3)*(OP_l_21_c_1_r_ + OP_l_1_c_1_r_*SH_MAG(3) + OP_l_2_c_1_r_*SH_MAG(2) + OP_l_3_c_1_r_*SH_MAG(1) - OP_l_18_c_1_r_*(SH_MAG(4) - SH_MAG(5) + SH_MAG(6) - SH_MAG(7)) - OP_l_17_c_1_r_*(2*q0*q3 - 2*q1*q2) + OP_l_19_c_1_r_*(2*q0*q1 + 2*q2*q3) - OP_l_4_c_1_r_*(SH_MAG(8) + SH_MAG(9) - 2*magD*q2)) + SH_MAG(2)*(OP_l_21_c_2_r_ + OP_l_1_c_2_r_*SH_MAG(3) + OP_l_2_c_2_r_*SH_MAG(2) + OP_l_3_c_2_r_*SH_MAG(1) - OP_l_18_c_2_r_*(SH_MAG(4) - SH_MAG(5) + SH_MAG(6) - SH_MAG(7)) - OP_l_17_c_2_r_*(2*q0*q3 - 2*q1*q2) + OP_l_19_c_2_r_*(2*q0*q1 + 2*q2*q3) - OP_l_4_c_2_r_*(SH_MAG(8) + SH_MAG(9) - 2*magD*q2)) + SH_MAG(1)*(OP_l_21_c_3_r_ + OP_l_1_c_3_r_*SH_MAG(3) + OP_l_2_c_3_r_*SH_MAG(2) + OP_l_3_c_3_r_*SH_MAG(1) - OP_l_18_c_3_r_*(SH_MAG(4) - SH_MAG(5) + SH_MAG(6) - SH_MAG(7)) - OP_l_17_c_3_r_*(2*q0*q3 - 2*q1*q2) + OP_l_19_c_3_r_*(2*q0*q1 + 2*q2*q3) - OP_l_4_c_3_r_*(SH_MAG(8) + SH_MAG(9) - 2*magD*q2)) - (SH_MAG(4) - SH_MAG(5) + SH_MAG(6) - SH_MAG(7))*(OP_l_21_c_18_r_ + OP_l_1_c_18_r_*SH_MAG(3) + OP_l_2_c_18_r_*SH_MAG(2) + OP_l_3_c_18_r_*SH_MAG(1) - OP_l_18_c_18_r_*(SH_MAG(4) - SH_MAG(5) + SH_MAG(6) - SH_MAG(7)) - OP_l_17_c_18_r_*(2*q0*q3 - 2*q1*q2) + OP_l_19_c_18_r_*(2*q0*q1 + 2*q2*q3) - OP_l_4_c_18_r_*(SH_MAG(8) + SH_MAG(9) - 2*magD*q2)) - OP_l_4_c_21_r_*(SH_MAG(8) + SH_MAG(9) - 2*magD*q2)); +SK_MY(2) = SH_MAG(4) - SH_MAG(5) + SH_MAG(6) - SH_MAG(7); +SK_MY(3) = SH_MAG(8) + SH_MAG(9) - 2*magD*q2; +SK_MY(4) = 2*q0*q3 - 2*q1*q2; +SK_MY(5) = 2*q0*q1 + 2*q2*q3; Kfusion = zeros(24,1); Kfusion = zeros(1,1); -Kfusion(1) = SK_MY(1)*(OP_l_1_c_21_r_ + OP_l_1_c_18_r_*SH_MAG(1) + OP_l_1_c_19_r_*SH_MAG(4) + OP_l_1_c_1_r_*SK_MY(3) - OP_l_1_c_3_r_*SK_MY(2) - OP_l_1_c_17_r_*SK_MY(4)); -Kfusion(2) = SK_MY(1)*(OP_l_2_c_21_r_ + OP_l_2_c_18_r_*SH_MAG(1) + OP_l_2_c_19_r_*SH_MAG(4) + OP_l_2_c_1_r_*SK_MY(3) - OP_l_2_c_3_r_*SK_MY(2) - OP_l_2_c_17_r_*SK_MY(4)); -Kfusion(3) = SK_MY(1)*(OP_l_3_c_21_r_ + OP_l_3_c_18_r_*SH_MAG(1) + OP_l_3_c_19_r_*SH_MAG(4) + OP_l_3_c_1_r_*SK_MY(3) - OP_l_3_c_3_r_*SK_MY(2) - OP_l_3_c_17_r_*SK_MY(4)); -Kfusion(4) = SK_MY(1)*(OP_l_4_c_21_r_ + OP_l_4_c_18_r_*SH_MAG(1) + OP_l_4_c_19_r_*SH_MAG(4) + OP_l_4_c_1_r_*SK_MY(3) - OP_l_4_c_3_r_*SK_MY(2) - OP_l_4_c_17_r_*SK_MY(4)); -Kfusion(5) = SK_MY(1)*(OP_l_5_c_21_r_ + OP_l_5_c_18_r_*SH_MAG(1) + OP_l_5_c_19_r_*SH_MAG(4) + OP_l_5_c_1_r_*SK_MY(3) - OP_l_5_c_3_r_*SK_MY(2) - OP_l_5_c_17_r_*SK_MY(4)); -Kfusion(6) = SK_MY(1)*(OP_l_6_c_21_r_ + OP_l_6_c_18_r_*SH_MAG(1) + OP_l_6_c_19_r_*SH_MAG(4) + OP_l_6_c_1_r_*SK_MY(3) - OP_l_6_c_3_r_*SK_MY(2) - OP_l_6_c_17_r_*SK_MY(4)); -Kfusion(7) = SK_MY(1)*(OP_l_7_c_21_r_ + OP_l_7_c_18_r_*SH_MAG(1) + OP_l_7_c_19_r_*SH_MAG(4) + OP_l_7_c_1_r_*SK_MY(3) - OP_l_7_c_3_r_*SK_MY(2) - OP_l_7_c_17_r_*SK_MY(4)); -Kfusion(8) = SK_MY(1)*(OP_l_8_c_21_r_ + OP_l_8_c_18_r_*SH_MAG(1) + OP_l_8_c_19_r_*SH_MAG(4) + OP_l_8_c_1_r_*SK_MY(3) - OP_l_8_c_3_r_*SK_MY(2) - OP_l_8_c_17_r_*SK_MY(4)); -Kfusion(9) = SK_MY(1)*(OP_l_9_c_21_r_ + OP_l_9_c_18_r_*SH_MAG(1) + OP_l_9_c_19_r_*SH_MAG(4) + OP_l_9_c_1_r_*SK_MY(3) - OP_l_9_c_3_r_*SK_MY(2) - OP_l_9_c_17_r_*SK_MY(4)); -Kfusion(10) = SK_MY(1)*(OP_l_10_c_21_r_ + OP_l_10_c_18_r_*SH_MAG(1) + OP_l_10_c_19_r_*SH_MAG(4) + OP_l_10_c_1_r_*SK_MY(3) - OP_l_10_c_3_r_*SK_MY(2) - OP_l_10_c_17_r_*SK_MY(4)); -Kfusion(11) = SK_MY(1)*(OP_l_11_c_21_r_ + OP_l_11_c_18_r_*SH_MAG(1) + OP_l_11_c_19_r_*SH_MAG(4) + OP_l_11_c_1_r_*SK_MY(3) - OP_l_11_c_3_r_*SK_MY(2) - OP_l_11_c_17_r_*SK_MY(4)); -Kfusion(12) = SK_MY(1)*(OP_l_12_c_21_r_ + OP_l_12_c_18_r_*SH_MAG(1) + OP_l_12_c_19_r_*SH_MAG(4) + OP_l_12_c_1_r_*SK_MY(3) - OP_l_12_c_3_r_*SK_MY(2) - OP_l_12_c_17_r_*SK_MY(4)); -Kfusion(13) = SK_MY(1)*(OP_l_13_c_21_r_ + OP_l_13_c_18_r_*SH_MAG(1) + OP_l_13_c_19_r_*SH_MAG(4) + OP_l_13_c_1_r_*SK_MY(3) - OP_l_13_c_3_r_*SK_MY(2) - OP_l_13_c_17_r_*SK_MY(4)); -Kfusion(14) = SK_MY(1)*(OP_l_14_c_21_r_ + OP_l_14_c_18_r_*SH_MAG(1) + OP_l_14_c_19_r_*SH_MAG(4) + OP_l_14_c_1_r_*SK_MY(3) - OP_l_14_c_3_r_*SK_MY(2) - OP_l_14_c_17_r_*SK_MY(4)); -Kfusion(15) = SK_MY(1)*(OP_l_15_c_21_r_ + OP_l_15_c_18_r_*SH_MAG(1) + OP_l_15_c_19_r_*SH_MAG(4) + OP_l_15_c_1_r_*SK_MY(3) - OP_l_15_c_3_r_*SK_MY(2) - OP_l_15_c_17_r_*SK_MY(4)); -Kfusion(16) = SK_MY(1)*(OP_l_16_c_21_r_ + OP_l_16_c_18_r_*SH_MAG(1) + OP_l_16_c_19_r_*SH_MAG(4) + OP_l_16_c_1_r_*SK_MY(3) - OP_l_16_c_3_r_*SK_MY(2) - OP_l_16_c_17_r_*SK_MY(4)); -Kfusion(17) = SK_MY(1)*(OP_l_17_c_21_r_ + OP_l_17_c_18_r_*SH_MAG(1) + OP_l_17_c_19_r_*SH_MAG(4) + OP_l_17_c_1_r_*SK_MY(3) - OP_l_17_c_3_r_*SK_MY(2) - OP_l_17_c_17_r_*SK_MY(4)); -Kfusion(18) = SK_MY(1)*(OP_l_18_c_21_r_ + OP_l_18_c_18_r_*SH_MAG(1) + OP_l_18_c_19_r_*SH_MAG(4) + OP_l_18_c_1_r_*SK_MY(3) - OP_l_18_c_3_r_*SK_MY(2) - OP_l_18_c_17_r_*SK_MY(4)); -Kfusion(19) = SK_MY(1)*(OP_l_19_c_21_r_ + OP_l_19_c_18_r_*SH_MAG(1) + OP_l_19_c_19_r_*SH_MAG(4) + OP_l_19_c_1_r_*SK_MY(3) - OP_l_19_c_3_r_*SK_MY(2) - OP_l_19_c_17_r_*SK_MY(4)); -Kfusion(20) = SK_MY(1)*(OP_l_20_c_21_r_ + OP_l_20_c_18_r_*SH_MAG(1) + OP_l_20_c_19_r_*SH_MAG(4) + OP_l_20_c_1_r_*SK_MY(3) - OP_l_20_c_3_r_*SK_MY(2) - OP_l_20_c_17_r_*SK_MY(4)); -Kfusion(21) = SK_MY(1)*(OP_l_21_c_21_r_ + OP_l_21_c_18_r_*SH_MAG(1) + OP_l_21_c_19_r_*SH_MAG(4) + OP_l_21_c_1_r_*SK_MY(3) - OP_l_21_c_3_r_*SK_MY(2) - OP_l_21_c_17_r_*SK_MY(4)); -Kfusion(22) = SK_MY(1)*(OP_l_22_c_21_r_ + OP_l_22_c_18_r_*SH_MAG(1) + OP_l_22_c_19_r_*SH_MAG(4) + OP_l_22_c_1_r_*SK_MY(3) - OP_l_22_c_3_r_*SK_MY(2) - OP_l_22_c_17_r_*SK_MY(4)); -Kfusion(23) = SK_MY(1)*(OP_l_23_c_21_r_ + OP_l_23_c_18_r_*SH_MAG(1) + OP_l_23_c_19_r_*SH_MAG(4) + OP_l_23_c_1_r_*SK_MY(3) - OP_l_23_c_3_r_*SK_MY(2) - OP_l_23_c_17_r_*SK_MY(4)); -Kfusion(24) = SK_MY(1)*(OP_l_24_c_21_r_ + OP_l_24_c_18_r_*SH_MAG(1) + OP_l_24_c_19_r_*SH_MAG(4) + OP_l_24_c_1_r_*SK_MY(3) - OP_l_24_c_3_r_*SK_MY(2) - OP_l_24_c_17_r_*SK_MY(4)); +Kfusion(1) = SK_MY(1)*(OP_l_1_c_21_r_ + OP_l_1_c_1_r_*SH_MAG(3) + OP_l_1_c_2_r_*SH_MAG(2) + OP_l_1_c_3_r_*SH_MAG(1) - OP_l_1_c_4_r_*SK_MY(3) - OP_l_1_c_18_r_*SK_MY(2) - OP_l_1_c_17_r_*SK_MY(4) + OP_l_1_c_19_r_*SK_MY(5)); +Kfusion(2) = SK_MY(1)*(OP_l_2_c_21_r_ + OP_l_2_c_1_r_*SH_MAG(3) + OP_l_2_c_2_r_*SH_MAG(2) + OP_l_2_c_3_r_*SH_MAG(1) - OP_l_2_c_4_r_*SK_MY(3) - OP_l_2_c_18_r_*SK_MY(2) - OP_l_2_c_17_r_*SK_MY(4) + OP_l_2_c_19_r_*SK_MY(5)); +Kfusion(3) = SK_MY(1)*(OP_l_3_c_21_r_ + OP_l_3_c_1_r_*SH_MAG(3) + OP_l_3_c_2_r_*SH_MAG(2) + OP_l_3_c_3_r_*SH_MAG(1) - OP_l_3_c_4_r_*SK_MY(3) - OP_l_3_c_18_r_*SK_MY(2) - OP_l_3_c_17_r_*SK_MY(4) + OP_l_3_c_19_r_*SK_MY(5)); +Kfusion(4) = SK_MY(1)*(OP_l_4_c_21_r_ + OP_l_4_c_1_r_*SH_MAG(3) + OP_l_4_c_2_r_*SH_MAG(2) + OP_l_4_c_3_r_*SH_MAG(1) - OP_l_4_c_4_r_*SK_MY(3) - OP_l_4_c_18_r_*SK_MY(2) - OP_l_4_c_17_r_*SK_MY(4) + OP_l_4_c_19_r_*SK_MY(5)); +Kfusion(5) = SK_MY(1)*(OP_l_5_c_21_r_ + OP_l_5_c_1_r_*SH_MAG(3) + OP_l_5_c_2_r_*SH_MAG(2) + OP_l_5_c_3_r_*SH_MAG(1) - OP_l_5_c_4_r_*SK_MY(3) - OP_l_5_c_18_r_*SK_MY(2) - OP_l_5_c_17_r_*SK_MY(4) + OP_l_5_c_19_r_*SK_MY(5)); +Kfusion(6) = SK_MY(1)*(OP_l_6_c_21_r_ + OP_l_6_c_1_r_*SH_MAG(3) + OP_l_6_c_2_r_*SH_MAG(2) + OP_l_6_c_3_r_*SH_MAG(1) - OP_l_6_c_4_r_*SK_MY(3) - OP_l_6_c_18_r_*SK_MY(2) - OP_l_6_c_17_r_*SK_MY(4) + OP_l_6_c_19_r_*SK_MY(5)); +Kfusion(7) = SK_MY(1)*(OP_l_7_c_21_r_ + OP_l_7_c_1_r_*SH_MAG(3) + OP_l_7_c_2_r_*SH_MAG(2) + OP_l_7_c_3_r_*SH_MAG(1) - OP_l_7_c_4_r_*SK_MY(3) - OP_l_7_c_18_r_*SK_MY(2) - OP_l_7_c_17_r_*SK_MY(4) + OP_l_7_c_19_r_*SK_MY(5)); +Kfusion(8) = SK_MY(1)*(OP_l_8_c_21_r_ + OP_l_8_c_1_r_*SH_MAG(3) + OP_l_8_c_2_r_*SH_MAG(2) + OP_l_8_c_3_r_*SH_MAG(1) - OP_l_8_c_4_r_*SK_MY(3) - OP_l_8_c_18_r_*SK_MY(2) - OP_l_8_c_17_r_*SK_MY(4) + OP_l_8_c_19_r_*SK_MY(5)); +Kfusion(9) = SK_MY(1)*(OP_l_9_c_21_r_ + OP_l_9_c_1_r_*SH_MAG(3) + OP_l_9_c_2_r_*SH_MAG(2) + OP_l_9_c_3_r_*SH_MAG(1) - OP_l_9_c_4_r_*SK_MY(3) - OP_l_9_c_18_r_*SK_MY(2) - OP_l_9_c_17_r_*SK_MY(4) + OP_l_9_c_19_r_*SK_MY(5)); +Kfusion(10) = SK_MY(1)*(OP_l_10_c_21_r_ + OP_l_10_c_1_r_*SH_MAG(3) + OP_l_10_c_2_r_*SH_MAG(2) + OP_l_10_c_3_r_*SH_MAG(1) - OP_l_10_c_4_r_*SK_MY(3) - OP_l_10_c_18_r_*SK_MY(2) - OP_l_10_c_17_r_*SK_MY(4) + OP_l_10_c_19_r_*SK_MY(5)); +Kfusion(11) = SK_MY(1)*(OP_l_11_c_21_r_ + OP_l_11_c_1_r_*SH_MAG(3) + OP_l_11_c_2_r_*SH_MAG(2) + OP_l_11_c_3_r_*SH_MAG(1) - OP_l_11_c_4_r_*SK_MY(3) - OP_l_11_c_18_r_*SK_MY(2) - OP_l_11_c_17_r_*SK_MY(4) + OP_l_11_c_19_r_*SK_MY(5)); +Kfusion(12) = SK_MY(1)*(OP_l_12_c_21_r_ + OP_l_12_c_1_r_*SH_MAG(3) + OP_l_12_c_2_r_*SH_MAG(2) + OP_l_12_c_3_r_*SH_MAG(1) - OP_l_12_c_4_r_*SK_MY(3) - OP_l_12_c_18_r_*SK_MY(2) - OP_l_12_c_17_r_*SK_MY(4) + OP_l_12_c_19_r_*SK_MY(5)); +Kfusion(13) = SK_MY(1)*(OP_l_13_c_21_r_ + OP_l_13_c_1_r_*SH_MAG(3) + OP_l_13_c_2_r_*SH_MAG(2) + OP_l_13_c_3_r_*SH_MAG(1) - OP_l_13_c_4_r_*SK_MY(3) - OP_l_13_c_18_r_*SK_MY(2) - OP_l_13_c_17_r_*SK_MY(4) + OP_l_13_c_19_r_*SK_MY(5)); +Kfusion(14) = SK_MY(1)*(OP_l_14_c_21_r_ + OP_l_14_c_1_r_*SH_MAG(3) + OP_l_14_c_2_r_*SH_MAG(2) + OP_l_14_c_3_r_*SH_MAG(1) - OP_l_14_c_4_r_*SK_MY(3) - OP_l_14_c_18_r_*SK_MY(2) - OP_l_14_c_17_r_*SK_MY(4) + OP_l_14_c_19_r_*SK_MY(5)); +Kfusion(15) = SK_MY(1)*(OP_l_15_c_21_r_ + OP_l_15_c_1_r_*SH_MAG(3) + OP_l_15_c_2_r_*SH_MAG(2) + OP_l_15_c_3_r_*SH_MAG(1) - OP_l_15_c_4_r_*SK_MY(3) - OP_l_15_c_18_r_*SK_MY(2) - OP_l_15_c_17_r_*SK_MY(4) + OP_l_15_c_19_r_*SK_MY(5)); +Kfusion(16) = SK_MY(1)*(OP_l_16_c_21_r_ + OP_l_16_c_1_r_*SH_MAG(3) + OP_l_16_c_2_r_*SH_MAG(2) + OP_l_16_c_3_r_*SH_MAG(1) - OP_l_16_c_4_r_*SK_MY(3) - OP_l_16_c_18_r_*SK_MY(2) - OP_l_16_c_17_r_*SK_MY(4) + OP_l_16_c_19_r_*SK_MY(5)); +Kfusion(17) = SK_MY(1)*(OP_l_17_c_21_r_ + OP_l_17_c_1_r_*SH_MAG(3) + OP_l_17_c_2_r_*SH_MAG(2) + OP_l_17_c_3_r_*SH_MAG(1) - OP_l_17_c_4_r_*SK_MY(3) - OP_l_17_c_18_r_*SK_MY(2) - OP_l_17_c_17_r_*SK_MY(4) + OP_l_17_c_19_r_*SK_MY(5)); +Kfusion(18) = SK_MY(1)*(OP_l_18_c_21_r_ + OP_l_18_c_1_r_*SH_MAG(3) + OP_l_18_c_2_r_*SH_MAG(2) + OP_l_18_c_3_r_*SH_MAG(1) - OP_l_18_c_4_r_*SK_MY(3) - OP_l_18_c_18_r_*SK_MY(2) - OP_l_18_c_17_r_*SK_MY(4) + OP_l_18_c_19_r_*SK_MY(5)); +Kfusion(19) = SK_MY(1)*(OP_l_19_c_21_r_ + OP_l_19_c_1_r_*SH_MAG(3) + OP_l_19_c_2_r_*SH_MAG(2) + OP_l_19_c_3_r_*SH_MAG(1) - OP_l_19_c_4_r_*SK_MY(3) - OP_l_19_c_18_r_*SK_MY(2) - OP_l_19_c_17_r_*SK_MY(4) + OP_l_19_c_19_r_*SK_MY(5)); +Kfusion(20) = SK_MY(1)*(OP_l_20_c_21_r_ + OP_l_20_c_1_r_*SH_MAG(3) + OP_l_20_c_2_r_*SH_MAG(2) + OP_l_20_c_3_r_*SH_MAG(1) - OP_l_20_c_4_r_*SK_MY(3) - OP_l_20_c_18_r_*SK_MY(2) - OP_l_20_c_17_r_*SK_MY(4) + OP_l_20_c_19_r_*SK_MY(5)); +Kfusion(21) = SK_MY(1)*(OP_l_21_c_21_r_ + OP_l_21_c_1_r_*SH_MAG(3) + OP_l_21_c_2_r_*SH_MAG(2) + OP_l_21_c_3_r_*SH_MAG(1) - OP_l_21_c_4_r_*SK_MY(3) - OP_l_21_c_18_r_*SK_MY(2) - OP_l_21_c_17_r_*SK_MY(4) + OP_l_21_c_19_r_*SK_MY(5)); +Kfusion(22) = SK_MY(1)*(OP_l_22_c_21_r_ + OP_l_22_c_1_r_*SH_MAG(3) + OP_l_22_c_2_r_*SH_MAG(2) + OP_l_22_c_3_r_*SH_MAG(1) - OP_l_22_c_4_r_*SK_MY(3) - OP_l_22_c_18_r_*SK_MY(2) - OP_l_22_c_17_r_*SK_MY(4) + OP_l_22_c_19_r_*SK_MY(5)); +Kfusion(23) = SK_MY(1)*(OP_l_23_c_21_r_ + OP_l_23_c_1_r_*SH_MAG(3) + OP_l_23_c_2_r_*SH_MAG(2) + OP_l_23_c_3_r_*SH_MAG(1) - OP_l_23_c_4_r_*SK_MY(3) - OP_l_23_c_18_r_*SK_MY(2) - OP_l_23_c_17_r_*SK_MY(4) + OP_l_23_c_19_r_*SK_MY(5)); +Kfusion(24) = SK_MY(1)*(OP_l_24_c_21_r_ + OP_l_24_c_1_r_*SH_MAG(3) + OP_l_24_c_2_r_*SH_MAG(2) + OP_l_24_c_3_r_*SH_MAG(1) - OP_l_24_c_4_r_*SK_MY(3) - OP_l_24_c_18_r_*SK_MY(2) - OP_l_24_c_17_r_*SK_MY(4) + OP_l_24_c_19_r_*SK_MY(5)); H_MAG = zeros(1,24); -H_MAG(1) = magN*(SH_MAG(9) - 2*q1*q2) - magD*SH_MAG(4) - magE*SH_MAG(1); -H_MAG(2) = magE*SH_MAG(5) + magD*SH_MAG(8) + magN*SH_MAG(2); -H_MAG(17) = SH_MAG(6); +H_MAG(1) = SH_MAG(2); +H_MAG(2) = -SH_MAG(3); +H_MAG(3) = SH_MAG(8) + SH_MAG(9) - 2*magD*q2; +H_MAG(4) = SH_MAG(1); +H_MAG(17) = 2*q0*q2 + 2*q1*q3; H_MAG(18) = 2*q2*q3 - 2*q0*q1; -H_MAG(19) = SH_MAG(3); +H_MAG(19) = SH_MAG(4) - SH_MAG(5) - SH_MAG(6) + SH_MAG(7); H_MAG(22) = 1; -SK_MZ = zeros(4,1); -SK_MZ(1) = 1/(OP_l_22_c_22_r_ + R_MAG + OP_l_17_c_22_r_*SH_MAG(6) + OP_l_19_c_22_r_*SH_MAG(3) - (2*q0*q1 - 2*q2*q3)*(OP_l_22_c_18_r_ + OP_l_17_c_18_r_*SH_MAG(6) + OP_l_19_c_18_r_*SH_MAG(3) - OP_l_1_c_18_r_*(magE*SH_MAG(1) + magD*SH_MAG(4) - magN*(SH_MAG(9) - 2*q1*q2)) + OP_l_2_c_18_r_*(magE*SH_MAG(5) + magD*SH_MAG(8) + magN*SH_MAG(2)) - OP_l_18_c_18_r_*(2*q0*q1 - 2*q2*q3)) - OP_l_1_c_22_r_*(magE*SH_MAG(1) + magD*SH_MAG(4) - magN*(SH_MAG(9) - 2*q1*q2)) + OP_l_2_c_22_r_*(magE*SH_MAG(5) + magD*SH_MAG(8) + magN*SH_MAG(2)) + SH_MAG(6)*(OP_l_22_c_17_r_ + OP_l_17_c_17_r_*SH_MAG(6) + OP_l_19_c_17_r_*SH_MAG(3) - OP_l_1_c_17_r_*(magE*SH_MAG(1) + magD*SH_MAG(4) - magN*(SH_MAG(9) - 2*q1*q2)) + OP_l_2_c_17_r_*(magE*SH_MAG(5) + magD*SH_MAG(8) + magN*SH_MAG(2)) - OP_l_18_c_17_r_*(2*q0*q1 - 2*q2*q3)) + SH_MAG(3)*(OP_l_22_c_19_r_ + OP_l_17_c_19_r_*SH_MAG(6) + OP_l_19_c_19_r_*SH_MAG(3) - OP_l_1_c_19_r_*(magE*SH_MAG(1) + magD*SH_MAG(4) - magN*(SH_MAG(9) - 2*q1*q2)) + OP_l_2_c_19_r_*(magE*SH_MAG(5) + magD*SH_MAG(8) + magN*SH_MAG(2)) - OP_l_18_c_19_r_*(2*q0*q1 - 2*q2*q3)) - (magE*SH_MAG(1) + magD*SH_MAG(4) - magN*(SH_MAG(9) - 2*q1*q2))*(OP_l_22_c_1_r_ + OP_l_17_c_1_r_*SH_MAG(6) + OP_l_19_c_1_r_*SH_MAG(3) - OP_l_1_c_1_r_*(magE*SH_MAG(1) + magD*SH_MAG(4) - magN*(SH_MAG(9) - 2*q1*q2)) + OP_l_2_c_1_r_*(magE*SH_MAG(5) + magD*SH_MAG(8) + magN*SH_MAG(2)) - OP_l_18_c_1_r_*(2*q0*q1 - 2*q2*q3)) - OP_l_18_c_22_r_*(2*q0*q1 - 2*q2*q3) + (magE*SH_MAG(5) + magD*SH_MAG(8) + magN*SH_MAG(2))*(OP_l_22_c_2_r_ + OP_l_17_c_2_r_*SH_MAG(6) + OP_l_19_c_2_r_*SH_MAG(3) - OP_l_1_c_2_r_*(magE*SH_MAG(1) + magD*SH_MAG(4) - magN*(SH_MAG(9) - 2*q1*q2)) + OP_l_2_c_2_r_*(magE*SH_MAG(5) + magD*SH_MAG(8) + magN*SH_MAG(2)) - OP_l_18_c_2_r_*(2*q0*q1 - 2*q2*q3))); -SK_MZ(2) = magE*SH_MAG(1) + magD*SH_MAG(4) - magN*(SH_MAG(9) - 2*q1*q2); -SK_MZ(3) = magE*SH_MAG(5) + magD*SH_MAG(8) + magN*SH_MAG(2); +SK_MZ = zeros(5,1); +SK_MZ(1) = 1/(OP_l_22_c_22_r_ + R_MAG + OP_l_1_c_22_r_*SH_MAG(2) - OP_l_2_c_22_r_*SH_MAG(3) + OP_l_4_c_22_r_*SH_MAG(1) + OP_l_19_c_22_r_*(SH_MAG(4) - SH_MAG(5) - SH_MAG(6) + SH_MAG(7)) + (2*q0*q2 + 2*q1*q3)*(OP_l_22_c_17_r_ + OP_l_1_c_17_r_*SH_MAG(2) - OP_l_2_c_17_r_*SH_MAG(3) + OP_l_4_c_17_r_*SH_MAG(1) + OP_l_19_c_17_r_*(SH_MAG(4) - SH_MAG(5) - SH_MAG(6) + SH_MAG(7)) + OP_l_17_c_17_r_*(2*q0*q2 + 2*q1*q3) - OP_l_18_c_17_r_*(2*q0*q1 - 2*q2*q3) + OP_l_3_c_17_r_*(SH_MAG(8) + SH_MAG(9) - 2*magD*q2)) - (2*q0*q1 - 2*q2*q3)*(OP_l_22_c_18_r_ + OP_l_1_c_18_r_*SH_MAG(2) - OP_l_2_c_18_r_*SH_MAG(3) + OP_l_4_c_18_r_*SH_MAG(1) + OP_l_19_c_18_r_*(SH_MAG(4) - SH_MAG(5) - SH_MAG(6) + SH_MAG(7)) + OP_l_17_c_18_r_*(2*q0*q2 + 2*q1*q3) - OP_l_18_c_18_r_*(2*q0*q1 - 2*q2*q3) + OP_l_3_c_18_r_*(SH_MAG(8) + SH_MAG(9) - 2*magD*q2)) + (SH_MAG(8) + SH_MAG(9) - 2*magD*q2)*(OP_l_22_c_3_r_ + OP_l_1_c_3_r_*SH_MAG(2) - OP_l_2_c_3_r_*SH_MAG(3) + OP_l_4_c_3_r_*SH_MAG(1) + OP_l_19_c_3_r_*(SH_MAG(4) - SH_MAG(5) - SH_MAG(6) + SH_MAG(7)) + OP_l_17_c_3_r_*(2*q0*q2 + 2*q1*q3) - OP_l_18_c_3_r_*(2*q0*q1 - 2*q2*q3) + OP_l_3_c_3_r_*(SH_MAG(8) + SH_MAG(9) - 2*magD*q2)) + OP_l_17_c_22_r_*(2*q0*q2 + 2*q1*q3) - OP_l_18_c_22_r_*(2*q0*q1 - 2*q2*q3) + SH_MAG(2)*(OP_l_22_c_1_r_ + OP_l_1_c_1_r_*SH_MAG(2) - OP_l_2_c_1_r_*SH_MAG(3) + OP_l_4_c_1_r_*SH_MAG(1) + OP_l_19_c_1_r_*(SH_MAG(4) - SH_MAG(5) - SH_MAG(6) + SH_MAG(7)) + OP_l_17_c_1_r_*(2*q0*q2 + 2*q1*q3) - OP_l_18_c_1_r_*(2*q0*q1 - 2*q2*q3) + OP_l_3_c_1_r_*(SH_MAG(8) + SH_MAG(9) - 2*magD*q2)) - SH_MAG(3)*(OP_l_22_c_2_r_ + OP_l_1_c_2_r_*SH_MAG(2) - OP_l_2_c_2_r_*SH_MAG(3) + OP_l_4_c_2_r_*SH_MAG(1) + OP_l_19_c_2_r_*(SH_MAG(4) - SH_MAG(5) - SH_MAG(6) + SH_MAG(7)) + OP_l_17_c_2_r_*(2*q0*q2 + 2*q1*q3) - OP_l_18_c_2_r_*(2*q0*q1 - 2*q2*q3) + OP_l_3_c_2_r_*(SH_MAG(8) + SH_MAG(9) - 2*magD*q2)) + SH_MAG(1)*(OP_l_22_c_4_r_ + OP_l_1_c_4_r_*SH_MAG(2) - OP_l_2_c_4_r_*SH_MAG(3) + OP_l_4_c_4_r_*SH_MAG(1) + OP_l_19_c_4_r_*(SH_MAG(4) - SH_MAG(5) - SH_MAG(6) + SH_MAG(7)) + OP_l_17_c_4_r_*(2*q0*q2 + 2*q1*q3) - OP_l_18_c_4_r_*(2*q0*q1 - 2*q2*q3) + OP_l_3_c_4_r_*(SH_MAG(8) + SH_MAG(9) - 2*magD*q2)) + (SH_MAG(4) - SH_MAG(5) - SH_MAG(6) + SH_MAG(7))*(OP_l_22_c_19_r_ + OP_l_1_c_19_r_*SH_MAG(2) - OP_l_2_c_19_r_*SH_MAG(3) + OP_l_4_c_19_r_*SH_MAG(1) + OP_l_19_c_19_r_*(SH_MAG(4) - SH_MAG(5) - SH_MAG(6) + SH_MAG(7)) + OP_l_17_c_19_r_*(2*q0*q2 + 2*q1*q3) - OP_l_18_c_19_r_*(2*q0*q1 - 2*q2*q3) + OP_l_3_c_19_r_*(SH_MAG(8) + SH_MAG(9) - 2*magD*q2)) + OP_l_3_c_22_r_*(SH_MAG(8) + SH_MAG(9) - 2*magD*q2)); +SK_MZ(2) = SH_MAG(4) - SH_MAG(5) - SH_MAG(6) + SH_MAG(7); +SK_MZ(3) = SH_MAG(8) + SH_MAG(9) - 2*magD*q2; SK_MZ(4) = 2*q0*q1 - 2*q2*q3; +SK_MZ(5) = 2*q0*q2 + 2*q1*q3; Kfusion = zeros(24,1); Kfusion = zeros(1,1); -Kfusion(1) = SK_MZ(1)*(OP_l_1_c_22_r_ + OP_l_1_c_19_r_*SH_MAG(3) + OP_l_1_c_17_r_*SH_MAG(6) - OP_l_1_c_1_r_*SK_MZ(2) + OP_l_1_c_2_r_*SK_MZ(3) - OP_l_1_c_18_r_*SK_MZ(4)); -Kfusion(2) = SK_MZ(1)*(OP_l_2_c_22_r_ + OP_l_2_c_19_r_*SH_MAG(3) + OP_l_2_c_17_r_*SH_MAG(6) - OP_l_2_c_1_r_*SK_MZ(2) + OP_l_2_c_2_r_*SK_MZ(3) - OP_l_2_c_18_r_*SK_MZ(4)); -Kfusion(3) = SK_MZ(1)*(OP_l_3_c_22_r_ + OP_l_3_c_19_r_*SH_MAG(3) + OP_l_3_c_17_r_*SH_MAG(6) - OP_l_3_c_1_r_*SK_MZ(2) + OP_l_3_c_2_r_*SK_MZ(3) - OP_l_3_c_18_r_*SK_MZ(4)); -Kfusion(4) = SK_MZ(1)*(OP_l_4_c_22_r_ + OP_l_4_c_19_r_*SH_MAG(3) + OP_l_4_c_17_r_*SH_MAG(6) - OP_l_4_c_1_r_*SK_MZ(2) + OP_l_4_c_2_r_*SK_MZ(3) - OP_l_4_c_18_r_*SK_MZ(4)); -Kfusion(5) = SK_MZ(1)*(OP_l_5_c_22_r_ + OP_l_5_c_19_r_*SH_MAG(3) + OP_l_5_c_17_r_*SH_MAG(6) - OP_l_5_c_1_r_*SK_MZ(2) + OP_l_5_c_2_r_*SK_MZ(3) - OP_l_5_c_18_r_*SK_MZ(4)); -Kfusion(6) = SK_MZ(1)*(OP_l_6_c_22_r_ + OP_l_6_c_19_r_*SH_MAG(3) + OP_l_6_c_17_r_*SH_MAG(6) - OP_l_6_c_1_r_*SK_MZ(2) + OP_l_6_c_2_r_*SK_MZ(3) - OP_l_6_c_18_r_*SK_MZ(4)); -Kfusion(7) = SK_MZ(1)*(OP_l_7_c_22_r_ + OP_l_7_c_19_r_*SH_MAG(3) + OP_l_7_c_17_r_*SH_MAG(6) - OP_l_7_c_1_r_*SK_MZ(2) + OP_l_7_c_2_r_*SK_MZ(3) - OP_l_7_c_18_r_*SK_MZ(4)); -Kfusion(8) = SK_MZ(1)*(OP_l_8_c_22_r_ + OP_l_8_c_19_r_*SH_MAG(3) + OP_l_8_c_17_r_*SH_MAG(6) - OP_l_8_c_1_r_*SK_MZ(2) + OP_l_8_c_2_r_*SK_MZ(3) - OP_l_8_c_18_r_*SK_MZ(4)); -Kfusion(9) = SK_MZ(1)*(OP_l_9_c_22_r_ + OP_l_9_c_19_r_*SH_MAG(3) + OP_l_9_c_17_r_*SH_MAG(6) - OP_l_9_c_1_r_*SK_MZ(2) + OP_l_9_c_2_r_*SK_MZ(3) - OP_l_9_c_18_r_*SK_MZ(4)); -Kfusion(10) = SK_MZ(1)*(OP_l_10_c_22_r_ + OP_l_10_c_19_r_*SH_MAG(3) + OP_l_10_c_17_r_*SH_MAG(6) - OP_l_10_c_1_r_*SK_MZ(2) + OP_l_10_c_2_r_*SK_MZ(3) - OP_l_10_c_18_r_*SK_MZ(4)); -Kfusion(11) = SK_MZ(1)*(OP_l_11_c_22_r_ + OP_l_11_c_19_r_*SH_MAG(3) + OP_l_11_c_17_r_*SH_MAG(6) - OP_l_11_c_1_r_*SK_MZ(2) + OP_l_11_c_2_r_*SK_MZ(3) - OP_l_11_c_18_r_*SK_MZ(4)); -Kfusion(12) = SK_MZ(1)*(OP_l_12_c_22_r_ + OP_l_12_c_19_r_*SH_MAG(3) + OP_l_12_c_17_r_*SH_MAG(6) - OP_l_12_c_1_r_*SK_MZ(2) + OP_l_12_c_2_r_*SK_MZ(3) - OP_l_12_c_18_r_*SK_MZ(4)); -Kfusion(13) = SK_MZ(1)*(OP_l_13_c_22_r_ + OP_l_13_c_19_r_*SH_MAG(3) + OP_l_13_c_17_r_*SH_MAG(6) - OP_l_13_c_1_r_*SK_MZ(2) + OP_l_13_c_2_r_*SK_MZ(3) - OP_l_13_c_18_r_*SK_MZ(4)); -Kfusion(14) = SK_MZ(1)*(OP_l_14_c_22_r_ + OP_l_14_c_19_r_*SH_MAG(3) + OP_l_14_c_17_r_*SH_MAG(6) - OP_l_14_c_1_r_*SK_MZ(2) + OP_l_14_c_2_r_*SK_MZ(3) - OP_l_14_c_18_r_*SK_MZ(4)); -Kfusion(15) = SK_MZ(1)*(OP_l_15_c_22_r_ + OP_l_15_c_19_r_*SH_MAG(3) + OP_l_15_c_17_r_*SH_MAG(6) - OP_l_15_c_1_r_*SK_MZ(2) + OP_l_15_c_2_r_*SK_MZ(3) - OP_l_15_c_18_r_*SK_MZ(4)); -Kfusion(16) = SK_MZ(1)*(OP_l_16_c_22_r_ + OP_l_16_c_19_r_*SH_MAG(3) + OP_l_16_c_17_r_*SH_MAG(6) - OP_l_16_c_1_r_*SK_MZ(2) + OP_l_16_c_2_r_*SK_MZ(3) - OP_l_16_c_18_r_*SK_MZ(4)); -Kfusion(17) = SK_MZ(1)*(OP_l_17_c_22_r_ + OP_l_17_c_19_r_*SH_MAG(3) + OP_l_17_c_17_r_*SH_MAG(6) - OP_l_17_c_1_r_*SK_MZ(2) + OP_l_17_c_2_r_*SK_MZ(3) - OP_l_17_c_18_r_*SK_MZ(4)); -Kfusion(18) = SK_MZ(1)*(OP_l_18_c_22_r_ + OP_l_18_c_19_r_*SH_MAG(3) + OP_l_18_c_17_r_*SH_MAG(6) - OP_l_18_c_1_r_*SK_MZ(2) + OP_l_18_c_2_r_*SK_MZ(3) - OP_l_18_c_18_r_*SK_MZ(4)); -Kfusion(19) = SK_MZ(1)*(OP_l_19_c_22_r_ + OP_l_19_c_19_r_*SH_MAG(3) + OP_l_19_c_17_r_*SH_MAG(6) - OP_l_19_c_1_r_*SK_MZ(2) + OP_l_19_c_2_r_*SK_MZ(3) - OP_l_19_c_18_r_*SK_MZ(4)); -Kfusion(20) = SK_MZ(1)*(OP_l_20_c_22_r_ + OP_l_20_c_19_r_*SH_MAG(3) + OP_l_20_c_17_r_*SH_MAG(6) - OP_l_20_c_1_r_*SK_MZ(2) + OP_l_20_c_2_r_*SK_MZ(3) - OP_l_20_c_18_r_*SK_MZ(4)); -Kfusion(21) = SK_MZ(1)*(OP_l_21_c_22_r_ + OP_l_21_c_19_r_*SH_MAG(3) + OP_l_21_c_17_r_*SH_MAG(6) - OP_l_21_c_1_r_*SK_MZ(2) + OP_l_21_c_2_r_*SK_MZ(3) - OP_l_21_c_18_r_*SK_MZ(4)); -Kfusion(22) = SK_MZ(1)*(OP_l_22_c_22_r_ + OP_l_22_c_19_r_*SH_MAG(3) + OP_l_22_c_17_r_*SH_MAG(6) - OP_l_22_c_1_r_*SK_MZ(2) + OP_l_22_c_2_r_*SK_MZ(3) - OP_l_22_c_18_r_*SK_MZ(4)); -Kfusion(23) = SK_MZ(1)*(OP_l_23_c_22_r_ + OP_l_23_c_19_r_*SH_MAG(3) + OP_l_23_c_17_r_*SH_MAG(6) - OP_l_23_c_1_r_*SK_MZ(2) + OP_l_23_c_2_r_*SK_MZ(3) - OP_l_23_c_18_r_*SK_MZ(4)); -Kfusion(24) = SK_MZ(1)*(OP_l_24_c_22_r_ + OP_l_24_c_19_r_*SH_MAG(3) + OP_l_24_c_17_r_*SH_MAG(6) - OP_l_24_c_1_r_*SK_MZ(2) + OP_l_24_c_2_r_*SK_MZ(3) - OP_l_24_c_18_r_*SK_MZ(4)); +Kfusion(1) = SK_MZ(1)*(OP_l_1_c_22_r_ + OP_l_1_c_1_r_*SH_MAG(2) - OP_l_1_c_2_r_*SH_MAG(3) + OP_l_1_c_4_r_*SH_MAG(1) + OP_l_1_c_3_r_*SK_MZ(3) + OP_l_1_c_19_r_*SK_MZ(2) + OP_l_1_c_17_r_*SK_MZ(5) - OP_l_1_c_18_r_*SK_MZ(4)); +Kfusion(2) = SK_MZ(1)*(OP_l_2_c_22_r_ + OP_l_2_c_1_r_*SH_MAG(2) - OP_l_2_c_2_r_*SH_MAG(3) + OP_l_2_c_4_r_*SH_MAG(1) + OP_l_2_c_3_r_*SK_MZ(3) + OP_l_2_c_19_r_*SK_MZ(2) + OP_l_2_c_17_r_*SK_MZ(5) - OP_l_2_c_18_r_*SK_MZ(4)); +Kfusion(3) = SK_MZ(1)*(OP_l_3_c_22_r_ + OP_l_3_c_1_r_*SH_MAG(2) - OP_l_3_c_2_r_*SH_MAG(3) + OP_l_3_c_4_r_*SH_MAG(1) + OP_l_3_c_3_r_*SK_MZ(3) + OP_l_3_c_19_r_*SK_MZ(2) + OP_l_3_c_17_r_*SK_MZ(5) - OP_l_3_c_18_r_*SK_MZ(4)); +Kfusion(4) = SK_MZ(1)*(OP_l_4_c_22_r_ + OP_l_4_c_1_r_*SH_MAG(2) - OP_l_4_c_2_r_*SH_MAG(3) + OP_l_4_c_4_r_*SH_MAG(1) + OP_l_4_c_3_r_*SK_MZ(3) + OP_l_4_c_19_r_*SK_MZ(2) + OP_l_4_c_17_r_*SK_MZ(5) - OP_l_4_c_18_r_*SK_MZ(4)); +Kfusion(5) = SK_MZ(1)*(OP_l_5_c_22_r_ + OP_l_5_c_1_r_*SH_MAG(2) - OP_l_5_c_2_r_*SH_MAG(3) + OP_l_5_c_4_r_*SH_MAG(1) + OP_l_5_c_3_r_*SK_MZ(3) + OP_l_5_c_19_r_*SK_MZ(2) + OP_l_5_c_17_r_*SK_MZ(5) - OP_l_5_c_18_r_*SK_MZ(4)); +Kfusion(6) = SK_MZ(1)*(OP_l_6_c_22_r_ + OP_l_6_c_1_r_*SH_MAG(2) - OP_l_6_c_2_r_*SH_MAG(3) + OP_l_6_c_4_r_*SH_MAG(1) + OP_l_6_c_3_r_*SK_MZ(3) + OP_l_6_c_19_r_*SK_MZ(2) + OP_l_6_c_17_r_*SK_MZ(5) - OP_l_6_c_18_r_*SK_MZ(4)); +Kfusion(7) = SK_MZ(1)*(OP_l_7_c_22_r_ + OP_l_7_c_1_r_*SH_MAG(2) - OP_l_7_c_2_r_*SH_MAG(3) + OP_l_7_c_4_r_*SH_MAG(1) + OP_l_7_c_3_r_*SK_MZ(3) + OP_l_7_c_19_r_*SK_MZ(2) + OP_l_7_c_17_r_*SK_MZ(5) - OP_l_7_c_18_r_*SK_MZ(4)); +Kfusion(8) = SK_MZ(1)*(OP_l_8_c_22_r_ + OP_l_8_c_1_r_*SH_MAG(2) - OP_l_8_c_2_r_*SH_MAG(3) + OP_l_8_c_4_r_*SH_MAG(1) + OP_l_8_c_3_r_*SK_MZ(3) + OP_l_8_c_19_r_*SK_MZ(2) + OP_l_8_c_17_r_*SK_MZ(5) - OP_l_8_c_18_r_*SK_MZ(4)); +Kfusion(9) = SK_MZ(1)*(OP_l_9_c_22_r_ + OP_l_9_c_1_r_*SH_MAG(2) - OP_l_9_c_2_r_*SH_MAG(3) + OP_l_9_c_4_r_*SH_MAG(1) + OP_l_9_c_3_r_*SK_MZ(3) + OP_l_9_c_19_r_*SK_MZ(2) + OP_l_9_c_17_r_*SK_MZ(5) - OP_l_9_c_18_r_*SK_MZ(4)); +Kfusion(10) = SK_MZ(1)*(OP_l_10_c_22_r_ + OP_l_10_c_1_r_*SH_MAG(2) - OP_l_10_c_2_r_*SH_MAG(3) + OP_l_10_c_4_r_*SH_MAG(1) + OP_l_10_c_3_r_*SK_MZ(3) + OP_l_10_c_19_r_*SK_MZ(2) + OP_l_10_c_17_r_*SK_MZ(5) - OP_l_10_c_18_r_*SK_MZ(4)); +Kfusion(11) = SK_MZ(1)*(OP_l_11_c_22_r_ + OP_l_11_c_1_r_*SH_MAG(2) - OP_l_11_c_2_r_*SH_MAG(3) + OP_l_11_c_4_r_*SH_MAG(1) + OP_l_11_c_3_r_*SK_MZ(3) + OP_l_11_c_19_r_*SK_MZ(2) + OP_l_11_c_17_r_*SK_MZ(5) - OP_l_11_c_18_r_*SK_MZ(4)); +Kfusion(12) = SK_MZ(1)*(OP_l_12_c_22_r_ + OP_l_12_c_1_r_*SH_MAG(2) - OP_l_12_c_2_r_*SH_MAG(3) + OP_l_12_c_4_r_*SH_MAG(1) + OP_l_12_c_3_r_*SK_MZ(3) + OP_l_12_c_19_r_*SK_MZ(2) + OP_l_12_c_17_r_*SK_MZ(5) - OP_l_12_c_18_r_*SK_MZ(4)); +Kfusion(13) = SK_MZ(1)*(OP_l_13_c_22_r_ + OP_l_13_c_1_r_*SH_MAG(2) - OP_l_13_c_2_r_*SH_MAG(3) + OP_l_13_c_4_r_*SH_MAG(1) + OP_l_13_c_3_r_*SK_MZ(3) + OP_l_13_c_19_r_*SK_MZ(2) + OP_l_13_c_17_r_*SK_MZ(5) - OP_l_13_c_18_r_*SK_MZ(4)); +Kfusion(14) = SK_MZ(1)*(OP_l_14_c_22_r_ + OP_l_14_c_1_r_*SH_MAG(2) - OP_l_14_c_2_r_*SH_MAG(3) + OP_l_14_c_4_r_*SH_MAG(1) + OP_l_14_c_3_r_*SK_MZ(3) + OP_l_14_c_19_r_*SK_MZ(2) + OP_l_14_c_17_r_*SK_MZ(5) - OP_l_14_c_18_r_*SK_MZ(4)); +Kfusion(15) = SK_MZ(1)*(OP_l_15_c_22_r_ + OP_l_15_c_1_r_*SH_MAG(2) - OP_l_15_c_2_r_*SH_MAG(3) + OP_l_15_c_4_r_*SH_MAG(1) + OP_l_15_c_3_r_*SK_MZ(3) + OP_l_15_c_19_r_*SK_MZ(2) + OP_l_15_c_17_r_*SK_MZ(5) - OP_l_15_c_18_r_*SK_MZ(4)); +Kfusion(16) = SK_MZ(1)*(OP_l_16_c_22_r_ + OP_l_16_c_1_r_*SH_MAG(2) - OP_l_16_c_2_r_*SH_MAG(3) + OP_l_16_c_4_r_*SH_MAG(1) + OP_l_16_c_3_r_*SK_MZ(3) + OP_l_16_c_19_r_*SK_MZ(2) + OP_l_16_c_17_r_*SK_MZ(5) - OP_l_16_c_18_r_*SK_MZ(4)); +Kfusion(17) = SK_MZ(1)*(OP_l_17_c_22_r_ + OP_l_17_c_1_r_*SH_MAG(2) - OP_l_17_c_2_r_*SH_MAG(3) + OP_l_17_c_4_r_*SH_MAG(1) + OP_l_17_c_3_r_*SK_MZ(3) + OP_l_17_c_19_r_*SK_MZ(2) + OP_l_17_c_17_r_*SK_MZ(5) - OP_l_17_c_18_r_*SK_MZ(4)); +Kfusion(18) = SK_MZ(1)*(OP_l_18_c_22_r_ + OP_l_18_c_1_r_*SH_MAG(2) - OP_l_18_c_2_r_*SH_MAG(3) + OP_l_18_c_4_r_*SH_MAG(1) + OP_l_18_c_3_r_*SK_MZ(3) + OP_l_18_c_19_r_*SK_MZ(2) + OP_l_18_c_17_r_*SK_MZ(5) - OP_l_18_c_18_r_*SK_MZ(4)); +Kfusion(19) = SK_MZ(1)*(OP_l_19_c_22_r_ + OP_l_19_c_1_r_*SH_MAG(2) - OP_l_19_c_2_r_*SH_MAG(3) + OP_l_19_c_4_r_*SH_MAG(1) + OP_l_19_c_3_r_*SK_MZ(3) + OP_l_19_c_19_r_*SK_MZ(2) + OP_l_19_c_17_r_*SK_MZ(5) - OP_l_19_c_18_r_*SK_MZ(4)); +Kfusion(20) = SK_MZ(1)*(OP_l_20_c_22_r_ + OP_l_20_c_1_r_*SH_MAG(2) - OP_l_20_c_2_r_*SH_MAG(3) + OP_l_20_c_4_r_*SH_MAG(1) + OP_l_20_c_3_r_*SK_MZ(3) + OP_l_20_c_19_r_*SK_MZ(2) + OP_l_20_c_17_r_*SK_MZ(5) - OP_l_20_c_18_r_*SK_MZ(4)); +Kfusion(21) = SK_MZ(1)*(OP_l_21_c_22_r_ + OP_l_21_c_1_r_*SH_MAG(2) - OP_l_21_c_2_r_*SH_MAG(3) + OP_l_21_c_4_r_*SH_MAG(1) + OP_l_21_c_3_r_*SK_MZ(3) + OP_l_21_c_19_r_*SK_MZ(2) + OP_l_21_c_17_r_*SK_MZ(5) - OP_l_21_c_18_r_*SK_MZ(4)); +Kfusion(22) = SK_MZ(1)*(OP_l_22_c_22_r_ + OP_l_22_c_1_r_*SH_MAG(2) - OP_l_22_c_2_r_*SH_MAG(3) + OP_l_22_c_4_r_*SH_MAG(1) + OP_l_22_c_3_r_*SK_MZ(3) + OP_l_22_c_19_r_*SK_MZ(2) + OP_l_22_c_17_r_*SK_MZ(5) - OP_l_22_c_18_r_*SK_MZ(4)); +Kfusion(23) = SK_MZ(1)*(OP_l_23_c_22_r_ + OP_l_23_c_1_r_*SH_MAG(2) - OP_l_23_c_2_r_*SH_MAG(3) + OP_l_23_c_4_r_*SH_MAG(1) + OP_l_23_c_3_r_*SK_MZ(3) + OP_l_23_c_19_r_*SK_MZ(2) + OP_l_23_c_17_r_*SK_MZ(5) - OP_l_23_c_18_r_*SK_MZ(4)); +Kfusion(24) = SK_MZ(1)*(OP_l_24_c_22_r_ + OP_l_24_c_1_r_*SH_MAG(2) - OP_l_24_c_2_r_*SH_MAG(3) + OP_l_24_c_4_r_*SH_MAG(1) + OP_l_24_c_3_r_*SK_MZ(3) + OP_l_24_c_19_r_*SK_MZ(2) + OP_l_24_c_17_r_*SK_MZ(5) - OP_l_24_c_18_r_*SK_MZ(4)); -SH_ACCX = zeros(7,1); +SH_ACCX = zeros(4,1); SH_ACCX(1) = q0^2 + q1^2 - q2^2 - q3^2; -SH_ACCX(2) = 2*q0*q3 + 2*q1*q2; -SH_ACCX(3) = vn - vwn; -SH_ACCX(4) = ve - vwe; -SH_ACCX(5) = q3^2; -SH_ACCX(6) = 2*q0*q2; -SH_ACCX(7) = 2*q0*q1; +SH_ACCX(2) = vn - vwn; +SH_ACCX(3) = ve - vwe; +SH_ACCX(4) = 2*q0*q3 + 2*q1*q2; H_ACCX = zeros(1,24); -H_ACCX(1,2) = Kaccx*(SH_ACCX(3)*(SH_ACCX(6) + 2*q1*q3) - SH_ACCX(4)*(SH_ACCX(7) - 2*q2*q3) + vd*(SH_ACCX(5) + q0^2 - q1^2 - q2^2)); -H_ACCX(1,3) = Kaccx*(SH_ACCX(3)*(2*q0*q3 - 2*q1*q2) + SH_ACCX(4)*(SH_ACCX(5) - q0^2 + q1^2 - q2^2) - vd*(SH_ACCX(7) + 2*q2*q3)); -H_ACCX(1,4) = -Kaccx*SH_ACCX(1); -H_ACCX(1,5) = -Kaccx*SH_ACCX(2); -H_ACCX(1,6) = Kaccx*(SH_ACCX(6) - 2*q1*q3); +H_ACCX(1,1) = -Kaccx*(2*q0*SH_ACCX(2) + 2*q3*SH_ACCX(3) - 2*q2*vd); +H_ACCX(1,2) = -Kaccx*(2*q1*SH_ACCX(2) + 2*q2*SH_ACCX(3) + 2*q3*vd); +H_ACCX(1,3) = Kaccx*(2*q2*SH_ACCX(2) - 2*q1*SH_ACCX(3) + 2*q0*vd); +H_ACCX(1,4) = -Kaccx*(2*q0*SH_ACCX(3) - 2*q3*SH_ACCX(2) + 2*q1*vd); +H_ACCX(1,5) = -Kaccx*SH_ACCX(1); +H_ACCX(1,6) = -Kaccx*SH_ACCX(4); +H_ACCX(1,7) = Kaccx*(2*q0*q2 - 2*q1*q3); H_ACCX(1,23) = Kaccx*SH_ACCX(1); -H_ACCX(1,24) = Kaccx*SH_ACCX(2); +H_ACCX(1,24) = Kaccx*SH_ACCX(4); -SK_ACCX = zeros(5,1); -SK_ACCX(1) = 1/(R_ACC - Kaccx*SH_ACCX(1)*(Kaccx*OP_l_23_c_4_r_*SH_ACCX(1) - Kaccx*OP_l_5_c_4_r_*SH_ACCX(2) - Kaccx*OP_l_4_c_4_r_*SH_ACCX(1) + Kaccx*OP_l_24_c_4_r_*SH_ACCX(2) + Kaccx*OP_l_3_c_4_r_*(SH_ACCX(3)*(2*q0*q3 - 2*q1*q2) + SH_ACCX(4)*(SH_ACCX(5) - q0^2 + q1^2 - q2^2) - vd*(SH_ACCX(7) + 2*q2*q3)) + Kaccx*OP_l_2_c_4_r_*(SH_ACCX(3)*(SH_ACCX(6) + 2*q1*q3) - SH_ACCX(4)*(SH_ACCX(7) - 2*q2*q3) + vd*(SH_ACCX(5) + q0^2 - q1^2 - q2^2)) + Kaccx*OP_l_6_c_4_r_*(SH_ACCX(6) - 2*q1*q3)) - Kaccx*SH_ACCX(2)*(Kaccx*OP_l_23_c_5_r_*SH_ACCX(1) - Kaccx*OP_l_5_c_5_r_*SH_ACCX(2) - Kaccx*OP_l_4_c_5_r_*SH_ACCX(1) + Kaccx*OP_l_24_c_5_r_*SH_ACCX(2) + Kaccx*OP_l_3_c_5_r_*(SH_ACCX(3)*(2*q0*q3 - 2*q1*q2) + SH_ACCX(4)*(SH_ACCX(5) - q0^2 + q1^2 - q2^2) - vd*(SH_ACCX(7) + 2*q2*q3)) + Kaccx*OP_l_2_c_5_r_*(SH_ACCX(3)*(SH_ACCX(6) + 2*q1*q3) - SH_ACCX(4)*(SH_ACCX(7) - 2*q2*q3) + vd*(SH_ACCX(5) + q0^2 - q1^2 - q2^2)) + Kaccx*OP_l_6_c_5_r_*(SH_ACCX(6) - 2*q1*q3)) + Kaccx*SH_ACCX(1)*(Kaccx*OP_l_23_c_23_r_*SH_ACCX(1) - Kaccx*OP_l_5_c_23_r_*SH_ACCX(2) - Kaccx*OP_l_4_c_23_r_*SH_ACCX(1) + Kaccx*OP_l_24_c_23_r_*SH_ACCX(2) + Kaccx*OP_l_3_c_23_r_*(SH_ACCX(3)*(2*q0*q3 - 2*q1*q2) + SH_ACCX(4)*(SH_ACCX(5) - q0^2 + q1^2 - q2^2) - vd*(SH_ACCX(7) + 2*q2*q3)) + Kaccx*OP_l_2_c_23_r_*(SH_ACCX(3)*(SH_ACCX(6) + 2*q1*q3) - SH_ACCX(4)*(SH_ACCX(7) - 2*q2*q3) + vd*(SH_ACCX(5) + q0^2 - q1^2 - q2^2)) + Kaccx*OP_l_6_c_23_r_*(SH_ACCX(6) - 2*q1*q3)) + Kaccx*SH_ACCX(2)*(Kaccx*OP_l_23_c_24_r_*SH_ACCX(1) - Kaccx*OP_l_5_c_24_r_*SH_ACCX(2) - Kaccx*OP_l_4_c_24_r_*SH_ACCX(1) + Kaccx*OP_l_24_c_24_r_*SH_ACCX(2) + Kaccx*OP_l_3_c_24_r_*(SH_ACCX(3)*(2*q0*q3 - 2*q1*q2) + SH_ACCX(4)*(SH_ACCX(5) - q0^2 + q1^2 - q2^2) - vd*(SH_ACCX(7) + 2*q2*q3)) + Kaccx*OP_l_2_c_24_r_*(SH_ACCX(3)*(SH_ACCX(6) + 2*q1*q3) - SH_ACCX(4)*(SH_ACCX(7) - 2*q2*q3) + vd*(SH_ACCX(5) + q0^2 - q1^2 - q2^2)) + Kaccx*OP_l_6_c_24_r_*(SH_ACCX(6) - 2*q1*q3)) + Kaccx*(SH_ACCX(3)*(2*q0*q3 - 2*q1*q2) + SH_ACCX(4)*(SH_ACCX(5) - q0^2 + q1^2 - q2^2) - vd*(SH_ACCX(7) + 2*q2*q3))*(Kaccx*OP_l_23_c_3_r_*SH_ACCX(1) - Kaccx*OP_l_5_c_3_r_*SH_ACCX(2) - Kaccx*OP_l_4_c_3_r_*SH_ACCX(1) + Kaccx*OP_l_24_c_3_r_*SH_ACCX(2) + Kaccx*OP_l_3_c_3_r_*(SH_ACCX(3)*(2*q0*q3 - 2*q1*q2) + SH_ACCX(4)*(SH_ACCX(5) - q0^2 + q1^2 - q2^2) - vd*(SH_ACCX(7) + 2*q2*q3)) + Kaccx*OP_l_2_c_3_r_*(SH_ACCX(3)*(SH_ACCX(6) + 2*q1*q3) - SH_ACCX(4)*(SH_ACCX(7) - 2*q2*q3) + vd*(SH_ACCX(5) + q0^2 - q1^2 - q2^2)) + Kaccx*OP_l_6_c_3_r_*(SH_ACCX(6) - 2*q1*q3)) + Kaccx*(SH_ACCX(3)*(SH_ACCX(6) + 2*q1*q3) - SH_ACCX(4)*(SH_ACCX(7) - 2*q2*q3) + vd*(SH_ACCX(5) + q0^2 - q1^2 - q2^2))*(Kaccx*OP_l_23_c_2_r_*SH_ACCX(1) - Kaccx*OP_l_5_c_2_r_*SH_ACCX(2) - Kaccx*OP_l_4_c_2_r_*SH_ACCX(1) + Kaccx*OP_l_24_c_2_r_*SH_ACCX(2) + Kaccx*OP_l_3_c_2_r_*(SH_ACCX(3)*(2*q0*q3 - 2*q1*q2) + SH_ACCX(4)*(SH_ACCX(5) - q0^2 + q1^2 - q2^2) - vd*(SH_ACCX(7) + 2*q2*q3)) + Kaccx*OP_l_2_c_2_r_*(SH_ACCX(3)*(SH_ACCX(6) + 2*q1*q3) - SH_ACCX(4)*(SH_ACCX(7) - 2*q2*q3) + vd*(SH_ACCX(5) + q0^2 - q1^2 - q2^2)) + Kaccx*OP_l_6_c_2_r_*(SH_ACCX(6) - 2*q1*q3)) + Kaccx*(SH_ACCX(6) - 2*q1*q3)*(Kaccx*OP_l_23_c_6_r_*SH_ACCX(1) - Kaccx*OP_l_5_c_6_r_*SH_ACCX(2) - Kaccx*OP_l_4_c_6_r_*SH_ACCX(1) + Kaccx*OP_l_24_c_6_r_*SH_ACCX(2) + Kaccx*OP_l_3_c_6_r_*(SH_ACCX(3)*(2*q0*q3 - 2*q1*q2) + SH_ACCX(4)*(SH_ACCX(5) - q0^2 + q1^2 - q2^2) - vd*(SH_ACCX(7) + 2*q2*q3)) + Kaccx*OP_l_2_c_6_r_*(SH_ACCX(3)*(SH_ACCX(6) + 2*q1*q3) - SH_ACCX(4)*(SH_ACCX(7) - 2*q2*q3) + vd*(SH_ACCX(5) + q0^2 - q1^2 - q2^2)) + Kaccx*OP_l_6_c_6_r_*(SH_ACCX(6) - 2*q1*q3))); -SK_ACCX(2) = SH_ACCX(3)*(2*q0*q3 - 2*q1*q2) + SH_ACCX(4)*(SH_ACCX(5) - q0^2 + q1^2 - q2^2) - vd*(SH_ACCX(7) + 2*q2*q3); -SK_ACCX(3) = SH_ACCX(3)*(SH_ACCX(6) + 2*q1*q3) - SH_ACCX(4)*(SH_ACCX(7) - 2*q2*q3) + vd*(SH_ACCX(5) + q0^2 - q1^2 - q2^2); -SK_ACCX(4) = SH_ACCX(6) - 2*q1*q3; -SK_ACCX(5) = SH_ACCX(2); +SK_ACCX = zeros(7,1); +SK_ACCX(1) = 1/(R_ACC + Kaccx*SH_ACCX(1)*(Kaccx*OP_l_5_c_5_r_*SH_ACCX(1) + Kaccx*OP_l_6_c_5_r_*SH_ACCX(4) - Kaccx*OP_l_23_c_5_r_*SH_ACCX(1) - Kaccx*OP_l_24_c_5_r_*SH_ACCX(4) - Kaccx*OP_l_7_c_5_r_*(2*q0*q2 - 2*q1*q3) + Kaccx*OP_l_1_c_5_r_*(2*q0*SH_ACCX(2) + 2*q3*SH_ACCX(3) - 2*q2*vd) + Kaccx*OP_l_2_c_5_r_*(2*q1*SH_ACCX(2) + 2*q2*SH_ACCX(3) + 2*q3*vd) - Kaccx*OP_l_3_c_5_r_*(2*q2*SH_ACCX(2) - 2*q1*SH_ACCX(3) + 2*q0*vd) + Kaccx*OP_l_4_c_5_r_*(2*q0*SH_ACCX(3) - 2*q3*SH_ACCX(2) + 2*q1*vd)) + Kaccx*SH_ACCX(4)*(Kaccx*OP_l_5_c_6_r_*SH_ACCX(1) + Kaccx*OP_l_6_c_6_r_*SH_ACCX(4) - Kaccx*OP_l_23_c_6_r_*SH_ACCX(1) - Kaccx*OP_l_24_c_6_r_*SH_ACCX(4) - Kaccx*OP_l_7_c_6_r_*(2*q0*q2 - 2*q1*q3) + Kaccx*OP_l_1_c_6_r_*(2*q0*SH_ACCX(2) + 2*q3*SH_ACCX(3) - 2*q2*vd) + Kaccx*OP_l_2_c_6_r_*(2*q1*SH_ACCX(2) + 2*q2*SH_ACCX(3) + 2*q3*vd) - Kaccx*OP_l_3_c_6_r_*(2*q2*SH_ACCX(2) - 2*q1*SH_ACCX(3) + 2*q0*vd) + Kaccx*OP_l_4_c_6_r_*(2*q0*SH_ACCX(3) - 2*q3*SH_ACCX(2) + 2*q1*vd)) - Kaccx*SH_ACCX(1)*(Kaccx*OP_l_5_c_23_r_*SH_ACCX(1) + Kaccx*OP_l_6_c_23_r_*SH_ACCX(4) - Kaccx*OP_l_23_c_23_r_*SH_ACCX(1) - Kaccx*OP_l_24_c_23_r_*SH_ACCX(4) - Kaccx*OP_l_7_c_23_r_*(2*q0*q2 - 2*q1*q3) + Kaccx*OP_l_1_c_23_r_*(2*q0*SH_ACCX(2) + 2*q3*SH_ACCX(3) - 2*q2*vd) + Kaccx*OP_l_2_c_23_r_*(2*q1*SH_ACCX(2) + 2*q2*SH_ACCX(3) + 2*q3*vd) - Kaccx*OP_l_3_c_23_r_*(2*q2*SH_ACCX(2) - 2*q1*SH_ACCX(3) + 2*q0*vd) + Kaccx*OP_l_4_c_23_r_*(2*q0*SH_ACCX(3) - 2*q3*SH_ACCX(2) + 2*q1*vd)) - Kaccx*SH_ACCX(4)*(Kaccx*OP_l_5_c_24_r_*SH_ACCX(1) + Kaccx*OP_l_6_c_24_r_*SH_ACCX(4) - Kaccx*OP_l_23_c_24_r_*SH_ACCX(1) - Kaccx*OP_l_24_c_24_r_*SH_ACCX(4) - Kaccx*OP_l_7_c_24_r_*(2*q0*q2 - 2*q1*q3) + Kaccx*OP_l_1_c_24_r_*(2*q0*SH_ACCX(2) + 2*q3*SH_ACCX(3) - 2*q2*vd) + Kaccx*OP_l_2_c_24_r_*(2*q1*SH_ACCX(2) + 2*q2*SH_ACCX(3) + 2*q3*vd) - Kaccx*OP_l_3_c_24_r_*(2*q2*SH_ACCX(2) - 2*q1*SH_ACCX(3) + 2*q0*vd) + Kaccx*OP_l_4_c_24_r_*(2*q0*SH_ACCX(3) - 2*q3*SH_ACCX(2) + 2*q1*vd)) - Kaccx*(2*q0*q2 - 2*q1*q3)*(Kaccx*OP_l_5_c_7_r_*SH_ACCX(1) + Kaccx*OP_l_6_c_7_r_*SH_ACCX(4) - Kaccx*OP_l_23_c_7_r_*SH_ACCX(1) - Kaccx*OP_l_24_c_7_r_*SH_ACCX(4) - Kaccx*OP_l_7_c_7_r_*(2*q0*q2 - 2*q1*q3) + Kaccx*OP_l_1_c_7_r_*(2*q0*SH_ACCX(2) + 2*q3*SH_ACCX(3) - 2*q2*vd) + Kaccx*OP_l_2_c_7_r_*(2*q1*SH_ACCX(2) + 2*q2*SH_ACCX(3) + 2*q3*vd) - Kaccx*OP_l_3_c_7_r_*(2*q2*SH_ACCX(2) - 2*q1*SH_ACCX(3) + 2*q0*vd) + Kaccx*OP_l_4_c_7_r_*(2*q0*SH_ACCX(3) - 2*q3*SH_ACCX(2) + 2*q1*vd)) + Kaccx*(2*q0*SH_ACCX(2) + 2*q3*SH_ACCX(3) - 2*q2*vd)*(Kaccx*OP_l_5_c_1_r_*SH_ACCX(1) + Kaccx*OP_l_6_c_1_r_*SH_ACCX(4) - Kaccx*OP_l_23_c_1_r_*SH_ACCX(1) - Kaccx*OP_l_24_c_1_r_*SH_ACCX(4) - Kaccx*OP_l_7_c_1_r_*(2*q0*q2 - 2*q1*q3) + Kaccx*OP_l_1_c_1_r_*(2*q0*SH_ACCX(2) + 2*q3*SH_ACCX(3) - 2*q2*vd) + Kaccx*OP_l_2_c_1_r_*(2*q1*SH_ACCX(2) + 2*q2*SH_ACCX(3) + 2*q3*vd) - Kaccx*OP_l_3_c_1_r_*(2*q2*SH_ACCX(2) - 2*q1*SH_ACCX(3) + 2*q0*vd) + Kaccx*OP_l_4_c_1_r_*(2*q0*SH_ACCX(3) - 2*q3*SH_ACCX(2) + 2*q1*vd)) + Kaccx*(2*q1*SH_ACCX(2) + 2*q2*SH_ACCX(3) + 2*q3*vd)*(Kaccx*OP_l_5_c_2_r_*SH_ACCX(1) + Kaccx*OP_l_6_c_2_r_*SH_ACCX(4) - Kaccx*OP_l_23_c_2_r_*SH_ACCX(1) - Kaccx*OP_l_24_c_2_r_*SH_ACCX(4) - Kaccx*OP_l_7_c_2_r_*(2*q0*q2 - 2*q1*q3) + Kaccx*OP_l_1_c_2_r_*(2*q0*SH_ACCX(2) + 2*q3*SH_ACCX(3) - 2*q2*vd) + Kaccx*OP_l_2_c_2_r_*(2*q1*SH_ACCX(2) + 2*q2*SH_ACCX(3) + 2*q3*vd) - Kaccx*OP_l_3_c_2_r_*(2*q2*SH_ACCX(2) - 2*q1*SH_ACCX(3) + 2*q0*vd) + Kaccx*OP_l_4_c_2_r_*(2*q0*SH_ACCX(3) - 2*q3*SH_ACCX(2) + 2*q1*vd)) - Kaccx*(2*q2*SH_ACCX(2) - 2*q1*SH_ACCX(3) + 2*q0*vd)*(Kaccx*OP_l_5_c_3_r_*SH_ACCX(1) + Kaccx*OP_l_6_c_3_r_*SH_ACCX(4) - Kaccx*OP_l_23_c_3_r_*SH_ACCX(1) - Kaccx*OP_l_24_c_3_r_*SH_ACCX(4) - Kaccx*OP_l_7_c_3_r_*(2*q0*q2 - 2*q1*q3) + Kaccx*OP_l_1_c_3_r_*(2*q0*SH_ACCX(2) + 2*q3*SH_ACCX(3) - 2*q2*vd) + Kaccx*OP_l_2_c_3_r_*(2*q1*SH_ACCX(2) + 2*q2*SH_ACCX(3) + 2*q3*vd) - Kaccx*OP_l_3_c_3_r_*(2*q2*SH_ACCX(2) - 2*q1*SH_ACCX(3) + 2*q0*vd) + Kaccx*OP_l_4_c_3_r_*(2*q0*SH_ACCX(3) - 2*q3*SH_ACCX(2) + 2*q1*vd)) + Kaccx*(2*q0*SH_ACCX(3) - 2*q3*SH_ACCX(2) + 2*q1*vd)*(Kaccx*OP_l_5_c_4_r_*SH_ACCX(1) + Kaccx*OP_l_6_c_4_r_*SH_ACCX(4) - Kaccx*OP_l_23_c_4_r_*SH_ACCX(1) - Kaccx*OP_l_24_c_4_r_*SH_ACCX(4) - Kaccx*OP_l_7_c_4_r_*(2*q0*q2 - 2*q1*q3) + Kaccx*OP_l_1_c_4_r_*(2*q0*SH_ACCX(2) + 2*q3*SH_ACCX(3) - 2*q2*vd) + Kaccx*OP_l_2_c_4_r_*(2*q1*SH_ACCX(2) + 2*q2*SH_ACCX(3) + 2*q3*vd) - Kaccx*OP_l_3_c_4_r_*(2*q2*SH_ACCX(2) - 2*q1*SH_ACCX(3) + 2*q0*vd) + Kaccx*OP_l_4_c_4_r_*(2*q0*SH_ACCX(3) - 2*q3*SH_ACCX(2) + 2*q1*vd))); +SK_ACCX(2) = 2*q0*SH_ACCX(3) - 2*q3*SH_ACCX(2) + 2*q1*vd; +SK_ACCX(3) = 2*q2*SH_ACCX(2) - 2*q1*SH_ACCX(3) + 2*q0*vd; +SK_ACCX(4) = 2*q0*SH_ACCX(2) + 2*q3*SH_ACCX(3) - 2*q2*vd; +SK_ACCX(5) = 2*q1*SH_ACCX(2) + 2*q2*SH_ACCX(3) + 2*q3*vd; +SK_ACCX(6) = 2*q0*q2 - 2*q1*q3; +SK_ACCX(7) = SH_ACCX(4); Kfusion = zeros(24,1); Kfusion = zeros(1,1); -Kfusion(1) = SK_ACCX(1)*(Kaccx*OP_l_1_c_23_r_*SH_ACCX(1) - Kaccx*OP_l_1_c_4_r_*SH_ACCX(1) + Kaccx*OP_l_1_c_2_r_*SK_ACCX(3) + Kaccx*OP_l_1_c_3_r_*SK_ACCX(2) - Kaccx*OP_l_1_c_5_r_*SK_ACCX(5) + Kaccx*OP_l_1_c_6_r_*SK_ACCX(4) + Kaccx*OP_l_1_c_24_r_*SK_ACCX(5)); -Kfusion(2) = SK_ACCX(1)*(Kaccx*OP_l_2_c_23_r_*SH_ACCX(1) - Kaccx*OP_l_2_c_4_r_*SH_ACCX(1) + Kaccx*OP_l_2_c_2_r_*SK_ACCX(3) + Kaccx*OP_l_2_c_3_r_*SK_ACCX(2) - Kaccx*OP_l_2_c_5_r_*SK_ACCX(5) + Kaccx*OP_l_2_c_6_r_*SK_ACCX(4) + Kaccx*OP_l_2_c_24_r_*SK_ACCX(5)); -Kfusion(3) = SK_ACCX(1)*(Kaccx*OP_l_3_c_23_r_*SH_ACCX(1) - Kaccx*OP_l_3_c_4_r_*SH_ACCX(1) + Kaccx*OP_l_3_c_2_r_*SK_ACCX(3) + Kaccx*OP_l_3_c_3_r_*SK_ACCX(2) - Kaccx*OP_l_3_c_5_r_*SK_ACCX(5) + Kaccx*OP_l_3_c_6_r_*SK_ACCX(4) + Kaccx*OP_l_3_c_24_r_*SK_ACCX(5)); -Kfusion(4) = SK_ACCX(1)*(Kaccx*OP_l_4_c_23_r_*SH_ACCX(1) - Kaccx*OP_l_4_c_4_r_*SH_ACCX(1) + Kaccx*OP_l_4_c_2_r_*SK_ACCX(3) + Kaccx*OP_l_4_c_3_r_*SK_ACCX(2) - Kaccx*OP_l_4_c_5_r_*SK_ACCX(5) + Kaccx*OP_l_4_c_6_r_*SK_ACCX(4) + Kaccx*OP_l_4_c_24_r_*SK_ACCX(5)); -Kfusion(5) = SK_ACCX(1)*(Kaccx*OP_l_5_c_23_r_*SH_ACCX(1) - Kaccx*OP_l_5_c_4_r_*SH_ACCX(1) + Kaccx*OP_l_5_c_2_r_*SK_ACCX(3) + Kaccx*OP_l_5_c_3_r_*SK_ACCX(2) - Kaccx*OP_l_5_c_5_r_*SK_ACCX(5) + Kaccx*OP_l_5_c_6_r_*SK_ACCX(4) + Kaccx*OP_l_5_c_24_r_*SK_ACCX(5)); -Kfusion(6) = SK_ACCX(1)*(Kaccx*OP_l_6_c_23_r_*SH_ACCX(1) - Kaccx*OP_l_6_c_4_r_*SH_ACCX(1) + Kaccx*OP_l_6_c_2_r_*SK_ACCX(3) + Kaccx*OP_l_6_c_3_r_*SK_ACCX(2) - Kaccx*OP_l_6_c_5_r_*SK_ACCX(5) + Kaccx*OP_l_6_c_6_r_*SK_ACCX(4) + Kaccx*OP_l_6_c_24_r_*SK_ACCX(5)); -Kfusion(7) = SK_ACCX(1)*(Kaccx*OP_l_7_c_23_r_*SH_ACCX(1) - Kaccx*OP_l_7_c_4_r_*SH_ACCX(1) + Kaccx*OP_l_7_c_2_r_*SK_ACCX(3) + Kaccx*OP_l_7_c_3_r_*SK_ACCX(2) - Kaccx*OP_l_7_c_5_r_*SK_ACCX(5) + Kaccx*OP_l_7_c_6_r_*SK_ACCX(4) + Kaccx*OP_l_7_c_24_r_*SK_ACCX(5)); -Kfusion(8) = SK_ACCX(1)*(Kaccx*OP_l_8_c_23_r_*SH_ACCX(1) - Kaccx*OP_l_8_c_4_r_*SH_ACCX(1) + Kaccx*OP_l_8_c_2_r_*SK_ACCX(3) + Kaccx*OP_l_8_c_3_r_*SK_ACCX(2) - Kaccx*OP_l_8_c_5_r_*SK_ACCX(5) + Kaccx*OP_l_8_c_6_r_*SK_ACCX(4) + Kaccx*OP_l_8_c_24_r_*SK_ACCX(5)); -Kfusion(9) = SK_ACCX(1)*(Kaccx*OP_l_9_c_23_r_*SH_ACCX(1) - Kaccx*OP_l_9_c_4_r_*SH_ACCX(1) + Kaccx*OP_l_9_c_2_r_*SK_ACCX(3) + Kaccx*OP_l_9_c_3_r_*SK_ACCX(2) - Kaccx*OP_l_9_c_5_r_*SK_ACCX(5) + Kaccx*OP_l_9_c_6_r_*SK_ACCX(4) + Kaccx*OP_l_9_c_24_r_*SK_ACCX(5)); -Kfusion(10) = SK_ACCX(1)*(Kaccx*OP_l_10_c_23_r_*SH_ACCX(1) - Kaccx*OP_l_10_c_4_r_*SH_ACCX(1) + Kaccx*OP_l_10_c_2_r_*SK_ACCX(3) + Kaccx*OP_l_10_c_3_r_*SK_ACCX(2) - Kaccx*OP_l_10_c_5_r_*SK_ACCX(5) + Kaccx*OP_l_10_c_6_r_*SK_ACCX(4) + Kaccx*OP_l_10_c_24_r_*SK_ACCX(5)); -Kfusion(11) = SK_ACCX(1)*(Kaccx*OP_l_11_c_23_r_*SH_ACCX(1) - Kaccx*OP_l_11_c_4_r_*SH_ACCX(1) + Kaccx*OP_l_11_c_2_r_*SK_ACCX(3) + Kaccx*OP_l_11_c_3_r_*SK_ACCX(2) - Kaccx*OP_l_11_c_5_r_*SK_ACCX(5) + Kaccx*OP_l_11_c_6_r_*SK_ACCX(4) + Kaccx*OP_l_11_c_24_r_*SK_ACCX(5)); -Kfusion(12) = SK_ACCX(1)*(Kaccx*OP_l_12_c_23_r_*SH_ACCX(1) - Kaccx*OP_l_12_c_4_r_*SH_ACCX(1) + Kaccx*OP_l_12_c_2_r_*SK_ACCX(3) + Kaccx*OP_l_12_c_3_r_*SK_ACCX(2) - Kaccx*OP_l_12_c_5_r_*SK_ACCX(5) + Kaccx*OP_l_12_c_6_r_*SK_ACCX(4) + Kaccx*OP_l_12_c_24_r_*SK_ACCX(5)); -Kfusion(13) = SK_ACCX(1)*(Kaccx*OP_l_13_c_23_r_*SH_ACCX(1) - Kaccx*OP_l_13_c_4_r_*SH_ACCX(1) + Kaccx*OP_l_13_c_2_r_*SK_ACCX(3) + Kaccx*OP_l_13_c_3_r_*SK_ACCX(2) - Kaccx*OP_l_13_c_5_r_*SK_ACCX(5) + Kaccx*OP_l_13_c_6_r_*SK_ACCX(4) + Kaccx*OP_l_13_c_24_r_*SK_ACCX(5)); -Kfusion(14) = SK_ACCX(1)*(Kaccx*OP_l_14_c_23_r_*SH_ACCX(1) - Kaccx*OP_l_14_c_4_r_*SH_ACCX(1) + Kaccx*OP_l_14_c_2_r_*SK_ACCX(3) + Kaccx*OP_l_14_c_3_r_*SK_ACCX(2) - Kaccx*OP_l_14_c_5_r_*SK_ACCX(5) + Kaccx*OP_l_14_c_6_r_*SK_ACCX(4) + Kaccx*OP_l_14_c_24_r_*SK_ACCX(5)); -Kfusion(15) = SK_ACCX(1)*(Kaccx*OP_l_15_c_23_r_*SH_ACCX(1) - Kaccx*OP_l_15_c_4_r_*SH_ACCX(1) + Kaccx*OP_l_15_c_2_r_*SK_ACCX(3) + Kaccx*OP_l_15_c_3_r_*SK_ACCX(2) - Kaccx*OP_l_15_c_5_r_*SK_ACCX(5) + Kaccx*OP_l_15_c_6_r_*SK_ACCX(4) + Kaccx*OP_l_15_c_24_r_*SK_ACCX(5)); -Kfusion(16) = SK_ACCX(1)*(Kaccx*OP_l_16_c_23_r_*SH_ACCX(1) - Kaccx*OP_l_16_c_4_r_*SH_ACCX(1) + Kaccx*OP_l_16_c_2_r_*SK_ACCX(3) + Kaccx*OP_l_16_c_3_r_*SK_ACCX(2) - Kaccx*OP_l_16_c_5_r_*SK_ACCX(5) + Kaccx*OP_l_16_c_6_r_*SK_ACCX(4) + Kaccx*OP_l_16_c_24_r_*SK_ACCX(5)); -Kfusion(17) = SK_ACCX(1)*(Kaccx*OP_l_17_c_23_r_*SH_ACCX(1) - Kaccx*OP_l_17_c_4_r_*SH_ACCX(1) + Kaccx*OP_l_17_c_2_r_*SK_ACCX(3) + Kaccx*OP_l_17_c_3_r_*SK_ACCX(2) - Kaccx*OP_l_17_c_5_r_*SK_ACCX(5) + Kaccx*OP_l_17_c_6_r_*SK_ACCX(4) + Kaccx*OP_l_17_c_24_r_*SK_ACCX(5)); -Kfusion(18) = SK_ACCX(1)*(Kaccx*OP_l_18_c_23_r_*SH_ACCX(1) - Kaccx*OP_l_18_c_4_r_*SH_ACCX(1) + Kaccx*OP_l_18_c_2_r_*SK_ACCX(3) + Kaccx*OP_l_18_c_3_r_*SK_ACCX(2) - Kaccx*OP_l_18_c_5_r_*SK_ACCX(5) + Kaccx*OP_l_18_c_6_r_*SK_ACCX(4) + Kaccx*OP_l_18_c_24_r_*SK_ACCX(5)); -Kfusion(19) = SK_ACCX(1)*(Kaccx*OP_l_19_c_23_r_*SH_ACCX(1) - Kaccx*OP_l_19_c_4_r_*SH_ACCX(1) + Kaccx*OP_l_19_c_2_r_*SK_ACCX(3) + Kaccx*OP_l_19_c_3_r_*SK_ACCX(2) - Kaccx*OP_l_19_c_5_r_*SK_ACCX(5) + Kaccx*OP_l_19_c_6_r_*SK_ACCX(4) + Kaccx*OP_l_19_c_24_r_*SK_ACCX(5)); -Kfusion(20) = SK_ACCX(1)*(Kaccx*OP_l_20_c_23_r_*SH_ACCX(1) - Kaccx*OP_l_20_c_4_r_*SH_ACCX(1) + Kaccx*OP_l_20_c_2_r_*SK_ACCX(3) + Kaccx*OP_l_20_c_3_r_*SK_ACCX(2) - Kaccx*OP_l_20_c_5_r_*SK_ACCX(5) + Kaccx*OP_l_20_c_6_r_*SK_ACCX(4) + Kaccx*OP_l_20_c_24_r_*SK_ACCX(5)); -Kfusion(21) = SK_ACCX(1)*(Kaccx*OP_l_21_c_23_r_*SH_ACCX(1) - Kaccx*OP_l_21_c_4_r_*SH_ACCX(1) + Kaccx*OP_l_21_c_2_r_*SK_ACCX(3) + Kaccx*OP_l_21_c_3_r_*SK_ACCX(2) - Kaccx*OP_l_21_c_5_r_*SK_ACCX(5) + Kaccx*OP_l_21_c_6_r_*SK_ACCX(4) + Kaccx*OP_l_21_c_24_r_*SK_ACCX(5)); -Kfusion(22) = SK_ACCX(1)*(Kaccx*OP_l_22_c_23_r_*SH_ACCX(1) - Kaccx*OP_l_22_c_4_r_*SH_ACCX(1) + Kaccx*OP_l_22_c_2_r_*SK_ACCX(3) + Kaccx*OP_l_22_c_3_r_*SK_ACCX(2) - Kaccx*OP_l_22_c_5_r_*SK_ACCX(5) + Kaccx*OP_l_22_c_6_r_*SK_ACCX(4) + Kaccx*OP_l_22_c_24_r_*SK_ACCX(5)); -Kfusion(23) = SK_ACCX(1)*(Kaccx*OP_l_23_c_23_r_*SH_ACCX(1) - Kaccx*OP_l_23_c_4_r_*SH_ACCX(1) + Kaccx*OP_l_23_c_2_r_*SK_ACCX(3) + Kaccx*OP_l_23_c_3_r_*SK_ACCX(2) - Kaccx*OP_l_23_c_5_r_*SK_ACCX(5) + Kaccx*OP_l_23_c_6_r_*SK_ACCX(4) + Kaccx*OP_l_23_c_24_r_*SK_ACCX(5)); -Kfusion(24) = SK_ACCX(1)*(Kaccx*OP_l_24_c_23_r_*SH_ACCX(1) - Kaccx*OP_l_24_c_4_r_*SH_ACCX(1) + Kaccx*OP_l_24_c_2_r_*SK_ACCX(3) + Kaccx*OP_l_24_c_3_r_*SK_ACCX(2) - Kaccx*OP_l_24_c_5_r_*SK_ACCX(5) + Kaccx*OP_l_24_c_6_r_*SK_ACCX(4) + Kaccx*OP_l_24_c_24_r_*SK_ACCX(5)); +Kfusion(1) = -SK_ACCX(1)*(Kaccx*OP_l_1_c_5_r_*SH_ACCX(1) - Kaccx*OP_l_1_c_23_r_*SH_ACCX(1) + Kaccx*OP_l_1_c_1_r_*SK_ACCX(4) - Kaccx*OP_l_1_c_3_r_*SK_ACCX(3) + Kaccx*OP_l_1_c_4_r_*SK_ACCX(2) + Kaccx*OP_l_1_c_2_r_*SK_ACCX(5) + Kaccx*OP_l_1_c_6_r_*SK_ACCX(7) - Kaccx*OP_l_1_c_7_r_*SK_ACCX(6) - Kaccx*OP_l_1_c_24_r_*SK_ACCX(7)); +Kfusion(2) = -SK_ACCX(1)*(Kaccx*OP_l_2_c_5_r_*SH_ACCX(1) - Kaccx*OP_l_2_c_23_r_*SH_ACCX(1) + Kaccx*OP_l_2_c_1_r_*SK_ACCX(4) - Kaccx*OP_l_2_c_3_r_*SK_ACCX(3) + Kaccx*OP_l_2_c_4_r_*SK_ACCX(2) + Kaccx*OP_l_2_c_2_r_*SK_ACCX(5) + Kaccx*OP_l_2_c_6_r_*SK_ACCX(7) - Kaccx*OP_l_2_c_7_r_*SK_ACCX(6) - Kaccx*OP_l_2_c_24_r_*SK_ACCX(7)); +Kfusion(3) = -SK_ACCX(1)*(Kaccx*OP_l_3_c_5_r_*SH_ACCX(1) - Kaccx*OP_l_3_c_23_r_*SH_ACCX(1) + Kaccx*OP_l_3_c_1_r_*SK_ACCX(4) - Kaccx*OP_l_3_c_3_r_*SK_ACCX(3) + Kaccx*OP_l_3_c_4_r_*SK_ACCX(2) + Kaccx*OP_l_3_c_2_r_*SK_ACCX(5) + Kaccx*OP_l_3_c_6_r_*SK_ACCX(7) - Kaccx*OP_l_3_c_7_r_*SK_ACCX(6) - Kaccx*OP_l_3_c_24_r_*SK_ACCX(7)); +Kfusion(4) = -SK_ACCX(1)*(Kaccx*OP_l_4_c_5_r_*SH_ACCX(1) - Kaccx*OP_l_4_c_23_r_*SH_ACCX(1) + Kaccx*OP_l_4_c_1_r_*SK_ACCX(4) - Kaccx*OP_l_4_c_3_r_*SK_ACCX(3) + Kaccx*OP_l_4_c_4_r_*SK_ACCX(2) + Kaccx*OP_l_4_c_2_r_*SK_ACCX(5) + Kaccx*OP_l_4_c_6_r_*SK_ACCX(7) - Kaccx*OP_l_4_c_7_r_*SK_ACCX(6) - Kaccx*OP_l_4_c_24_r_*SK_ACCX(7)); +Kfusion(5) = -SK_ACCX(1)*(Kaccx*OP_l_5_c_5_r_*SH_ACCX(1) - Kaccx*OP_l_5_c_23_r_*SH_ACCX(1) + Kaccx*OP_l_5_c_1_r_*SK_ACCX(4) - Kaccx*OP_l_5_c_3_r_*SK_ACCX(3) + Kaccx*OP_l_5_c_4_r_*SK_ACCX(2) + Kaccx*OP_l_5_c_2_r_*SK_ACCX(5) + Kaccx*OP_l_5_c_6_r_*SK_ACCX(7) - Kaccx*OP_l_5_c_7_r_*SK_ACCX(6) - Kaccx*OP_l_5_c_24_r_*SK_ACCX(7)); +Kfusion(6) = -SK_ACCX(1)*(Kaccx*OP_l_6_c_5_r_*SH_ACCX(1) - Kaccx*OP_l_6_c_23_r_*SH_ACCX(1) + Kaccx*OP_l_6_c_1_r_*SK_ACCX(4) - Kaccx*OP_l_6_c_3_r_*SK_ACCX(3) + Kaccx*OP_l_6_c_4_r_*SK_ACCX(2) + Kaccx*OP_l_6_c_2_r_*SK_ACCX(5) + Kaccx*OP_l_6_c_6_r_*SK_ACCX(7) - Kaccx*OP_l_6_c_7_r_*SK_ACCX(6) - Kaccx*OP_l_6_c_24_r_*SK_ACCX(7)); +Kfusion(7) = -SK_ACCX(1)*(Kaccx*OP_l_7_c_5_r_*SH_ACCX(1) - Kaccx*OP_l_7_c_23_r_*SH_ACCX(1) + Kaccx*OP_l_7_c_1_r_*SK_ACCX(4) - Kaccx*OP_l_7_c_3_r_*SK_ACCX(3) + Kaccx*OP_l_7_c_4_r_*SK_ACCX(2) + Kaccx*OP_l_7_c_2_r_*SK_ACCX(5) + Kaccx*OP_l_7_c_6_r_*SK_ACCX(7) - Kaccx*OP_l_7_c_7_r_*SK_ACCX(6) - Kaccx*OP_l_7_c_24_r_*SK_ACCX(7)); +Kfusion(8) = -SK_ACCX(1)*(Kaccx*OP_l_8_c_5_r_*SH_ACCX(1) - Kaccx*OP_l_8_c_23_r_*SH_ACCX(1) + Kaccx*OP_l_8_c_1_r_*SK_ACCX(4) - Kaccx*OP_l_8_c_3_r_*SK_ACCX(3) + Kaccx*OP_l_8_c_4_r_*SK_ACCX(2) + Kaccx*OP_l_8_c_2_r_*SK_ACCX(5) + Kaccx*OP_l_8_c_6_r_*SK_ACCX(7) - Kaccx*OP_l_8_c_7_r_*SK_ACCX(6) - Kaccx*OP_l_8_c_24_r_*SK_ACCX(7)); +Kfusion(9) = -SK_ACCX(1)*(Kaccx*OP_l_9_c_5_r_*SH_ACCX(1) - Kaccx*OP_l_9_c_23_r_*SH_ACCX(1) + Kaccx*OP_l_9_c_1_r_*SK_ACCX(4) - Kaccx*OP_l_9_c_3_r_*SK_ACCX(3) + Kaccx*OP_l_9_c_4_r_*SK_ACCX(2) + Kaccx*OP_l_9_c_2_r_*SK_ACCX(5) + Kaccx*OP_l_9_c_6_r_*SK_ACCX(7) - Kaccx*OP_l_9_c_7_r_*SK_ACCX(6) - Kaccx*OP_l_9_c_24_r_*SK_ACCX(7)); +Kfusion(10) = -SK_ACCX(1)*(Kaccx*OP_l_10_c_5_r_*SH_ACCX(1) - Kaccx*OP_l_10_c_23_r_*SH_ACCX(1) + Kaccx*OP_l_10_c_1_r_*SK_ACCX(4) - Kaccx*OP_l_10_c_3_r_*SK_ACCX(3) + Kaccx*OP_l_10_c_4_r_*SK_ACCX(2) + Kaccx*OP_l_10_c_2_r_*SK_ACCX(5) + Kaccx*OP_l_10_c_6_r_*SK_ACCX(7) - Kaccx*OP_l_10_c_7_r_*SK_ACCX(6) - Kaccx*OP_l_10_c_24_r_*SK_ACCX(7)); +Kfusion(11) = -SK_ACCX(1)*(Kaccx*OP_l_11_c_5_r_*SH_ACCX(1) - Kaccx*OP_l_11_c_23_r_*SH_ACCX(1) + Kaccx*OP_l_11_c_1_r_*SK_ACCX(4) - Kaccx*OP_l_11_c_3_r_*SK_ACCX(3) + Kaccx*OP_l_11_c_4_r_*SK_ACCX(2) + Kaccx*OP_l_11_c_2_r_*SK_ACCX(5) + Kaccx*OP_l_11_c_6_r_*SK_ACCX(7) - Kaccx*OP_l_11_c_7_r_*SK_ACCX(6) - Kaccx*OP_l_11_c_24_r_*SK_ACCX(7)); +Kfusion(12) = -SK_ACCX(1)*(Kaccx*OP_l_12_c_5_r_*SH_ACCX(1) - Kaccx*OP_l_12_c_23_r_*SH_ACCX(1) + Kaccx*OP_l_12_c_1_r_*SK_ACCX(4) - Kaccx*OP_l_12_c_3_r_*SK_ACCX(3) + Kaccx*OP_l_12_c_4_r_*SK_ACCX(2) + Kaccx*OP_l_12_c_2_r_*SK_ACCX(5) + Kaccx*OP_l_12_c_6_r_*SK_ACCX(7) - Kaccx*OP_l_12_c_7_r_*SK_ACCX(6) - Kaccx*OP_l_12_c_24_r_*SK_ACCX(7)); +Kfusion(13) = -SK_ACCX(1)*(Kaccx*OP_l_13_c_5_r_*SH_ACCX(1) - Kaccx*OP_l_13_c_23_r_*SH_ACCX(1) + Kaccx*OP_l_13_c_1_r_*SK_ACCX(4) - Kaccx*OP_l_13_c_3_r_*SK_ACCX(3) + Kaccx*OP_l_13_c_4_r_*SK_ACCX(2) + Kaccx*OP_l_13_c_2_r_*SK_ACCX(5) + Kaccx*OP_l_13_c_6_r_*SK_ACCX(7) - Kaccx*OP_l_13_c_7_r_*SK_ACCX(6) - Kaccx*OP_l_13_c_24_r_*SK_ACCX(7)); +Kfusion(14) = -SK_ACCX(1)*(Kaccx*OP_l_14_c_5_r_*SH_ACCX(1) - Kaccx*OP_l_14_c_23_r_*SH_ACCX(1) + Kaccx*OP_l_14_c_1_r_*SK_ACCX(4) - Kaccx*OP_l_14_c_3_r_*SK_ACCX(3) + Kaccx*OP_l_14_c_4_r_*SK_ACCX(2) + Kaccx*OP_l_14_c_2_r_*SK_ACCX(5) + Kaccx*OP_l_14_c_6_r_*SK_ACCX(7) - Kaccx*OP_l_14_c_7_r_*SK_ACCX(6) - Kaccx*OP_l_14_c_24_r_*SK_ACCX(7)); +Kfusion(15) = -SK_ACCX(1)*(Kaccx*OP_l_15_c_5_r_*SH_ACCX(1) - Kaccx*OP_l_15_c_23_r_*SH_ACCX(1) + Kaccx*OP_l_15_c_1_r_*SK_ACCX(4) - Kaccx*OP_l_15_c_3_r_*SK_ACCX(3) + Kaccx*OP_l_15_c_4_r_*SK_ACCX(2) + Kaccx*OP_l_15_c_2_r_*SK_ACCX(5) + Kaccx*OP_l_15_c_6_r_*SK_ACCX(7) - Kaccx*OP_l_15_c_7_r_*SK_ACCX(6) - Kaccx*OP_l_15_c_24_r_*SK_ACCX(7)); +Kfusion(16) = -SK_ACCX(1)*(Kaccx*OP_l_16_c_5_r_*SH_ACCX(1) - Kaccx*OP_l_16_c_23_r_*SH_ACCX(1) + Kaccx*OP_l_16_c_1_r_*SK_ACCX(4) - Kaccx*OP_l_16_c_3_r_*SK_ACCX(3) + Kaccx*OP_l_16_c_4_r_*SK_ACCX(2) + Kaccx*OP_l_16_c_2_r_*SK_ACCX(5) + Kaccx*OP_l_16_c_6_r_*SK_ACCX(7) - Kaccx*OP_l_16_c_7_r_*SK_ACCX(6) - Kaccx*OP_l_16_c_24_r_*SK_ACCX(7)); +Kfusion(17) = -SK_ACCX(1)*(Kaccx*OP_l_17_c_5_r_*SH_ACCX(1) - Kaccx*OP_l_17_c_23_r_*SH_ACCX(1) + Kaccx*OP_l_17_c_1_r_*SK_ACCX(4) - Kaccx*OP_l_17_c_3_r_*SK_ACCX(3) + Kaccx*OP_l_17_c_4_r_*SK_ACCX(2) + Kaccx*OP_l_17_c_2_r_*SK_ACCX(5) + Kaccx*OP_l_17_c_6_r_*SK_ACCX(7) - Kaccx*OP_l_17_c_7_r_*SK_ACCX(6) - Kaccx*OP_l_17_c_24_r_*SK_ACCX(7)); +Kfusion(18) = -SK_ACCX(1)*(Kaccx*OP_l_18_c_5_r_*SH_ACCX(1) - Kaccx*OP_l_18_c_23_r_*SH_ACCX(1) + Kaccx*OP_l_18_c_1_r_*SK_ACCX(4) - Kaccx*OP_l_18_c_3_r_*SK_ACCX(3) + Kaccx*OP_l_18_c_4_r_*SK_ACCX(2) + Kaccx*OP_l_18_c_2_r_*SK_ACCX(5) + Kaccx*OP_l_18_c_6_r_*SK_ACCX(7) - Kaccx*OP_l_18_c_7_r_*SK_ACCX(6) - Kaccx*OP_l_18_c_24_r_*SK_ACCX(7)); +Kfusion(19) = -SK_ACCX(1)*(Kaccx*OP_l_19_c_5_r_*SH_ACCX(1) - Kaccx*OP_l_19_c_23_r_*SH_ACCX(1) + Kaccx*OP_l_19_c_1_r_*SK_ACCX(4) - Kaccx*OP_l_19_c_3_r_*SK_ACCX(3) + Kaccx*OP_l_19_c_4_r_*SK_ACCX(2) + Kaccx*OP_l_19_c_2_r_*SK_ACCX(5) + Kaccx*OP_l_19_c_6_r_*SK_ACCX(7) - Kaccx*OP_l_19_c_7_r_*SK_ACCX(6) - Kaccx*OP_l_19_c_24_r_*SK_ACCX(7)); +Kfusion(20) = -SK_ACCX(1)*(Kaccx*OP_l_20_c_5_r_*SH_ACCX(1) - Kaccx*OP_l_20_c_23_r_*SH_ACCX(1) + Kaccx*OP_l_20_c_1_r_*SK_ACCX(4) - Kaccx*OP_l_20_c_3_r_*SK_ACCX(3) + Kaccx*OP_l_20_c_4_r_*SK_ACCX(2) + Kaccx*OP_l_20_c_2_r_*SK_ACCX(5) + Kaccx*OP_l_20_c_6_r_*SK_ACCX(7) - Kaccx*OP_l_20_c_7_r_*SK_ACCX(6) - Kaccx*OP_l_20_c_24_r_*SK_ACCX(7)); +Kfusion(21) = -SK_ACCX(1)*(Kaccx*OP_l_21_c_5_r_*SH_ACCX(1) - Kaccx*OP_l_21_c_23_r_*SH_ACCX(1) + Kaccx*OP_l_21_c_1_r_*SK_ACCX(4) - Kaccx*OP_l_21_c_3_r_*SK_ACCX(3) + Kaccx*OP_l_21_c_4_r_*SK_ACCX(2) + Kaccx*OP_l_21_c_2_r_*SK_ACCX(5) + Kaccx*OP_l_21_c_6_r_*SK_ACCX(7) - Kaccx*OP_l_21_c_7_r_*SK_ACCX(6) - Kaccx*OP_l_21_c_24_r_*SK_ACCX(7)); +Kfusion(22) = -SK_ACCX(1)*(Kaccx*OP_l_22_c_5_r_*SH_ACCX(1) - Kaccx*OP_l_22_c_23_r_*SH_ACCX(1) + Kaccx*OP_l_22_c_1_r_*SK_ACCX(4) - Kaccx*OP_l_22_c_3_r_*SK_ACCX(3) + Kaccx*OP_l_22_c_4_r_*SK_ACCX(2) + Kaccx*OP_l_22_c_2_r_*SK_ACCX(5) + Kaccx*OP_l_22_c_6_r_*SK_ACCX(7) - Kaccx*OP_l_22_c_7_r_*SK_ACCX(6) - Kaccx*OP_l_22_c_24_r_*SK_ACCX(7)); +Kfusion(23) = -SK_ACCX(1)*(Kaccx*OP_l_23_c_5_r_*SH_ACCX(1) - Kaccx*OP_l_23_c_23_r_*SH_ACCX(1) + Kaccx*OP_l_23_c_1_r_*SK_ACCX(4) - Kaccx*OP_l_23_c_3_r_*SK_ACCX(3) + Kaccx*OP_l_23_c_4_r_*SK_ACCX(2) + Kaccx*OP_l_23_c_2_r_*SK_ACCX(5) + Kaccx*OP_l_23_c_6_r_*SK_ACCX(7) - Kaccx*OP_l_23_c_7_r_*SK_ACCX(6) - Kaccx*OP_l_23_c_24_r_*SK_ACCX(7)); +Kfusion(24) = -SK_ACCX(1)*(Kaccx*OP_l_24_c_5_r_*SH_ACCX(1) - Kaccx*OP_l_24_c_23_r_*SH_ACCX(1) + Kaccx*OP_l_24_c_1_r_*SK_ACCX(4) - Kaccx*OP_l_24_c_3_r_*SK_ACCX(3) + Kaccx*OP_l_24_c_4_r_*SK_ACCX(2) + Kaccx*OP_l_24_c_2_r_*SK_ACCX(5) + Kaccx*OP_l_24_c_6_r_*SK_ACCX(7) - Kaccx*OP_l_24_c_7_r_*SK_ACCX(6) - Kaccx*OP_l_24_c_24_r_*SK_ACCX(7)); -SH_ACCY = zeros(6,1); +SH_ACCY = zeros(3,1); SH_ACCY(1) = q0^2 - q1^2 + q2^2 - q3^2; -SH_ACCY(2) = ve - vwe; -SH_ACCY(3) = vn - vwn; -SH_ACCY(4) = q1^2; -SH_ACCY(5) = 2*q0*q1; -SH_ACCY(6) = 2*q0*q3; +SH_ACCY(2) = vn - vwn; +SH_ACCY(3) = ve - vwe; H_ACCY = zeros(1,24); -H_ACCY(1,1) = Kaccy*(SH_ACCY(2)*(SH_ACCY(5) - 2*q2*q3) - SH_ACCY(3)*(2*q0*q2 + 2*q1*q3) + vd*(SH_ACCY(4) - q0^2 + q2^2 - q3^2)); -H_ACCY(1,3) = Kaccy*(SH_ACCY(3)*(SH_ACCY(4) + q0^2 - q2^2 - q3^2) + SH_ACCY(2)*(SH_ACCY(6) + 2*q1*q2) - 2*vd*(q0*q2 - q1*q3)); -H_ACCY(1,4) = Kaccy*(SH_ACCY(6) - 2*q1*q2); -H_ACCY(1,5) = -Kaccy*SH_ACCY(1); -H_ACCY(1,6) = -Kaccy*(SH_ACCY(5) + 2*q2*q3); +H_ACCY(1,1) = -Kaccy*(2*q0*SH_ACCY(3) - 2*q3*SH_ACCY(2) + 2*q1*vd); +H_ACCY(1,2) = -Kaccy*(2*q2*SH_ACCY(2) - 2*q1*SH_ACCY(3) + 2*q0*vd); +H_ACCY(1,3) = -Kaccy*(2*q1*SH_ACCY(2) + 2*q2*SH_ACCY(3) + 2*q3*vd); +H_ACCY(1,4) = Kaccy*(2*q0*SH_ACCY(2) + 2*q3*SH_ACCY(3) - 2*q2*vd); +H_ACCY(1,5) = Kaccy*(2*q0*q3 - 2*q1*q2); +H_ACCY(1,6) = -Kaccy*SH_ACCY(1); +H_ACCY(1,7) = -Kaccy*(2*q0*q1 + 2*q2*q3); H_ACCY(1,23) = -2*Kaccy*(q0*q3 - q1*q2); H_ACCY(1,24) = Kaccy*SH_ACCY(1); -SK_ACCY = zeros(7,1); -SK_ACCY(1) = 1/(R_ACC - Kaccy*SH_ACCY(1)*(Kaccy*OP_l_24_c_5_r_*SH_ACCY(1) - Kaccy*OP_l_5_c_5_r_*SH_ACCY(1) + Kaccy*OP_l_1_c_5_r_*(SH_ACCY(2)*(SH_ACCY(5) - 2*q2*q3) - SH_ACCY(3)*(2*q0*q2 + 2*q1*q3) + vd*(SH_ACCY(4) - q0^2 + q2^2 - q3^2)) + Kaccy*OP_l_3_c_5_r_*(SH_ACCY(3)*(SH_ACCY(4) + q0^2 - q2^2 - q3^2) + SH_ACCY(2)*(SH_ACCY(6) + 2*q1*q2) - 2*vd*(q0*q2 - q1*q3)) - 2*Kaccy*OP_l_23_c_5_r_*(q0*q3 - q1*q2) + Kaccy*OP_l_4_c_5_r_*(SH_ACCY(6) - 2*q1*q2) - Kaccy*OP_l_6_c_5_r_*(SH_ACCY(5) + 2*q2*q3)) + Kaccy*SH_ACCY(1)*(Kaccy*OP_l_24_c_24_r_*SH_ACCY(1) - Kaccy*OP_l_5_c_24_r_*SH_ACCY(1) + Kaccy*OP_l_1_c_24_r_*(SH_ACCY(2)*(SH_ACCY(5) - 2*q2*q3) - SH_ACCY(3)*(2*q0*q2 + 2*q1*q3) + vd*(SH_ACCY(4) - q0^2 + q2^2 - q3^2)) + Kaccy*OP_l_3_c_24_r_*(SH_ACCY(3)*(SH_ACCY(4) + q0^2 - q2^2 - q3^2) + SH_ACCY(2)*(SH_ACCY(6) + 2*q1*q2) - 2*vd*(q0*q2 - q1*q3)) - 2*Kaccy*OP_l_23_c_24_r_*(q0*q3 - q1*q2) + Kaccy*OP_l_4_c_24_r_*(SH_ACCY(6) - 2*q1*q2) - Kaccy*OP_l_6_c_24_r_*(SH_ACCY(5) + 2*q2*q3)) + Kaccy*(SH_ACCY(2)*(SH_ACCY(5) - 2*q2*q3) - SH_ACCY(3)*(2*q0*q2 + 2*q1*q3) + vd*(SH_ACCY(4) - q0^2 + q2^2 - q3^2))*(Kaccy*OP_l_24_c_1_r_*SH_ACCY(1) - Kaccy*OP_l_5_c_1_r_*SH_ACCY(1) + Kaccy*OP_l_1_c_1_r_*(SH_ACCY(2)*(SH_ACCY(5) - 2*q2*q3) - SH_ACCY(3)*(2*q0*q2 + 2*q1*q3) + vd*(SH_ACCY(4) - q0^2 + q2^2 - q3^2)) + Kaccy*OP_l_3_c_1_r_*(SH_ACCY(3)*(SH_ACCY(4) + q0^2 - q2^2 - q3^2) + SH_ACCY(2)*(SH_ACCY(6) + 2*q1*q2) - 2*vd*(q0*q2 - q1*q3)) - 2*Kaccy*OP_l_23_c_1_r_*(q0*q3 - q1*q2) + Kaccy*OP_l_4_c_1_r_*(SH_ACCY(6) - 2*q1*q2) - Kaccy*OP_l_6_c_1_r_*(SH_ACCY(5) + 2*q2*q3)) + Kaccy*(SH_ACCY(3)*(SH_ACCY(4) + q0^2 - q2^2 - q3^2) + SH_ACCY(2)*(SH_ACCY(6) + 2*q1*q2) - 2*vd*(q0*q2 - q1*q3))*(Kaccy*OP_l_24_c_3_r_*SH_ACCY(1) - Kaccy*OP_l_5_c_3_r_*SH_ACCY(1) + Kaccy*OP_l_1_c_3_r_*(SH_ACCY(2)*(SH_ACCY(5) - 2*q2*q3) - SH_ACCY(3)*(2*q0*q2 + 2*q1*q3) + vd*(SH_ACCY(4) - q0^2 + q2^2 - q3^2)) + Kaccy*OP_l_3_c_3_r_*(SH_ACCY(3)*(SH_ACCY(4) + q0^2 - q2^2 - q3^2) + SH_ACCY(2)*(SH_ACCY(6) + 2*q1*q2) - 2*vd*(q0*q2 - q1*q3)) - 2*Kaccy*OP_l_23_c_3_r_*(q0*q3 - q1*q2) + Kaccy*OP_l_4_c_3_r_*(SH_ACCY(6) - 2*q1*q2) - Kaccy*OP_l_6_c_3_r_*(SH_ACCY(5) + 2*q2*q3)) - 2*Kaccy*(q0*q3 - q1*q2)*(Kaccy*OP_l_24_c_23_r_*SH_ACCY(1) - Kaccy*OP_l_5_c_23_r_*SH_ACCY(1) + Kaccy*OP_l_1_c_23_r_*(SH_ACCY(2)*(SH_ACCY(5) - 2*q2*q3) - SH_ACCY(3)*(2*q0*q2 + 2*q1*q3) + vd*(SH_ACCY(4) - q0^2 + q2^2 - q3^2)) + Kaccy*OP_l_3_c_23_r_*(SH_ACCY(3)*(SH_ACCY(4) + q0^2 - q2^2 - q3^2) + SH_ACCY(2)*(SH_ACCY(6) + 2*q1*q2) - 2*vd*(q0*q2 - q1*q3)) - 2*Kaccy*OP_l_23_c_23_r_*(q0*q3 - q1*q2) + Kaccy*OP_l_4_c_23_r_*(SH_ACCY(6) - 2*q1*q2) - Kaccy*OP_l_6_c_23_r_*(SH_ACCY(5) + 2*q2*q3)) + Kaccy*(SH_ACCY(6) - 2*q1*q2)*(Kaccy*OP_l_24_c_4_r_*SH_ACCY(1) - Kaccy*OP_l_5_c_4_r_*SH_ACCY(1) + Kaccy*OP_l_1_c_4_r_*(SH_ACCY(2)*(SH_ACCY(5) - 2*q2*q3) - SH_ACCY(3)*(2*q0*q2 + 2*q1*q3) + vd*(SH_ACCY(4) - q0^2 + q2^2 - q3^2)) + Kaccy*OP_l_3_c_4_r_*(SH_ACCY(3)*(SH_ACCY(4) + q0^2 - q2^2 - q3^2) + SH_ACCY(2)*(SH_ACCY(6) + 2*q1*q2) - 2*vd*(q0*q2 - q1*q3)) - 2*Kaccy*OP_l_23_c_4_r_*(q0*q3 - q1*q2) + Kaccy*OP_l_4_c_4_r_*(SH_ACCY(6) - 2*q1*q2) - Kaccy*OP_l_6_c_4_r_*(SH_ACCY(5) + 2*q2*q3)) - Kaccy*(SH_ACCY(5) + 2*q2*q3)*(Kaccy*OP_l_24_c_6_r_*SH_ACCY(1) - Kaccy*OP_l_5_c_6_r_*SH_ACCY(1) + Kaccy*OP_l_1_c_6_r_*(SH_ACCY(2)*(SH_ACCY(5) - 2*q2*q3) - SH_ACCY(3)*(2*q0*q2 + 2*q1*q3) + vd*(SH_ACCY(4) - q0^2 + q2^2 - q3^2)) + Kaccy*OP_l_3_c_6_r_*(SH_ACCY(3)*(SH_ACCY(4) + q0^2 - q2^2 - q3^2) + SH_ACCY(2)*(SH_ACCY(6) + 2*q1*q2) - 2*vd*(q0*q2 - q1*q3)) - 2*Kaccy*OP_l_23_c_6_r_*(q0*q3 - q1*q2) + Kaccy*OP_l_4_c_6_r_*(SH_ACCY(6) - 2*q1*q2) - Kaccy*OP_l_6_c_6_r_*(SH_ACCY(5) + 2*q2*q3))); -SK_ACCY(2) = SH_ACCY(3)*(SH_ACCY(4) + q0^2 - q2^2 - q3^2) + SH_ACCY(2)*(SH_ACCY(6) + 2*q1*q2) - 2*vd*(q0*q2 - q1*q3); -SK_ACCY(3) = SH_ACCY(2)*(SH_ACCY(5) - 2*q2*q3) - SH_ACCY(3)*(2*q0*q2 + 2*q1*q3) + vd*(SH_ACCY(4) - q0^2 + q2^2 - q3^2); -SK_ACCY(4) = q0*q3 - q1*q2; -SK_ACCY(5) = SH_ACCY(6) - 2*q1*q2; -SK_ACCY(6) = SH_ACCY(5) + 2*q2*q3; -SK_ACCY(7) = SH_ACCY(1); +SK_ACCY = zeros(9,1); +SK_ACCY(1) = 1/(R_ACC + Kaccy*SH_ACCY(1)*(Kaccy*OP_l_6_c_6_r_*SH_ACCY(1) - Kaccy*OP_l_24_c_6_r_*SH_ACCY(1) - Kaccy*OP_l_5_c_6_r_*(2*q0*q3 - 2*q1*q2) + Kaccy*OP_l_7_c_6_r_*(2*q0*q1 + 2*q2*q3) + 2*Kaccy*OP_l_23_c_6_r_*(q0*q3 - q1*q2) + Kaccy*OP_l_1_c_6_r_*(2*q0*SH_ACCY(3) - 2*q3*SH_ACCY(2) + 2*q1*vd) + Kaccy*OP_l_2_c_6_r_*(2*q2*SH_ACCY(2) - 2*q1*SH_ACCY(3) + 2*q0*vd) + Kaccy*OP_l_3_c_6_r_*(2*q1*SH_ACCY(2) + 2*q2*SH_ACCY(3) + 2*q3*vd) - Kaccy*OP_l_4_c_6_r_*(2*q0*SH_ACCY(2) + 2*q3*SH_ACCY(3) - 2*q2*vd)) - Kaccy*SH_ACCY(1)*(Kaccy*OP_l_6_c_24_r_*SH_ACCY(1) - Kaccy*OP_l_24_c_24_r_*SH_ACCY(1) - Kaccy*OP_l_5_c_24_r_*(2*q0*q3 - 2*q1*q2) + Kaccy*OP_l_7_c_24_r_*(2*q0*q1 + 2*q2*q3) + 2*Kaccy*OP_l_23_c_24_r_*(q0*q3 - q1*q2) + Kaccy*OP_l_1_c_24_r_*(2*q0*SH_ACCY(3) - 2*q3*SH_ACCY(2) + 2*q1*vd) + Kaccy*OP_l_2_c_24_r_*(2*q2*SH_ACCY(2) - 2*q1*SH_ACCY(3) + 2*q0*vd) + Kaccy*OP_l_3_c_24_r_*(2*q1*SH_ACCY(2) + 2*q2*SH_ACCY(3) + 2*q3*vd) - Kaccy*OP_l_4_c_24_r_*(2*q0*SH_ACCY(2) + 2*q3*SH_ACCY(3) - 2*q2*vd)) - Kaccy*(2*q0*q3 - 2*q1*q2)*(Kaccy*OP_l_6_c_5_r_*SH_ACCY(1) - Kaccy*OP_l_24_c_5_r_*SH_ACCY(1) - Kaccy*OP_l_5_c_5_r_*(2*q0*q3 - 2*q1*q2) + Kaccy*OP_l_7_c_5_r_*(2*q0*q1 + 2*q2*q3) + 2*Kaccy*OP_l_23_c_5_r_*(q0*q3 - q1*q2) + Kaccy*OP_l_1_c_5_r_*(2*q0*SH_ACCY(3) - 2*q3*SH_ACCY(2) + 2*q1*vd) + Kaccy*OP_l_2_c_5_r_*(2*q2*SH_ACCY(2) - 2*q1*SH_ACCY(3) + 2*q0*vd) + Kaccy*OP_l_3_c_5_r_*(2*q1*SH_ACCY(2) + 2*q2*SH_ACCY(3) + 2*q3*vd) - Kaccy*OP_l_4_c_5_r_*(2*q0*SH_ACCY(2) + 2*q3*SH_ACCY(3) - 2*q2*vd)) + Kaccy*(2*q0*q1 + 2*q2*q3)*(Kaccy*OP_l_6_c_7_r_*SH_ACCY(1) - Kaccy*OP_l_24_c_7_r_*SH_ACCY(1) - Kaccy*OP_l_5_c_7_r_*(2*q0*q3 - 2*q1*q2) + Kaccy*OP_l_7_c_7_r_*(2*q0*q1 + 2*q2*q3) + 2*Kaccy*OP_l_23_c_7_r_*(q0*q3 - q1*q2) + Kaccy*OP_l_1_c_7_r_*(2*q0*SH_ACCY(3) - 2*q3*SH_ACCY(2) + 2*q1*vd) + Kaccy*OP_l_2_c_7_r_*(2*q2*SH_ACCY(2) - 2*q1*SH_ACCY(3) + 2*q0*vd) + Kaccy*OP_l_3_c_7_r_*(2*q1*SH_ACCY(2) + 2*q2*SH_ACCY(3) + 2*q3*vd) - Kaccy*OP_l_4_c_7_r_*(2*q0*SH_ACCY(2) + 2*q3*SH_ACCY(3) - 2*q2*vd)) + 2*Kaccy*(q0*q3 - q1*q2)*(Kaccy*OP_l_6_c_23_r_*SH_ACCY(1) - Kaccy*OP_l_24_c_23_r_*SH_ACCY(1) - Kaccy*OP_l_5_c_23_r_*(2*q0*q3 - 2*q1*q2) + Kaccy*OP_l_7_c_23_r_*(2*q0*q1 + 2*q2*q3) + 2*Kaccy*OP_l_23_c_23_r_*(q0*q3 - q1*q2) + Kaccy*OP_l_1_c_23_r_*(2*q0*SH_ACCY(3) - 2*q3*SH_ACCY(2) + 2*q1*vd) + Kaccy*OP_l_2_c_23_r_*(2*q2*SH_ACCY(2) - 2*q1*SH_ACCY(3) + 2*q0*vd) + Kaccy*OP_l_3_c_23_r_*(2*q1*SH_ACCY(2) + 2*q2*SH_ACCY(3) + 2*q3*vd) - Kaccy*OP_l_4_c_23_r_*(2*q0*SH_ACCY(2) + 2*q3*SH_ACCY(3) - 2*q2*vd)) + Kaccy*(2*q0*SH_ACCY(3) - 2*q3*SH_ACCY(2) + 2*q1*vd)*(Kaccy*OP_l_6_c_1_r_*SH_ACCY(1) - Kaccy*OP_l_24_c_1_r_*SH_ACCY(1) - Kaccy*OP_l_5_c_1_r_*(2*q0*q3 - 2*q1*q2) + Kaccy*OP_l_7_c_1_r_*(2*q0*q1 + 2*q2*q3) + 2*Kaccy*OP_l_23_c_1_r_*(q0*q3 - q1*q2) + Kaccy*OP_l_1_c_1_r_*(2*q0*SH_ACCY(3) - 2*q3*SH_ACCY(2) + 2*q1*vd) + Kaccy*OP_l_2_c_1_r_*(2*q2*SH_ACCY(2) - 2*q1*SH_ACCY(3) + 2*q0*vd) + Kaccy*OP_l_3_c_1_r_*(2*q1*SH_ACCY(2) + 2*q2*SH_ACCY(3) + 2*q3*vd) - Kaccy*OP_l_4_c_1_r_*(2*q0*SH_ACCY(2) + 2*q3*SH_ACCY(3) - 2*q2*vd)) + Kaccy*(2*q2*SH_ACCY(2) - 2*q1*SH_ACCY(3) + 2*q0*vd)*(Kaccy*OP_l_6_c_2_r_*SH_ACCY(1) - Kaccy*OP_l_24_c_2_r_*SH_ACCY(1) - Kaccy*OP_l_5_c_2_r_*(2*q0*q3 - 2*q1*q2) + Kaccy*OP_l_7_c_2_r_*(2*q0*q1 + 2*q2*q3) + 2*Kaccy*OP_l_23_c_2_r_*(q0*q3 - q1*q2) + Kaccy*OP_l_1_c_2_r_*(2*q0*SH_ACCY(3) - 2*q3*SH_ACCY(2) + 2*q1*vd) + Kaccy*OP_l_2_c_2_r_*(2*q2*SH_ACCY(2) - 2*q1*SH_ACCY(3) + 2*q0*vd) + Kaccy*OP_l_3_c_2_r_*(2*q1*SH_ACCY(2) + 2*q2*SH_ACCY(3) + 2*q3*vd) - Kaccy*OP_l_4_c_2_r_*(2*q0*SH_ACCY(2) + 2*q3*SH_ACCY(3) - 2*q2*vd)) + Kaccy*(2*q1*SH_ACCY(2) + 2*q2*SH_ACCY(3) + 2*q3*vd)*(Kaccy*OP_l_6_c_3_r_*SH_ACCY(1) - Kaccy*OP_l_24_c_3_r_*SH_ACCY(1) - Kaccy*OP_l_5_c_3_r_*(2*q0*q3 - 2*q1*q2) + Kaccy*OP_l_7_c_3_r_*(2*q0*q1 + 2*q2*q3) + 2*Kaccy*OP_l_23_c_3_r_*(q0*q3 - q1*q2) + Kaccy*OP_l_1_c_3_r_*(2*q0*SH_ACCY(3) - 2*q3*SH_ACCY(2) + 2*q1*vd) + Kaccy*OP_l_2_c_3_r_*(2*q2*SH_ACCY(2) - 2*q1*SH_ACCY(3) + 2*q0*vd) + Kaccy*OP_l_3_c_3_r_*(2*q1*SH_ACCY(2) + 2*q2*SH_ACCY(3) + 2*q3*vd) - Kaccy*OP_l_4_c_3_r_*(2*q0*SH_ACCY(2) + 2*q3*SH_ACCY(3) - 2*q2*vd)) - Kaccy*(2*q0*SH_ACCY(2) + 2*q3*SH_ACCY(3) - 2*q2*vd)*(Kaccy*OP_l_6_c_4_r_*SH_ACCY(1) - Kaccy*OP_l_24_c_4_r_*SH_ACCY(1) - Kaccy*OP_l_5_c_4_r_*(2*q0*q3 - 2*q1*q2) + Kaccy*OP_l_7_c_4_r_*(2*q0*q1 + 2*q2*q3) + 2*Kaccy*OP_l_23_c_4_r_*(q0*q3 - q1*q2) + Kaccy*OP_l_1_c_4_r_*(2*q0*SH_ACCY(3) - 2*q3*SH_ACCY(2) + 2*q1*vd) + Kaccy*OP_l_2_c_4_r_*(2*q2*SH_ACCY(2) - 2*q1*SH_ACCY(3) + 2*q0*vd) + Kaccy*OP_l_3_c_4_r_*(2*q1*SH_ACCY(2) + 2*q2*SH_ACCY(3) + 2*q3*vd) - Kaccy*OP_l_4_c_4_r_*(2*q0*SH_ACCY(2) + 2*q3*SH_ACCY(3) - 2*q2*vd))); +SK_ACCY(2) = 2*q0*SH_ACCY(2) + 2*q3*SH_ACCY(3) - 2*q2*vd; +SK_ACCY(3) = 2*q2*SH_ACCY(2) - 2*q1*SH_ACCY(3) + 2*q0*vd; +SK_ACCY(4) = 2*q0*SH_ACCY(3) - 2*q3*SH_ACCY(2) + 2*q1*vd; +SK_ACCY(5) = 2*q1*SH_ACCY(2) + 2*q2*SH_ACCY(3) + 2*q3*vd; +SK_ACCY(6) = 2*q0*q3 - 2*q1*q2; +SK_ACCY(7) = q0*q3 - q1*q2; +SK_ACCY(8) = 2*q0*q1 + 2*q2*q3; +SK_ACCY(9) = SH_ACCY(1); Kfusion = zeros(24,1); Kfusion = zeros(1,1); -Kfusion(1) = SK_ACCY(1)*(Kaccy*OP_l_1_c_1_r_*SK_ACCY(3) + Kaccy*OP_l_1_c_3_r_*SK_ACCY(2) + Kaccy*OP_l_1_c_4_r_*SK_ACCY(5) - Kaccy*OP_l_1_c_5_r_*SK_ACCY(7) - Kaccy*OP_l_1_c_6_r_*SK_ACCY(6) - 2*Kaccy*OP_l_1_c_23_r_*SK_ACCY(4) + Kaccy*OP_l_1_c_24_r_*SK_ACCY(7)); -Kfusion(2) = SK_ACCY(1)*(Kaccy*OP_l_2_c_1_r_*SK_ACCY(3) + Kaccy*OP_l_2_c_3_r_*SK_ACCY(2) + Kaccy*OP_l_2_c_4_r_*SK_ACCY(5) - Kaccy*OP_l_2_c_5_r_*SK_ACCY(7) - Kaccy*OP_l_2_c_6_r_*SK_ACCY(6) - 2*Kaccy*OP_l_2_c_23_r_*SK_ACCY(4) + Kaccy*OP_l_2_c_24_r_*SK_ACCY(7)); -Kfusion(3) = SK_ACCY(1)*(Kaccy*OP_l_3_c_1_r_*SK_ACCY(3) + Kaccy*OP_l_3_c_3_r_*SK_ACCY(2) + Kaccy*OP_l_3_c_4_r_*SK_ACCY(5) - Kaccy*OP_l_3_c_5_r_*SK_ACCY(7) - Kaccy*OP_l_3_c_6_r_*SK_ACCY(6) - 2*Kaccy*OP_l_3_c_23_r_*SK_ACCY(4) + Kaccy*OP_l_3_c_24_r_*SK_ACCY(7)); -Kfusion(4) = SK_ACCY(1)*(Kaccy*OP_l_4_c_1_r_*SK_ACCY(3) + Kaccy*OP_l_4_c_3_r_*SK_ACCY(2) + Kaccy*OP_l_4_c_4_r_*SK_ACCY(5) - Kaccy*OP_l_4_c_5_r_*SK_ACCY(7) - Kaccy*OP_l_4_c_6_r_*SK_ACCY(6) - 2*Kaccy*OP_l_4_c_23_r_*SK_ACCY(4) + Kaccy*OP_l_4_c_24_r_*SK_ACCY(7)); -Kfusion(5) = SK_ACCY(1)*(Kaccy*OP_l_5_c_1_r_*SK_ACCY(3) + Kaccy*OP_l_5_c_3_r_*SK_ACCY(2) + Kaccy*OP_l_5_c_4_r_*SK_ACCY(5) - Kaccy*OP_l_5_c_5_r_*SK_ACCY(7) - Kaccy*OP_l_5_c_6_r_*SK_ACCY(6) - 2*Kaccy*OP_l_5_c_23_r_*SK_ACCY(4) + Kaccy*OP_l_5_c_24_r_*SK_ACCY(7)); -Kfusion(6) = SK_ACCY(1)*(Kaccy*OP_l_6_c_1_r_*SK_ACCY(3) + Kaccy*OP_l_6_c_3_r_*SK_ACCY(2) + Kaccy*OP_l_6_c_4_r_*SK_ACCY(5) - Kaccy*OP_l_6_c_5_r_*SK_ACCY(7) - Kaccy*OP_l_6_c_6_r_*SK_ACCY(6) - 2*Kaccy*OP_l_6_c_23_r_*SK_ACCY(4) + Kaccy*OP_l_6_c_24_r_*SK_ACCY(7)); -Kfusion(7) = SK_ACCY(1)*(Kaccy*OP_l_7_c_1_r_*SK_ACCY(3) + Kaccy*OP_l_7_c_3_r_*SK_ACCY(2) + Kaccy*OP_l_7_c_4_r_*SK_ACCY(5) - Kaccy*OP_l_7_c_5_r_*SK_ACCY(7) - Kaccy*OP_l_7_c_6_r_*SK_ACCY(6) - 2*Kaccy*OP_l_7_c_23_r_*SK_ACCY(4) + Kaccy*OP_l_7_c_24_r_*SK_ACCY(7)); -Kfusion(8) = SK_ACCY(1)*(Kaccy*OP_l_8_c_1_r_*SK_ACCY(3) + Kaccy*OP_l_8_c_3_r_*SK_ACCY(2) + Kaccy*OP_l_8_c_4_r_*SK_ACCY(5) - Kaccy*OP_l_8_c_5_r_*SK_ACCY(7) - Kaccy*OP_l_8_c_6_r_*SK_ACCY(6) - 2*Kaccy*OP_l_8_c_23_r_*SK_ACCY(4) + Kaccy*OP_l_8_c_24_r_*SK_ACCY(7)); -Kfusion(9) = SK_ACCY(1)*(Kaccy*OP_l_9_c_1_r_*SK_ACCY(3) + Kaccy*OP_l_9_c_3_r_*SK_ACCY(2) + Kaccy*OP_l_9_c_4_r_*SK_ACCY(5) - Kaccy*OP_l_9_c_5_r_*SK_ACCY(7) - Kaccy*OP_l_9_c_6_r_*SK_ACCY(6) - 2*Kaccy*OP_l_9_c_23_r_*SK_ACCY(4) + Kaccy*OP_l_9_c_24_r_*SK_ACCY(7)); -Kfusion(10) = SK_ACCY(1)*(Kaccy*OP_l_10_c_1_r_*SK_ACCY(3) + Kaccy*OP_l_10_c_3_r_*SK_ACCY(2) + Kaccy*OP_l_10_c_4_r_*SK_ACCY(5) - Kaccy*OP_l_10_c_5_r_*SK_ACCY(7) - Kaccy*OP_l_10_c_6_r_*SK_ACCY(6) - 2*Kaccy*OP_l_10_c_23_r_*SK_ACCY(4) + Kaccy*OP_l_10_c_24_r_*SK_ACCY(7)); -Kfusion(11) = SK_ACCY(1)*(Kaccy*OP_l_11_c_1_r_*SK_ACCY(3) + Kaccy*OP_l_11_c_3_r_*SK_ACCY(2) + Kaccy*OP_l_11_c_4_r_*SK_ACCY(5) - Kaccy*OP_l_11_c_5_r_*SK_ACCY(7) - Kaccy*OP_l_11_c_6_r_*SK_ACCY(6) - 2*Kaccy*OP_l_11_c_23_r_*SK_ACCY(4) + Kaccy*OP_l_11_c_24_r_*SK_ACCY(7)); -Kfusion(12) = SK_ACCY(1)*(Kaccy*OP_l_12_c_1_r_*SK_ACCY(3) + Kaccy*OP_l_12_c_3_r_*SK_ACCY(2) + Kaccy*OP_l_12_c_4_r_*SK_ACCY(5) - Kaccy*OP_l_12_c_5_r_*SK_ACCY(7) - Kaccy*OP_l_12_c_6_r_*SK_ACCY(6) - 2*Kaccy*OP_l_12_c_23_r_*SK_ACCY(4) + Kaccy*OP_l_12_c_24_r_*SK_ACCY(7)); -Kfusion(13) = SK_ACCY(1)*(Kaccy*OP_l_13_c_1_r_*SK_ACCY(3) + Kaccy*OP_l_13_c_3_r_*SK_ACCY(2) + Kaccy*OP_l_13_c_4_r_*SK_ACCY(5) - Kaccy*OP_l_13_c_5_r_*SK_ACCY(7) - Kaccy*OP_l_13_c_6_r_*SK_ACCY(6) - 2*Kaccy*OP_l_13_c_23_r_*SK_ACCY(4) + Kaccy*OP_l_13_c_24_r_*SK_ACCY(7)); -Kfusion(14) = SK_ACCY(1)*(Kaccy*OP_l_14_c_1_r_*SK_ACCY(3) + Kaccy*OP_l_14_c_3_r_*SK_ACCY(2) + Kaccy*OP_l_14_c_4_r_*SK_ACCY(5) - Kaccy*OP_l_14_c_5_r_*SK_ACCY(7) - Kaccy*OP_l_14_c_6_r_*SK_ACCY(6) - 2*Kaccy*OP_l_14_c_23_r_*SK_ACCY(4) + Kaccy*OP_l_14_c_24_r_*SK_ACCY(7)); -Kfusion(15) = SK_ACCY(1)*(Kaccy*OP_l_15_c_1_r_*SK_ACCY(3) + Kaccy*OP_l_15_c_3_r_*SK_ACCY(2) + Kaccy*OP_l_15_c_4_r_*SK_ACCY(5) - Kaccy*OP_l_15_c_5_r_*SK_ACCY(7) - Kaccy*OP_l_15_c_6_r_*SK_ACCY(6) - 2*Kaccy*OP_l_15_c_23_r_*SK_ACCY(4) + Kaccy*OP_l_15_c_24_r_*SK_ACCY(7)); -Kfusion(16) = SK_ACCY(1)*(Kaccy*OP_l_16_c_1_r_*SK_ACCY(3) + Kaccy*OP_l_16_c_3_r_*SK_ACCY(2) + Kaccy*OP_l_16_c_4_r_*SK_ACCY(5) - Kaccy*OP_l_16_c_5_r_*SK_ACCY(7) - Kaccy*OP_l_16_c_6_r_*SK_ACCY(6) - 2*Kaccy*OP_l_16_c_23_r_*SK_ACCY(4) + Kaccy*OP_l_16_c_24_r_*SK_ACCY(7)); -Kfusion(17) = SK_ACCY(1)*(Kaccy*OP_l_17_c_1_r_*SK_ACCY(3) + Kaccy*OP_l_17_c_3_r_*SK_ACCY(2) + Kaccy*OP_l_17_c_4_r_*SK_ACCY(5) - Kaccy*OP_l_17_c_5_r_*SK_ACCY(7) - Kaccy*OP_l_17_c_6_r_*SK_ACCY(6) - 2*Kaccy*OP_l_17_c_23_r_*SK_ACCY(4) + Kaccy*OP_l_17_c_24_r_*SK_ACCY(7)); -Kfusion(18) = SK_ACCY(1)*(Kaccy*OP_l_18_c_1_r_*SK_ACCY(3) + Kaccy*OP_l_18_c_3_r_*SK_ACCY(2) + Kaccy*OP_l_18_c_4_r_*SK_ACCY(5) - Kaccy*OP_l_18_c_5_r_*SK_ACCY(7) - Kaccy*OP_l_18_c_6_r_*SK_ACCY(6) - 2*Kaccy*OP_l_18_c_23_r_*SK_ACCY(4) + Kaccy*OP_l_18_c_24_r_*SK_ACCY(7)); -Kfusion(19) = SK_ACCY(1)*(Kaccy*OP_l_19_c_1_r_*SK_ACCY(3) + Kaccy*OP_l_19_c_3_r_*SK_ACCY(2) + Kaccy*OP_l_19_c_4_r_*SK_ACCY(5) - Kaccy*OP_l_19_c_5_r_*SK_ACCY(7) - Kaccy*OP_l_19_c_6_r_*SK_ACCY(6) - 2*Kaccy*OP_l_19_c_23_r_*SK_ACCY(4) + Kaccy*OP_l_19_c_24_r_*SK_ACCY(7)); -Kfusion(20) = SK_ACCY(1)*(Kaccy*OP_l_20_c_1_r_*SK_ACCY(3) + Kaccy*OP_l_20_c_3_r_*SK_ACCY(2) + Kaccy*OP_l_20_c_4_r_*SK_ACCY(5) - Kaccy*OP_l_20_c_5_r_*SK_ACCY(7) - Kaccy*OP_l_20_c_6_r_*SK_ACCY(6) - 2*Kaccy*OP_l_20_c_23_r_*SK_ACCY(4) + Kaccy*OP_l_20_c_24_r_*SK_ACCY(7)); -Kfusion(21) = SK_ACCY(1)*(Kaccy*OP_l_21_c_1_r_*SK_ACCY(3) + Kaccy*OP_l_21_c_3_r_*SK_ACCY(2) + Kaccy*OP_l_21_c_4_r_*SK_ACCY(5) - Kaccy*OP_l_21_c_5_r_*SK_ACCY(7) - Kaccy*OP_l_21_c_6_r_*SK_ACCY(6) - 2*Kaccy*OP_l_21_c_23_r_*SK_ACCY(4) + Kaccy*OP_l_21_c_24_r_*SK_ACCY(7)); -Kfusion(22) = SK_ACCY(1)*(Kaccy*OP_l_22_c_1_r_*SK_ACCY(3) + Kaccy*OP_l_22_c_3_r_*SK_ACCY(2) + Kaccy*OP_l_22_c_4_r_*SK_ACCY(5) - Kaccy*OP_l_22_c_5_r_*SK_ACCY(7) - Kaccy*OP_l_22_c_6_r_*SK_ACCY(6) - 2*Kaccy*OP_l_22_c_23_r_*SK_ACCY(4) + Kaccy*OP_l_22_c_24_r_*SK_ACCY(7)); -Kfusion(23) = SK_ACCY(1)*(Kaccy*OP_l_23_c_1_r_*SK_ACCY(3) + Kaccy*OP_l_23_c_3_r_*SK_ACCY(2) + Kaccy*OP_l_23_c_4_r_*SK_ACCY(5) - Kaccy*OP_l_23_c_5_r_*SK_ACCY(7) - Kaccy*OP_l_23_c_6_r_*SK_ACCY(6) - 2*Kaccy*OP_l_23_c_23_r_*SK_ACCY(4) + Kaccy*OP_l_23_c_24_r_*SK_ACCY(7)); -Kfusion(24) = SK_ACCY(1)*(Kaccy*OP_l_24_c_1_r_*SK_ACCY(3) + Kaccy*OP_l_24_c_3_r_*SK_ACCY(2) + Kaccy*OP_l_24_c_4_r_*SK_ACCY(5) - Kaccy*OP_l_24_c_5_r_*SK_ACCY(7) - Kaccy*OP_l_24_c_6_r_*SK_ACCY(6) - 2*Kaccy*OP_l_24_c_23_r_*SK_ACCY(4) + Kaccy*OP_l_24_c_24_r_*SK_ACCY(7)); +Kfusion(1) = -SK_ACCY(1)*(Kaccy*OP_l_1_c_1_r_*SK_ACCY(4) + Kaccy*OP_l_1_c_2_r_*SK_ACCY(3) - Kaccy*OP_l_1_c_4_r_*SK_ACCY(2) + Kaccy*OP_l_1_c_3_r_*SK_ACCY(5) - Kaccy*OP_l_1_c_5_r_*SK_ACCY(6) + Kaccy*OP_l_1_c_6_r_*SK_ACCY(9) + Kaccy*OP_l_1_c_7_r_*SK_ACCY(8) + 2*Kaccy*OP_l_1_c_23_r_*SK_ACCY(7) - Kaccy*OP_l_1_c_24_r_*SK_ACCY(9)); +Kfusion(2) = -SK_ACCY(1)*(Kaccy*OP_l_2_c_1_r_*SK_ACCY(4) + Kaccy*OP_l_2_c_2_r_*SK_ACCY(3) - Kaccy*OP_l_2_c_4_r_*SK_ACCY(2) + Kaccy*OP_l_2_c_3_r_*SK_ACCY(5) - Kaccy*OP_l_2_c_5_r_*SK_ACCY(6) + Kaccy*OP_l_2_c_6_r_*SK_ACCY(9) + Kaccy*OP_l_2_c_7_r_*SK_ACCY(8) + 2*Kaccy*OP_l_2_c_23_r_*SK_ACCY(7) - Kaccy*OP_l_2_c_24_r_*SK_ACCY(9)); +Kfusion(3) = -SK_ACCY(1)*(Kaccy*OP_l_3_c_1_r_*SK_ACCY(4) + Kaccy*OP_l_3_c_2_r_*SK_ACCY(3) - Kaccy*OP_l_3_c_4_r_*SK_ACCY(2) + Kaccy*OP_l_3_c_3_r_*SK_ACCY(5) - Kaccy*OP_l_3_c_5_r_*SK_ACCY(6) + Kaccy*OP_l_3_c_6_r_*SK_ACCY(9) + Kaccy*OP_l_3_c_7_r_*SK_ACCY(8) + 2*Kaccy*OP_l_3_c_23_r_*SK_ACCY(7) - Kaccy*OP_l_3_c_24_r_*SK_ACCY(9)); +Kfusion(4) = -SK_ACCY(1)*(Kaccy*OP_l_4_c_1_r_*SK_ACCY(4) + Kaccy*OP_l_4_c_2_r_*SK_ACCY(3) - Kaccy*OP_l_4_c_4_r_*SK_ACCY(2) + Kaccy*OP_l_4_c_3_r_*SK_ACCY(5) - Kaccy*OP_l_4_c_5_r_*SK_ACCY(6) + Kaccy*OP_l_4_c_6_r_*SK_ACCY(9) + Kaccy*OP_l_4_c_7_r_*SK_ACCY(8) + 2*Kaccy*OP_l_4_c_23_r_*SK_ACCY(7) - Kaccy*OP_l_4_c_24_r_*SK_ACCY(9)); +Kfusion(5) = -SK_ACCY(1)*(Kaccy*OP_l_5_c_1_r_*SK_ACCY(4) + Kaccy*OP_l_5_c_2_r_*SK_ACCY(3) - Kaccy*OP_l_5_c_4_r_*SK_ACCY(2) + Kaccy*OP_l_5_c_3_r_*SK_ACCY(5) - Kaccy*OP_l_5_c_5_r_*SK_ACCY(6) + Kaccy*OP_l_5_c_6_r_*SK_ACCY(9) + Kaccy*OP_l_5_c_7_r_*SK_ACCY(8) + 2*Kaccy*OP_l_5_c_23_r_*SK_ACCY(7) - Kaccy*OP_l_5_c_24_r_*SK_ACCY(9)); +Kfusion(6) = -SK_ACCY(1)*(Kaccy*OP_l_6_c_1_r_*SK_ACCY(4) + Kaccy*OP_l_6_c_2_r_*SK_ACCY(3) - Kaccy*OP_l_6_c_4_r_*SK_ACCY(2) + Kaccy*OP_l_6_c_3_r_*SK_ACCY(5) - Kaccy*OP_l_6_c_5_r_*SK_ACCY(6) + Kaccy*OP_l_6_c_6_r_*SK_ACCY(9) + Kaccy*OP_l_6_c_7_r_*SK_ACCY(8) + 2*Kaccy*OP_l_6_c_23_r_*SK_ACCY(7) - Kaccy*OP_l_6_c_24_r_*SK_ACCY(9)); +Kfusion(7) = -SK_ACCY(1)*(Kaccy*OP_l_7_c_1_r_*SK_ACCY(4) + Kaccy*OP_l_7_c_2_r_*SK_ACCY(3) - Kaccy*OP_l_7_c_4_r_*SK_ACCY(2) + Kaccy*OP_l_7_c_3_r_*SK_ACCY(5) - Kaccy*OP_l_7_c_5_r_*SK_ACCY(6) + Kaccy*OP_l_7_c_6_r_*SK_ACCY(9) + Kaccy*OP_l_7_c_7_r_*SK_ACCY(8) + 2*Kaccy*OP_l_7_c_23_r_*SK_ACCY(7) - Kaccy*OP_l_7_c_24_r_*SK_ACCY(9)); +Kfusion(8) = -SK_ACCY(1)*(Kaccy*OP_l_8_c_1_r_*SK_ACCY(4) + Kaccy*OP_l_8_c_2_r_*SK_ACCY(3) - Kaccy*OP_l_8_c_4_r_*SK_ACCY(2) + Kaccy*OP_l_8_c_3_r_*SK_ACCY(5) - Kaccy*OP_l_8_c_5_r_*SK_ACCY(6) + Kaccy*OP_l_8_c_6_r_*SK_ACCY(9) + Kaccy*OP_l_8_c_7_r_*SK_ACCY(8) + 2*Kaccy*OP_l_8_c_23_r_*SK_ACCY(7) - Kaccy*OP_l_8_c_24_r_*SK_ACCY(9)); +Kfusion(9) = -SK_ACCY(1)*(Kaccy*OP_l_9_c_1_r_*SK_ACCY(4) + Kaccy*OP_l_9_c_2_r_*SK_ACCY(3) - Kaccy*OP_l_9_c_4_r_*SK_ACCY(2) + Kaccy*OP_l_9_c_3_r_*SK_ACCY(5) - Kaccy*OP_l_9_c_5_r_*SK_ACCY(6) + Kaccy*OP_l_9_c_6_r_*SK_ACCY(9) + Kaccy*OP_l_9_c_7_r_*SK_ACCY(8) + 2*Kaccy*OP_l_9_c_23_r_*SK_ACCY(7) - Kaccy*OP_l_9_c_24_r_*SK_ACCY(9)); +Kfusion(10) = -SK_ACCY(1)*(Kaccy*OP_l_10_c_1_r_*SK_ACCY(4) + Kaccy*OP_l_10_c_2_r_*SK_ACCY(3) - Kaccy*OP_l_10_c_4_r_*SK_ACCY(2) + Kaccy*OP_l_10_c_3_r_*SK_ACCY(5) - Kaccy*OP_l_10_c_5_r_*SK_ACCY(6) + Kaccy*OP_l_10_c_6_r_*SK_ACCY(9) + Kaccy*OP_l_10_c_7_r_*SK_ACCY(8) + 2*Kaccy*OP_l_10_c_23_r_*SK_ACCY(7) - Kaccy*OP_l_10_c_24_r_*SK_ACCY(9)); +Kfusion(11) = -SK_ACCY(1)*(Kaccy*OP_l_11_c_1_r_*SK_ACCY(4) + Kaccy*OP_l_11_c_2_r_*SK_ACCY(3) - Kaccy*OP_l_11_c_4_r_*SK_ACCY(2) + Kaccy*OP_l_11_c_3_r_*SK_ACCY(5) - Kaccy*OP_l_11_c_5_r_*SK_ACCY(6) + Kaccy*OP_l_11_c_6_r_*SK_ACCY(9) + Kaccy*OP_l_11_c_7_r_*SK_ACCY(8) + 2*Kaccy*OP_l_11_c_23_r_*SK_ACCY(7) - Kaccy*OP_l_11_c_24_r_*SK_ACCY(9)); +Kfusion(12) = -SK_ACCY(1)*(Kaccy*OP_l_12_c_1_r_*SK_ACCY(4) + Kaccy*OP_l_12_c_2_r_*SK_ACCY(3) - Kaccy*OP_l_12_c_4_r_*SK_ACCY(2) + Kaccy*OP_l_12_c_3_r_*SK_ACCY(5) - Kaccy*OP_l_12_c_5_r_*SK_ACCY(6) + Kaccy*OP_l_12_c_6_r_*SK_ACCY(9) + Kaccy*OP_l_12_c_7_r_*SK_ACCY(8) + 2*Kaccy*OP_l_12_c_23_r_*SK_ACCY(7) - Kaccy*OP_l_12_c_24_r_*SK_ACCY(9)); +Kfusion(13) = -SK_ACCY(1)*(Kaccy*OP_l_13_c_1_r_*SK_ACCY(4) + Kaccy*OP_l_13_c_2_r_*SK_ACCY(3) - Kaccy*OP_l_13_c_4_r_*SK_ACCY(2) + Kaccy*OP_l_13_c_3_r_*SK_ACCY(5) - Kaccy*OP_l_13_c_5_r_*SK_ACCY(6) + Kaccy*OP_l_13_c_6_r_*SK_ACCY(9) + Kaccy*OP_l_13_c_7_r_*SK_ACCY(8) + 2*Kaccy*OP_l_13_c_23_r_*SK_ACCY(7) - Kaccy*OP_l_13_c_24_r_*SK_ACCY(9)); +Kfusion(14) = -SK_ACCY(1)*(Kaccy*OP_l_14_c_1_r_*SK_ACCY(4) + Kaccy*OP_l_14_c_2_r_*SK_ACCY(3) - Kaccy*OP_l_14_c_4_r_*SK_ACCY(2) + Kaccy*OP_l_14_c_3_r_*SK_ACCY(5) - Kaccy*OP_l_14_c_5_r_*SK_ACCY(6) + Kaccy*OP_l_14_c_6_r_*SK_ACCY(9) + Kaccy*OP_l_14_c_7_r_*SK_ACCY(8) + 2*Kaccy*OP_l_14_c_23_r_*SK_ACCY(7) - Kaccy*OP_l_14_c_24_r_*SK_ACCY(9)); +Kfusion(15) = -SK_ACCY(1)*(Kaccy*OP_l_15_c_1_r_*SK_ACCY(4) + Kaccy*OP_l_15_c_2_r_*SK_ACCY(3) - Kaccy*OP_l_15_c_4_r_*SK_ACCY(2) + Kaccy*OP_l_15_c_3_r_*SK_ACCY(5) - Kaccy*OP_l_15_c_5_r_*SK_ACCY(6) + Kaccy*OP_l_15_c_6_r_*SK_ACCY(9) + Kaccy*OP_l_15_c_7_r_*SK_ACCY(8) + 2*Kaccy*OP_l_15_c_23_r_*SK_ACCY(7) - Kaccy*OP_l_15_c_24_r_*SK_ACCY(9)); +Kfusion(16) = -SK_ACCY(1)*(Kaccy*OP_l_16_c_1_r_*SK_ACCY(4) + Kaccy*OP_l_16_c_2_r_*SK_ACCY(3) - Kaccy*OP_l_16_c_4_r_*SK_ACCY(2) + Kaccy*OP_l_16_c_3_r_*SK_ACCY(5) - Kaccy*OP_l_16_c_5_r_*SK_ACCY(6) + Kaccy*OP_l_16_c_6_r_*SK_ACCY(9) + Kaccy*OP_l_16_c_7_r_*SK_ACCY(8) + 2*Kaccy*OP_l_16_c_23_r_*SK_ACCY(7) - Kaccy*OP_l_16_c_24_r_*SK_ACCY(9)); +Kfusion(17) = -SK_ACCY(1)*(Kaccy*OP_l_17_c_1_r_*SK_ACCY(4) + Kaccy*OP_l_17_c_2_r_*SK_ACCY(3) - Kaccy*OP_l_17_c_4_r_*SK_ACCY(2) + Kaccy*OP_l_17_c_3_r_*SK_ACCY(5) - Kaccy*OP_l_17_c_5_r_*SK_ACCY(6) + Kaccy*OP_l_17_c_6_r_*SK_ACCY(9) + Kaccy*OP_l_17_c_7_r_*SK_ACCY(8) + 2*Kaccy*OP_l_17_c_23_r_*SK_ACCY(7) - Kaccy*OP_l_17_c_24_r_*SK_ACCY(9)); +Kfusion(18) = -SK_ACCY(1)*(Kaccy*OP_l_18_c_1_r_*SK_ACCY(4) + Kaccy*OP_l_18_c_2_r_*SK_ACCY(3) - Kaccy*OP_l_18_c_4_r_*SK_ACCY(2) + Kaccy*OP_l_18_c_3_r_*SK_ACCY(5) - Kaccy*OP_l_18_c_5_r_*SK_ACCY(6) + Kaccy*OP_l_18_c_6_r_*SK_ACCY(9) + Kaccy*OP_l_18_c_7_r_*SK_ACCY(8) + 2*Kaccy*OP_l_18_c_23_r_*SK_ACCY(7) - Kaccy*OP_l_18_c_24_r_*SK_ACCY(9)); +Kfusion(19) = -SK_ACCY(1)*(Kaccy*OP_l_19_c_1_r_*SK_ACCY(4) + Kaccy*OP_l_19_c_2_r_*SK_ACCY(3) - Kaccy*OP_l_19_c_4_r_*SK_ACCY(2) + Kaccy*OP_l_19_c_3_r_*SK_ACCY(5) - Kaccy*OP_l_19_c_5_r_*SK_ACCY(6) + Kaccy*OP_l_19_c_6_r_*SK_ACCY(9) + Kaccy*OP_l_19_c_7_r_*SK_ACCY(8) + 2*Kaccy*OP_l_19_c_23_r_*SK_ACCY(7) - Kaccy*OP_l_19_c_24_r_*SK_ACCY(9)); +Kfusion(20) = -SK_ACCY(1)*(Kaccy*OP_l_20_c_1_r_*SK_ACCY(4) + Kaccy*OP_l_20_c_2_r_*SK_ACCY(3) - Kaccy*OP_l_20_c_4_r_*SK_ACCY(2) + Kaccy*OP_l_20_c_3_r_*SK_ACCY(5) - Kaccy*OP_l_20_c_5_r_*SK_ACCY(6) + Kaccy*OP_l_20_c_6_r_*SK_ACCY(9) + Kaccy*OP_l_20_c_7_r_*SK_ACCY(8) + 2*Kaccy*OP_l_20_c_23_r_*SK_ACCY(7) - Kaccy*OP_l_20_c_24_r_*SK_ACCY(9)); +Kfusion(21) = -SK_ACCY(1)*(Kaccy*OP_l_21_c_1_r_*SK_ACCY(4) + Kaccy*OP_l_21_c_2_r_*SK_ACCY(3) - Kaccy*OP_l_21_c_4_r_*SK_ACCY(2) + Kaccy*OP_l_21_c_3_r_*SK_ACCY(5) - Kaccy*OP_l_21_c_5_r_*SK_ACCY(6) + Kaccy*OP_l_21_c_6_r_*SK_ACCY(9) + Kaccy*OP_l_21_c_7_r_*SK_ACCY(8) + 2*Kaccy*OP_l_21_c_23_r_*SK_ACCY(7) - Kaccy*OP_l_21_c_24_r_*SK_ACCY(9)); +Kfusion(22) = -SK_ACCY(1)*(Kaccy*OP_l_22_c_1_r_*SK_ACCY(4) + Kaccy*OP_l_22_c_2_r_*SK_ACCY(3) - Kaccy*OP_l_22_c_4_r_*SK_ACCY(2) + Kaccy*OP_l_22_c_3_r_*SK_ACCY(5) - Kaccy*OP_l_22_c_5_r_*SK_ACCY(6) + Kaccy*OP_l_22_c_6_r_*SK_ACCY(9) + Kaccy*OP_l_22_c_7_r_*SK_ACCY(8) + 2*Kaccy*OP_l_22_c_23_r_*SK_ACCY(7) - Kaccy*OP_l_22_c_24_r_*SK_ACCY(9)); +Kfusion(23) = -SK_ACCY(1)*(Kaccy*OP_l_23_c_1_r_*SK_ACCY(4) + Kaccy*OP_l_23_c_2_r_*SK_ACCY(3) - Kaccy*OP_l_23_c_4_r_*SK_ACCY(2) + Kaccy*OP_l_23_c_3_r_*SK_ACCY(5) - Kaccy*OP_l_23_c_5_r_*SK_ACCY(6) + Kaccy*OP_l_23_c_6_r_*SK_ACCY(9) + Kaccy*OP_l_23_c_7_r_*SK_ACCY(8) + 2*Kaccy*OP_l_23_c_23_r_*SK_ACCY(7) - Kaccy*OP_l_23_c_24_r_*SK_ACCY(9)); +Kfusion(24) = -SK_ACCY(1)*(Kaccy*OP_l_24_c_1_r_*SK_ACCY(4) + Kaccy*OP_l_24_c_2_r_*SK_ACCY(3) - Kaccy*OP_l_24_c_4_r_*SK_ACCY(2) + Kaccy*OP_l_24_c_3_r_*SK_ACCY(5) - Kaccy*OP_l_24_c_5_r_*SK_ACCY(6) + Kaccy*OP_l_24_c_6_r_*SK_ACCY(9) + Kaccy*OP_l_24_c_7_r_*SK_ACCY(8) + 2*Kaccy*OP_l_24_c_23_r_*SK_ACCY(7) - Kaccy*OP_l_24_c_24_r_*SK_ACCY(9)); diff --git a/matlab/scripts/Inertial Nav EKF/calcH_YAW312.c b/matlab/scripts/Inertial Nav EKF/calcH_YAW312.c index 19868e1a17..399e544299 100644 --- a/matlab/scripts/Inertial Nav EKF/calcH_YAW312.c +++ b/matlab/scripts/Inertial Nav EKF/calcH_YAW312.c @@ -1,16 +1,17 @@ -t2 = q0*q0; -t3 = q1*q1; -t4 = q2*q2; -t5 = q3*q3; -t6 = t2-t3+t4-t5; -t7 = q0*q3*2.0; -t10 = q1*q2*2.0; -t8 = t7-t10; -t9 = 1.0/(t6*t6); -t11 = t8*t8; -t12 = t9*t11; +t9 = q0*q3; +t10 = q1*q2; +t2 = t9-t10; +t3 = q0*q0; +t4 = q1*q1; +t5 = q2*q2; +t6 = q3*q3; +t7 = t3-t4+t5-t6; +t8 = 1.0/(t7*t7); +t11 = t2*t2; +t12 = t8*t11*4.0; t13 = t12+1.0; t14 = 1.0/t13; -t15 = 1.0/t6; -A0[0][0] = -t14*(t15*(q0*q2*2.0+q1*q3*2.0)-t8*t9*(q0*q1*2.0-q2*q3*2.0)); -A0[0][2] = t14*(t15*(t2+t3-t4-t5)+t8*t9*(t7+t10)); +A0[0][0] = t8*t14*(q3*t3+q3*t4-q3*t5+q3*t6-q0*q1*q2*2.0)*-2.0; +A0[0][1] = t8*t14*(q2*t3+q2*t4+q2*t5-q2*t6-q0*q1*q3*2.0)*-2.0; +A0[0][2] = t8*t14*(-q1*t3+q1*t4+q1*t5+q1*t6-q0*q2*q3*2.0)*2.0; +A0[0][3] = t8*t14*(q0*t3-q0*t4+q0*t5+q0*t6-q1*q2*q3*2.0)*2.0; diff --git a/matlab/scripts/Inertial Nav EKF/calcH_YAW321.c b/matlab/scripts/Inertial Nav EKF/calcH_YAW321.c index 1e303866cb..90ad9098c2 100644 --- a/matlab/scripts/Inertial Nav EKF/calcH_YAW321.c +++ b/matlab/scripts/Inertial Nav EKF/calcH_YAW321.c @@ -1,16 +1,17 @@ -t2 = q0*q0; -t3 = q1*q1; -t4 = q2*q2; -t5 = q3*q3; -t6 = t2+t3-t4-t5; -t7 = q0*q3*2.0; -t8 = q1*q2*2.0; -t9 = t7+t8; -t10 = 1.0/(t6*t6); -t11 = t9*t9; -t12 = t10*t11; +t9 = q0*q3; +t10 = q1*q2; +t2 = t9+t10; +t3 = q0*q0; +t4 = q1*q1; +t5 = q2*q2; +t6 = q3*q3; +t7 = t3+t4-t5-t6; +t8 = 1.0/(t7*t7); +t11 = t2*t2; +t12 = t8*t11*4.0; t13 = t12+1.0; t14 = 1.0/t13; -t15 = 1.0/t6; -A0[0][1] = t14*(t15*(q0*q1*2.0-q2*q3*2.0)+t9*t10*(q0*q2*2.0+q1*q3*2.0)); -A0[0][2] = t14*(t15*(t2-t3+t4-t5)+t9*t10*(t7-t8)); +A0[0][0] = t8*t14*(q3*t3-q3*t4+q3*t5+q3*t6+q0*q1*q2*2.0)*-2.0; +A0[0][1] = t8*t14*(-q2*t3+q2*t4+q2*t5+q2*t6+q0*q1*q3*2.0)*-2.0; +A0[0][2] = t8*t14*(q1*t3+q1*t4+q1*t5-q1*t6+q0*q2*q3*2.0)*2.0; +A0[0][3] = t8*t14*(q0*t3+q0*t4-q0*t5+q0*t6+q1*q2*q3*2.0)*2.0; diff --git a/matlab/scripts/Inertial Nav EKF/temp1.mat b/matlab/scripts/Inertial Nav EKF/temp1.mat index 804be63a426f48efeae2bd63faea3f6c0fb917b9..28375e502221a8012cee924945ba108ddafa41d1 100644 GIT binary patch delta 782 zcmV+p1M&Qx3X=$sHxx}_c_1J$ATcyLGdDUhF(5K9F*cD=BavVRk#xI%-~s>uc%0Q# zOLE#k5FJsDD_O*qT*0fPSRiA`5w6NYA4VTELP7|EHZD-~*9eTj0#4u~9ud96G`+o9}yVWmC!YK9Z`FJ+-<~KK0J$X>S zzwc4+?%c(<`Ok@`-~IKc{8|;ORU}L56+f2zQl0ORgM5v_anzoOAA&fdi6imd_dJzH z9Elyn*}?wt;J=(y@xyug#J<<7N|&#lPU7ope?G zT5E`rfC83BaiRx*I@bhPxO7-Otjj9nPNNiyBTMnd>5Np-NOV}X?TE78_IWnCnwosJ;Nreu zdc93s9deA5dS-ZKYZB>pUQOkE;GGP10L22$)FO3XaE2J delta 1051 zcmV+$1mydZ2%ZX%Hxxl|av&fxATlyKG&VXlHy|=FF*cD=BavVRk#xI%>jMA)c%02u zOOm5T5Jigi%y{7r`wFx21Pjp;sHKVUqWFVAdE`}aY)$>F|?i}1&{ zzStyAPKGuohOQWLTQ;}3MNVddY=T;=!8DCc+RzB;-|R8tO%N3qVppxNYSjO^rEua zI$&5-@pNd=%8a>xQ=!?ixlGF;pyVV~LzQHryc&`>8pbNF!Q~u=$GN>c(D+d@GajpE z(iZphgpUsnT2kZ96o6Ymq-(#~1hG>^F>lkH-mD{VXya)k!QBkVc_WA^NoCs_r6m%D zhU?&ldY4AnU_cow32)RpC8@+*O$)b1!G2|lV0AZ%CRQkaq8jQPHv^u4pe`H<54j9A zK{;nIHKNeDAkCRcydwgTj_@tD*ppNxE@MHeamv*8iC{+5aHuez3U7ABQfFrMb_v&l z?U!4FVXShj*HeqrN;p$jVZsq}(0#nRemv5RCw}_U>&5Y;KqpP^V zlwZdRF);6cT8YnA@tCtoz(mvHcJtHQcVE{({m=TR|3B#;VU|VOLZ-baDg%z#8ezU$ z`q9AwYJ>{X#M{JK&e^8uyV(|#WSesUU>r_RnScWEcmt_oPbLNpef`Kt7CCV;A4cQl zoX0#xXcA%}2a9BFE<>;m{Z=V#Ol{<0-H;Vo3b;~#hZf=ZI2$e4P|@vFt^o-#JP?a8 zAf>%L5eut@<6sbp^Zmpw2AMvT8y*^ad%!GqJS81{EysDHP!n%e2uG$$)tu^nqfS*d z)O=aO&C0;|mM_^crAfP7PeRFzXhn-4LqnAGL^l$|wrPy%_@GEL^j4cW&8dHKI2S_y z*!2%~XO+GNrbX93G`CVv2-wE+%Se>@y_ZK5!)S=aA)U5+_H^kex%R*u7P&Ekqx2xE zQyReLW|iA*J{kh9RcEw#>YdB|^9%CwJ>EzDd5=$!FV7zY`E>sL*ZDsqU!I>9^64D0 V?h8K7PyS!_|JwO^!e0Xkb+Ewj6@>r* diff --git a/matlab/scripts/Inertial Nav EKF/temp2.mat b/matlab/scripts/Inertial Nav EKF/temp2.mat index bc29af7ab52906e763cf091f035e88ad5eec8030..698457b1fd12b6f7aa8c9f999f938b675ca6b9af 100644 GIT binary patch delta 2274 zcmV<82p#vC6M_?vHxx}_c_1J$ATcyLGdDUhG9WTAF*cD=BavVRk#u5zs0aW6c$}?Q z$5 z)zg2|JwwmHfsj6hzQ~BkOyw5&<>7Gn>Q{%u&!74iPrN<6m!G}xS5N%?i}(7Synf+_ zSK{Rz|MH37fAKN?^=IOLKj6Ln&3A3DUVJVm&G?Y#pTGQ==hrX(ul}vyeCPX)KZkqZ z?p5OSLDwbyx8J_R|K*eTkNv&pZ+G_;d7aSbXzM z+PAea_V*_H&DV*vS9}T2JY+*&F_nOEWZ_dc8kUtq>@ZtLL$Ir>WZ0K`nfWJ4c(g%{ z4nwFdXk#NVR7R)U6%*a=C|(SX-J@v{z>LWyp`Rh{#2m%so*T7D!@5B3W9kv&jdyM% zh6(^cCo#28Xw6!GM42j!2 z{(wCli2*AZ;c6MYokrvh(|~y2$*_!xpn`i*UsGLQGVGKc6Xtw>Ord_!ikvy<~~&x zL?PEuAavShhP1P(4BPc0G_SFy)k#znKJ87=ZMCtgtWu#Y!N7;aVimAPIi~{Vth&Zj zcO}3V5s;>PlXSQaoMI8ciY*&TuIZ4h_wI6b;(-UPgoY<%mF_1o!U;nQIZbQ(^d%4zMhJ>~B_bA%j#Z z<{jjHATA(m;>v0jRW`&kM2)%CUfLcK-8l=<2G(&}TFo9E)xf3dnM6wLIP-$d0{zj3 z@19>qyCaz0!w)rmT29RtG0o9h+9Y;`>sX|cPiWYGtezKx%1;q}JKbUR2ffb0ZjTB{tL<-ubB9?iHtcJcfy9m^ySPo7rT7gVK zcucqHy%`12aNBf!`j zWHJqZ4Ii7;dSjgPwcofa;w|ljj`z@OR!cwV!ch@~ts|FSQ4wj10BeH~cj}r;wvxSaIdR0`&%tvtp2^bPcUgcwm*k^&QE@#W88FBwN9M zebH<5VBX2wloQ*0SE5~|*@Y%2b&MwCLV3Ih0d|XzV^v!LNJ?k_2(T*eiiNfeglAeC zB$OfE-6E<5As?fzi>ArC*HMIa!%z+8b8X<~AQ^3hPx3})qg;hkb*-ex7BLe)N@M~h zsWxqW>Xk7%IJh|X$Jp4J&~*UXZd=BGA+Bi?0hv2+#3^z^T^tfcf_8ltLO7C4YvvmY z+Yx0SjFrZDpr~B}<6={A20)efJRYCxoW_seSn!NiWclo~3@I#!D5yWSkhkA4ho zAG^V%>TyNdJF>l7kLE5n!(KgVz5=cl!pP4V=uk&dTi*ljWun>u%V4JNE4u6QQ01~| ze{Nt~@lCu2BV^BcPN{2LG`)y_*kzwgh*(Q*Ix2|ByMCG}xr9MNfkbJQ;7rc?9&+_*rWl@x&}nY#GFehE*l z#`gOIzK$cs0P19^iq1N&=i0}PN~$U;j+efGX_z-uHNXI3pR!6R+qDaS$-FGUkY3a? zylvPFCzl6_#hK6~d8N7w#q3lUIqAGvnsHhvv$g&$2XTdHPKSOW`gO{!nHjdhVT zp5i!N-yy`Jjv!y^F^kR|3->!*Wt@RxrY}Kwt|z(I^*xv@3dKDSBBCUGbOa^!aYoh2 zac$60>39q=X@jfs8UvMoi88*cAOyk15sD$9n;1L+~?Q=%QWEF^If6rB26E z>=0ZQ`H?J8`}%w?d_nTdU{nE`luL0;nfa{W)^#2RaY-@Mk3i+9uO8_sWOnNZtkR|| zoy-PUn~g$|bJ#}q)VYtS=F+L_HiNmJLG~EHj7OpkAB6$kH*wm3#YnG@Lg~yDMb`2h zLPXD0U_sK&W7$o5vSTys?R1U$-Nii&Jv&;T9sR!EXmRA4uX)9bArTV6MaWQcva07@%1lS_m~L4>S83~<;>OTHmNIhrE-20bZtE&SCFu<^TWy delta 2297 zcmVzW(~7|J%>_f8h6j`gh;8y?M3K4!ZRr&hI~o^V?VZH~*IJzO#M7FWrm9E%W-Q zZL|JQe|q)*$FDy6f9&r)e)ofMyx9MJ_v7>a+YjvDzUtn-GV)~OmH+(YzrMDApkX(x z_3rcZ_DA%e(wooVH=n^jwEI9`eIkGN%a8MX_p1MNfByN!$2h-#dBxAs-{bO|Z$N*q zt+6kf{10De@-`l;aXun0A@NfcIj55w4NxR_S40?QXKzXF?b2GVR#a`|S%!H*(>@6B z^g3tr)Q=M-bl1maw)U4(uF4phdcO+JP(>>BzH8GnNCPOq4t+ z=#>sA$&MP&r$)=bgHXL}5`K~3>7m}0i6V}EiG*Oir}k2WI;mzi_Jk%Xrke!OGxt+a zh9Dfx19IdT+5#{xsH4~LS0u(yS!&xVWe{<$=m$a)1!56@u_kUpzOIW&<3M_->|63+ z(E&)24QC4j?k=e|$#!PXdyS}_rHot5xUj8#C?Eam7NNzntrS>|fah>!q%otcS|;Ce z6yNfNsL5kWG{`K4q|_RWz;|3bkAaxEa^5Kv@40wF;<`x7TjMn8)m&Nq>bPpr#dj?r z^J`}4sW&cvoxrseiKBKq26UOYNM_5Bi*%Egie!;Pv%Eo^lwrt1R!|K5)#sN^YQ;pzp|2iS|4bP+ib8Ac`ZVU%gDhC{39gKFdLWb=iX# z2|0w~YS5}R3(^O#9|U7rIL6VArJBQ0D4&b-z3+>E1%u7vfwb#_$TD(gMrDvwM%yo} zLX&lxmAB?N=gZMx5$U<#bVtAoB#;b>8@|rLm!56dt%%WzRLrT5!@1`(1sBFfgxa|esU&L> z50Hs}yPWZ^kuR14+Z8`(tcu5okySn?i6>jS@8_ZNp|eRg*h0X)sdn95_QAntO)Bk+1~F+U16g{Lc6Rv+dC!>bGtnpg;qdIy(v zsd(_!VDaKCFsJ2U4uxdj8DkpR{dB}085=@knzp@=4QH$@ITZDsJ0Xw{fto#UtkKjN z5)Y^KIH+p*s)pQpzAdxiX7YZFZZWif8Hu~)Aa5Eh9X!LNv#<%gIU1!qZ8w{F0x^0U zxE5keid|?)ZbMdQ>offjyZr_2gB-fFAw*S$;mOa_ zR@Sw#AkC3vbdkM!H9Q&mdDPeqy3I}-vD_4;@)T^`NH+t(9i+dxY_;HX`MjNfa*wG# zm!aO?j!zoPH4_^@_v+~A48;%wV{hmboQ)cxHA(EA$5RtyMrTG;!h%^tK}Y3!Kf0({ z6U~&Z(|M|uc4!)_9hovMuYOBdF1)|d2RJ@D3~stD{W#?SUJ&e1#%d z2l?8=T`=Nhi6jEkQVy;aN|R%MWNN4<@+2?!bnI942A~iW%-q-%tiZaG@L5x>wo9wF zwA?%K*k;+3SOAd$9ZYvX6WU?hHlsUtOtSRUCfIlM8ZBjLaJVoZhLsS(@pxUN$HbQ% z9E_Nng1euqn_;Q4+(6HVOa*)x_!Y``4+gZsW|F-ZHy+TOCA&$o0#RLm44-RAB6A{2 zBzDXck{Soj*V9p#9F{*54Z!;A!mz>qaZ>Fq88(ca_6xL6WMMlzuDF`8b9~X+$GOZ$ zAL8((W!YR4z?KVss?la@M6ekK=4FJR6CR=DKs#!Qp&Ym7em zxJ@}|85HAVD{#j)CX!Y0d&L5Kjd>XDATmj|PZyeorjdjiA8Xiu+5#bbW$__Q8t38j zu~6ZChUd#%5NIgQEJ}+O++-*|PDlRwd}4H}?}@GJ@UVPH^ObcVgGS)Bt zVP1LS{IKC$h)j?@O8sE=fL5Og#+sYGK5rI)HnUO%m4Yq%m^0&eC0$>vFbN*&28vaq z?XQy3scJj$Y6SMYQuDwA6?im6X;2nkVAv^UDwsRg_G4aD)b8MnHq2<2sw12Dyig5{ z7)wnvQ2y<=U;puAefUzh{#f1ocK4rkGqd~YdVjb3e!c(y_W#T7r~fPd?)!DS|6Rb3 T{}t)K^#8y9S6=8}+iYbDqlAfU diff --git a/matlab/scripts/Inertial Nav EKF/temp3.mat b/matlab/scripts/Inertial Nav EKF/temp3.mat index d50def9d24bb0ebae83ce7bffe4d2405dd6c2d68..24e0cc9cf4ddc4966f1d59bca6987f20beb5aeb5 100644 GIT binary patch delta 2283 zcmVtpl*g1+yJoxdEt3#sTX#+TrSV$p*(C_p67We+bfnFfg^Af#0fYCN1$H! z-@K;j1{Q=AN_~+Lk&%jY`peHxr_*nKc{=^{HGcZi&raXSPu}pmm;U`1-;5vR{Tn{L zyD1;==P%WN@iG4W55#|etKZl^`Fif%n~!qV%y092`kg$#e)E6#&+(J5eLvt=xhKA; z6K4$iJ{iCI>Mi~+KmQp2alLQwC*P~%ga6-7Kfdojf6xE@o9+FZLLc`1rhj9`&_?*DLgZF6B}ICUb$${cPG!4qc|zW=!Ex-$nDG6jkm^qA+wp zgHBVZJ<;}oz)%&PjXQR8d*-H?{N;$2rvPSbE(+rc@n@-!F#cRAEI20m(FAllI$iTr zbqN66ay`-|K};xr%Ws~6tcwJ)k$m6vDg-bH8>w?*5s5A;cyQa1fwgfvv7A&5W7Q?j z^N>F{I!qnpa0mje&#Pa~z*tlYMWcQj&H;WypfG#bB}hRP=sDKn>Nl#Eo(2rem@j9A zjOA>KU6CzdHNeP)Hm1v2f`}+77lp-Pm02^uj96n6m>b4_T`!~&qfT>am~5fMII`qK z!h3STt{T(=ZPtON> z_+rT==`})sA6|cEAW9*p9*d9$J9z&n{PGS}BO_Ki6yY>g>K^1BssZlV<<19E`D{ar zRA?Z@4q=;;m48mvBIa35k}Xs}neFVL;e zQ_OlbosLaS^Yt@0dDx0TBoUc4m?C;vTyVL%`ue>^w&q#jua>8k4fr|?i%MNQbEe$f zR*)?b!wumEGXV%O0$G;JTv`Gsj^Vf@i^9>@g-BJ5OQ*^=%_fY4wb6jb!usndhKUm{ zc&bBx!Ie(yP2e9KGj4oF_)o7u<~kKnfPOvjIsF^}*fs#&7(1_9%&xP!?xXV24pD43=@gp)!LBJ}hIj3cRbV9g@;-Z`Cu7;cxm|?^94nPhbchId4?Gfw2IAI*LYnvE< z2N-ea;RRdZuuER07pQWihN35K8M<;+>Q}Z<^*YePkoW8B3hZ~}uIHRl@3&);wdOJ_ zGmG;;U}MQWB_b-hdFPfFCL4%3kqWu6yk{sU^twZUXPtT73!2>!Yw_HnL8>B=&Mx>8 zq=@tlV@dBaa;8~LpW4dNd<^i~ww;OP(hY8F z0ZJtBJtBG=Rip+g)5>-2$I(fzoA(5eoe0)taCRaiF_A_In^r=N(QGD19spbAmPMl? zcAd*vS zU?;i6$>Fd8daa8(f~6kId-8Sjj(ML}Vw{C=)Tn@!c<$EhhSmF? zg6LZjM~Y?+c#I)oXM&qSM>LvU$!)|{DPAVv;G8yg?~=J9TDKD^9`S8!ZxlCivg4Ot z%t3q-JCZu3jK0xk-{V-Zljpq?^bwk5%3XW!=iC>JPZ`AkdN9o3|P-7nLab93{BYiuei`R!q;O!-$qD-I-(h=A( zC>IWB$N}_FFH#&QW>F%4RwKTT7CD_CFq)Q+E{r0^?#Xew=;C=@Wp8Z_dk9BIqP2(^ zBI5PUoV_#fSo<RK9cr$;4Nne;BW@E5>hy9faU3-DBzHJVp9o>J7}^b_S^K4zdv&D(n$K&}|ccr$dUkx45O!h04f= za0JrAE-RI~Q;BF^I`88^rootSZ9)JA9VR>vO!z<%;-w+&8C;PEtz$we0A4wT@--j# z_~{$|{9J>UlYKJ2-R!8JduT+>v4-X72I4sP*ky`&5e~mM!?RAYm`v{kz|`k9RDnI= z$%~75_rQOWalB63fM|zPo@W8bn6y zm9IOWOTkjT<)EdZ0LCw)IJ04+z0ooKg%OPCAo)`Q>ka|B(lN z;HN*vkKdpEogY)D|IF)8r+?-3|L^!ep8oT@#6A5hKX<=Q`0-sL{Fn9r*LTSW`3H8n FV3`%)ZZ`k` delta 2291 zcmV57J0x3H$giN26da0u(XD|7nx%n;X6cIp8ff+%8aVmrNAM%~aeQ+4QG9gI z%s-xyJd%BIMr34Ul9{!TS@qS|yWQ@)KkRnDeabJM{N?UF{pLk~_2hqk^)oKNJ6df#2KTy!-a*#Yf|G>qDMzKFRaP7ynoPmT%tqzSW=8-3eJ4 zyM55MasT6wFY$l-{m1x^+~dE3%p{evdF_UURHw_yprW* z+#~r*f^bFBkogwlY`ntwZAvHYykMt&p95=P&#bXG8{=Sq&K5D84zeb&3C^u#)pW}B zy!E)KBa#m84X}>any8ybuQ|*0lxgu$PcfNx;5J*vox-qeq^TeJQ8c(&hE)II>^ZJ-D$FO>*k|& zOg22P!rnQ5nqr++NojB+(di3j61BgTMK|mtnap`AkvE8yE|l-n{z+uTtfkp?S!~YR zfOv(Ne84B+U^SJiV}W7X`QGORU@3vQ=AIY9 zbeWBcj-ZKlX5=VSXe3s`d=L2}K8fRXsq}Fue*rBIURw zx}K{Ef(0$J;OU*aU9_g9N#l&qU^;R9O^YT7@o)zbr{+u+C`>2lq^zaHO*dBWF~rTI zxf2yNjOx>1dBUS=?u5H6bK=}&vu#R$irfr5TK36MR$`2)QbP|nFl^H3@o*$>%%~>n zk`B*9g~>vTp(IV3m!_-c6N>u?#zEmcb+@(hDN!CxW=4t=gh`BYYX` zE2m(ZGrpQ@LCRMhtf z<;;iJa(O%0pZIhhm;f*H%-84urv}{K5dEeb9ZqPT(@f!=9d13lI>Zmaz05dN@wqPqR*3@f5 z3up-7wFgSVVOxdX%tuec*fq0%`5L{RjsC$L<@^AJ(%>iwV*{l1r+lT3v!>pt>rsZ$ zsS4G@V(6mSy0?iAPq3We4K&2mk&S!;pxtSLZ)r|#Ro|4XyAq{@QN*?%R$NM|;J$c| zftR~ybJ0qa48olUbKwTAq0Rbz=vey!R0|XCL?YTHUt8m|mLYtB=uWwRT$Tp&61j#j z;tt6Vfg$4OLE>V2iq}z$@8UGWZ9w^t1|*nsBtElOLBb-Kt;3#;cAD!RE^5+h1(j5Xh?FvPJ~1oj9Rl)79b#I$tIT&Iai@_A^4Us?5u3Z=iNG*D+2KYpHQ_3t!B?dxij^2Ma)n8LsZ$^zAlOp zv3D{zqD{RJ+aRJi-h|wY5WakyT4HtCj0cB(fUq%z)rT7yEIq}4ByEItMueqP4gsHq zT0LuHyLE^1&KX{QJK=K8JBK5nYY)y{{g$j;OEPoVCu&)ddT$8kFvEQm1Ymg@gP=Lv z_*^FG^en_h0j+WNF8P81818BP*Gr3>mr)2RkhM+)SEvqoA!c-n&d z_-v%u{si&brMudH6#3j4ZF4;mni={81qUsNEothz468Sm(8EUUC|OI6R798kF!;Hyyr zxPtQ#>*)q4&JP!(ACdILVx{DE-cpYAH4>LjVhP8P4T$DWAaw@5S-DILs}`ks;Bk2z z&K&ve_wVuGTb%k!IQjMNKXEd>`*nQ3+x-;Z|G(q^y!-X{iMRVHPWRp={P;eR{>%9P N>-*#_{R^)@U(q+frvLx|