From 8c41772584397f1baafd6ebedd3f216ca515652c Mon Sep 17 00:00:00 2001 From: Nicholas Sherlock Date: Mon, 8 Dec 2014 22:06:57 +1300 Subject: [PATCH 01/24] Add Blackbox 0.1.0 --- Makefile | 3 +- README.md | 86 +- obj/cleanflight_CC3D.bin | Bin 79948 -> 0 bytes obj/cleanflight_CC3D.hex | 5002 ---------- obj/cleanflight_CJMCU.hex | 3927 -------- obj/cleanflight_NAZE.hex | 11460 ++++++++++++----------- src/main/blackbox/blackbox.c | 756 ++ src/main/blackbox/blackbox.h | 36 + src/main/blackbox/blackbox_fielddefs.h | 54 + src/main/config/config.h | 3 +- src/main/flight/flight.c | 17 + src/main/flight/flight.h | 2 + src/main/flight/mixer.c | 2 +- src/main/io/serial.c | 8 +- src/main/io/serial.h | 9 +- src/main/io/serial_cli.c | 3 +- src/main/main.c | 5 + src/main/mw.c | 26 + src/main/target/NAZE/target.h | 1 + src/main/target/NAZE32PRO/target.h | 1 + 20 files changed, 6797 insertions(+), 14604 deletions(-) delete mode 100755 obj/cleanflight_CC3D.bin delete mode 100644 obj/cleanflight_CC3D.hex delete mode 100644 obj/cleanflight_CJMCU.hex create mode 100644 src/main/blackbox/blackbox.c create mode 100644 src/main/blackbox/blackbox.h create mode 100644 src/main/blackbox/blackbox_fielddefs.h diff --git a/Makefile b/Makefile index e2335be512..b05e838b2b 100644 --- a/Makefile +++ b/Makefile @@ -212,7 +212,8 @@ HIGHEND_SRC = flight/autotune.c \ telemetry/msp.c \ telemetry/smartport.c \ sensors/sonar.c \ - sensors/barometer.c + sensors/barometer.c \ + blackbox/blackbox.c NAZE_SRC = startup_stm32f10x_md_gcc.S \ drivers/accgyro_adxl345.c \ diff --git a/README.md b/README.md index 21a3768cb3..9ddd494400 100644 --- a/README.md +++ b/README.md @@ -1,66 +1,54 @@ -# Cleanflight +# Blackbox flight data recorder port for Cleanflight -Clean-code version of baseflight flight-controller - flight controllers are used to fly multi-rotor craft and fixed wing craft. +![Rendered flight log frame](http://i.imgur.com/FBphB8c.jpg) -This fork differs from baseflight in that it attempts to use modern software development practices which result in: +WARNING - This firmware is experimental, and may cause your craft to suddenly fall out of the sky. This port to +Cleanflight has only had 3 test flights! No warranty is offered: if your craft breaks, you get to keep both pieces. -1. greater reliability through code robustness and automated testing. -2. easier maintainance through code cleanliness. -3. easier to develop new features. -4. easier to re-use code though code de-coupling and modularisation. +## Introduction +This is a modified version of Cleanflight which adds a flight data recorder function ("Blackbox"). Flight data +information is transmitted over the flight controller's serial port on every control loop iteration to an external +logging device to be recorded. -The MultiWii software, from which baseflight originated, violates many good software development best-practices. Hopefully this fork will go some way to address them. If you see any bad code in this fork please immediately raise an issue so it can be fixed, or better yet submit a pull request. +After your flight, you can process the resulting logs on your computer to either turn them into CSV (comma-separated +values) or render your flight log as a video. -## Additional Features +This is a port of my Blackbox feature for Baseflight, so please follow the instructions there for usage details (just +use the Cleanflight firmware from this repository instead of the Baseflight firmware): -Cleanflight also has additional features not found in baseflight. Since the primary maintainer of baseflight also sells hardware there is no incentive for baseflight to support the target platforms and features that Cleanflight now provides. +https://github.com/thenickdude/blackbox -For a list of features, changes and some discussion please review the thread on MultiWii forums and consult the documenation. +Instructions which are specific to Cleanflight are included here. -http://www.multiwii.com/forum/viewtopic.php?f=23&t=5149 +## Installation of firmware +Before installing the new firmware onto your Naze32, back up your configuration: Connect to your flight controller +using the [Cleanflight Configurator][] , open up the CLI tab and enter "dump" into the box at the bottom and press enter. +Copy all of the text that results and paste it into a text document somewhere for safe-keeping. +Click the disconnect button, then on the main page choose the Firmware Flasher option. Tick the box for "Full Chip +Erase" (warning, this will erase all your settings!). Click the "Load firmware (local)" button, and select the file `cleanflight_NAZE.hex` +from the `obj/` directory. Click the "Flash Firmware" button and wait for it to complete. -## Documentation +Now you need to reload your configuration: Go to the CLI tab and paste in the dump that you saved earlier and press +enter, it should execute and restore your settings. -There is some documentation here: https://github.com/hydra/cleanflight/tree/master/docs +Before you leave the CLI tab, enable the Blackbox feature by typing in `feature BLACKBOX` and pressing enter. You also +need to assign the Blackbox to one of [your serial ports][]. Because it requires a 115200 baud port, the best choice on the +Naze32 to use is serial_port_1, which is the two-pin Tx/Rx header in the centre of the board. -If what you need is not covered then refer to the baseflight documentation. If you still can't find what you need then visit the #cleanflight on the Freenode IRC network +Use `set serial_port_1_scenario=10` to switch the port to Blackbox-only, or `set serial_port_1_scenario=11` to switch it +to MSP, CLI, Blackbox and GPS Passthrough (probably the most useful configuration, since this is the port connected to +USB and you'll still want to access the CLI over it). -## IRC Support and Developers Channel +Enter `save`. Your configuration should be saved and the flight controller will reboot. You're ready to go! -There's a dedicated IRC channel here: +If you ever need to disable the Blackbox (say, for example, to switch to using the serial port for an OSD instead), you +can either reflash the stock firmware using the Configurator, or you can just turn off the Blackbox feature +by entering `feature -BLACKBOX` on the CLI tab. -irc://irc.freenode.net/#cleanflight +[your serial ports]: https://github.com/cleanflight/cleanflight/blob/master/docs/Serial.md +[Cleanflight Configurator]: https://chrome.google.com/webstore/detail/cleanflight-configurator/enacoimjcgeinfnnnpajinjgmkahmfgb?hl=en -If you are using windows and don't have an IRC client installed then take a look at HydraIRC - here: http://hydrairc.com/ +## License -## Videos - - -There is a dedicated Cleanflight youtube channel which has progress update videos, flight demonstrations, instrutions and other related videos. - -https://www.youtube.com/playlist?list=PL6H1fAj_XUNVBEcp8vbMH2DrllZAGWkt8 - -Please subscribe and '+1' the videos if you find them useful. - -## Configuration Tool - -To configure Cleanflight you should use the Cleanlight-configurator GUI tool (Windows/OSX/Linux) that can be found here: - -https://chrome.google.com/webstore/detail/cleanflight-configurator/enacoimjcgeinfnnnpajinjgmkahmfgb - -The source for it is here: - -https://github.com/hydra/cleanflight-configurator - -## Contributing - -Before making any contributions, take a note of the https://github.com/multiwii/baseflight/wiki/CodingStyle - -For this fork it is also advised to read about clean code, here are some useful links: - -* http://cleancoders.com/ -* http://en.wikipedia.org/wiki/SOLID_%28object-oriented_design%29 -* http://en.wikipedia.org/wiki/Code_smell -* http://en.wikipedia.org/wiki/Code_refactoring -* http://www.amazon.co.uk/Working-Effectively-Legacy-Robert-Martin/dp/0131177052 +This project is licensed under GPLv3. \ No newline at end of file diff --git a/obj/cleanflight_CC3D.bin b/obj/cleanflight_CC3D.bin deleted file mode 100755 index 00521ab7c9b6b18fa7149aef3d0874bceab566a4..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 79948 zcmb@u4R}*U_Aoy8Bgsvgw&@3urUmi=(l$lX7Ufe-lX7Wu3*~FIe5ff!y#-tXxNHE0 z^g}2JZlQ>!RktduDC*Kcm8xt}cvoD}O%(hU&?ShwMY_A*Kuf1hll;%5#dY`n{om*J zKF`}elbJbl=Ht#ibIzGFXD*tD^e+!0ZcZ3+tzAPgNt1y7h%wot^E(2|9G5#%RY>`AOTGLK`Ir6%97t6 zF*%W`!l{tXVr{!zdSp-`{eV@{g$Ocn4a?^!8&nOYJ%N;b}|ceV3la^ai*+tnnkBvq@|*PcZ#O*v{X1S zjeom{maGF8Fl(6#^nliX3MrZNGEQlJy_jh_8VcTg6=r$UdT;3Fje`O;eTh>tK7&nq zh4Cfl3V3Ep8VvomD3@RTm|!W8BcD7Ia`0YoRyqWhk(YXG<6 z&eR5Vhne@7w6Lx{>(j_@g|0zwn#QL$l<_bx3rFtHXc+O_sOLsM$4cX)moT#2;~=em z2C0Q2b*HJvW!l$)43xnHE!eM9riIQu;#~rDZ=4m@gvk!;yTR#SdCP0)aZv@=<@bNR zJd>wP%5FsMbffG|KC|P&jOt~7b}O_0;k~0+bK#YsN-po_<)xA$Az?rsdC%&{>XSLw z6B6cLSIEC`#s}zb+rO1+ekx5UmzzfvPwu2+OgUaktTowA8L`Ftgpp9;*J@Ro

?WE^Gnku?W#xGxwzNz(s7 z0fZ=P&J>DMo7J6)pY@jbQ*Ut<@qzfCmHc_-?Qwjz90f-6tVNSa`ON&ruGfVo(bnTx z*W`p)qUfQRgZO~h;!r9==Nf>ourQA=IvT_jNDcV+i0|XSp@N7QTvPxB+I-F`j-Z*Jj_}St(>D%zGQaS%#|1}gR)r5Bf4Vj=_|3s-d=)>BkCT2M zp2pVzEKYheJfCOlt&sX%xR{s6QZ39Fj>D(HHyYTBv-+|6+d$iG9al#LeFH)}gWgE|6A| zCaln#oM}P}U*XgWSAlN{{j6yRtlWH&(ld6p9%iBhndFm9uFJTnWt>kriT0sMR{z*Q zzG#Zg)bs%AAhb{9&0Pb}&a9(BqCm)lfGm_X1LD?V#O;0_arGZpM;nux>;GKSLHb!5 zXXlHak`#%9HO#g}r2SR znXW!U2N;<5@9~D1+)zz;Vs4uLrbyja15)KCjJpMs_wqVUgI^do{JxAwNm0dhKWEA> zUn#7dn=Ur=t6_DW4T;e5=)nZ(#Q|7Zb#coJDnR};uw1Ap)p`i@c!=W5i{hjY z2c3Z5KDe}4|7a&BEkr{P0%S0>OnA_tb*|dDY;KB6(S3?p`s7kazVooS{LyB4VFzW( zcPgb5(S$?DkP7m23SPA_!A$u$Gwr89w%IL*#d$@iZd&Qx_#XYKo1Ov)$-D7=`rY_m z4Z!nq#oZvCPTf42hjKwyk(5!}K^Z`HK^ob1V=LemXc*vE6yQ$N@4-is+He4Ubkjra z#x{^%JZi&#(SXc%y^V`dC;K)o)UfCCg`@bQ1t6Bz-hr*Pz^O>O4eN3z7Qc-hmglfB zw-$>QWU9rL7Qyu*j24+wJ7^O!(XCXz0yz6u_>3hc^&9@g%MXBFvMv`ZEe*B{-s%2* zP^%WNvWyVMx<^j3N*`9CJD$Bl`1&rO&6j~zvw&6!ogN1|-BDLJ6I7-GA`3bJh9E=e zd=S!vzpJig6d-E`e`3nEyUqa&1it=z2pO;*$T}eFB3_R4ZH^c5OjLTE($d|WT-#bV zhRU?wxToqxd>_heU4S|CPU&$Qk|qPhIt+Ou1~CI3dwGT3JYsh4c(a zGmuWJ(zMDT9#NI9qRlUYUcmTKCI@rJ1Sm7t@gkmPc@Y=5?rVkFa!qJ|ImjufNsS$> z=|yaFO^HFrwzJciECM^!dST3`UMfr33FFeV20f)ny5`wdRApP>zZ#&;GC#mAHO0@^ zO8l3g{n`E(@x7KAh$gtiT72Af8lQF&Z3=WL z4Q)z!gJ@E<*yVccvDY8#dh9el;;O~(LU_-`?4_g$VWuf}Gnt?1JS*Wr3qOsgjB+V% zaD}j<_%yud6~bxkgI3R4EWB#8Qpya9jFcJ-IaETEoj6*|4GdDmtke;s(-tKt`^!&jf-E84?{9;}%eI673 z^UHUh_?u3UcQXl%*AmgQ5VV5kZk_w&opg|*buP|V@k?ZAT+DRKIgpznl-cDwEM8(~ zo|_Vo=1?4BkrlKi>&7C)tp-|u5Z2H#h(Fy9dsKjtJ;+l4BYM>15bshTeJ!l5!@^q* zru!470c%cvg;PD%7@Z_?(&s~WJUZ+1i@$T^Q%pCVU@uJkjJlhQ>t+`>>183)pA~pf zXuznxJxC??UU-pc_}rOU@}Nfk&x`kCjk;8Na(Nsiba6T3CYRFgi zb3uyZAsy&Sn8f&XZnBG{13I^n>?U2TbUeDfxK5}m+Tl2j-^!z4_X~W8I*kt{AH?1~ zpzXZV__*;j{?J%eT(*GDA7>u$djuWu*)a-hu*$PVK*k2F&1KC`bY8y3NDPxb?_orl zOJSGF`D^h>Bhkn|hL%1us!d#ghIIoR6@G_c3P_!TJZjMBDbuRr(w-}M3ZTE0K=Ws4 zp!vMQ0A+g2Ar=!1nMomagkUw$a-NJcPCAH}gEZ)cUzKz%8Yg`-fJ{zD<2*Ls3L||; zuw;-nN?~_S`WYKQdnuDfzj(Nx1EDhL=Ul8GjVXS(bkT6>&d>rV?TnRjL*ul71kh); zb0Fc2{m4YxJ}j28vhy4~8tT6I;mA1 z!`=rqQY25}D?yg7#ixztIY_GYOci9k``4YvQ zFKfPefz08RygLP?KaB_Tlu~*qN7#q27}G^$IE}C6J%=-M<=u4hGq%(C`{Ysy82g?t zF>6qRY-C^_(_tPFgEH^+d*Eq4!1sWjL-;+RTSC7P;O+Y$&PYdkb}GfO6w=S*kbXJH z5pJ08-?bHSRa+3(vW-Fo9>jfq_UwHK9Vr|KxD@OmK8N!01P4MAgoyx~27$<;$bA7Sf_?CF%$k16RZyd5KtyL17c3tDqLXy_kQ!uwZ}9qP3k`p-ePAGKe%KYjn`{fzXd=;0mlhnl^y{cqI_*h$gM43GwsVGn+n zXE(kZ(o;aYK0aUp>ybscF^|35b0_vIr6jDB67j^+55y%hYp~u!Ni^nKIXw!nddeV! zy~+n5@$%#;J)Sk==Fom*VE2p;n8kEAV@~uB#UuQjUM3xlP&|ph8AP!)#MUdJ4Vm;h zz)9?by~W@Bf9XmU*rti1&SiGnKS&lvJBtHE$2bT2h7;)J8y4y7fOfusnAm_~`&Z!2 zF`LibzoaHZ`tNsBu+13KOM0N5M06F%zXh~QnGOEC<|2cI&oQ3Hlkbn0%%NvZ>s`P_ zl>t+!^b~i~wGFuLHf;9f4CBR1X`!8f(_$heq}=Q=yJ^rlPUETfBWYulYdwu;-mjFV zhLCh?V632ZZr&&}GyXAPSv#{%=NS$0CWtcx!hbp7yE;f2iT%#?f!M4VbAFVdb&Te9 zPOwc3Wa^QG2V~9E3|Yf1f0mdm6uHN^X|NdVw=rLVUC~Sz_WKhYDXyLFh4zEkdiU5P zC$34qvA{DfgHQy|+X8d;7OZ2khL1qZ0$fAZ8^j*a@3=OFun-%NNm4Mo0Gd?@N$#WlEL!M}DQ-n@ zq^-0rqjFnAH+tw$YBIoFm0#(~Y-I%i-Po*9owu*7uJkXmtz;^xJm6qKCX{5dFDIqM7NYQ-692s|ElqD=Hh8T^0Y;h6%=`zb{>s+mM4smuscstX#N zJk!*!!6_Mx!-$hCAlm`%noVeCvIF{AT`#5;<_j5a>#bd;D^^a|XxroTIp;f5_?Z`y z-3|S-G&^l^{-m*77T4K;d5t!U>ZEd+Kn*U`(_l%c0a!zSAz)?r^~HPeY|Tfo%id!f zTO_~8bXT$CD)l(YO6B%;%^!oh3#gHnDjVZN;|!QC?e7{{%(*EG=c>W8^vFmVbdZ{@ z(VW-|zwNCpH+~#vy>W3q&}nCqJ1$Gs88@2BO>)_=2`B*>0at%O%jO}yC7Ubn_iIk1 zf*z=WK%UP9ffjVDsl24Zv=y$|q>P4@rnjVvX+RS*L7pmvmwPv@B`~rt)QRak1bahB zy4mba0SweZaA;Uto&~yC9>GF%&7Rt(7G=C1C97pLk(N@Z5Z&yN%XKa0b z4Nw!*4QTVrMAvLWTckdmugtD?|Is~0_&B(Nqr0osi);@M)ZxV*R^80 z1$qBhw@QUVDhcLv6DgGynlSyaYVrrRgWfOwz#q3K#FKd`bR#$H8AD7kZCbgVx^+5f zvAw`&WyPv}OFP;80@cG%{Bz?(%KU~nKjp+ql6`>sUwB3*pqn#THkR{(hIH!*&p zbSR5c#9d;t*kHqcg+n7IiGuJ}8~uCNOo;y+rS7`g1@llvWTy4TrBtV# zYg5JSIkjUrLC;?lZ`W^+Qc&Y$G!1@_##(tl`j0MBk85MZrIn4dIT#xwrvH?>1h%Fj zSo2S*rLolQ*}E0hwvt)=NAwmvSv}Bbtc4hkTp&+x;I&ZR6D9QAv~iL3g|(U!Zvh^m zXEJBw^zraiKSbxisQwm3Ib4al<6gZ1a+jkf5g9Z2rnS+&3y^NW#fYqqFS|%x&_nfq z>B4R5x$!0Ob3XEd)k!ReS?-9M#d3GkMvLgMHm&{Sroup=$A+Nx&F4U0;>6YMA3}tq~?8Nh`xw1}+_>>{qw;)<8=~;_t zfcYwk-qmWZ%P3^KQ^&Eu401d!XyqVLWL1^6sxc3@lfd{h~f3zsu&4lB6Z2TJn1D=c>1P7PfCCa zJBZw6x=*6|ez_&h273^FsT8#kepd_6p#m9Bcb}xc+88w}d|a{8eZaxRrTZukG&TZ9Vjkx2852F^?BYEV&BbkP0fKNV-6)}GKExv?V zYgH^=frohLR{-PmEU)3Iz41~RrkZLX9WQ-?;k2v1j8{o#`=^2Jo^Di0pY$*0W%We> z`?#MzAdjU^^k;z;pWq$uCl*tcbPTw14Orb(((eHxgZNcU@m45#9r6UT850Z^N?rnp z0^)kWU?AQtgK^>>7ZO+P@lZck^(qHJG$ZdRzw(GJ;2k z+g&+~@ep9RoTRmK7&pr+V?8W|QZl{=Al5@Hz_YV(wxN>d0)&jqF*ahFoP(&OJNjQ2tN8-J zRY`hilZ+%88vsV;WmJCw^h@xP`*Yzpaky6o=K`G6k;AA}5)*?frM@U>Azs>w<3V%9 zSPj2#^s9w5Q7Qcpjf31P{c7o8w8pDr3p-HnvGvVft@p$={2Q?21AQWNrSMW>u@!-A z2GLXil<8*RM2V52D7}>xv~?$Mp41S{&o!Iq&hwxS;k~q*;q}=FbiIC`GP}<=F`M=? ze8C(xV9w?`7`{~6@(Vbt9GB0J#FY7!pheN|Rc6I^PAev}dk_yjO9{LiJ+GAZfpq?% z>(1;^{@l`7jX2BHkG;z5#7>no9o~dWx^MV-w??yyhw4@XMPKXExoPP#Ju7>ve~Fun zfzGGyAY(}Fpz`T_bO$v9O-RAiB+GO^^v`sv3{*%lp||V3-lnaY9i=@@zdlaJI{$c3 zk*K)9@ySI0$A^L(NAW#f3Q3`u(#r8mt`jr!z zAfNtcwqb#kolJJj}(q}QFqVazw63yNhkhax94h;^Y4PD&G94nRCuyz z->s-Dl)8cz(jP>annC#E&Qgkt$=er@naEsq2iQ-zQpv)Zc$nLCW%~%8383uIx774o zU1%cvtp(`&_-yJP+y#6)J*m|Kx&D~E^;{3Ef3-WX{u!J663V2$wd!26X&+Yzybts` z22MVW*AZ$2O$&7pTY3V};|HzqE9%@#w%o54v~D_c*YJL3soT`51PK5%YIV(4K-tNg z9-!2rz0TJltH_@B81VNJhzb2BIV^1`^LU5VrYWfp-MGnuMly4}Xpf%*xf>J3iJQl_ zll>40RNz!MlR`s^4bgO*2lSEk#MbKYSWbBMHzH5vV^Ok~CNf&eTILmyK&>^Qk*}Bi)G( zWEv%&g1*yu8SnERv8lftg^h^HW0fz!xkDm4)KQU9XFJqUknv+zw~H0hfVxlz84GEX zjEnSv+cY{gKNi;Lh6wPtbfvT|GD=XqMEJ``5yC$+q3pwmfhY1sDZK|4jHwVG4y&ap zk%VHU^iD)2HDY-)Xf#g3&DBy?L<#U$A|TnM=ff(g0;9|ifj6nGEf$LtpRmB<$$9G8 z`&!gTXQ37~uW3_4TVPFrHD(8ki=L+fEVLwp`uS1v`(#8d4Gw~K;3RYE*{>DInGI=& zXai`YQc8)80lbXp=s9ENW;$CoDz2{6ENtA7V>dX?VLR{80Brq}O6h7?4*9=FL}v?Ne-l)Iw%c<-*1(bWXq2oyX6N=DEZ^ac z=f_&nq`Q6Z4Q#&&R&d)z>zDRD-t-xU>QPqK9PA`kXXDt6GzP6&ncvC;qf?P-EbJ{- zEoTD9aE^zh?_7!Q{Kl6rl2zI`dxO~51sdG5TtE~JzmWwFi7)?#4qOwDVXKA_cX%6T z|1q|5)q+RWXam2L&LiLhmEemDa4=T6uQ>Y_KW6qznhFN3hjK86k+OPWM&#~#d_q@_f;wu8T}mcNZkr9`!QKsG2JkoA7U&BNn7nc11w z)#_Q-)iNs{H&5oLj7`?l;<)QHEejN7v%`6#{bMJUuQ8t`JF6;2(1Ar}uXkv_8i6(R zvI9m@nj*FoGrcd^TjuEV_3Ev}@q7coA&v^?-9pL7n5IA0y8SGexb)Jo#DcE(bLu zuRjH~^low;>D{#T5XibsF8%d@ODXLc+y>OSKm0WOULI6RpGLL_Wu9q)H^q_c-RCzu z=8NSzl$Cpl?R}v@pF7|AWbxdMPZsCmk4sttk4hj`-{QV(BqQuWAOVb^t(Ia@*EaBWt#Jk z2`|_lE8#Af$ULlUoULsqsilyL#V|8(g14IU<>VgE!}EkT{Eg=Qez{)ZI|`@7Wx8sc z;@h;soi;jf6ldf%*-qZbtfh>|@EkT(J%`6pZ8)R64UbtH$4~F4tj*jp+v$!9X)ANd zOXq%QJKkZJtPGbW`Dd1tZ#iIN{V#9n2Tg&>MPOZdc|*m90%1yNn)~JU8R7+n;(T@c zy&#h=Db(j#>D~clUuROeZ^w>$v0z;VMiQxm*v z@LgaY_Zu83o|S<&#A3y)^GnQju&$=L(^|DI$~an>6Yy`z5UN0a_%|q9S>vpL+-QgM zj24i8>fy5ra%O=jr2jkcdLkQHNRvGTLYoTF$*qMaAszE`0^Vg6O3*UcW8}bkA~KZN zpou*-=KBG4KZpFEA$$ShL3pActCzy>KdT=ytNe`d`ggCJt&*bV&6vHH1uJht;C^^s zne{VmMx5=G+qmjv>@hu$vt?F^U$ zu+I4pIPwfho&%1rHp~z&F{<;=Ll4>Q&pVRc$?bb%Wt34JTQLh@JtTvs2%daWl+v}Q zxt=9fOxM?7!$u}$@Kt8~RPy|Sb%hqFp@;sY({jn^4C zb1bny+v}li%RqoYZP30?fr33AWVSfYcF=n8oSCL^sj|?G?>v{UQIb3{Ju`RNFFku- zcn#&bQwj&nhdKsKrt4SN=erbvbpTlbkQFh=dN_HH^zDnB4%~2C_@9^DbQvCx^w}ft z1@boj9G<`Soxr+(gREcsy8t;SxJ~Os2R#OPvQExIe4EyP5A;v=LW}N!^A(7RO^eV! zSrclola)X2aO(=sWFP7{V}vEJ&f!wQSkJ&%&&0+W=UN*mfBa9Ievb2}bvrlx9Os#J z4+D=XqyBZ?_oz-hB`~*N&?TC zGJO+RK3{jR=1lO%Q5kB%$BPOvrh^W7eu^{FcP;!c3P`b&_pc06;Dx{@azQn>wdaF( z9{n457RXZ1H^w9#v6s1833WDs?LNN_);X>A?=2=Crr$kcd^FA@59HTTMsm)W?*aa7 zoFSGeH0L+9=7FCaMbU7Iw8OjCo9kK7PVj3T1rkjqd6)nxr|CQow5{JGw+8DxTYw|% zRXlnADTvu@_XY6(elo8v*+;|ac(WIoH~60@HcEP$_z3)}NagvJgBraMPwyyFaTe9tW9#iRW+th3`COKml_x4=7xGNC{P ze@T&go`#n9!YZ=+9~R1smbl7=0!dHl#HC`chZ z?Fqd#5#$&-1C0MGGJaqNuNyxN9!u|;S%2xR$ojW&f<+bh1IPy2#0E}4je)m@;A-$t zJONL06fe@N3SWia6F32K_s4Sg>sjeV=zn)4QJ-p{jFCQR5Sd=xaPfQ8LDu9lSgT}> z5*bF;ELq=L*x$^9bxPJbIZyo~DTn+xfFA_>PROr-{5KG{0KN*&v5?{7Bf3XVVM%`q z_dvi91~sQJ0^bBSDcbkP4`eaB5aAV%3Pk5S+Al|s2-}a07R@^vZ3&l-^bV}~{YJ&b zk97~&U+o>Jcs_KqZ^aZQ@JVom0tHq~SSl=afKHRt(EoSKNO7r+-2;?pkTp!^Rr~_s zTkxCt>>=xozun6;ob6^9=Elv8o>@%i5QUL-I=cKkIDA z7l4i6M0Z8PWt{qQLnt!1MyiOLjx*}xLh2dnAf=w(pV5*yuw(FSw@OVU&I^EZwlEV@ zC!fRYNhYKoyjyqy*8lp#X76S=p@~G&1N-qq|63p5;#7hiIRy5R=ddg=G&Uxb5V=Em zDReWE5L}UPRNDZy$;)`($%GJxSC|?@H!+RXo_#o>UL9n(gpjiTK1Ab|?H&c}zCB9l-`Ec5BaLzgNtC7xckK z+sN3w6AgI4nFM+e(Q^nr5Z+F78FeHYC1)Fi2IO!qqUBHOhE6R`!8N=ZYg z?*`j#qhRI`3eow>XCOy=`*ld=t=27sIqB=0R(PPaY0iwgcd%TuL_QO^nzqjL>`5K+ za?;n4=ZZOLLevBPov($fz}grmjf{BswtgCM(kGE>NFhjl94Q71CMP9F3wQ=>dvpUQ zsiSaPfY$;v99Bx7;bK11GY@hIaH_y=$VnmCcNanYBb0xDMUPjs-lCZlD>5(ixdpjl zbX~=&(S`fqmcSzw8!#$&lUlbQR;=mJo zng@193&FR@R1IEmN5!2y*(sII$??G(-;?RS0P=y@d0>YC^1|6l0sktt5Gd?~0HST3 zBG7O)S*#y|5vh{dYIZMHECVU^FWhF>S7^XLnn0$4&3&&t{`^H~C8g)&8kz4d(C3wytRE|1g9T5duX-Tc zJx`H!J{iuZmXvP}5LzXCjL@qV0$?uWSS4|k- z#Prs$|7=AIlq@d4x;j~0)%v9lWvec|;2@=bk(3Yh*W~zWg+fXgH~?=YrByDy9U8bw z=^5#7;GKx1-Wt$w_a1F2fQPYkv6`1m4@8RSdKBiaFxkc`K_6tantC={u05_ON?(V2Bayzx@$2{+#FY?VM|oHC0sEV3b>}3A|5=?2wH~f1 zC_M@F{?e}qdbs}Y3ZUex>O%M(S#uYZm)6X`;)C4HDqH7Sh&NWrJ3oauzWPt_+v2(R z>K72>D(j7ZR7Lvk!jZmw@TIzpk9%InKIl0Idj1mPObj~Ok=OA#NE`8Ce29wljREXC z2;39t(_+-^K~{7KF8~Y$__wiu!9Xmh!hO-`b}WN96!m>~4*CEy`@GT9Lgzwyie?f9ThhmZ>&nNa{{>GO?)zQz5WXMXCx-i4qOapcsPelH1vEh? zHuA8K%`W$oISRu$sv^kIaoyE%ob*cQ7|55ygP(y8I8?e3N>#(94WW0S^aUv8hD%pM zX~J-6ZRm9<-91Q6VJ4CKfA%XTkv2y9!+rNhIq8Yei%|X))CRx(SkD4LD?^O{T?fz- z6z;P{lLO(t`=W8(3P!tj2y1FA*SLNtmpfFpftsS4^o1XNHw3-o-)fBgw;I}5j^JxI zboslkg!>Ys6EY2*8wC{1;K&(j9T)DCMK=muP^Msdcdkp@M7&$n`3<&ye|#X_U590s za9>Zv?Sk7{k>jp~FvfpG;xgF_lpYx(eT(sjS4t&0$APz61$bQ6xk#%BTD=%yGXLIL zhgI-w=OWM!#6F1S5TAuu0r44#Ifzd~tVGXWDI0!!A3`3Xp*Q(1q^aTb5lFMc={F%Q z8%`gDw0t=I5~S(an?Df2uE*h-e;cv?L?w^FXu)f=lnds>O%v%o;lBC^eW3LEXLM5G z8P7D4+Dl;DB2*K7AgPe6qV|USwnh}0knfx(g0*fvSOnMY^?Jc3$aGGJbLP+Jc~ykY zmPd$pw4(bn=6H}x)UH44p9C~IMgV((C)~F%!hz>DHHDj0gCD1E`VBzk55vxVOcgCH zjxf@<1EBxokpL|NXiC+n+nPQ=76U|8mHLzYhXL3U#rNm$f@hl$0dE?2XDhi6s{`GP ztSzFSv9Pwt`U3U5fY{H8UCKSY*Zv!T4Xe5$w9K>w}wDzm7c#@svlCko2PG3E>px);0z-U=!KzSr@||)w(7I{bkV_ z&_$@xIyk-gZFE}z>BD{ZM3LzzjP67jG%WiO=jIqRFB{*h30?gUsFp};= zujBinY+?94e80g%p&ne3Vh30*tp6~gw&O)mIz9Y6UX)8tnzVKTVW-TV^%pR5_+l@;m7f4>jPQ(6rUBS>1KpbVBM56s%y6aSXJI8JPq zC!HTFoWmLec*n#v26b!~FTcR_Cg;PQ>R!D5W30&?B{YjOT1OT&&SnE-y@&hCBcF6B zV!Jfdp#|Pf_Io2Cq(UJ3!Q1;oA_K^NunYpB$=kd?0JKMB29Xowt{V;Y$WHHhVb76t z@q_mLB_=mDgEgZY(zeUjQlvOJ`TvXjv|JBstT+4{f#r$MrO--&)cA*I2Y6G3`~De5 zng8?$y2fSJ%~AX0ohr~%p7q4T?=zl12C_5dzMM?f_ff#?TID+I`XaE>eWyFS5E-5l z{H}ktUv$6p#O&-ezi#8a?2-N@8)s)LK);v`+Q`L?1=$oirFdfH#&yDi7<^6)ZqH^r zXn-Gna&;*Mdwkk_x34&Gbd18x$Ig&gPLrB3VO9pJ;Jk47zJo@P-)a)4_rpT6>wD?7xn{`Rt5Z>TYDp&apY}gl8}DQ-*3h zPBRDgmgB&(GTAp%xa78)*$b}*r_jmNmtH!MPBD^1n>W4z@Le5KW>{ui@}?AC@*c3| zI@0|OPs05uc-oQvq+OGQ1-sHblLVb7F<=HSn`gnMpHn=ql5^Hq7CALrvx_;G|Cww@ z60tOyknw3e4*b?uxyL#Z%uMIvjFiIpu5aL`;W$gWBfWi(yTrQBMKBrAe#@_ngqx%d zc)Xs=MmLsJUA{(3akA7r`@*%mo6z!1uyGg_;KMmy)0ShE990C9%7eV#euaS*FkWAS z??5$p0)$L7?aD#W)oUTNK+q%%@jgPclSd8FFrj5a$84-_1D>F7z?mAl@JlbW0ag-d z1zOBPsaItG2aK|(*(-AJC>^hX79eCIL*b{S1r0@7&@A4)+Cg=*;|_X{^`fmi;EZn3 z)AOIM27K`Hefn>(-}&$QZQA`wHq-e~aZ+Iww!jJWUT@RWOLsSbUi*bdVJs7By13h8 zvedxY^eN9mIK75eEq@3MjU`hv*Fp5)cRhP?mPVd6+sAg&S;;;oE5~;@kes#5XUVck zuS4l%%`Ar|tFA+1NOEc1_F`mQ7O)l1TUF$&U&T3-R+Ce(Js~N0ZxIF9SaXjftu@I_ ztb}wR$!#FkLO4UI!TtJQ1oq;)G)Z7pl=+}t{kbvAZOaQ#Kn1%p47-F`{yQDFYupF8 zGk(IIuJ?_x*=#@I8r#SHgxP=}))*W~uA_LFMh}!_49s6W7RIt?we5x`HnP!>BUC=1 zNexunsGyqCTuj33GHuC-UnF5>*{E1dEgK1Oyn6)vQhC?A8gRcw<}e@Kiw7(zN6GB< zTc8aKWy%N;dbu0u#0v3kes|jjR*i;uAEBcu5N1Po0K#Jsfabw^_s-kD6JDF!Bwlpp ziA~Ofuuryu?NaA_6;?R~ek#aFPEuMRw@0zH_xZPf3oD7u+Inm6+b=?jl30oYU!tUT zvR~AJZ~OjIvL}4Lq;XD?-_zQxNI1V=$P`zKTIUjHq)&hD)}?@)f)%_yG{b`_<&YjLDr)=)E=0jQ!LnJ#1XciSBcaRS;_+BmO1 z)Hg`O%||;{oUAEjx)UfxNUb3A{Cr4~%L zIL`GE=z(0f04VMfz99#QB6DK=b=CmuYU71o<}Vd z(BAkrslCs`#ZvWWM4whS-(S4KcocYHd}EwvkwE-Zbe=-T?748x1#`-E=sb-eX}Jy+ zoT5zkeU0ZOkv0|5?;>C0GUz8$BqP`lH|!NsS6Cq(j(&}o8O9EH21GG&VCR4bO1Fpa z1D`R4^j|TobAZ(teYbykF7ke?eYfA4OB)sz5?f9Ke79q-x7qs|e$?<9UXlA6UJkJ{ zmonAC7$ylD#q_$VA_I2iv2(}HIfIuaoxx=kp`)E|$$O8lM-B4c_t#SmUt`hmHC_!G z!xxcNBBUrX#=`LE*eLcv|79>rF*jTMBYu)<*8LH?bBQkyWu6G!8+QDj^6v>hB>s=;f-*c;?>4Sm%5L zZiia<>6rE?q>F>>0fl6SC;BmRrW+xTR~gJyX2X6Valq4G1nqq~C<6=~VEiQlZzZJc zmLs5zK?Oh);mZaJNgX!8yP@FwJD*36+t^E7Q$2X@Xy98QQ=#;YLA_HUos5(flG;v@ z3+8ebn9UdA8wd*Nm9Vl|UrzIl?sH&IW%h!deDEQl#qZ#D`w*S%iS_X%+%eAt{GD(E zx0Wvk575uyI~xk=bO`LNCn??uWoMuc8S#f9;zvThX8`_t<&QdBoCz1?jSA^FjPS|G zYzMJ(57}GE84?*M($^GPZynErJNKc6S%*3r`1>3xL&L1&kfPug?M%laoEn!6w{>SY zR6$zxKAaKN&AYE>&EZ8|7MN|1CH+!3A(cg>(8jcIx zSq$%lQb-$M4AUc-WG)6?!v|mP#81rc#D~h?NwNI(A9gS#oqq-&$sG|OXAHZ51}`OkYPH~Kw5TT=R)bU?`;a@HsrM>Ky*CAg*4yuek(`p9j!=p@hQ=@d%AVx*7ueyI0Q7 z=$8Sl)eS%A7Xu3Eg>bzf_r81EXJo@m@CL{5N4#;tnQ`NB970}&_wGzilBxt#3kG8^W^YMxfWYpXgNvR5CwQ!|R<+F?BMbQb(*#>EI%) zo>>Uz%QS!7Er%P~3Taws4Ltd?Ft#B&y=RcLzGZ-T>MEqW;l6e)-1fgsr>=p2(diRV zhtQ)qP>40FDW0@j2={)K0DBb1oE_#~k{6N@j}Kd7bP4_{u@$utsB(yAEA8_ghZf9t z(08#D3xF=S_B{0a85_;5Z1W0Z1MuJy&>Lse2_*++C0sa%55b#w0(e-sZ)6xG%=#f8 z!$#ZIzJxdJF<*mYcu;>I)QR@V-nTlE;7e4A?oqAOqP915@T&Aob^HD^F~f2RtVCDaz;{3YfPr?UObbw~Q31?7RKC%FWr6I>ByZX?C02Q;3Zf9auI9HY!sk zX=i+Z&@rKD?O-%YX#F;w6WaeCcr@Y5gclP%HV5v}-qvdgAK!H^#XSLQ0Pek&(?%Wi zng!N&E%ch0of7NyfO~QKQunxG2A(XgP*+I$-;1Bp4E8-dJOV1fKuyyY+Du;{Hz`Mj z;bg&?6{rwpMk>F;S>Xl`gV_1UjT>OMD;>be&hl zFLiJqCZ)-yxS$ebdh*3FqW#F=djUzq`$!^($k@p<5Ivm8AtIAF;iBkQD9>FK7bv)M zm%wX9lc?@s^~6Vx_{R}{IoLs3$B?r^yUsnDR~^j|6mY*WgWPsMNt@Cg;1kT9TQ<3X zl@i$x!G|+0N7b2(nfheRdFbw1T6tZ~a-fl?meb&Y_BTH=nO%(g8C&87HMC(x&ek}` z4wMZ30oqEs)ykpXU%Ncu|1H%Z@RO5jI10`=Vf>FkI0tk8D8!1arVbj;dki2Gi4WrU zfJ5$W8PLg_e@3p^yC6TcO;bXdWPB~QS_Z++Qn9+=MqS=1U4!k_733QpIvFGkq5yxYbI^)B)(YGQjI~l`A^x7EozJ12vp==rj{pHQrJQGs!0sx!X$>>@%L1XBstgat^J*I<+TS)h&@?9?;E zJrDJ_0{Yqs;SmVrKF(mDC!7RlV5gIo{Icv(GX9~_i!gdouWC=sN%Dh7uz_+dXjRV9 zW{)V8VXB095Y}K(L%XJ)AiFyCFwZ#WVFbFVI24oEP?ZNQPf&bsqCHN~I?bDIA7^WdUn5rWEXbgF+Wi!dnY#~T@ z7nTQ(1(=pp?=G9tC)>Q+#`)ssOxyx-2W?33llz$D zD^BY1vJgcn=5TXI7e0q`=2Q8R6Re6uA1LZU?-pfhDZgRuc7lkFJ7sf2MTrMm{nZ^WSJ@?T$*55W8lNgAxLJGRG#l zmfInA&DIaYSb!x09t*IHVVD+R62P2VkkgFe`!C?AQu04Zvj3$07nV z+94+Vm3&t&1A+xYA%rprt08zGa4eKTus|q;PzGVFplMqo(vq5Hvl$yQupKCBk*ma1m7#Yjd}HO zQ-_+YO9{P*D*8;?5=;G zhyU?Nde9Rv5)=8pg=amCq({FZ=Fer{4l`2o(~Q*A)Wl|_AOOA3AL_jt-hr{lx-MCk z9B;d>Fxsxm@76gE!n=6)e?AjEXo2lI12#Sz+}V}|X5We~Fv6D~JqvaAZ8bC*!SGxR zjbLalo`$&qy2_!fW7{bB{ugHbc0=byVQSPd{$#tz*MuO4$5 zoI`^X)o483ZKYqqD>W=mSf&-zHfIAhw?|nlUpAzteCC$gF3O8KcDj{yjFc!V>KI{9 z0>7EjJ{E4&z0q?N*XmOOwY^)g6T>lfIDN*35izIHfYtzQl}+bpC14JSE< zF;rU}D;cW$?==_LhUzZ0y$U;&bnx$`gd^_?O_&mv_Iq)^fWBu?I3aMx? zYYyCx6s_>Jt^I>Ph*fZhNDlWDh_yj3Jso7hzd?;$mw8q9)n zQo}u5zB=^7aE&#?kP4__2)!XXV>MO`R#tjqH6Dg?(#FD2)=KhiOF8WS$qgns>`Rpr z7i#gGxQ1(nbiPdBbDeNDsSr3vx;wcJ_5@$af$P@08*R65q!EpogFV3a-~&kfa5Qac zpoiD#=V#R5I?bqJT2jzO?vb#Au`#(=qj?qY)F6|VPj)md0S!KOdjk7Ua&qYpp#+fJ ziG$?#S28JAjtJFCun2$$cPSn+yCbw`0he}{z5B~w$37BAmcF# zuC^i1EW*e2g1$)S)(eI?>26w@gh@V4)C+ftq?DHKz-ZhU;XCg_Y}6Eke-$%8-^jDk zK3x$lX)!ff>dFTHp!oBn9HWYo;rk)gOxj8~-@qe;v`tB^semQJsYQc*#{Lu6T-IbE zr6{cq8B2S9te_;^LH0>xOe;a|dtgqT2zeW=y8swCTSYNr7b||@b!gB zZX_?wNQuNP&5r5Fn_L$TXTJAgjbh8XRg4@HL zt)4cH&$V)WsSM<(G~^4enD9d7%I(7~b_gx@d8K8f#kBlX3u&p8aAwXoZXS1za^KtF z!?^QG8sWo`rZ_4g(eR8^qouHGj6*%=gttxL@K)wj4btupj~!`)xJVns={1pd%7oPK zXqwuQH;dCdB5zL8yn%L#Lp${aUPi7Q-jeKdIlSc;*xyPlnRrV#RsgbgkoU|QdCz%} zw-Rl89EN^6F$U-kbo_J120q$78)y3lk*;6qZ0lvBBJwy<;F`sWiJX-3t!o2y11XhF z#?_Z{t+~MH%(dwt^RsH#WSmuOp4kpr&c2QWkvnn}?Xeh=bC8r^PI|_`GyYkj#gF=lR4v;ok9ivOKO{C8zpT&DJ?%%FqrjPAf^!Sv= zZ#TSeRJv`B`yKBa73W`cyarp|o#@o zEOQ(-sxW3k!oJ`SHxg<})2eSI)WsLse3^=)&ntqIa&If0YpgiB`^#4BWI$y(T3vG^ zzV2?3n@8@7=viu)j{l-ZY_G)}^$ZNbsUdYNfPEHqB-+FfVM!Ci{$wSYW(0$DMY6ls6IZa?*(z0s7#fDcc10s0(CyRLFxl<8g@le;KtF12*zW@_Vte(+vh=47jMIzH+4EkgDa!RL83Qr7e zSV(J6)K!{rS1*!~Ekh62Q9%i$REPaLh74v+6{D3P?!KW)6Rmx=mAKaqA(eC3?HDRB z$9N?hkyNWd1+Z5YUR`dbG!q;o_G{5m^%5{Q&iENk?vx16_6?O; zh&9lY@emQhfd_ox)s0t0tr!S8&(;nulg(*$q6Qz6o<1{DzPw1DLB6rTH>k(Hb z=%Zgs6c>}hj|2|0`fIMVs>V8%t)gmG9h=cqMSBvheLYdVpRx^j)A#*SS0*nHvLk%< zuZvPwQ26U0Jdfj?_q1tua%4$;TXzkY$_F_=jI{1o> z@dO3uV3X~A^j$_v1?4{U1wV_Hyl-$GQc^)#{dX?XSJn)YSccFsBYkH%{4!T&6-j&V z;PpC{*%L`uHmKW$Z(MaJ?q$exg@ey6d<1>&*;Y<7r79>`1`7}i{656x4Ni;np8Kl) z``cJNY_#-MLyApa;I>4BMiP?$LQX`hr`B`**Y^;D2WUrZOrI!TNM`N55T zE}M4M{gCx?-9xzbe`Mj;;x~KV!X2A#DSaUe)XEI&X}{E-j$P{v2MOUI!+Vk3 zls8a1)BK9AR*^ZvwJw`4`6{lY6Bt+%RxLMASjxVvD50k1bv?Ojrk_3XuJKPDXGNy; zr8=Z;J_~NvH|MioUY>udV>!Qu|ND{x59#xyf0O=B`ZDSNWNt5k`vCel>DzHQZ<2MD z^nEf0NZ%*x6B!evl(CWA|7XsS)QUd4>oue7GTATC?j)>o`|92lDFbsjsf{a1UG-0F$ZcmRh6JR8E;yR>A}+z04}rtL#A` zHsFCIz8N%{cd(x#vQv*@-%aFY##<9ltLr#E?PuupbHIT)j89Ln={N9XwKNcP`ZUV- ztD%=gO7pTv>rGxpr*pk5GVrkx-#Yj>_#_culZ$D_O_829{GZA&{a?zs@Bc>`%F{<~ zCT?A~{YzQNMM%WtCZ5!7R5_|&_~^zWrn+{YI5#b=<& z-I+_zA!%t(tvENAv;mcEgFNRQxr71|l}+A_b8E17QyPN8q>kup17hdoX14(qBA49B zkvCqq{gN#8B0`vI34P&X$cvm3&B);x{*|8V4|d*IK*h8izzzHL4HX-@mR;NMa|Fff z z2Q}g}?3kx(31;%gqF(#4m=99`GgrF=u?8&}8|1#7jAgPv>n^@j@^rJ(vDm@9#eV#? zSYJco=^rY{2zgE9Zb~4jOzGXwj`Fow*)+k)_20eaj|gFP>ozgECcB}(#9$j3ht~J$ zkAd$tpfmJ8Raz@b;QKF13!k@?p1ho#B^KL!6JuaRhyGEWt&yoN;L-_Td(PU%;uBFR)UW( z(Nnesd#R6}1J-(MY$KkD_DoB&`BuiF7sjZ!u6(RUjPXp`a(P>gsI|ZRXpJbVU$gbA zM_=AL0Wo8nKNizFyVt4K+kDlA?h4?|mL6EQ-SV-R*;%%}vbfUnwW$1vI;dW^a@~RT zAB!cOwc_19HeX@vG4bB=$dLp z8Mx0J1=$~gi~E*42eB^1&I@N*r!Hjs^sy??2SA_sNS?Q4{#agcXDkc~Zv=zFb(r?x zJVz$zWYB=MSq7|}J9x=Wk8{{JHk{{>++4SL1;H2jD0x@BOYQhn+^<`S|3+QPu2;oh z=aHE)J)cO}eKTux4ZDIf9vN?BJ$dn?ZFm0V&n0&@9!#D`QAZ57GM|`tXY^z9ev2{b zNda~du!`-lzriz}381Cpyh_#`EW-whG8hD)ECO?Ip$@d4@r%~kDeUR{f-hlfI@U_> zryBNsr=WtuYr)%q5^Q%&gm$fXTc=v$OAaW(RVMLm2uOU>LTQd{N2UF|dX7EDIuQnV zp>?42yV%G*LM86e(s4Ic3)@BR)L;l-4&e_w1Do*ioPv${!<3ZvbaNG7$ETo`iS#iu zSq&MT_l@b76G17Ww4b%oGZR`$Co%?qPwEagPLxS4hK0pWk&eSoh?(6* zWf|NoI9S1NDW#_7x=jSf%{c+*1Q_5hA9Ada%(#dXsBa6<)Hq;89uAuv>K*4~=@(Z! zl1`3YnC-xB4D&v%4G517W&$(31ieQy)ca7AF<~Tp;~=@yi@`gSxP;&4wlSKpmd3i} zGz5ga-#XjLeu(hgWn%wAzCDqZ+6PkrI;VmM+5}3^#Qpl3aAu3ik+LHd2#A!12JO25 zC|DBy5b(8QaUNJ2z+FD@wf_P9#H(R_iv%dSx=E{zs|!J6P1o>*R!;IK_+Ik=D|+jS z2wpL{bC~vz8w;esv$72&ZP{X)Z`sR#qH^(*+f2o2>y)#Bf~_?cQyCwXk~!W63JSR$ zx^CB%UjP;n*2*PVvG!u6g3VWyIk>)j=8&VJ97s8vkCtDp$f)>x`KuN8Rbbz+1gqc@ zP%iXLhEhkr@d^0WUf=YBCGyQRX-VT`96slFov=GpU~R-y-bZg2MJ- zt|lPt7$kBI`Fn7pa73_&x{f zL;Wt?=(f{y2nNHy+(F@1V?_`wY(n;;LNQLeHVIqb~)80OT{1AZK1~ z0-pfn@y9JCQu+H$8|`n|Q#=VI^$uw6h)7t-<*Zyz#ah?do9t{P^;PgEHQ8z1#w`+$ z1ZlqnPm+drw$m2W7vEx8BIZMkqXCR9j;1t3&j690T27=s>RNC9@JIq=Kz^GQ=WYta(o6BZ8is^#MK1I2?i93-9$)Nh`2O3SwUGF- zHxMbU?DB`oiOT@jknlG#YeV6!K~VWYPAk9A^;yp(q@_wp3dkClgCF&V&NU=_h-ZSdYDu1O1^p*U>##h}@RxVS$f%H@G zpaId<1`h3LjKhBgBV(hA%r`pvf%%k%F^sm~?o6iZmzhyr&IM8UYKI_2F2`-k(l%K! zZmHqQZj%;EAvG+uP6MaBa{-}uJdZhRH4MS2KLGOzjPtZ=ky5v%+~9Lj3h?`cg^fc= z)61t_F?TNg%XYa1Pt%{a3 zC+_U;yw*cfU?g?nhKh_GIc*^02RtVw%8Xe4zVfh8Fr-IWvxYM8Jc*Z|&a}F;>bi|M zcm2QhkP(#O{b-?#Aggs?O*t3wO@wbFe18hlh*JcW+6UqLB;u0wMTqI0brNF z_g=&&1eDrT_)bK8zCemb1(e<65#K)o!#r4WLMz5QgmC^_beP`Gs=bS+6uY$DzROY`=@#&W@pckslP6M1IvH z_Is4>`CS$r`X{0N>uR;nAFb0pS8LSywy-uYYqEJ0O$4n5IxX3xF6t&_uQe)R8(=G7 zyI@22T*T(Oh-^xskELZEtuK})bb8_gm3{M3m#*fRnBT0e)q%b*kCaBVXXJWx&u>8a z%6~6^;9Hdav+@T#CQ=S5pOm9PIr>OB5c(f5R1hD^sTeM&V7MG;+$3*>)8{%}&BG|k zX3=52{OL`b{==L8tfT>IQz1An@J0jna+I`$_z2&?QCAb*Xf8@>`X6sp01QJ-XMS=x=~}338u+~^BatzndF8tfA)4wHE%s`!a4fqdPuOg>veU6+k<9xuI$GZ*-4Q( zU6z=b7!5N9MoD3Jz{-GBSpbd@u5T{zM7cf#`{CkJ{!MV=|54-&Y~-eg%fHi5i2o?hrz!SeK22W{iZUf?BJyDk@VdPxdBFl6^VRdZBXoxe24sAw}v>DXxsO zE*nXaG?L;9WOb4vDF`>}VWaHI7;Dl`e-ooiVTt zuw}4a1jBR0ron^DK11tjs&QWdNrO0w?4ii_#Z9as)9O1t0URGwEaO%usoqLnfp&^W zNU@t*=v-x1KXxa+_LLTaKf8+hvQ>%oTR)q~FQ%!Pto|#wFEU17N^YThtLP%?^O5*? zNa^+WOrM_Qwx?2QT)MQ9@HU@F-U%+&owB{H>_z?TTr&;*VD#K1;GTc)hD1i1%py%M zG_BVF%_c!&X$=na<0c!W*Q36P;L|2`C$cg?%uP$=#}utzeYjvaT#a_pJ>U2LR>bLinz$8q!pq7x|-cd56ZuEvdHjYBCN!%Httg)SC!p6*Gm zO!FkyX+X)D=-B|AePA4bry|J`7TyfsZ1I39N(DE7Q`CykIE4Nttl7XpmkkLkL|8P! zUJ6Iy?k)VPQg8lXKkN1TG1w@7?gEOsu*$_JFda(S8FxcBb&8 z9Qu;YQs=Q+7o-xMTWoJFr{Oth?xVw0MzK})E;wwp(P?8vwjLPQqSSX2TEqjZ{i@uS z=xna5cs|qB5B}?$J;n2B;9x)CKGVmMjvgR6RfrrkMW=D5Tvrv6wrN3VDOXDp!YrgdOy1E$CIv1U*c;kF)j5$$E zN==5OWN%Ml_Jpow;LGB4u{a@|ZzXMOBJpz%wG;u3jM6cld$MJ2T9*tI)I{ZQKL6<9 zv#$cFY@mnL_4m+_5_!%|rw0Tk7!c;dj0>)B+txG2qQU;2+lH@&o9G#3-dnq`G;W!;C>6X?6lM>wLoglDl3M3o;56#4MoNZc-|I(r(+yU z9mZ=e?7Lu;r)3tuaDSLeC(m6|T`gPUP~iLBITXsd2`wHrq^T{W<@dqfiM^8)c+T?7 zbiCuFqHC+89P#EN%t$QFOqF+NW?#b>k!Sb0sf_#AsGy5m>RU9F*+S2v z(q@EHJ@RS)!u`OYaL}(r$Yk6`#T9dJsLgvJqaSUKDp~<-SYXM4dW;!P7iFQLZ;Wv8 z^$lXoW1b{)4&iTp81;GqhKwNxY%*qcHIsTy9Qu7LHT@y?bIAYJ(C!k=2DGOyF=+UZ zzO4>*!(MX`PT79;cHL3_mi0Q@faKO8&~@vnvd3HVPAdLn*;`M({0U{+5j z^l>-d_tBCWd^Y5cD0%aI5;pd-iYL@^V7^9Z;8nQ6;CuxUYB_MR;m!pb9@b^xVE?_x zVWAtCm)KwVg;(&k>9;&(>x(qdH_!R52i95F6?6IIoTvnS-4FZ@Mb5w6Yb|@wL)I2a z&_h}V3)+@I>VP#X^_`jOa?$-O#H}bIy{BoA=yaf_8{FVbg48CF3fko&{79hZ59aeO zz7$*#>Gs$*n}zT+&E&y*(N9u7kgECcPRuqRsYtHz<%e`M$-HYjT=to0qk@y)ui@y?1w$k~~F_~CaJ{+t0S?piJ2_vxw zMq=X!Rc#aS?ZrW*ht~Urv*9Q!n}g@a`O5p<-2Vh)ATJDEE7yAEVm(ucyFoXtH23tHWLrZsu zpo5?d6nM+Z?P}<*Cwy|5;EPffr6JZGvbT*xO`8VCm4FjsQgX{!)b5E8(C{r157te5 zp$z-vws;G;bqs#t#r6VxC-UT}5aca@1i=Cee$A$tpudQQwcn7j;6mA?UcV@#<@?}% z0`A|B@Whe2zK$?wWIXQ<$=fDcrlZG90O#Ofh)SQ#XYiFRIW2UK6nIvDgU)WoBlZ0W z5`|-naB9z&LYC?Ko|tLeC31%sj~2}MhR%^)iL*}S^Za8qv8bohkn+uIH+O7-Jk3t_ zQcNTy;hSj7R6Z9YFE+#x-VVF7y$$u4kG8r2o6s+lm(lW>FiT-@>N1g$d`GCWwZ3g8 z^sVd@zlc92UeN9n|7+%S3$l%+?m3QZ^8qIZ zcVfid?bPr&=#zgBa=aXzYK(_G2aNCA*y$JCu^xp*>WS)=P{XtKuY*w*r8cr(#~tkc z4@w5FT-rRs9pbHI47`-tTg>$7&&e#H8Q%v8?yb+R?(HeV59u(X$tKSvK$i;bDKOE=x8XQX2_b@5kNeI+B*$N-}ytI$eA!5_69~79pG-JkL7% z_|MPQTS~&h#K2O|Hpn;_e3yWV^GNY;>}va#V%2>s%R6%$%RAF9+tuaH;&)|@>o2c= z#Cn;uQrhM6M%=eRyFK1D zf69NTX;}E9zodkkOz0J6{p5;o%U`Rwzv2_1@{jdJ#m(%}Y@{+L zcU^yo-A^~5O_oMO&!n{Bxt!C@!?s&r0|k}bhiaJ1_OZU`xSTHg#>|sV5202+D@V71 zK{-kt_JjLn`{nziBIP_gWXIic2pm!CBIN)%$$l?>x`!Kg6Z*T0X{_c@%IJNo?%}Dj zM%)P*!JFS$)wr9zNK(le){};RqG!Ib8f%INxAkOKQbiTehUR3f$Jl>lCgJQt?u;yy zVKu^zkHy_1+z}ZN1x@<&0OBK*TmhD5I%Xs}tB z2Sq=f-`A6A(PDMVjLesJ1j^bbj6G3q9GD)Z}T|YzOvNec}8O zUd^cS$aymKTBl$h@-6TS-+w^pR%8ZE41Cr`Ynlx;68d72<%b@^X~A~+g>!=m79c8m z<7O=xwt{=xyV%;$}Y{)5h-S_8WNSjUnMm zfUK7$N0~$4LPD~zgVF~FdU8B(IbIT}=1GAkflxK*B$g5#C6?1d;@kwM{dJdj3yb@-Mhnvh@aDq>1F9m zNR3GmY7HxOnLN3N=g4gvLX6?-j^SLcJ9LrU#()yV3=}Rg4$R+d1mCOL)%aZ6096s` zfiMQ*)%3nGX2JA zE!i+eYb0#Ao|;HK5w_ef+#FKsK;yy=R0^5_SBkv~?mnT*YY?~T|KDmjEDMEkKowB9 zHwB(ti18H#+P{+5L08Sde&?lPk|2>e?{X(zEUW zLFD>e63X{qXY&!ezQ%yK-dZ_gK0pmA-;d**D8_X4WwYM zZ9(XXn&sUO!yaFq(7h4%7d3|d=9;x7Ql#3Cx=@r~cnLNGdylx%+IjsEq|#S+`lQuP zxE`(Ej9gFDE-4v@C!UP7(342th4kA++rm@+b8u}%$OYI=G23y{e;n_(F_O{|`G=-k zgf5|?bwsm;UsxmV1M;L_m;zf0TL)VLdy;tldL_!-Ql;$P2K%?DMO4kBaQ(98G1TIr z+Wdu7dS<0xxI?`C`Z0w6wMN-}1TkxC6{y{GaT@ML{K6tJCt??i*|5dyKBWAnW(eu5 zk@i!gbxIL+G>DWtylG5n2hqMf`_h`*u+{1C56w5Cry#lV?)dM0#DJX}vzY?~#KJMd-YQ zPQOwG9#J7Y>7OuAN;c{FpPfm`IW-2k{4V@4!APe>Xd5KCo(*@R_8;Hqq&~jkVqBEL zYlO?dC{6fJFnB+r!1KqdOrr35_&tnFpxr=z9+VeN0=OgL(sJ4a@aDp$Q|c0Y2I5NB zq|*&Vzsp-zW*_lmhp;sPT$jLg9Pzu>LyyQ#ZZvj1%E24BApOUhVodZw=5UOO zJ*YEruqCh)2B@7TFU_KMkcpuZ)TU~1D5pZBS`&ELT}5kF(^?ujXvP{<9S05Io@7-W za+9w|6wE-nYygUA%=HAcUvl^{>tiJ;btiAS9!a}IW!TrsBYl&ZB?_@&>9kw!O(kS( zh=MFk#)c@cusP}>eB+^^;g|qy5_1bSM@_yq9QwmZXm2D`6ncg(^(axI2dCM4NBYcL zLrV0SxN8Lnzc55)tXL%J%i;1I-%vU;!95p&l9>lidE%49_bGhD9SwH}+^J^GOAB%bzcmmjK4BYxGD&)M<&ZpQz`yvO~))L3d@Id(ElY0 zX|T&+Pb7Yf9X0X89tZmX>;z&XJ{ER&<4l>1hgjb$h`s0EVqJrj zCdQ*PllI$zlsfYP^pb56m+C1}$|Hl(Ie&JahhFvJR1f@^s^Vv zx0XN;T^zY9IpY$AMS%D`g7EEwRQiSy87KvAEUVcy6CNyHwH*PSieSuo?fVK_C9d z4(bt}FzCd8+@NCGb@vtzH3c^#88*;|UpA&)US$2pYD#A<2KtJ;arJJ{;S_l%Z|>fC z)1BafZWdra|2kB~E7~SQABW5=_bi$(y^L`EfikM5QV{z9shxlZe+Y%2&Ij<{ua`Vxc(TTH8&ug zAqpRbQb)o%Ln$M!4?|dikT*>o^@xHNs7qvCdnXjzmSkl-%IQE`nfz5ll}iJp+=SqEHOn1W{-N z9)T$QDzt>GvO+_M%oac{!2d(|zuU7AGtKeJ>AZ`gq4!1JW==|?`?zF1bGU&a=5Lth>_RKEfP(ndShdssJ6#7`i zwT!y2hlJ;Z@~j6?o08Dlo|%!9y3i@VoW>jjJDOh7LnBpkD9c*5UE(3`M0}YBV7-dM z*TMNc=~kV&K~zR&&@Y1WoLlZWJqDzrLK8|rgOp&OgOs5l?p=-}H% zpF5-H6!2YfM+u}?QTRvjl(>ZMyiu#f9s^I5(o~cvyglp!x~m9|rMHcLcSrX?GB!fb zq(Ji-#S^T=Hz41R%x5nF=SHv*$tHq#q^a6#omlw{?g~<>_FxncRJU|@DGf^z3P@&XFGD?V*4mlw%uT4eAz>Fkg3&&q4nY@$6pqyW=dPe zL&uv)P5D~P*-K@vATkuqxIaZ`y69+m(wgOXyhv^TT%-)-q<=5ai_^qPYqzW2Q-)I{ z>x&0Pit@dW8w_F1n)ndl?P56t>bvk3Uk%PJ(%6qU zWO#p@&sE6y>cN?J#Bn>~{x*2T&UrMBJh(p})Y$W^IYk-=O0H*ozZ+zLB^ZVC^bzFv zT9|J9%uL=&TU;k5QHjo}c(W{+H1ZX5&$U83N0-`3=r(HSL~BM-8L0>I*cB!y+Y{Ty zV~@8!SM7?2RwelpDgr<&NJWogDNTQP>}l7E`*!%?;}$=m8<&iQsUW&pN(98dBF2SmWiV zIiz(VpXnocKz0mwtK>XMr9TTNJnB_8?|iAu%^omqKZD&|N}kEI zD&FE*Xf5!MRpKUB&-ND5pZ8JhLCB&NLEX7!zcBvvsT|xSb8g+(?O^UOc_1el3>O6NqFPS1O?XN$;BscQj-XpAeGnv>A6IHU1?g8&6|=^QHFio6V>Xo!C;8U zGucb&K2;15Q>kT`JC=zt8k_g+R5Rp*jOIr4$O<#P*JzR)NJwCMJqhVEncj7I>@>3& z<9cpsbRQi}?wofHtUNI?i*+0$-vE8Wj+d$B86L&)BZqCDZV_*O(-h z&9a6)R_R{ISw&>5sH`&`ON_%BaH#Y~)LqT9^^(1l`B(TUJh$%%zT4NL`6y1p`h&8S zUCgwyt}1BxQ8oA9>$2Xsm&gPE315py8Lr~V^NIZ9#b1f3owtFDX)YwWhQAntFQyCD zw`{`~1AW!S_>Kg(;0wJP!8QmBra>os-XP|a!5W@DxL)_i?f54BM1RYlo_d7vA3#3P zIA8K5;W}u9JYzk7fL~t>9J@_TWvk53VSgOMmlr*U8pQBTrEKF~F}@k!^hQb|*Fb8| z;x>oQ0;ch_yWC|(rNz6}zJD)4Ub?%u%6k=vLsy}LQu9cPDCt}#GW8R#Fw@3%m1-(Y z^^jTPGz5?LcfAV5RkPL7c5}zth_1>NRrBBOFp6Bga3ApDK8aTl3sNnJz_5s+D%6+zhz1?2Yrd^50#4$AZB zU<{GQ*bGUx8+g7??t$)1Ji*{TZ4UNU+(8pRr5N`c&8;grOs z5uYvkP%sc^G;6JY!OVV}pFPsQJ(aogSC0iQInXCUI%A2p7 z&0;k8EModKn!Q0^|5qZ{xm!)olFq3xv(x&Qke(;)W28F=gm;IrrbwUq_x@)=zw>p6 z!=ruB^}BHRTl7B#+1nt!6!vI8++nTaRdw7R$zI0yQlOH2{{U!x^)~dm$viV1NV!L2 z+}yzrFi%*wN9UE97|4r}HEnm$?D>UtwqK&@y;pKjZMGUo|BD&ve~#ie?>(fJHI}Yb znHk?hf&1{prl1Qm<28R~%Q`DG%B~3u(ZKj9$87F~UQ7djNi-`N;6bX;y2zJ`*-r0G zij-IqSc2yl2Z_e{25crNyOd8Q<*z8+6YwzGnl~Sj|XW zrT>lxU9g`DU<|cL>)C_k$;Sfz2N~bi07gH`boh-$Bu#Xvpv}OOSxgtww0td!F4_aW z3YS$RdZ-jFrJ(JS^o#tM4UVuFBLs1h%zbQdc-CWl#etYU1$(V526GHaT@8d(Xj?#< zS$?v<=K6`Y06ecTi|mofDC_TmwvCK$dLX^18u6b63))KgG=yIbk~+AKkUCTzksc^S zY+@vjSii*gS5a;KNnWrJ$(&aPKz}oJJzwNctPZCo~+^G4!DYPU|zx>dJ$d zpFXSF+eYgkCqpsXT^Q?wLJ`r#qTf)w!Sa!KTrYtB@306$PMD+-aH1!>r{B8PTkRz( zhafyY6qQNybl1F0o7)DA+*dc=YrC7D)^e}q4oISK*f%NLKH#NockwH&irar<>^uM0 zmfIcJ$$7GQarH!zRaP14uBLUdo|UPEZPT))-AC8y%oycWX}QP}*l*JEyYl6+JVu=iR#J#4CLo=3MK&S@Ui!K9Sg_nL2M^ z;fa;0N7s>Br<%2!1>yRjsb}ZZ9ydLwX&sfOGpjepSqgfjWFP)4*+Y=ML^SpcMi{b3 zA-o@T2qU!Q1qdsFA++z4MU?y=*jr#GMdUpHC-<*QJ1XaCgg!zd>nTkimGvAHy8Zh# zf{;GAO*5uXM$^ESJLrc-KD`5+J)<0FN{`~l*xixXq-^PV6>vJ2&5;6sk=76j)TkUN z`d}fIF2ii4wBEsgTL$h&xgNdcp24yf1vnI-lO<#TM-6l*grY2i!e2l+Ps%@abH*dz zx-;6OgsxL42-n(SS6#uoo*#M7$6%9F2#36Gf-p)*x(U1e7GSod;#ozHP{US?fx z`4*frgTm2}9?}!gR}o6eUyRrf21yCuyZ2&$ekZt3{s5dl%J-~`<-up4qrnPD&++#V zZj4VL>&y9)vEF9#0^!G*Ea8)MTTEYz1NBSAC@0$+B_~`XCqpc+21myoJl((%`u`y+ zbGdtMV0V9`aWS;~C@9+37AEpCjPFA~l{vqwTT~(p{LzuH*AX_S>kMuJ4oPjkB$f?I z_qW!Sb*$l&q*M8m4(Y{o3wY+X*5lR?I9YjJ;F;4{qSL8L;v43fivgNGJsUEv-O1RU zE3+ivmy-}&Id`&)@g&>|7k2}^f94ZKz z?VvW1{%1?=8Q!12h&KQEHy~$0A`f;9;U{3oH*ubh1&7F3w8#YTR-B0-$8gwr5{;x1 zXd}&M4`3I9nGo^<<<4Z?5n%a{dw4yxjL~`7PQrh}`NE*(k3PHV|M{%*$7h}GN-L+& z15U%qk@E7GVN8xld0XU_$!Vn~s=r2mz$m|LsT_5m!fiA`a;1og=oKXEZ$*jDQBhQu z8eO>yUoEVNZejUbJyUkvzvI;%R~IJ6v5jMj-j-N_mZ?eI$WB<_lPODNq-*g)OJI()U9mnfQ+$}aZ z4w!p?X#IWPT&Yscn@GNQnaA?CS~WlB{CnWxjplkg;=-*7Kj!;R>+f4X?VBqZ&3hK| z9uF>)v7m{L=WSkDRf~`n#ltDbrIWPn8v8bacya+U>`Q6!% zACfn=@<8QhpbMV8@yagX@j-WSQ&qHKQCK%Z6q!tY*&}YIMpG+)fvZF2~LaH)x zLsZIhM)n+~Te?k&vuyU0xZCME+_v#apzC%=0i}28wir-1GPkLmWH!(n1VQ})18myQ zxGyeU!VIBrC-teoxP70Q2UZpLHkFYsGHa+k?}$=L%PXjtQ$MAkvVKjV0&xv7fixX`wMzHG-i zbur`8ZHWsE9C@cXwnB`>h!c0fu_UE8slIUm=g!%q)(1NKh&vXdFQh!-XyftBwe2U8PSh*nZ z;Nv7^tnlAnPHYp_MlWu^rXy_u;`9i!`mgp#hu13f#B*)rySiYG!4MsQmr!@Yr8`|sN>0jq+_pkAUiQ+ZN1j%b2td#VkxeMWk6Uk`2wAt}rGo)c-^6g$xs zT9R*`?{P=gzZxR{Dx6+oT~ea62ZSp@S`!j>M|4rvx)xc(S`|MoEdx8nheRMjI<3XD zHo?L2zmipL<1Q9DS#8xeMqA~)TgF{H_@pKEz&2J>wk!cWLyE4(CpqoGWs6fk2i{TH zGIuJIdvM#iRw=?}+dgpAOGlrOAvRtr$MaEe)uqxi4{ZCqH5%^i+vV8V#!ltj!+FOb z?BJ8oJRfUG?L=?o;wCRbi6ZTR)XdD5ZA$G-#Q#d1zlp@#d}aeJ}jeM02y%)+LX}A2>p!gCrBH=LGG79ec1PIPBMcaIO20LpdqoBQ{_?+P@ZStLs}#+aa&HxK2#f*El{C zH8|HKivLIc-Szi(l#4XXP|0&~Q6$$)QTBfk9sw8Z>P$u>bU&&Ox|#^4z2Z zFYbiR)ie(r3F>Q6v-e1(l>LRf#B`MMxtOWHC43t>H{HSC626GINJ$6$i5{wc4rH`R z55qko${>0C^c=gL0nW%~>m(;BkC{;zDX(?t7ic$6Mcqg_wW1#7tXp?WI2ralNXmE> zHYwo&zv6$Ca0n%MDn`@yJh-L=JztMmzH6VjU&Ca9gTs~5Qj$+)sX$Y|$C_$4V?0xk z0SApf%#8GU0aDAur$3u*4!(oI*XEL=9qu10LA^Bg`WD`5L_3!k)`$g~YR6^N?EbLE zA=lm#$|811Q2T%FF+aLs?Ovz=95ut#nUC%DPC(bi|K~ zq|AgXWhCXmAW6w&k8!I?JP+;@^@wB9hUFWPOQbDt3D=1FK#XT&R|4KT(HD%nvn#=> z1cqDo$>Dc%4-VHZG&mi&T0We$`(OrOurz5>vF^Mq8Sc-dA0LCC$h4n<@qn)TUoiD> ze=X*_GZm*nRR@4msKO2!E}Plbf<{6w1d z7HHxpN`{e6-UXF*%FsUOa3?qqOm;1JDQe*(A;%XnLDs|q2c-&>lZoUA{q@ zGH6jA4*Sagz%Pg2 zH-vYTuoozunos5-DU|7VD?QtR0MrSIctu`%c1+hj7L}RW@wDvbMM#f;Is)k~NRa%q21%ca$$oUdxK*E7vGLJ;V#dr*(PyDIPe0xIo>)Pv?RgX4s>rcQ z`|RLZl>+&&w?f*#CNX;*?c>pQQ!KQv*gv_5_BDu;t&@vXcHhIa?*+sVj2PNC*PjMm z;p9vo;g1k$xeD_?IZG10hg7T!96h`?Sa1P$1?$3G#2H|6;HMCukMv~RJpupxKT`6R z&nWp{{!Ga)AdEx$QtSgbq&tRmwHP=5M0hvc`LHRf++1>JoVg3`FXM^~>9Ca%tSuH? z^#p56=8mx{Ea1=?Pf!m+LiJgkg?-}&nM`@N#40TTx}q#3ED*!O?L*gll-S>s_hc|5OPKQ&@%v^9rq59S4zJsGxYt|wF5}I z3qh;K_#UjZZHJE!RpQ?i+OhpHNGCjIA@T_!VNR$3GBdPqJN8AZ-FNa*{-UUK0Y8SP zeUBh)5qRGp#@)(AF{$~Ys5){{Osx-rqD}5u@U8vImIsilDzpKJ$wdBw=GVio43$OV z%Mia7emUaH5dSvfSHn+*N+az z{GOm3j7`fzZ9B?!Fa2?%*0h?xv)*}Omm^W{Z9 zc#yqoX*sn5e8(`P&m_T~3`6ema$(;IL*y=q%ps9+nGgRxFobXU0oa76c^m9%7$Rr& zOW41HA^oliHrcbc!2Sg09LyD%UYHOJZDEQ8;p`boP8ssS13v6Ob%vaw74X}9E(47e zZ=Hdz7>t?W_+w{?%quy+4*L)P=r1^}DY*d5tO<4Rw7w}-UA!RvS)*<_Q0Ho`Ul8v( zR0pk98tArCe%bomvSIhzdZ14LnVJp8>pl_B>a(R2@YH8W^@(zfbvLBu&x>cM^P*4b z0!~F|Yn|)7*sN>~_W9_bGVNoeENDlp{<0%2fX zoBN$3m@93{2o?|NFV54q1c_L1GO0wjBc`p%1*C|D(<^^}!$sY~{N=LxU3Oisqw}u2ZbB24vMn3Pj|^~KoQBiTNepv7xkpq~E0~ z?4xKl5DS+nAi1%kFxK;GpGFdkRCE@?Lzx{VxRoMtovOvX*Ei8VYQF3u+AQ`8@IasH zrKn%@(lii)CZ(Kj0nJ=-zDT~-tEX(!@l=z( z{Shz6O`4l}S&<)mh3iY=K0%I}0O!LqHw<3f*#x*7^MN;`Z~vrEF%pY&CPGQE*O3hBoxXjKmyMeUK4RQA z;mwz=mbeX6QDJ6BA$pCzJ?W;4o7+L(bj9o2Nn6kN4HXs+IBB#vrEe$st0Vc4GEzYq zXZTVtr0F`Ac-dJb=fVNdd5COlr2Q!1526PSxYl!hxg7G4z|f^V|L1rm%Ci7HfTXz# zX^i-a*Jzt}CJf`8)RExZX=?E8v{m`+i=7MhqJ*Rl;vX)H*xtsNUgsFL;3z&%rRpeNwwaR#X4`v zQq*LYD$-ts_--bA!Gf+MLFTWdb*=`Pze|0T(Gz6<4!`tjkiGjb-c!}F$VbN>>kD)5 zK?m{rn})62xwYO!u@4vWy;7;s`+IGncllzQ_fw6*dvB@D``78G`UVws9cOQP9+}t; z8Q0-{A3NIbo$V-v=P{}cUWP*L=u^F`xsN(7^eQBUUT(3oozx9Ah^6OJH{Nn3_1zZt z-{jsOt?NY3q&UsoS?I$lqkULHVT2C%V@W^B6Df^aq*nHxccRDMGWJU8d%dPuj3n=Q zC&?qyyYU={=OmPcK?L;}-NsJWo&B;88O~&|B05=|A`?f?kc~;`a7`ZJq zk|O%YXA6HezR>CsUnT8q|G)RC*TrMK5)S3Zl5t1oVaivB8Jx|-zGV4)Z(^d!o3IX} zCT+eqe(Zd&@;;lFnjDL|zKpxn{YEoH&^h!X=G-c|&6~@-r@jx;&cklofJ=$BIOn}y zCUzT6UTGcgskiY4uYwv$`)}c^|3moU{}6tKTJDv`s=91m32HWOn+>{;Y~GI{Pq1W* z&HE9?UutTno6N*9?m{mWnR(E{CGYi+FwDs&+!XxSyXW0H@$Ttf7PA}btN8ic?rg{V zE?R`ODd|7FSo;NV(1o1_aub01bApZpUeme&;PLQvg(?fhx z@-=788yI|-gr)WT)Gu}peEKeY;HnyP0zE;pbD;O#gdVKIOu|hnVeGm1i;oOcZaLXo zu_WP=&HFo@39GcpTe=kUl1+#CMTHsAxggS~7NC5+#Elq(yyFr4kA_nn#Z>$`l3)C} zF+b)Pd*SE#k-SFJlYAI(B82s$A*4R7eI8SK2RO}Auk;PA9&-tO8Q4LcOo_MD*@`*C z02&>}D>#*%|Est+kBhom|G>{@W?+UzS=?A$2GB%61;%}2W*7z#5Cq&S7&f602yn?t zM#UoS-fJ#pYF%$xS$0!UDl0E$R$6xN;Bv2Pak~}Prc*)gdZEm}o z9q(a2!!G0gts3{sYV?yBPJ$Hnh{c!c1?im4a7u?}=8D8*rp9W-x10G;zCSk~?=#xo z=}>q#w0lb!Rtax6vG%hWnc9H(kDE;DfOzK&wi#TxHyObz2m8d0q$g6UBhBJrr6DHb zRA!>NPSK>$S0wIi3$Yd@RidlM@iTfUCr7g{5sH5s&~ zGrnCisB2g~VO`}6&uB}fnRXz&?N$Zx>+l}kX389knYKA=7kcAvK)ERhYgW!%EeW9d zg^V?U*L?IW-}tu0euu1Fj5p+jHKNagrevmRyZqQHoW9~%UPq0jKVrTpPLPAj7#ku;3t!OeN-mVZZ}&#flNU0soQwu4DD!uo(} zNHxuAi(zW4IkVbQr8EOlEvQWqKULDC7PN+&(`%xhvKw^t2GElk?y&R0?h4FR-rS#B zy~WxFG*Nv$P0@%I&=iB;Yt5)R&IM8F#P=v#f2Aw*&jSaf4~HIk!}_{b0y~Moq|GUi zk^(om52U-__na8@$={cAiRsmLse~k*EJ<%uD`!H^#;o`@Kfm}k-(e)<9oktaW+&Pg`;2dTt$i`%_aJ=F3%=*!I|yI1;A@8O77OO64M&e|Y3|29 zpp0WXv}*L7fw72Mg<7O0_V-(3X6ye~+3p>btpYNt>3-@MNvWp0;+R6eu9a{ZBo^15 z3V&JaeYt2P z%(g77H>o!+Z)#|lvbv`8qh>XgV-G1tE@AAY@j%j?)25DcYo<}*4scD>zfG`@=0#&= ztzMxw=pC&-jSkBNywy!=^2G^opVMi);%A4Y+ky9KN~U~>SHOOblh)>#_CK^1$DaS8 zUHTo``Cp}_IyH3I(|sf?16Tvzjk7@3%9We}_TPL$_vx{$^IwvZ0qK zFR#J8JTRj<^KzZd2J-mzjK-R(PCasp!G;eD{}>}AdZy+a&6-%BIba2G-UnNb|D>P% zBW!V+-FfUrZIK-J{+Q%9`NxWM#Vf=0V}uj!I2DZB^|-FXR(2FOuEg%vebDZyC~5cd z`20uqEZzY8>9_F>y@=Oy$SOOEblI={PkbtaO~RW_pEI3*F|zS2@=WJG;|RQq^wG1( zxaRHJ<<}efwsfV`V-~{5C$-Rs__7*L9QQ`WPx5{r_g!#S|Mf>2V6_ah=tyY4Jn(Nrz*e(d@SQBdxkqvRN``s?HIF_+6ZJ*kjm_Zhj9pN^+Vyt>StzY?3-=8qFQX zI>i02Q8E|nXD!1H^&POTMsMwDB{RIfQr?GEaC*5sX6CCb6u5TOe3V0uTo0-*by|+=y=siH9uxaKIv(ir=zUQg?p<#+^UNCHN4$7j6T{1ggM?2e*s?)>juky4?`kERN+oXvf zCMd3tYWJ2yCaT~|A0`A|m&{qMgG>@$w=(X_cDejd^u#RnyzFL*(2s7-)A#={SMS^E z-lw?tw6^EcBV$>ZUuzI7G3}4ZYAv;u6M(} zAQl-9jm#pAv@EOtqC@Gf>~p`z^~t*=ee!PBC+`^>AL9LCFTBcN@18;s_RWkm6w-bc!2)(%RX5vac3;s5WmgdIUe<{bmD)y&?C^?s$hO zw=(GA2=p3GvmJWq5y;SMB$u{B56>HO_0OX1?{&Ic{Si}Q5%^0uh8`0|b%`;W4;bG> zUG||a+BT-W&)qosW9_)?|PdZ`cZ3^pXXhUtU zht<0;q0P$+=Q$Gat|xwff~3#AQ+7Q#(7VGiz5Mb!`Y#1d;CmF-5h@R>Tkp8O9o7`+ z!l?w=^|(McXhPoQG5Q49`h3SK3A+Ft_%rE%+rrCwQyy%1J=D5K=ocY<9=7MzO7x5e zyg#9*$UiAM*FT9X4l!34xLl2d%k@bOP%3kMl6{gCxjsoIo|)9eED_76bl8vn+h4!Q zSdH%vczCb@7>7I7@vbbuSEBX+QN}p+aJ(v~eKWdg@j6)H9Y^I%{?VAU`*@e-X79Ir z#;!l6Ugs6L_%2Smn{~Fpb}r71NZq#Av#^cVTk-m9C zT|kUX|CgQ$Dp>i{V7Uc1o^mO-AaIkj+?AUK%Pn|mlS{dUHxM#dZed`Jv)mOmgXI?P zuW>22@Oq82+@PYxEqnL^7;{>&emhO6H{ztxSPCbYwAM^~3QEc`Lq_Uk3&eYW{8g-1lfD%Lo&($g913yn^|^v?cPmGq zgJr=;?95U`(|3A{Wgbs-E>e2?FgW=Xq1~4E`cJ{iV0dn1{S|(A$QGQ8JkvSz=>Xlq zw3lEN`W!!;bKC8P?mz_2foe4Ks{9~;73vTVC?*Bb3E*=M}UPm95*q6psL z)^l*JYtlDMJf6aTJ;dVMKXf>RG@x@N4Pw}mLIovOLaenFyr_TlMhI{lRuv1-} z8=#l$vRkb9GD>l{-nWYFmV3B??{02H?vdOQXoI99+v`KvLHj6kBJUObE&tqKqME}? zaHIQeZkEHc2f5!Zc3^*zu-D#Pgq#0l`Xqc;chGU$gbwAd|eD~HS2or6oUf7L&HW;r4|y0cG0mVOT!x!bydzI# zZqB4Wai^Jb;vz?*)Fb#lbH4Jtis~Rmd%hFn#N&Y8_Ud z_@!|F7UI=Hy8I6Gw;Fp1q5#lvC5u>KVj)-f!;3xjpCrxf<<1=EPsXsGmQAtP+r`2b z@sj9=v5WP?lw8zJ!ep_~|A-Bl_`cgA;l6J^0WP?RQO#TVuS49>_x>Jo0(Z!umva%g z_wj>}NAUY$$lLh+7$JX)L9LXiRW!I4YIHJY5C4yl*HYT*FY{+O)Wk1#0>hci9`jbv z75Mgfjw4?Zu=6pytvx+2K|VhR{ek2|Ibo;EHY@m#Imz$y3#wxeY!5oj?+ZD}@Aq3- zcS29T{UHZnm-}GIW#9*6x?xBE3U7*W(|;NifRn3sOQPcnf5p#zr`@t2*tN~)c+=v2 zI9)8?IbFXgeM1iBFNgdkyJd&N_w!(?eIa%eJMi6oLzb*X-tn=t zbY|PCwoF61Y({&IWV-ugsa5*Xhs~?f3c_%5)f!nR$H|~o@dvD3)}tNCULJ4JYNXqu z?f^K`mH*DK2 zSNb_~F7RmV1X*bhO?F3GnPe71{$c0L+xo{Q<9;a#@%#n+PxW6xA3n@`N`mDxt_CD| zywz>_#CDBWWKhk*5$m1)ftuyxWPZ}2&3excZ?7A?%$Gu6x3dtmw@{NmqXlF>HxkUv z?n!Bw1E`-+-=IEn7eM=Mys^*544ls5Vqf2GkGDKJWUSlrjIFr%D(+RGIz53pZ58UY z4)s_L$|L~?G^%ed>iJVY3vmN}&vA(M_2N6C-Qw$*q`v?hJ)GIGuaA5R z_`KnhI4;1wkkpNP8ZST&0TTCpm>ccxkf!BHFG?}K5vg~Of?D$$Y=NHRl@gzQSNQNs&b$*jOv{|Kq1zIPTUF2T;Syhj zL?L9Wji^e28U;aQ0^7nCU=gHmT;Nwi^(nZQE_5jDa%=rh^hSqB+BNu$MR!{6YIu!T<2Ed9 zsI=t-ZgV4Fx8?7>WhsxO1)z*1l#wL)6r+kRwg-23Ug1+?@x5voGylQZ$Y;a`xU-I* zjk%EM3VFrVy?kcq!zuptd-<%;IrS{`9G@M^g$7l#&{|M}pTyk1SQ-h7d&W#yF_Ot^ z`OH}NX50ebGxD+2P|o~9udaoI1!(vyW@D!}_N4VqoYxy^@ zwm-)o0eA1j>K5)n$T|La{DA9JQa=c)UVY zrF!bb+EDag8Tu}rMV;RF$9dG3Xod(Xe-(bEw=e!+CIMEF*Y^bL@j3*I_U5eGl#a*1a1(w~3?%Dqg z#y`8Iub)3f<$4#~f?LX-}lNW2Mn#IwzdZ@AY8%h464>1SEpvE_1zwBUcI{0zjRwiCZp%5umF%b3C!5^#OY|dfqd4vp z%=GEoVYXW~Tes-L8)PkZ*rnK_Z$u7u%X%wrgA=6qIqs*TQ;l|5i*b&$C;H;RcNsKf z6UOvtBgy&%;%^pWy^B~$puE~Q9kEs+)}#FuMpeqRw6VolJK|cYZ0Qxg#lMlir#zm> zTk`s@@ON+@Wv*#FEZW?~m!RR1ORmwgqE~kI#AVsp2%<{#E!(p8c-X zPYnNB2=7KOlz`q1+gMWNThCs?yKF(1IpH3=dB41OTt_-i=dDSXX+J6LvmzT^M~nC2 ziKH9$#d*uo-p|1c!%q0_+H>h2;RZH!$1k;ecysL8Gr54kH8L;hvfQQ}%I3%|IJFLnEfgn!qxT0r8KLeB+4320i^bTb;#Ax4>!x?> z7|-5bbf%#j>wWj0?kZURz&!Rs-y4EW06W(A&KB8geGM)0O&{8Z>`o*85nej^+vaFx zw`Dz#eX^EAe7D7joxLn;gjwpQZ2l)o)^ygX_G`Va`y#x657&c#J_Pu~0{#p?9Qblr zQVft#+R^YW7V_GNyjH?SB2#Tm!z$YR=gks?#q*855~-(Px31e#%u7L=&2NIt=+^CY zvzt_AYV5rzp|hTDEmwJ2Smv|X31}v67xNz#ACT8vtxDU&E5af-;FKswH-9XQj|jou zzs{4q=P-9zmvEkpjN|AXqGV!I!`Uur=&1N^+7E|ZrtpY|)LiVY23W)p_84Mqqe7ml zvI!5xj|kg~(~@)W4!yvm%hK*>wDwwNq1OKVTxA!mE_zr;Wf&VgC%Q%N#Kv#p%Z(35 z$Um{3^_C_ra#Fi2eGVC@Ux6x9{gd~VKJ+ZCmsB}VwUX_*&+5a2`YpZvEL5G+Z&_t` zNAK~$$p>@4MDK;MU^eiL4ya^HwvIFDxyUASi{5HXDohTpef<Gd?l=-Nb)ytc|1d>C|T!`V`F(G#^kOGYa?$HDfJtTY%GE zzSldHtRHJSlUS1;yB!ucoh!LuE1p-)aT=V}H9sk=KTCPLWtNrd7bi$(pZm}&=djBX zyF9as@yyKQw8n$YM{rLC#&6(Dal5TOI>Q~6jIW!3UZl}`($ zJ(*0Y6MC^mwAN#mI0D}S_#_zrecp3g5hh1ZvlM0_AvOq zw6iJiG%ZqQ0XN%y-l86KvezHJ(_*Uc?LqLpC#L$w9tz(vJDdDYQ-X3C@T>MN%*E7` z!XrbP|A@C87!4}6q7CS&olgDEn=lIT_S)aK_S}09PjGHl-&`gkdAx5AKuDe4%{mg+ z4k_O*%b&1D?2dgBw`y}3r^avYvIO;C<)c)OFZ?uUx7J;+?tBY+r3hnT+xSHQUD#FL z8*VJdn`wY_K!VCM485mw8=o5H@4t;tLmXeCbZz4^RM5(hU{DtW3sCKnZ{ydgq*o>* zkM*hzEwaexnp9!2g72XuNIeU7F+SOAHRIke`SNtL`_Q3Q1;0E+-u{eypS7!3Y7ML- zJRM&q&_2UFfHyV3ij29IFRF_3tmRi%d0W}2p;o!&XP;WWFzZF<`RA&FPqt;rnkWkFVdF4S1PULH(+HPmA{97 zPBkuV)hWCKk#<>rw(aF#o<{RTWGxrYI-_f^@cY6>rLl-rSS37H6<2?iKd4gQdq1Wt zXouG8S_a;nQA$b3HssS~Ic3|%AF7IP*~|Y$)g|P~g?z^EL(5R;+qNz|p-mI}-`5xE z&lX4h&iFz=O56~saL@l%b+hhqMgS z)6Ifhw4aXXL_^pxD$!5hW!Yyt#~(!B>5hFDS|y1LZpJ$t)u;8J@kdm_#cwbCjDH9D z99Ip~?R&D%QjQhY5!JrOyDXb+MCDW-*tx>OJ_Fuu$q=luE!n(>KdEwBj!WPCQriAS zSNRVhx5c)*kPKmokl@E*s^U!%zRi-*;P7qyN#t-wKyPpZcJ`zn7v>_Ct#Qr#J_c`xGAygUrp z#jvMRRJ=b6IJJ$xC{6E{=HmUT>UhtYarIdYaTHj z@2RU>3t5KU{pG)DdB=J{}>fwcn|w4 zetn0%O|e6sN9>~%J7gE$XuV;)3F|vo(U;hykFh6611oSEd@XiI-0?0n>|w~YSz_?) zgQpJF_7)bhwFPU}*n*HvaNGQ%!Z6!*JP!OPKfZM@|Fw#2NYS0*(#UP_)i!aE@7I`H zzgDe?kHjqhtvsoT!;F>GB#Burr*(W%lPu;2{GKs?#_#Z$vF=Gt;W5|T=yxS31u^6B zdp_nBP`IA+kL^P^*R%1l8-m+sSmpE^(z}hh)2Oa~erBb+zp&P(c@3vkakuiu$LQW% z;21Oe@&k1=E(PjFx6oOUPxx*8x%^<^ogF=|(EMXc;}kSEIVC*=Pn0yzdR%SfN2(~d z74bI9>llHNQuQr=x8Ww<72cL^>e+O35C3=7kwq+WLHCBEZwhO{P2E*TyDY_h|Kv?r z30$lCG^o5y>hVwhit3BtPlFus@Oe6X++a81`s3+sH#W{ZMQeU(Grj#<(7og+y@&pm zPd$s9UGC-LHrCu}uW099dOrCUe@oTCJc@_u@^okUmSHRE&bxVC+2Iy(bqC6QSf1Uq zJ!L!W>mp2r+pqL>3-Nrjo8Ce9TK=Tp@ojE&czA5TwPwJ7+b zr}<~5kt7emjuf5e_Qkm#qG81|Eo%|o#=0*ty#57H=*CbA$q-hKZrEYEN1)0u-aZ5C zmd}h2J*CI<#M2mK(@e;JxF6d8FR&FC)GVFkeod1Szlcsd2Q;bh^n`m&XUiwauIZBL z6n_BrcAsgGhWlRAz%LQ}o-IUizotr=F-T)A(O6@^c38_g{R@1q?C%Z7wcgji;crRb zW6?Tw9m5&LfZ}z!&-oT97t_}Ir}~BU-~_h1>HObttT|YyTgyzMflEBKv}{EvwSAcB zWbgUdlf9pZ#)i0BmD`PP$#`4RakJq<1MM{O(g!Z|s;7B40&j1wgkg>u?~&qpiVMZF zD4v_28&4EjO6V!yg`e^}$HOi|i*#Wxo^5C@pmQb{MLj3IKMXht_z-Xg@HyZh;1EEK zIpZQ+TEAW9Zw=eSh6b*yTjwsn!bLxsa<*YNpF8|{ZO64gx18wxJTGuc$ZbD9v|=~E z=Z@U$Zh3Tdhf6BMSuSr2X^=|%!bGT!0=nn~#Zz4|h z`?#|({1$F)n=#?W@8|QPGoPCS`Kc&oz7#BJK3#?11YLdI;`FKaP`{lx3uXm@-GgrZyz?U_U2qY?vtQ%e3B(=RpP)|afU{K4^C`F-Q9mPV}h=bU2UaotysI#(O@ zd}xa#d|0~Fgq0+07D!t*J{gMHc~AZm)eg(qkFN52R9!*1>!;k&{n1h9O5=%YtSEW8 z-kHNr-Z-_U`>#h~pAz2&-};F3hheQw>wDiu7PcGrAzpm&9PSV6#W_cbPO9IHlTffD z5Zu>_JwR+oN`-I_V(o*GfvfPWE|qeTJ08TYwrT$jShvC5EOqCmz^A$sgg0z>DsF35 z;wEIAl|UJE<}y@2Yy*d0(${?P!7C_*MfElNp1#l^(c{L%xxw{2aNn^nc0{mAR#O06 z!9r6ci?B8a1aY$}5`AzFxz!C8<&yP^1N#zLxa6kPR5p5oK1%=J)+E|9^2brIhhWx> zDR$Stv&KhnJC&hi=Kt_V3TtzZu94;Haz`6(0Xt}T&~S9kt-OPIN7p=yZj$RLc9zBD;y@m@z-Wu40{s3D(mF7mpDc|Do6EZz4Y_IaskK(yU7t}Xu z`H zdX(UGfai_}V6qdYarQ(wfJn}}18;h*H#U#6{h zuQ!bKqchEaBHk2X$6E;}J&$f2rk5>r(|hZEizh+j$$E~%QrSdum!xpGxl-8gA^0mA zzaBjS?`Ra$y(iCV@}9sZyX)g_{y{tcatJKf2Ixcdf2sE>UKKp_idQ7=@5;Rx@O8$x zmglsR=DcD_Zcs}~ael71eq@WcKDqeE))8bY18+Z>c_OdOorJd!3^tPEM|1iSrgNjm zqo?2&(&h=dvJNj6Hb#lv8J`AunO17Q%cwXVtv3WQvlqT<{I}UVOqGlM+2}84Ft>aR znAPZ>%EH{ROEWANEr~oO&0)pT`pDc_r_UqY17{-h>jQKpdhBYr=8G@h6^U*s-Z(2r zI~UQ9Q-DUKyR}=7bNW%YPjooaWjFgRt9j>5i6!8ErWLY+ zjZ(Icd&v*CgL<0w*K>G}{|o<9D+_^55Sw_bBJM(?FF5~h<;?%)3A@$G%q_O-DD#?6 za$I!dnXWIg4|mi^$3{|V%3I4v2j3hSncmjC*5mdkT_YLognnV(A+;M?m#iE4(TQYO zn(nuR@Z3&rUkI=up7>RvS5u6B%XfX`p6MDXL+%;6ZYDd^@d6v)hh5B*Z<%hO?0NZk zZ{9e@rJey|J#CgQ$NhSKiZoINn|3Bi_)wFnp6biYMxjpaR8!P>ttb}?BN?n2sHYJ3 z5!=672SRfBX0hHCjoWc9otY2tp{efrJ-ztOuacT@q3kj3v!cu~{tWR-3D(C=SN`cF};4)a?^7~feF$4VZjnv{NIyU9V^u8v=trHzj=J?$>(czuL zx@wItC-J8_c>Xlr_I7=3gnbZTXF9($I=`pdEd6$R$JK9+ zTPP(`S{;8(##wrM2=E@qbHMKk_%Dv_!0!n7kB&Ovw*>q@j;DcN6Y$%P+GMhW2EStq zs9y=xOAaIOF9iIeV-xTu0skD|sy8jRSw6%!)o^fI$gb z!GYd^ki+&#xSuK-*k6!>`oRk9LYW2sOF|AfOAps(*=2Xi;04D@a09<%1qyg{Wj1Qq6Eg zBIig!R?&`0z{3PQ!Z8u}H~}B;m;ii~fRA;A0Usvd0S@7IPjhzPII%^19AgnG5kfs2 zqk-G|sg0$MAmH}|oOFU(q(k_sYr}h7l3AzSA2GfMjpXnjxUi*wUtiSVMnCkb>88(x zIK?l1vt%{tbM$`W=O6K0v|#7)Hx?XyJ7U3<&tINzP({a0UdE|sHwUVVLta(gKzy=$ zaRU&7z5WdtXJJE6Kl~PSJE0Licm2>?_0aJ-raz66nwHpf6_ z3d}?p2T*=rJ*A&yqI7|#w}UQ?m=_Uvi%pt!lVqRhVCF`^%XV&Rlu0r*)WncWC~CB+ zKLo#zQw^q!xH%4aj!pUrdnEbOJgj~4YG&U0H)o!bsa+`dQxi8e*hD>P1mgH1?L(pz zmQfxU;rY|^V$a=R$_uUhX~|S?q){M^%;bsqG-LCpJ%9}W$u0TJl+z!nNEReR0MSS` zO?SQ;c?O`SwaZZ&t#x~}&mMQz578IgKC*C+cJwV4{${ee>n9`HzyFPt@xo2&?)n1L zVQ@B-S}T|Oibww;_}%+C>=_HtJMH`)MEbnjCm}EWjn)xQ#~p6}BAaCOsl#S@vtNp{ zMoPUKMzVHWy7?Jc`|0R6BJ?Ce_aR>ytaiBXLH`#+zr#KVIqZ8>;>!{;JH0oX=*gdDZ%WTMwmpVlORhn?#Q{V@r?L$7HjtvB~vQ zVXah+*sE>H_${!pDaE-!FCNZ zO+l^43sRtV9b=1te>B>_p(@UOxOFd#F5{$~M$*Bw@!E*olH6?EC#`O!eI=xuQ*(=R z@ts$i+&T{Fm~E^eRU5vkI;GlUrE#F!>dbFOYar?aKcp~Q;PHFd=GF*U3%W-JF-}+GEAM!6nY{f>2K8>zvS$RYpS1F) zhj%la;9A83C3F(8@9J6n`szM!rC5(ZJ~qn)^l$8p*L{q-P5u#A=iy}YdmTwR_*SD& zzG1UW6f9N0Y@|IxHp@!eB0;uGZE28bij}03VM_rXFW?Jp$-v_TTxUxJK2yLK*b;!N z1bi0ko-47Zi}X3xropKe(v!*1Bf0_EW(kKL5G4rwkv5Eki?KVyX7R%f5d2o+dZf)c zkNDeY9+3>!%c%PN#kzWM7+ZvK$)W4$r;I=a5745`Z z?j1GQ_24Y&R^R499$R1w$7Z?QH^AvN=!lck%T_0+pY=I8{RD0j;-1FchWu7oBHQV; z=w>VBNPgC|=wFF{y;toM^JM4lY1|OgOoP{Zb1;w0$A;bouuC4t*iN{!;%Hp__PEz> zZmwka<*`Xk!^V7o^DJS@e^ z$6P5nIA14gf5wBGj&WHL`i^JI3hdK@T&>*9V_F?>+KuXgxuWw1Hxq9o25CLbiv6_v z_uDOs{ay#4F^YpM^jLaZonoSnO^^s-otxd-<#@tl9stj!ya!vw%f`UA5@eBqx@&N< zM&|LCge`h=^TH!)-tCZVdIGFGD)tXON^g{g?0z2aY@e0Ncgy!bd~}$O-q&XF8SjMM z9?~&QvGCX^-A>(*zowhZ7E^AaR#+RunD=ELjn*{Y1&ZZ(_1Ul&XN5iiJL8t|vLQB$ ztS7F1 z>aNwBJ#da==#dOQB>F7&GRF6@P6?hFf`i=m?b4m;kjvxy)6cj&WsDoL_EB!nbc=W(Y=)5 zxqJSN+kDia(6_(T-R7f>lJ@PA^STS|QjcL{q`Ta9m+Y4xK#O@SJSJ(cQ+&<)?i`2O zEr;B(&gzvMknU%Z8H=F}Uc+wUMu|hD8*l4KGgbCn}+F|n3CU@b60cL&^ZBDa}ALvdgyp7!;bn4RmfLgyo z`!)7AGV>mc@6Tvxb$LqID^jzWw1`F$M=$1oXwsW_?s`T;Eq_n2f{OJ&Z?n8-9eOmL zpTtNnj$7RidUSAZifKdNa^IuDPW}NN3axCiOrL(UY;=0tHpS=dPj4L3G0S7&(NA>g zZQDKf>8SoIcrWy`>RuXwK0{e$i<3Yh4*u4Av_s}~IYFlXsTuptcirZdhuHWNdg)%- zi}ddL1MDLhag#kTQ;+=wEpKXlZY}5CeOF-LE!G6!m3Z63b2C3oz&*kpGWVZvJbZ-V zt~zeoYY9ito8$RI58h~&zAXE5@j+=6!`Y*6?+!PA#SY?M4D-FOQ5A9ium2$E7qpx7 zt44w|5X!&*;2e)fTbG}b>o35^Jn#43nr`mhu|JTO!{W1?G(FC;<6So4)gRbob=NJ} zk=W+-@X;CX;+)Z(RXX?f?Vefuq35#otMt>~{zyL+-wMv_amV`#4eG(|VpvH`;b}&t zT216N_gx$HnI?5=T>bMy!F>aM>UA3l0Ow~9ZM%35@KXw*v~!WcV* zr#U+bY2A5}w;R7S;Y(g-q??P|noCE!x7WfNq+$lj9b?5l){}VG$);{H&DcNlfX6{v zHPC8;?#Mcn8=9M+E7>o>8=4$gU&cG8$!HIy=gk@KmX2mh%E_6_WiglOCZvz|ILP7s z%#3|j%V!QYS#f*DJF@m|ZiqR~YWbVv9hB!&Pvv;*&-hL5vu~D;p7E}0&Tj}g55)KV zReY)bLaY1!q3>k#6QUJ!NY~wW(On1)@1i^@^?7c-Vh)?sYjWT9<_}!h@E^Pm9Ax_M zN$-;ShQ6Jq*FwAZ{{XwutsV!d{>~b2Yh}u{tv2*Kao)$1cM_hwee^r^Qq24jcssGo z6e7&U4@1V(Z&vb?#An7Oe0Z|ek|aDurSlH}*9mwsKOXoz0gvZHfzNVm*3+5LP}3~* zZ<_UI^2sllIOItmR#XgDaN95l~bEq)G~N1b{zg7-$= z3J1;2KH$!Z{oWL+#2Y}GYcF4zGIiS2f5is>GHV7mBxClob&7fP%tn?FV3#HtzfHLH zvxeUOI-kt`g8L5K^@^MHTvU!H5OvofV>#WCu(>SdW$pS~jUBq2;+t4Q&Lo*wEmy#m z5w6Lx8vI%<7ac|5=o36GTP>eE3V?qk;Ab3pz#9epLq{&~V*-BC@i6eW>>9*>*YO}$ z?^M^f9IHS*D8zUTPxn^K3j+Q!p6;!dodW(Mp6;#K!%8JR?|5P~$uQMqwQR)`u+>tB z+t1R|viONOnXy5jti?0=5`H4HS}L%wCi*7Ti9^gs?Sv&DuOjj3_<>#){s<COYnH z;Nx&#`ODf#w_fWpNnh6LZc(ZXA+FW35UvrUDak^Q5{P@dgH4p-#5?Idqu7&$aw8zs;kVMwHH*>y$g2jkHHC%?ZyKzY(PExg91`TI!lZo+Ra}hD3u%4yoPKV>$1^+79HgCm^l=;&it(#vq<-_?ClKt`g{`P{9 zS4W(Fw4-eP-e+E(KkJYGng8|0)CJ)<%Qp+~WoPnZ4#$habF0G9|B9Q!w~Wo$OCW_Uvz{Zm+pTPBt4S)z)8VLL#2@hl zdje{%Spuy-1iKk0a2lSwB!kZ_MLTxCmb)eee!RmGzg)XqL%iFOc2*-&=_I&)eTaUz ziJp~*Tsn!T5ueLbIpT=rgW)Dn} zKriGs@nn~clO^;1(>fxFnJ4qZQIjP5tkc6gM*0l9k=mJ|dRgnIH{bR_=vaOTLT4k? zPwxf)NZtef82Du!fy`Oj8JvztMY}!#D)y4jb2xIfuMVNQVqY=!Q?&wiP&nK|Np+!j z{2O2Z58u=r^8jYTx$44#qBW0{RF$sgyd*Fcy%sKmOMmWw@$i#-ZZ2#~igZd>3%?K!mkK*P z$LWq2-NUo*#~;XVz@_vB2&eQixC3-5|IRFzbO@)vFF`vFcmePv;GsmO2n6)#VGkB? z8u0xOOpy%Q8sPKcP6Y^w&vNYeBHSqh5ZM1WV|RgjrlY&Tn&(tKZUVu;OhXy zr*Q&fWOtJQ7H_0-sY2!<^OSkXIGIEymC0moGKYgnIEh3emB=J+64y8gai)=aNIj)q zQcfztwS6+FoAh_mh;b0YjB&(@^Uv7y8$ZG*e1QHdSBxu!55#kIDO`**kUzPu<+=KQ zm5-SAf5OH526$pdk-s>^bO{r17eDdA5NDtaSDa{qpW+ixJh-lT2)IZW!hsK_iL=P2 z6CjN;mw~v>JOn@GM|n_OcI551$v*&1$KQ^i zFam-0YyV*Uf$)L&LR?BC#vk-k8O}c;KcpM@8}R>+JCL_a9!_3Fo+w<5LwWr+{UA+D z@9G!uU!`}}e=v?%pFzJ^ABN$VlQ0fnB4H%J4FeYA=^G_F1e{Sq*ppf8sYAyE7BUJcE1;czKuoLq=cb~8r!rZQr+$YFd zWGwJy>3sr|NZ9mWWcLY1v}MCxWVIFc&FcWq0sahl9`GXI0DwxOc`y!mA|M^G4Dc|Z z1n?N(alj^kz!iRI{$!YgsohCm2K?0aq%(pab1t>{*s%q|UntW{Lf95g2@`F&KMl!} zu{5ZIlBP=hSuN+sc8YKa?ji19v=#vPB{9Y1zhM4{n+zDtALY}Z5-?CcQPeJepugge z{G>Aj@kzM{)&sOgpg*CK{{}*UKs8N$9I7QtUZ&S%a}t@tSGg!5YuOTA)SNkt%?EF< zgU>3!i0e%83Gocq2loh%1Ox-305bp@Kq`P_zYH$5LoVD$0B>aDK6SWtfIk8D0bT{X z4FD%BGd(qRZbou;eA3(%nq_k}so8Tg%Bu)6=Poj=%bc5F1aibHpmwM zVgU@>9?nC{T>ljy&jEida0hfiv5ZqR?qG^2xY2+gpJNI=+!Vme$Cx4qZXuxL1XKJS ze60h%_&ihWhPw~&>~~D@1zggnHK1Pveg!c9eWthz_b0&KW~Ok!9lD%TEPq2``q_u%YI?0}5>#*J zf<)SE7g~%+o8v-D5^1TRMI-GdzzWbZ;LZb$+Ly-9B9W$cp;d`AotPiRGm5k%mv}FM zMlzTt#v`8J5NXpz8WnR=q|I=NcMi182n)v>NH`b=82h_Oi*=!06KV5YXy1vnNiMXX zMViWm#*4K1E;K3n9F-g4LK`B|rn%5YiL?bSv=Gp0k@nIUC(qOuri$_YDbhHE>%@51 zK%;dA#mf|FH(Y4BV%n=>TGE3u&@^zzi?X6=*eKF6Txh#R+F}=(9u{etF0>Co%S9g9 zpuGXT!t*~fiL~XQrGiE}c~?yPpi5frVJ9ySxzM~p(;XJsSENxt4;N{E zppguyFD(#h{w}m^F~8xUk?edYGFB|oMvD1WVjOx(OdBB5DDDA~_Fu98(qQ+7Nc+Ww zc3h;HU1%SImW247ppguUk>OV&t=olmTcq7{q5TXR$v^^LsLg88NK(uLMC%jFph@2w zG!1BU=L|VUz-Td^4e==LU8J2X((Ep@IM6mDyau{~tXLmlu}CwD`a<+1k@l2GQ-W3` z(l)v1Rh3Aq6=`@q!TtbRE!-`jQC?J!H$kIu2&P2_$Dz}pZ2|4?hzC&#W7Ah6?H^)( zl>Rnoo8eZ7eMSPj6Es?B<%KXMyh1(tL|VQ`BRNQNo$(4>Xr3ai(1kWkq!qc)!bI9? z7h04^D|Vqx2TcZE9s!NyPW@5`8u9$OSPvS9vP9Y!F0>-hNLJ@T8%VoBq^teV!REa{HV=86KO_~M&(=)X`5YW-+^`r zVNZgFDhkgTonpK_VmzXA2CVPkt^@6g-9hgNnXgEzcAr8=}V*M;UQ(jr}G0U~X>3r#7~;#_FqB5kq@ZHh>n z=|Y<((ljnKs!y~6@2Bzh0S|}@rtqZ~)^cCDQqE+)GNl3$6iiL;uhkTJEDOhTmf%;y zD;sm)&%v*7@so~vlb;^T6r7sE+35Rz3YU>z%pW{3@3CCKpdSeoE`B4$Cw~+tn5j*q$N)Zm;Iwn>%ZTgIvvu10w@wxpfAvZVCP%Oy16Vvla-a7l(_`CB_w1dWX@%&3A!}Ra=}eaUj{cdIWZ|ai}FcLMs|tm zOA|5|r6Xo~mQI<47}*J_326!0nJd8JlI-;CC5uo*R{A0h;!I&#k5^R}u2C+js4iJk zI7d05Kv`9oUtU&F6{TESURrHf?IcDhqo>3yRfbO}$WrDRs;dhtAD;y2#Ahr)lC-3a zQObhC>cV_{4MO^|s`ARJIk=v-O35_w@kz^&Zxx#|A)m!Ro?lw1%odA^QYOd7D-$X! zh3FFsqLe7PsARRWs$`>3EJ`pGJW^>WTV1G}u=aodQ~25qzoCPu(JfC!tFg37%2jCBwS^BU zCo8Lp%hxMcApl7pQaa-Zfk?TiTv@dij0)5!6%hlg*MB>4hOL2YoXKgB}HDC1fT8OH0pA&&

6r6m~5(L|Hc5?wq&CzJ`GR_t6;i<%;F&Oj z37wEQA10Y61(e~@RDA3tJQ@wodWCSv1DV32| zYAAb@kO(D2<1A7b4y&9C5QwdMEisPeNTrZDb(b*Zy28q;lJYVr1^K8El+HLJMW_jI zXN`n0n3^4fnb7=jmC??BLITP}Y!LVdMx)6>x&fcy8RAJ%Aw$aBP~jZiokU1@FfT!K z1fR&9xDXIYzxF{>Mf!k(yQU<8(iB4Fx(F8(3^;7@5{)iH_+8Gl$t*EBO^Xq4#SE+{ zm(O7O)D_8#5_6W}hpm_<(3Z3G`0VuMvjj(#k6#FjHnawbNvMG1(Rnw%388=Vs$ zj{#Qj&5q8|B_y(?*%&OHStT)yzB$?HG|nzfXSyYt)cEua8ZWa@U}}QsiC==DHw~+w zObmz4MYAC3?|GOy1oLwV8tc8PoMJRFgeedO0p~!yTz!TOPG4!^`oVUD zs4F+*pu0M2R$W+HxTX-ZPpWq$EaLVM*TmB<_!ZT4I!hoSSB;^aVsa^P+`c&vYD*|1x-wyK|qB*QwY^s=X_uj zsigR>)O_bMJ_q$GtQ6D#npR#^gxQR(!CIwceF=KsuTnTC1BPdm)nz%WAFnJIQA2*d zh^;ZK7O}i?^n@H*e*cOfEX99C!LnTFuR^cLDJg?WLJk=48I_PzT2X|F3Cn%z(1n;U zO40NbkiVv)D5nTIT@E!IAgmdnpdaNpJCfMlQKm>K!UQ7>E2|3`3LhL0*gz+TBH?i- zpLob|PJF)?;_Stgfv9)XXPv2>*$(=uD@$^)z^z<^fk7BBup)7)2lYYHFM4ofmHAFx zgj=|wqMX=)-WCY1KpP*jL2mKq+v z??o&BmNZbq`;llw#v@3+3k9R9Kv`X~CJzG>Mlf1@<>%*Ma4A@Cs4NsbXtBXo$j{$E zoxwTcQs~Ct_$YEdhK!;jA+0DTXtv;mG$=k0#lFJcBL50D#VgXL>FTVX>W2;rbP zUCdvU8g%+C5q=AVU#1-R3#Y#U&waPf_t$^e+bRBubdB)G{m!2=f>!v$M$rHHqi`kO z2>$>6M>|)(GUS(66^X1=JyuyQ;Mk+ia7LPa^@5uDTu`$tEAWvT_VZK?=o%K2r(s!7 zXxNN+cZzhzR+rszxGw|(+k)NC#&;ytT zxD7Z1xCzJu>;=38z&>mi57-IN0PKLpfPBDFz&C)80G|O2fcF980aP}&>M$)J4R8t2 z0&oW;1Ev7l0Q4P*_}B#)4WRtT0NO==JzV1ZO~3-cUBDK=bO7;A`B3>($6COTfP;Vv zzykpK)|&&^1R(xr1D*%`Q^ZM5St8yIm(o%`lx7D2W_bj8(hKmpfN=mG@FIY|Yf=4a zU*0|d?UVZjFcshjp!D?pnZ5_F0Z>|UX8?$we*ma0z5X13Cat0OkYa0IH`2upN*IAo)@rj{>X!%9CVEJpBRi5P&`tEComb z^!Kti$jevBC$aP#h5~|`x0XL94zZbmCSr6rZ^;2b<$_JitItm%Kv!* zY(d05yzhxPvJDZw(^11wmckG1Gj;xPri3uT9~r;T6^z7x45`CW9o%l^XOjqv|M+yfOL G9{(SFFd|0) diff --git a/obj/cleanflight_CC3D.hex b/obj/cleanflight_CC3D.hex deleted file mode 100644 index 1ae4812e89..0000000000 --- a/obj/cleanflight_CC3D.hex +++ /dev/null @@ -1,5002 +0,0 @@ -:020000040800F2 -:1000000000500020A1CC00084DCD0008B1B7000879 -:100010004DCD00084DCD00084DCD0008000000007A -:100020000000000000000000000000004DCD0008AE -:100030004DCD0008000000004DCD0008A1B700081C -:100040004DCD00084DCD00084DCD00084DCD000828 -:100050004DCD00084DCD00084DCD00084DCD000818 -:100060004DCD00084DCD00084DCD00084DCD000808 -:100070004DCD00084DCD00083DB600084DCD00081F -:1000800079B600084DCD00084DCD00084DCD0008D3 -:100090004DCD00084DCD00084DCD00084DCD0008D8 -:1000A0004DCD000851B500084DCD000861B50008E0 -:1000B00041B5000831B5000821B500084DCD000854 -:1000C0004DCD00084DCD00084DCD00084DCD0008A8 -:1000D0004DCD0008F9B500084DCD000871B50008F8 -:1000E0004DCD00084DCD00084DCD000800000000AA -:1000F0000000000000000000000000000000000000 -:0C01000000000000000000005FF808F1A3 -:100110002DE9F04F684B694C9FB02360002363606A -:1001200007F0CCF818B906F065FC07F0E9F80AF01A -:10013000D9FE00230893624D09930A934FF4E0130C -:100140000B932B685F4A43F48033917B2B60AB6940 -:10015000924643F01003AB612B6803F4003309931C -:10016000089B01330893099B1BB9089BB3F5A06F4B -:10017000F2D12A68524B12F4003201D0022315E06A -:10018000186840F00100186008922B6803F0020321 -:100190000993089B01330893099B1BB9089BB3F58E -:1001A000A06FF2D12B689F073BD501230A93464BE2 -:1001B00046481A6842F010021A601A6822F00302D8 -:1001C0001A601A6842F002021A606B686B606B6812 -:1001D0006B606B6843F480636B603D4B1A68043B53 -:1001E00022F070425A603B4A10606868904620F4E2 -:1001F0007C106860586840F000405860D86820F46F -:100200000040D8609B6813F4004F17BF324B4FF487 -:10021000E01313604FF480130B930A9B012B01D161 -:1002200017E0FEE7022B18D169B10B9BB3F5801FD5 -:1002300002D14FF4A01305E00B9BB3F5E01F02D1F0 -:100240004FF400130B936A680B9B134343F4803302 -:1002500002E06B6843F460136B602B6843F08073BB -:100260002B602A68164B9601FBD55A6822F00302D0 -:100270005A605A6842F002025A606B68104A03F0F2 -:100280000C03082B0593F8D15168144B01F00C01B5 -:10029000042903D0082905D00C4A01E0D8F8002031 -:1002A0001A6028E051685068C1F38341C00301F12E -:1002B000020117D40A4A1CE0BD1D0008A405002055 -:1002C000001002400C1A00200020024000127A00A8 -:1002D0000410014014000020001BB700840000201F -:1002E00000093D00526812F4003FD8F8002018BF02 -:1002F0005208514319606A68DFF844B3C2F303122D -:10030000424411791A681EAFCA401A60BB4B0026DE -:10031000CBF80830BA4BBB48CBF80C30AB69DFF8F0 -:10032000249343F00103AB616B6A43F080736B620B -:10033000AB6943F01C03AB614FF6FF7327F82C3D0C -:10034000394603928DF84E6002F048FAAE483946BD -:1003500002F044FA3946AD4802F040FAD9F80430C8 -:10036000384643F00073C9F8043005F0A1F8139B38 -:10037000A749039AB3FBF1F3A3604FF47A73B2FB7E -:10038000F3F2A44B013A5A60F0228BF823200722A3 -:100390009E6064201A6001F0FCFB9F483146A02259 -:1003A0000EF0DFFBD9F8043023F4406343F07063B0 -:1003B00043F40063C9F80430EB6943F00703EB61D1 -:1003C000AB6943F4006343F00C03AB613346934ED7 -:1003D0004FF0000906F10C0203F8029001330C2BD8 -:1003E000F5D1FF2333767376B376F376AB69DFF816 -:1003F00058B243F008039BE8030087E80300AB61B1 -:10040000814B08221A61139814A902F0E7F9AA692E -:100410004FF40043ADF84C3014238DF84E3042F0C9 -:10042000040202238DF84F307648AA6139460293C0 -:1004300002F0D4F97A497B4A48460BF1080B116067 -:1004400001F0B1FB9BE80300AA6987E8030042F0D2 -:100450000802AA61139814A902F0C0F908F050FA32 -:10046000DAF808B049460BF400600490102206F157 -:100470001C000EF076FB029B012207211BF4004FAB -:100480008DF83B908DF83A30ADF83820B277F1779F -:1004900006F11C090CD0032086F8202086F82120C4 -:1004A00086F8222086F82310ADF838001E4600E0BA -:1004B000164654480EA905F0B5F9049B9BB10223DA -:1004C00051480EA9ADF8383005F0ACF909230122E6 -:1004D00084F8283084F82A20731C072284F82960C5 -:1004E00084F82B20DEB26B694F4843F001036B6147 -:1004F000AB69DFF834B143F40073AB6104F060FF23 -:100500004A4B002513934A4B012E14930CBF2B46E4 -:10051000802318934FF4807319934FF480631A93D8 -:10052000202339461B9358464FF4005316961C93CC -:10053000159517951D9504F025FFDBF800303D4A11 -:1005400043F00103CBF800305368012E23F47023ED -:1005500094BF0021012123F4807343EA01235360F7 -:100560009168354B013E0B4043F4602343F0020396 -:100570009360D16AF6B221F4700141EA0656D66260 -:100580002846012309EB00018A78002A7AD02B4AF9 -:100590005D1C825CCF78092AEDB2264910D9A2F100 -:1005A0000A0606EB46064FF0070E0EFA06FEB740A7 -:1005B000D1F80CC02CEA0E0E4EEA0706CE600DE014 -:1005C00002EB42064FF0070E0EFA06FEB740D1F8D6 -:1005D00010C02CEA0E0E4EEA07060E61062B1549D6 -:1005E00034D8013B03EB83031F269E409A404F6B98 -:1005F00027EA060646EA02034B6344E000000008CF -:100600000005FA0500080140000C014000100140FF -:1006100040420F0010E000E0BC180020A4050020BC -:1006200059160008B4210020080002404C24014063 -:10063000D005002000240140FDF7F1FFC005002097 -:1006400000ED00E0000001402C0701080C2B0CD845 -:10065000073B03EB83031F269E409A400F6B27EA5C -:10066000060646EA02030B630DE00D3B03EB830332 -:100670001F269E409A40CF6A27EA060646EA0203F2 -:10068000CB6200E01D460430102801D02B4679E7EC -:10069000A74B9A6842F480729A609A6842F001020D -:1006A0009A609A6842F008029A609968A04A09071D -:1006B000FBD4936843F0040393609D4A936813F05E -:1006C0000403FAD19168BAF8E60041F4A001916000 -:1006D000984A50B9B2F9E83033B9B2F9EA30D3F1F7 -:1006E000010338BF002300E0034613F0010340F08C -:1006F000818088F8143000B20BF08CFD8E490BF02D -:10070000DDFD8C4F0646B7F9E8000BF083FD8A4902 -:100710000BF0D4FD0546B7F9EA000BF07BFD8649E6 -:100720000BF0CCFD814630460EF04AFC07463046C1 -:100730000EF0BAFC804628460EF042FC06462846DB -:100740000EF0B2FC054648460EF03AFC824648469A -:100750000EF0AAFC3946814650460BF0AFFD3946F3 -:10076000834648460BF0AAFD5146049040460BF0E4 -:10077000A5FD4946069040460BF0A0FD3146079086 -:1007800050460BF09BFD4946606306F100400BF0BC -:1007900095FD2946A063E56306980BF08FFD0146A1 -:1007A00004980BF083FC2946206407980BF086FD23 -:1007B000014658460BF078FC3146606408F1004071 -:1007C0000BF07CFD2946A06458460BF077FD0146EE -:1007D00007980BF069FC2946E06404980BF06EFD65 -:1007E000014606980BF062FC3946206530460BF056 -:1007F00065FD6065514E524A33684E4D43F0020329 -:100800003360136894F858A0B3F852B04D4B0021F0 -:10081000B5F8EE8095F8ED7019709946BAF1000FB1 -:1008200008D00023A4F85A30BAF1000F08D106F01E -:100830006FFE05E009F06CFC002800F0FA80F0E79C -:10084000B8F1140F19D009D8B8F1050F19D0B8F1C3 -:100850000A0F14D0B8F1000F0DD114E0B8F1BC0F9D -:1008600013D0B8F5807F04D0B8F1620F03D1022114 -:100870000CE000210AE0032108E0042106E0052144 -:1008800004E0062102E0072100E001212E4B1A209E -:100890001A8822F040021204120C1A801A8822F0E0 -:1008A00038021204120C42F030021A801A8892B2F6 -:1008B00042F040021A8006F01DFE012001F05EF9B0 -:1008C00013A805F063FF9DF94E30013303D19DF964 -:1008D0004C30013303D0B4F85A309BB21BB1002323 -:1008E000A4F85A30A5E0194C194B64202360194B29 -:1008F000A0466360184BE36001F04BF9042389F8CC -:10090000003033680120034304903360134C00230C -:10091000062F2370DFF848A024D0092F02D0002F23 -:1009200040D11FE0336823F0020333603AE000BF98 -:10093000002401400C1A002035FA8E3C8802002069 -:100940001802002032020020003001401C0200206A -:10095000B11900088D67000890C1793D9E02002002 -:10096000B1210020A34A92F8583033B10021A2F8F7 -:100970005A1053B906F0CCFD07E00392029309F038 -:10098000C7FB039A029B68B1F0E79B4B9B4A64202C -:100990001A609B4A5A6001F0FCF806238AF800307E -:1009A000042323709AF8003033B90FB11F46ADE726 -:1009B000336823F002033360336823F004023260AB -:1009C00095F8E2200AB189F8002095F8E3200AB1F1 -:1009D0008C490A7095F8E4200AB18B490A709A078D -:1009E00002D5854B1B689847D8F800309847336884 -:1009F000804C13F0080F19D00FFA8BF9642799FB7C -:100A0000F7F630460BF006FC824607FB169000B264 -:100A10000BF000FC7D490BF051FC014650460BF0F9 -:100A200045FB7B490BF04AFCE06505E00023E365EC -:100A300002E0032001F0E4F8764B08221A610A274D -:100A4000744E1920F368013F83F00803F36001F04E -:100A5000A0F8012001F0A7F8192001F09AF8002071 -:100A600001F0A1F817F0FF07EAD1082333616A4BC0 -:100A70006A4E1B6893F90C000BF0CCFB68490BF035 -:100A80001DFC0EF09DFA074630880BF0C3FB39467B -:100A90000BF014FC0EF0CAFA624B634F18803088DA -:100AA0000BF0B8FB014661480BF0BCFC60490BF051 -:100AB000B9FC5B492066D8F80C000BF0FFFB5D49E0 -:100AC0000BF0FCFB5C4B5D4A18606B795C4E13705D -:100AD00007EBC3035B7C5B4A3360AB6862669B06D3 -:100AE00044BF0123336009F0BDFF0EA8002114228A -:100AF0000EF037F86B790E2B01D0082B02D10123B1 -:100B00008DF84330AB685048C3F340028DF83D2068 -:100B1000C3F38041C3F380128DF83F208DF83E105F -:100B2000C3F3403231688DF83820C3F3C03200314E -:100B30008DF83A20C3F3C02218BF01218DF83B2065 -:100B4000C3F300428DF840208DF8411003F00102FC -:100B500001688DF8392091F8B011B5F8E000C1F3C3 -:100B600080018DF84210ADF84600B5F8DE104FF464 -:100B70007A70ADF84800D804ADF8441004D5334B72 -:100B8000B3F8DA30ADF84830B1F5FA7F84BF00230E -:100B9000ADF84830B5F81A312D49ADF84A3095F81E -:100BA000223184F86830002384F869304B709DF856 -:100BB0004330002B14BF0223002302B1013307EBA3 -:100BC0008303D3F8C8304FF000090693CA4606994C -:100BD0004FF6FF7231F809309342D9B23AD194F806 -:100BE000693084F86B30154B1F78162F40F0BC81AC -:100BF00000268EE1A40500208C020020A119000827 -:100C0000296700089E020020B82100208988883CBE -:100C100000002041000C0140D8020020000000200C -:100C200035FA8E3CFC0200202C0701080AE81C4122 -:100C300000401C46BD378635D4020020E803002062 -:100C4000E40300201C1A0020180200200C1A0020C7 -:100C50000D060020B54A9DF83C004FEA011802EB52 -:100C6000080618B1881E012840F23D819DF83F001A -:100C700028B152F80800AE4FB84200F034819DF818 -:100C8000400028B152F80800A94FB84200F02B816B -:100C90009DF83A0010B1012900F025819DF83D70C2 -:100CA00017B1042900F01F819DF83B7017B103298B -:100CB00000F0198110B1052900F015811B0A022BE3 -:100CC0009DF8380003D1002808BF002303E0012B62 -:100CD00008BF9DF839309DF841703FB19DF84370D1 -:100CE00027B9A1F10807012F98BF04239DF842708E -:100CF00037B19DF843701FB90439032998BF042305 -:100D0000A8B1D91EC9B2012909D852F80810B1F109 -:100D1000804F00F0E8808648814252D1E3E0022B08 -:100D200005D152F8083083498B424CD1DBE0012BCE -:100D300047D19DF83E303BB152F808307D498B4297 -:100D400004BF032384F86C30FF23F17B84F8B430B4 -:100D500084F8B530B3680027706884F8B870C4F8B8 -:100D6000C460ADF84C308DF84E10022313A98DF8F5 -:100D70004F3084F870706767A767E767C4F8B07092 -:100D800084F8B67084F8B770039201F027FD039AD7 -:100D9000317B52F808003A4604F0F8FC30463946F8 -:100DA000012206F00BFC644B6449C4F8C830644B64 -:100DB000C4F8D070C4F8CC3030460A1D09F01CFCD1 -:100DC00091E0022B3DD15FFA8AF31C2159435D4823 -:100DD0004FF0000B4718012387F801A087F802B0F5 -:100DE00087F80AB04354B16896F80FE0ADF84C109C -:100DF00002217068FE608DF84F1013A98DF84EE047 -:100E00000293039201F0EAFC039A317B52F8080046 -:100E10005A4604F0BBFC029B30461A46594606F07F -:100E2000CDFB494BC7F818B03B61484B30467B615E -:100E300007F1100107F1140209F0DEFB0AF1010AC3 -:100E400051E0032B36D19DF83E3033B194F86A70EF -:100E5000304608214FF6FF721CE0BDF8443094F88C -:100E60006A70B3F5FA7F0FD9394A3046B2FBF3F214 -:100E70000821BDF8483092B206F0BBFB04EB8707AF -:100E8000C7F89801334B0EE0334A3046B2FBF3F219 -:100E9000012192B2BDF8483006F0ABFB04EB8707A6 -:100EA0002E4BC7F89801C36094F86A30013384F878 -:100EB0006A3018E0042B16D1BDF84630264A304679 -:100EC00092FBF3F20121BDF84A3092B294F86970B6 -:100ED00006F08FFB94F8693004EB87070133C7F8FD -:100EE000C80184F8693009F10209B9F1180F7FF4DB -:100EF0006EAE74E61A4B06EB030E98E80F008EE810 -:100F00000F00184B10361A78C02E02F101021A7029 -:100F100008D0636E0021985903EB06080BF062FBC2 -:100F20000028E7D0AB68DB043CD437E0F01D0108B3 -:100F30000004004000080040791800086C060020FA -:100F40005D1900085C060020C95700084D1800080C -:100F500000127A007D19000840420F006D19000848 -:100F60008C07002084210020AB4BAC4A03EBC70365 -:100F700093F810C0D3F8148082F800C0B8F1000FC5 -:100F8000D0D000266645CDDAA54A330103EB020E28 -:100F900043440FCB01368EE80F00F3E7082FA14B37 -:100FA00028D129E09D4B93F80090B9F1010FF5D9B4 -:100FB0009D4E4FF00008C84506F11006EEDA56F8CF -:100FC000100C4FF07C510BF079F94FF07C5146F842 -:100FD000100C56F8140C0BF071F94FF07C5146F8D8 -:100FE000140C56F80C0C0BF069F908F1010846F8DE -:100FF0000C0CE0E70E2F03D11A7842F0100202E049 -:101000001A7822F010021A7004F0B8FF8749884B52 -:101010008848894AC4F8AC3201600023B5F81A0147 -:10102000C4F8A812A4F8B23284F8B432C4F8B822D2 -:10103000C4F8BC22814958520233242BFAD1804B88 -:101040001A60AB681E0740F181807E4B002293F846 -:101050001831042B74D8DFE803F003032A505F0033 -:10106000012B4FF0030208D184F8C022072284F834 -:10107000C23284F8C1220C2308E0022384F8C03273 -:10108000002384F8C23284F8C122072384F8C332D3 -:1010900000230093102001236B494FF4E13207F045 -:1010A000CDFB6A4BC4F8C802C4F8CC3244E001233B -:1010B000674A684900931020052307F0BFFBC4F876 -:1010C000D0020646B5F81A010BF0A4F862490BF0FD -:1010D000F5F862490AF0E8FF0BF0DCFA0023604AF9 -:1010E00098500433402BFAD15E4B301CC4F8CC32FC -:1010F0004FF0100384F8C3321FE000920123102048 -:1011000059494FF4E13207F099FB584BC4F8D40227 -:10111000C4F8CC3210230DE0009201231020544972 -:101120004FF4E13207F08AFB524BC4F8D802C4F8FE -:10113000CC32082384F8C332003018BF012028B90C -:10114000082001F022F90023C4F8CC32AB6858041F -:1011500005D5082284F8C322474AC4F8CC2242F2BB -:1011600001021A4003F0010103F400505AB1434A4E -:10117000C4F8CC2218B1424A082082F8C30211B147 -:101180000C2284F8C32294F8C32213F0800FA2F13A -:10119000040284F8C4222B4D00F08480384B05F5FE -:1011A0009672D5F83811C3F8DC2200231A4A02EBF4 -:1011B0000310D0F804011646884204D00133DBB294 -:1011C000042BF3D9002384F8E1322E4B0020C4F81D -:1011D000FC3209F01BFB2C4B94F8E1221B68002128 -:1011E000C4F8E83295F8283106EB02128B42C4F8B5 -:1011F000E4124FF020000091D2F804210CBF01232B -:10120000032307F01BFBC4F8000300283ED1802015 -:1012100001F0BBF83DE000BF2C070108842100204D -:101220008C070020FE020020940700201C1B0020D9 -:101230000408010804010020500800206205002075 -:10124000080200200C1A0020354F0008814E0008CB -:10125000A086010041500008CDCCCC3F0000B04436 -:101260002401002001160008CD4F0008254F00087A -:10127000814F0008114F00082D160008391600088C -:10128000A4050020341B0020081A0020012009F0CA -:10129000BDFA864B1868864B00F5D97204301A6087 -:1012A00001F09CF9834B8449D4F8B8220B60803359 -:1012B000C4F80433814B824F1A60AB680026D9030F -:1012C0003E7040F1B4804FF00108DFF828B201F021 -:1012D000C1F840F22A3A01F0F9F801F0D3F887F8A2 -:1012E0000080784F5246314658460DF03AFCBB69B3 -:1012F0004FF0100943F00803BB6118238DF8333019 -:10130000714803230CA98DF83230ADF8309004F009 -:1013100089FAFB696D4D43F00203FB616C4BA7F644 -:1013200094771A686B4BB2FBF3F22B88013A23F4E3 -:101330005C7303FA09F323FA09F392B22B801D239D -:10134000AB852A85A5F814802B8C23F0010303FAC2 -:1013500009F323FA09F32B842B8CA9882A8B23F019 -:10136000020322F0730202FA09F203FA09F322FAE5 -:1013700009F223FA09F389B242F0600243EA080352 -:10138000A9802A83AE862B842B8B23F0080303FAD3 -:1013900009F323FA09F343F008032B83B5F844302B -:1013A0006FEA43436FEA53439BB2A5F84430D7F842 -:1013B000A83F43EA0803C7F8A83F384604F000F8FE -:1013C000454B38461393802318934FF48073199339 -:1013D00013A94FF400531C93CDF850B0CDF854909E -:1013E000CDF858A017961A961B961D9603F0CAFFC3 -:1013F000AB890DA89BB243F40073AB813B6843F00B -:1014000002033B608DF834908DF835808DF836609E -:101410008DF8378006F0B8FA304B1A68304BF2502E -:101420000436802EF8D109F011F809F00FF82D4F8D -:10143000BB685A0540F1908001F002F808B108201D -:1014400000E00420012105F08FFDBB6884F832061E -:1014500013F4806F244D02D1002104911DE02B680C -:101460001B78032B0FD12B681B78032B15D1082079 -:1014700005F0B3FE0146082005F0DCFC003018BF83 -:101480000120049009E0042005F0A7FE0146042095 -:1014900005F0D0FC0028E6D1DEE7144B049A2D6855 -:1014A0001A702B7843BB124B1D6049E018020020D4 -:1014B000D4030020601B0020DC04002088050020ED -:1014C000CE04002000100240000C01400004004047 -:1014D0008400002000366E0134040040EC06010850 -:1014E000E00400200C1A0020F4030020F003002088 -:1014F0001C040020AC080020012B21D1354E002116 -:1015000030462C22C4F834560DF02BFB8E2373701A -:101510004FF07C09E0234FF07D08F37086F80090CF -:1015200086F82B802C4E002130462C220DF019FB22 -:101530008A237370A02386F80090F37086F82B80BE -:101540002B78022B08BFC4F8385600F079FF08B199 -:10155000C4F83C5609F038FB00F0F6FA1F4B18604F -:101560007B79052B03D11E4B4FF4C8721A801D4B9B -:101570004FF47A721A801C4B1A7842F008021A70E3 -:101580001A4B1A7822F002021A70BB689B071ED50C -:10159000174B184A1D461A6004F060FA282000F024 -:1015A000F8FA059B013B0593F6D12968124B487860 -:1015B0001E7802460123964203D30133082B0244CE -:1015C000F9D10E4A13708A785343A4F840361FB0FD -:1015D000BDE8F08F300400205C04002048030020A8 -:1015E000A0020020AC210020FE020020B02100203B -:1015F00004040020101B00200804002080000020AC -:1016000008B5074B53F821000AF000FE05490AF01F -:1016100055FE05490AF04AFD0BF03CF880B208BDC2 -:10162000240100200000203F00005C44014B33F8FF -:101630001100704762050020014B33F8110070471C -:101640003E100020034B4FF4004208B11A6170476E -:101650005A61704700080140034B4FF4004208B143 -:101660005A6170471A61704700080140032810B59D -:101670000F4B0DD80F4A126894888C4208D2D2883A -:101680008A4205D9012202FA00F01A781043187034 -:101690001B780F2B0BD1064B00221A70064B998832 -:1016A00008B2142802DD1439998010BD9A8010BD4B -:1016B000E80B0020041A002050080020024B9A88F2 -:1016C00001329A80704700BF50080020074B1A680B -:1016D000074B1178B3F9040053780B4403EB8303F1 -:1016E0009842D4BF00200120704700BF041A002098 -:1016F00050080020064BB3F90400064B1B681B780A -:1017000003EB83039842D4BF00200120704700BF41 -:1017100050080020041A002010B50446FFF7EAFF25 -:10172000002814BF2046002000F0010010BD024B2D -:1017300001221A72704700BF50080020014B187A2E -:10174000704700BF50080020034BB3F90400D0F1EC -:10175000010038BF0020704750080020014B0022D4 -:101760009A8070475008002003685A1C0260197064 -:101770007047016B0346C26810B5406941B1196CEE -:10178000541A005D013918BF0A46C0B21A6410BD70 -:10179000196A405C0131B1FBF2F402FB1412C0B2D1 -:1017A0001A6210BD026B03691AB15168013B026CE9 -:1017B00002E0C169026A013B881A1840C0B2704752 -:1017C000436B13B190F844007047826A436AD31A9E -:1017D00058425841704743799B070AD5436A82694A -:1017E000D154426A03690132B2FBF3F103FB1123C6 -:1017F00043627047437913F0010307D0C368C1699E -:10180000026A013B881A1840C0B2704718467047F8 -:10181000437910B513F0010304460DD0FFF7EAFF3A -:1018200058B1226A6369985CE3680132B2FBF3F154 -:1018300003FB1123236210BD184610BD426A806A63 -:10184000131A5842584170474171704710F80A3CCA -:101850000133DBB20A2B00F80A3C0AD910F8123C1B -:1018600023B910F8131C034A22F81130002300F8A2 -:101870000A3C70473E100020344A10B5136C906843 -:101880001944334B1C7840F68C23E140081A9842E7 -:101890009160D060516013463CD9127893F945109D -:1018A0008A420BD1111F082908D893F8461018292D -:1018B00001D8013103E083F8442002E0002183F8DD -:1018C000461093F944108A421CD1204991F84710E0 -:1018D000C1B1002191421F4806DA03EB810424695B -:1018E00020F811400131F5E7511E00EB410116309F -:1018F000814203D0002421F8024FF9E71649087805 -:101900000130087083F84520002201211A7083F805 -:10191000471010BD92F84710B9B1A0F2EF2440F281 -:10192000DA518C4208D811780B2905D80B1D0131EA -:10193000117042F8230010BD002283F84720991847 -:1019400004320020302A0861F9D110BD14060020AD -:10195000100600203E10002070100020024B1A6C70 -:10196000013211441964704714060020024B53F8E9 -:1019700020301B68198070473C070020074BA1F5F9 -:101980007A7153F820304FF47A701A681B894B43F0 -:1019900093FBF0F39BB21380704700BF3C0700201D -:1019A000024B4FF480521A80704700BF00000020A5 -:1019B000704738B50C68054620460DF013F92146EE -:1019C00002462868BDE838400DF014B9034B1B6887 -:1019D000DA79511CD9711344187A7047A804002091 -:1019E00010B5FFF7F3FF0446FFF7F0FF04EB00200C -:1019F00080B210BD10B5FFF7F3FF0446FFF7F0FF0C -:101A000004EB004010BD094B5A6882420AD01A69A3 -:101A1000824206D0DA69824208BF183302D000231E -:101A200000E00C3300225A725A60704748000020D0 -:101A30000E4B1A7A824215D01A7D82420FD093F84B -:101A4000202082420DD003F124011A7A024001D0F5 -:101A500043B909E00C338B42F7D1104670470C3381 -:101A600000E0183358687047184670474800002057 -:101A70002DE9F0478278C6781E4BC2F1640802EB6C -:101A8000820C54425FFA88F84FEA4C0CC6F16409A4 -:101A9000A4B203F11807A5B228B2002804DC002D77 -:101AA00014BF1546012500E0454600FB00FA6D43D2 -:101AB0000AFB06FA9AFBF5F54D4468434FF00A0A13 -:101AC00090FBFAF0604480B258800D88B1F802A013 -:101AD00000B2C5EB0A0A00FB0AF04FF47A7A90FBD9 -:101AE000FAF0054423F8025F0A34BB42A4B2D2D113 -:101AF000BDE8F0870E0D002010B544780078002373 -:101B000003FB03F11939614301F6C4115943414301 -:101B100040F6C41291FBF2F1034A22F8131001338C -:101B2000072BEDD110BD00BFF80C002010B5044C00 -:101B30002068FFF7E1FF20680249BDE8104097E701 -:101B4000E0030020DC1A002010B5094A0949136897 -:101B50008C6812689342F8D1074A106811684FF4F4 -:101B60007A725043001BB0FBF1F002FB030010BD82 -:101B7000081A002010E000E0AC05002038B504464B -:101B8000FFF7E2FF0546FFF7DFFF401BA042FAD355 -:101B900038BD10B504462CB14FF47A70FFF7EEFF54 -:101BA000013CF8E710BD08B5014B1B68984708BD1C -:101BB000B42100202DE9F04106460F46904600254D -:101BC000EBB2434518D20024E3B2B3420FD20B4B21 -:101BD0000120DA68013482F00802DA60FFF7E3FFDF -:101BE0003846FFF7D6FF0020FFF7DDFFECE73C208B -:101BF000FFF7CFFF0135E3E7BDE8F081000C0140BE -:101C000040F2DB14604308B50A4B08221A61841EB7 -:101C1000084B2046DA6882F00802DA60FFF7B9FF65 -:101C20000120FFF7C0FF1920FFF7B3FF0020FFF7E7 -:101C3000BAFFEDE7000C014008B503685B699847FF -:101C400008BD08B503681B69984708BD08B5036857 -:101C5000DB68984708BD08B503689B68984708BDCE -:101C600008B503685B68984708BD10B5044C206848 -:101C7000FFF7F6FF18B12068FFF7EDFFF6E710BD9C -:101C80009004002008B503681B68984708BD064B00 -:101C900010B5044621461868FFF7F4FF034B1B6894 -:101CA0009A7954409C7110BDAC040020A804002017 -:101CB00038B5044624200D46FFF7E9FF4D20FFF715 -:101CC000E6FF002C084C0CBF3E202120FFF7DFFF71 -:101CD0002368002228469A71FFF7D9FF236893F8FA -:101CE0004900BDE83840D2E7A804002001460020A2 -:101CF000DEE7F8B50C4E0D4C0D4DC1B2074630680D -:101D00006170FFF7BFFF2B6861789A7930684A40AD -:101D10009A71C7F307216170FFF7B4FF2B686178F0 -:101D20009A794A409A71F8BDAC040020E80B002073 -:101D3000A8040020F8B5174D174C184F0646C1B23D -:101D40002868A170FFF79EFF3B68A1789A79286800 -:101D50004A409A71C6F30721A170FFF793FF3B68D1 -:101D6000A1789A7928684A409A71C6F30741A17010 -:101D7000FFF788FF3B68A1789A7928684A409A71F2 -:101D8000310EA170FFF77EFF3B68A1789A794A4037 -:101D90009A71F8BDAC040020E80B0020A8040020D4 -:101DA00010B5441E14F8011F21B1034B1868FFF74A -:101DB00069FFF7E710BD00BF5C180020014B1868F1 -:101DC00060E700BF28180020A0F17D03012B70B54B -:101DD00004460D460A4E05D830687D21FFF752FFB4 -:101DE00084F0200430682146FFF74CFF35B12B8882 -:101DF0001C4404EB142404F0FF042C8070BD00BFCD -:101E0000B804002038B5054C05465E212068FFF770 -:101E100039FF20682946BDE8384033E7F803002041 -:101E2000014B5E2118682DE7F803002010B50A4C1D -:101E30005E280146206805D15D21FFF723FF206859 -:101E40003E2105E05D2903D1FFF71CFF20683D21FD -:101E5000BDE8104016E700BFF803002010B50446A7 -:101E6000C0B2FFF7E3FFC4F30720BDE81040FFF75F -:101E7000DDBF064B1B6803EBC00090F9063019422A -:101E80000CBF01204FF0FF30704700BF84180020C6 -:101E90000A4B1A6802EBC002D379FF2B07D008491E -:101EA0000978994203D9074A32F8130004E0072859 -:101EB000D4BF908840F2DC5000B2704784180020F4 -:101EC00067080020620500202DE9F04F0C68836848 -:101ED00089B0D0F800A0D0F80480064620460393CD -:101EE0008B460DF06DF8074620460DF0DDF8DBF867 -:101EF0000440814620460DF063F8054620460DF06B -:101F0000D3F8DBF808200446104601920DF058F88B -:101F1000019A834610460DF0C7F83946029058469C -:101F20000AF0CCF93946049002980AF0C7F95946EC -:101F3000059048460AF0C2F90299069048460AF010 -:101F4000BDF92946079058460AF0B8F901465046AF -:101F50000AF0B4F92146834606980AF0AFF9014623 -:101F600005980AF0A3F8014640460AF0A7F9014691 -:101F700058460AF09BF82146834604980AF09EF9D9 -:101F8000014607980AF090F8014603980AF096F97E -:101F9000014658460AF08AF83060029905F100407F -:101FA0000AF08CF9014650460AF088F9214683462A -:101FB00007980AF083F9014604980AF075F801467B -:101FC00040460AF07BF9014658460AF06FF8214670 -:101FD000834605980AF072F9014606980AF066F8F9 -:101FE000014603980AF06AF9014658460AF05EF87D -:101FF0002146706050460AF061F92946044609F10D -:1020000000400AF05BF9014640460AF057F90146E4 -:1020100020460AF04BF83946044628460AF04EF9A5 -:10202000014603980AF04AF9014620460AF03EF8B4 -:10203000B06009B0BDE8F08F2DE9F84F2E4E044690 -:10204000376838460CF0BCFF054638460DF02CF8D2 -:102050007668804630460CF0B3FF834630460DF07C -:1020600023F8D4F804900646294648460AF026F993 -:10207000A7688246414638460AF020F90146504694 -:102080000AF012F82168824658460AF017F94146CC -:10209000044648460AF012F931460AF00FF90146A3 -:1020A00020460AF003F83146044638460AF006F99D -:1020B00029460AF003F90146204609F0F7FF0146D8 -:1020C00050460DF07FF80D490AF0F8F80C490AF077 -:1020D000A9F90C4B196809F0E9FF0B490AF0A2F9BC -:1020E0000CF0A4FF83B21A0444BF00F5B4739BB292 -:1020F00018B2BDE8F88F00BF000300200000E144E3 -:10210000DB0F49400006002000002041064B1B78F1 -:1021100003F0040303F0FF001BB1044B1888C0F365 -:10212000C01000F001007047B021002050030020D3 -:102130002DE9F04102780346202A00F10100F9D090 -:10214000092AF7D02D2A02D10346414D04E02B2A5B -:1021500008BF03464FF07E551E460024334616F84E -:10216000012BA2F13007F9B209290DD839492046CF -:102170000AF0A4F8044638460AF04CF80146204616 -:1021800009F094FF0446E9E72E2A17D1314F334670 -:1021900016F8010B3038C2B2092A0FD80AF03AF803 -:1021A00039460AF03FF90146204609F07FFF2949E8 -:1021B000044638460AF082F80746E8E71A7802F043 -:1021C000DF02452A38D15A782D2A02D1023301265E -:1021D00004E02B2A14BF013302330026013B002701 -:1021E00013F8012F303AD1B2092903D80A2101FB93 -:1021F0000727F5E7B7F59A7F28BF4FF49A77B846D7 -:102200004FF07E51B8F1070F07D9084612490AF07E -:1022100055F8A8F108080146F4E707F0070737B1B9 -:1022200008460C490AF04AF8013F0146F7E72EB18B -:1022300020460AF0F7F804E04FF07E5120460AF0FD -:102240003DF8014628460AF039F8BDE8F08100BFA4 -:10225000000080BF0000204120BCBE4CF0B501242E -:10226000B0FBF4F58D4201D34C43F9E70026DCB115 -:10227000B0FBF4F504FB1500B4FBF1F41EB9002D1E -:1022800001DC002CF3D1092D03F101075FFA85FC75 -:1022900004DD002A0CBF5725372500E030256544B2 -:1022A0001D7001363B46E2E71C70F0BDF0B501241D -:1022B000B0FBF4F58D4201D34C43F9E70026DCB1C5 -:1022C000B0FBF4F504FB1500B4FBF1F41EB9002DCE -:1022D00001DC002CF3D1092D03F101075FFA85FC25 -:1022E00004DD002A0CBF5725372500E03025654462 -:1022F0001D7001363B46E2E71C70F0BD70B5064626 -:10230000B6FBF2F40846154614B12046FFF7F6FF77 -:1023100005FB1464024B1B5D00F8013B70BD00BF60 -:102320008A1F01082DE9F041069C002B06460F4646 -:102330000CBF4FF020084FF03008234613F8011B64 -:1023400009B9154603E0002AFBDD013AF6E7002D46 -:1023500004DD30464146B847013DF8E714F8011B5B -:1023600011B13046B847F9E7BDE8F08180EAE07383 -:10237000A3EBE0738B4206DB002801DD401A7047B7 -:1023800002D00844704700207047034B9A6822EA45 -:1023900000009860704700BF0C1A00200E4B1B789D -:1023A000BBB10E4B1B681A78032A06D10C4B187868 -:1023B00002288CBF0020012070475B7823B1094BB5 -:1023C0001868C0F3C0407047074B1878C0F380000E -:1023D00070470120704700BFD60B0020F403002097 -:1023E000B40400204C030020B0210020114A30B575 -:1023F0000028B8BF4042104C90FBF2F304FB0300EE -:102400003C2568430D4D90FBF2F22D682D7B25B9DC -:1024100003EB830303EB830301E0C3EB031302EB42 -:10242000830304FB02020B804FF47A7392FBF3F2F6 -:102430004A8030BD80969800806967FF1C040020A8 -:10244000034B1B681878C31E58425841704700BFA1 -:10245000F4030020094A0A48002310B511680370EC -:102460001A46CC1864880CB9CC5C24B10433013210 -:10247000802BD2B2F5D1027010BD00BFDC04002069 -:102480006005002010B50B4B0B4819780B4BDA7820 -:102490004B085C1E047001F0010109480B440370F5 -:1024A00008495308581E087002F0010206491344F7 -:1024B0000B7010BD9905002094050020E80B00204A -:1024C000960500209705002095050020F0B50F4ADD -:1024D0000F4816780F4A00231768C3701A4619462A -:1024E0000546D0B2B0420CD217F8220001320409DE -:1024F0009C4200F00F00A8BF631C8842A8BF411C8B -:10250000EFE7EB70044B1970F0BD00BF60050020D1 -:10251000E80B0020DC04002099050020F8B5101A13 -:102520000C461F4609F076FE0546381B09F072FE80 -:10253000174B079E196809F0C1FE29460446284634 -:1025400009F0BCFE21460746204609F0B7FE0146C9 -:10255000384609F0ABFD0CF037FE0E4909F0AEFE2F -:102560000AF098F8069B2146186005F100400CF02F -:1025700029FE094909F0A2FE084909F097FD0AF071 -:1025800063F80028BCBF00F50C40A0303060F8BDF7 -:10259000300000202C7D8E3FA00CB34500A00C46DF -:1025A00010B509F037FE002104460AF043F808B1DF -:1025B000204601E004F10040054909F033FF0549D8 -:1025C00009F07CFE0CF0FCFC034B186010BD00BF52 -:1025D0008096184B35FA8E3C3000002070B50446CA -:1025E000007909F013FE1E4909F01CFF1D4D1E4E17 -:1025F0002860A07B09F00AFE194909F013FFEE607C -:102600006860607909F002FE184909F00BFF184D67 -:102610002860E07B09F0FAFD114909F003FF6860CA -:10262000607E09F0F3FD134909F0FCFEEE60A8603E -:10263000A07909F0EBFD0D4909F0F4FE0E4D28607C -:10264000207C09F0E3FD064909F0ECFE6860A07EFD -:1026500009F0DCFD074909F0E5FEEE60A86070BDF9 -:102660000000C842900F00200000FA440000204102 -:10267000A00F002000007A44C40F002044F25063F1 -:10268000984203DDA0F50C40A0387047034B9842F8 -:10269000BCBF00F50C40A030704700BFB0B9FFFFD1 -:1026A0002DE9F041038A87890446BFB20D461F40D9 -:1026B000002F36D0B7FA87F34FF00042DA40D2430A -:1026C00091B21B3B21821740042BF1D8DFE803F0C5 -:1026D000221F1C1903006B6A33B103F1FF3800237A -:1026E0001FFA88F86B6203E0B4F82C801FFA88F8B0 -:1026F0002E6A002EDCD03368304641469847766813 -:10270000F7E72868A18E08E06868218F05E0A868CF -:10271000A18F02E0E868B4F84010036889B29847D6 -:10272000C6E7BDE8F0810C4B800A98420CD003D874 -:10273000B0F5801F0ED00BE0084B984206D049330D -:10274000984205D10020704702207047032070474F -:10275000FE207047012070470100100002001000A9 -:1027600090F83B3210B57BB990F83A3290F83922A4 -:10277000934209D201219940B0F8404201332143EC -:10278000A0F84012DBB2F3E710BD8379012B03D12F -:10279000D1F1010138BF0021D0F834315A681B89CA -:1027A00009B11361704753617047044B53F82030EF -:1027B0001BB107289CBF1B68198070476C0700205D -:1027C00010B5054C00202188FFF7EFFF618801203C -:1027D000BDE81040E9E700BF6C0000202DE9F041A2 -:1027E0000F88002347FA03F2D2072BD58A7803F02B -:1027F000070512F0100F18BF91F803C002F00F0682 -:1028000018BF46EA0C06AD004FF00F0C0CFA05FCA1 -:1028100006FA05F5DC0850F82480282A28EA0C0C72 -:1028200045EA0C0540F8245005D101229A40C468BD -:1028300024EA020205E0482A04D101229A40C46831 -:102840002243C2600133102BCCD1BDE8F081034B91 -:102850001A88013292B21A80704700BFFE0500202C -:10286000A14A2DE9F04F1368A04903F59C43A04D00 -:1028700020330B60AB6885B013F4807F174604D01B -:102880009C4B1B681B681B699847AB6842F20104AC -:102890001C405CB9984E337873B1964B1B681B682B -:1028A0001B68984703F094FA347005E0934B1A784C -:1028B00001321A7003F08CFAAB68DA0405D5904B3C -:1028C0001B68DB0701D408F0EFFE8E4B3C681868EC -:1028D000037CCBB18C4A013B32F91300A0F57A702E -:1028E000B0F57A7FA8BF4FF47A7020EAE07009F063 -:1028F00091FC864909F096FD854909F0DFFC09F055 -:10290000C9FE7E4B588039E0AA68160436D57B4A4A -:102910005168611A002931DB04F59C412031516076 -:102920007C494E797C4931F81660417CB6B296FB01 -:10293000F1F0117A013101F00F0111720A44507265 -:1029400018466E4E06F109029A5C01331044102BB2 -:1029500080B2F6D100B290FBF3F000B26428A8BFB9 -:10296000642020EAE07009F055FC6C4909F05AFD3A -:10297000674909F0A3FC09F08DFE7080AB68D805AB -:1029800010D5674B9C42674C08D923681B681B6AAB -:10299000984718B923681B685B6A984723681B68C7 -:1029A0005B699847AA68DFF860A112F4805F504B1A -:1029B000B5F8DC10BAF9062007D0B3F81A31581A66 -:1029C000824207DD19448A4202E0B3F81C319A4280 -:1029D000C0F228840122002195F8238195F8240172 -:1029E000B5F81C61B5F81E710B463AF901409B0819 -:1029F000B442C4BF63F07F03DBB20231BC42B8BF54 -:102A000043F040030829F0D13C4C617E994204D147 -:102A1000A17EF92903D8013100E00021A176637677 -:102A2000414B374F1978A1B93B68D90707D582B90F -:102A30003E4B1B78DB070CD504F03EFA09E03B4B1C -:102A40001B785E0705D510B108F02EFE01E0002AC4 -:102A5000FAD0A37E294A142B354E40F09980334B8F -:102A600018F100081B7818BF4FF0010803F00403A9 -:102A700003F0FF0093B12C490B78002B00F0888005 -:102A8000537E5F2B01D108F00FFEB8F1000F7FD00D -:102A9000637E7D2B7CD108F007FE79E0537E572BB7 -:102AA0000BD1244B4FF47A721A80234B1B6813F01E -:102AB00008036DD1214A13806AE0A968490745D50A -:102AC0005A2B43D11E4B197819B1187001221D4B96 -:102AD0004DE0D17E1C4B81F00101D17609B1042279 -:102AE00045E0062243E000BFA02100200C020020A8 -:102AF0000C1A00200802002000010020EC0B00202E -:102B00004C030020040100206205002000007A44EC -:102B100000C07F44C0050020D00500200000C8424E -:102B2000404B4C005C0800202C000020B02100200D -:102B300018020020AC210020880200201803002089 -:102B4000CD020020CF020020CE0200205D2B00F03D -:102B5000EF825B2B00F0EE825E2B0AD10322EAE2C9 -:102B6000A72B40F00783AA4B1A7842F004021A7090 -:102B70000EE0562B01D105F067FFA64A1378002B13 -:102B800000F0EF82637E6F2B40F0E58204F094F951 -:102B9000AB68590731D5E37E9BB19F4B1B785A0731 -:102BA0000FD59E4BBAF90620B3F81C319A4208DDC6 -:102BB0003B6813F0010304D1994A32211180994AEC -:102BC000D3763B68DB030AD5974B1A782AB9974A24 -:102BD000127812B9924A3221118001220CE0934BF3 -:102BE0001A7852B18C4A127802F0040202F0FF0106 -:102BF0001AB919708E4B01221A70D6F80090002372 -:102C000009F1750B3B6009F1770698460BF1020359 -:102C100003EB080113F808204B7816F8010C9A42D0 -:102C20000AD2314607F0EEFB30B116F8023C012221 -:102C30009A403B6813433B6008F10408B8F1A00FC9 -:102C400006F10406E2D17B4B1B7843B13B68DFF809 -:102C5000FC8113F0020F784E40F09A818FE109F267 -:102C60001512019209F58B769846019A16F8010C17 -:102C7000531C03EB080113F808204B789A4228D222 -:102C8000314607F0BFFB20B3B0786C4B013800EB46 -:102C9000400096F804B018444FF00C0CF3780CFB8D -:102CA0000BFC00935F4B03F11C0909EB0C014A6814 -:102CB00082420ED0009A09F80C2000228A6001227C -:102CC00002FA0BFB93F84C20486022EA0B0B83F8C6 -:102CD0004CB008F10608B8F1480F06F10606C4D159 -:102CE000574BDFF86C811E68564B4FF00009D3F844 -:102CF00000B0D8F80030002B00F038811978002996 -:102D000000F03481D8F80420C2EB0B02002A0CDB5F -:102D10000BF5FA72C8F80420012202FA09F294F8BD -:102D20004C0020EA020284F84C2018F8040C5A786F -:102D30000430C0B2002A40F0E1803AF91020B5F822 -:102D40001A0100F1C80C624501DD9B7813E0C83818 -:102D5000824202DA9B785B420DE0012303FA09F319 -:102D600094F84C2022EA030384F84C300BF5FA73F4 -:102D7000C8F80430FAE094F84C2042FA09F2D0077F -:102D800000F1F480002B304ACCBF02200120013931 -:102D900010700A2900F2E280DFE801F0060F1B281C -:102DA000315C6E80929CA60032781344FA2BA8BF47 -:102DB000FA2323EAE373337007E072781344642B39 -:102DC000A8BF642323EAE37373703046FEF794FED2 -:102DD000C4E0F27830461344642BA8BF642323EA8E -:102DE000E373F370216DFEF743FEB7E032791344CD -:102DF000642BA8BF642323EAE3733371AEE07279D6 -:102E00001344642BA8BF642323EAE3737371A5E022 -:102E1000FE0200202C000020B02100200C1A00200F -:102E2000B4020020EC0B0020CC020020CD020020D8 -:102E3000CF020020AF21002050030020540D0108D4 -:102E4000E0030020081A0020CE02002088020020A3 -:102E50000C0C0020616D4A781A44C82AA8BFC82209 -:102E600022EAE2724A700A781344C82BA8BFC8232A -:102E700023EAE3730B7071E0616DCA7A1A44C82AC1 -:102E8000A8BFC82222EAE272CA728A7A1344C82B07 -:102E9000A8BFC82323EAE3738B725FE0616D4A7DAC -:102EA0001A44C82AA8BFC82222EAE2724A750A7DDB -:102EB0001344C82BA8BFC82323EAE3730B754DE066 -:102EC000626D91780B44C82BA8BFC82323EAE37333 -:102ED000937043E0626D117B0B44C82BA8BFC823DD -:102EE00023EAE373137339E0626D917D0B44C82BC1 -:102EF000A8BFC82323EAE37393752FE0012A2DD1DD -:102F00003AF910009B784FF49662B0F5617F92FB1E -:102F1000F3F305DB40F633029042B8BF024601E00E -:102F20004FF46172A2F5617292FBF3F3DBB2AB4A2C -:102F3000581C0C29107011D194F858209A420DD0C9 -:102F4000A74A042B28BF02230A2184F8583001FB2A -:102F50000323A44A06331360FEF7E8FD012303FAB6 -:102F600009F394F84C20134384F84C3009F101091B -:102F7000B9F1040F08F10C087FF4BBAE66E6AB684C -:102F8000DB0514D5984B1B681B689B68984770B18C -:102F9000D8F800309A070AD5338813F001020CD113 -:102FA000924943F00103E26522660B8006E0338814 -:102FB000012223F00103338000E000223B68580720 -:102FC00010D57AB1328822F0010102F0020289B2F2 -:102FD00092B2318052B9E2652266844A41F0020120 -:102FE000118003E0328822F002023280D8F80020FB -:102FF000910640F188807E4A127892077CD57D4AFE -:103000001278042A78D913F4007C328812D002F0A6 -:1030100010039BB2002B76D1744922F0200242F0BB -:10302000100275480A80754A011D537003F0BCFEFA -:10303000022366E022F0100189B2580531802ED5B6 -:103040006F4B1B6858896F4BB3F90080B8F1000FC4 -:10305000B8BFC8F10008804509DAB3F90230002B87 -:10306000B8BF5B428342ACBF0023012300E063464C -:10307000DB0714D502F0200292B2002A43D15F4B45 -:1030800061485A70614B41F020011A685B683180D9 -:10309000011D6367226703F087FE012331E022F000 -:1030A00030023280554A53786BBB012151701A4669 -:1030B0005749002050525749574C5052574904EB3A -:1030C000030C5052002119510232CCF80400CCF804 -:1030D000081004F1280C503443F80C1019519C448A -:1030E0001C44042ACCF80400CCF808106060A160ED -:1030F00003F11403DCD106E0338823F0300333807E -:10310000002384F86C303B6813F4006F338814BFDD -:1031100043F4807323F4807333806B79082B02D0DF -:103120000E2B40F09280338823F0400333808CE0F4 -:10313000012200E002225FFA82F808F1FF3385F8ED -:10314000543704F0DDF807F0CDFE02202821424676 -:10315000FEF730FD1CE5B8F1000F02D07E2B3FF4E6 -:1031600015AD637E972B7FF4FBAC2D4B4FF4C872EB -:103170001A800DE50022BB2B039201D1022303E04C -:10318000B72B04D14FF6FE73ADF80E300AE0BE2B1C -:1031900001D1022304E0BD2B7FF4FAAC4FF6FE739D -:1031A000ADF80C303368BDF80C10B3F854200A4465 -:1031B000A3F85420BDF80E10B3F856200A44A3F823 -:1031C000562004F09DF807F08DFE0F2014210122F7 -:1031D000FEF7F0FC0023A376DAE400BFCE02002065 -:1031E0005C210020E00300205C0800205003002048 -:1031F000FE02002018040020500C00202C000020AB -:10320000D4030020C60300205C0C0020240400200E -:10321000A4210020D8030020640C0020DC0300203F -:10322000A00200200A4B00220021DA651A66C3F8CA -:10323000F020C3F8F420C3F8F820C3F8FC10C3F85A -:103240000011C3F80411FFF7C6BB05B0BDE8F08F4D -:10325000EC0B0020664B2DE9F04FB3F90600654BEF -:1032600087B01D682B8998420EDBB0F5FA6FAF79F5 -:1032700007DAC21A5743A3F5FA6397FBF3F76437EB -:1032800003E0C7F1640700E064275B4B5B4AB3F8D7 -:103290001A1193F9EC3016685B4204919BB200213D -:1032A000059334460A46524BDDF810C0CB5E40F21F -:1032B000E63E0393CCEB030303F2F31CF44503D87F -:1032C000002BB8BF5B4201E04FF4FA73022ADFF82B -:1032D000388131D096F85DE1BEF1000F04D073451E -:1032E000CCBFCEEB030300234FF0640EDFF814A134 -:1032F00093FBFEFC6FF0630B3AF81C900BFB0C3B4E -:103300000CF1010C3AF91CA00FFA89FCCCEB0A0C69 -:103310000CFB0BFC9CFBFEFCCC4428F801C095F890 -:1033200004C003FB0CFC364B9CFBF3F373449BB2D1 -:103330007B4393FBFEFE1BE096F85EE1BEF1000FBF -:1033400004D07345CCBFCEEB03030023DDF814C0DB -:1033500003FB0CFEA8F804E095F805E0002BB8BFCD -:103360005B4203FB0EFE264B9EFBF3FE0EF1640E4A -:10337000B31893F80480DFF894C00EFB08F86423B8 -:1033800098FBF3F802F80C8094F80E900CF1030807 -:103390000EFB09F999FBF3F902F8089094F81880EC -:1033A0000CF1060C0EFB08FE9EFBF3F302F80C304A -:1033B000DDF80CE0049B9E45DFF84CE004DA3EF8B3 -:1033C00001305B422EF801300132032A01F1020183 -:1033D00004F101047FF467AF074EB6F81C31984240 -:1033E00016DBB0F5FA6FA8BF4FF4FA6011E000BF2A -:1033F00062050020E00300200C1A002018020020C3 -:103400000CFEFFFFF80C0020C6030020060D002074 -:103410001846C01A4FF47A725043C3F5FA63B0FBF2 -:10342000F3F36427A24C93FBF7F204EB42016FF035 -:10343000630000FB0233098B04EB4202B2F91A006D -:103440000AB2821A534393FBF7F73944994F9A4DC6 -:103450003B88AEF806105A063CD5984B1888238E48 -:10346000C01A00B208F0D6FE954908F027FF804642 -:103470000BF0A6FD814640460BF016FE8046B5F9DE -:10348000020008F0C7FE8246B5F9000008F0C2FE4F -:103490004946834608F012FF4146034650460293D0 -:1034A00008F00CFF029B0146184608F0FDFD09F0EC -:1034B000CBF849462880504608F000FF4146814637 -:1034C000584608F0FBFE0146484608F0EFFD09F0BB -:1034D000BBF86880B26840F602031340002B53D05B -:1034E000784B06211D88636B1D4494F83830656362 -:1034F0000133DBB2B3FBF1F084F8383001FB103359 -:1035000013F0FF0F40D1930706D502F0A7FA02F09F -:103510008FFA674B83F83900B368180532D56A4BC8 -:10352000E16B5A7B694B33F81200082391FBF3F2ED -:1035300080B28A1A0244E26392FBF3F292B240F63E -:10354000E4435A43624B40F6FF71B2FBF1F2196853 -:103550004FF47A73C8888988121A5A4392FBF1F2A1 -:1035600055435C4995FBF3F30A60D4E91001C01898 -:1035700041EBE371C4E910010023574A09F0AAF8AE -:10358000564B1860002363635549494A0B6894F809 -:10359000398013F4805318BF012382F84830B36890 -:1035A0008A4613F4807F4F4D2CD0DFF84C91287859 -:1035B000D9F80030C0F380001B685B68984760B1A1 -:1035C000012384F84930D9F800301B68DB6898473C -:1035D00018B1374B022283F84920D9F800301B6814 -:1035E0009B68984728B12B7859075CBF022384F861 -:1035F0004930D9F800301B689B69984710B1002307 -:1036000084F84930384B1A6892060DD5DAF8003044 -:1036100013F4C06F05D0354B1B789B0701D40123F1 -:1036200000E0002384F84A3094F84920204B022A15 -:1036300002D14C204E211EE0012A06D153204D21FB -:103640004C220B4607F058F82BE093F84A20012A49 -:1036500003D1532001464E2206E093F84820012A68 -:1036600004D15320014602464D23EBE7B8F1000F89 -:1036700004D053204D210A464423E3E73A88170635 -:1036800003D553204D210246DBE7194A12781AB1BF -:10369000192007F005F804E0404683F84B80FEF758 -:1036A00082FA2A78500729D5124B08225A617BE00A -:1036B000F80C002050030020C6030020180300204F -:1036C00035FA8E3C44030020C0050020D0050020C0 -:1036D000040400200C040020407E0500100400209B -:1036E0004C030020B021002088020020FE020020B0 -:1036F000CE020020000C014060080020DAF8003003 -:10370000D90703D4BB4942F001020A70BA4A1288B1 -:103710001AB1BA490A68920705D4B94A1288003228 -:1037200018BF012200E0012242B1B64AD16881F0FF -:103730000801D1602A7822F001022A70B24A127878 -:10374000170703D42A7822F001022A70D80203D581 -:103750002B7823F001032B702B78AC4A13F0010F68 -:1037600005D00023E364A74B082119610BE0E16C4D -:10377000136841B9A64903F5F42303F59073CB64AC -:10378000A04B08215961E36C12686BB1D21A002A70 -:103790000ADB9C4A03F5F423D16803F5907381F0AA -:1037A0000801D1609A4AD36407F00EFA994B1B784E -:1037B00013B106F0ADFBFAE3012003F0E6FB0028AD -:1037C00000F0F583DFF86C9299F84A30012B40F055 -:1037D000E883914A914BD9F80010C2F80090196023 -:1037E00092468E4A1068FEF73BFA002800F0D38319 -:1037F0008A4B1868FEF72FFADAF8003093F8482061 -:10380000DAB9B0F124014A424A4183F84820002A3B -:10381000E7D12B785B07E4D4232802D106F078FBAC -:10382000DFE7D4F8E8301B7D8342DAD17C4A7D4B58 -:103830001A607D4A7D4BDA60D3E7012A04D14D2816 -:1038400014BF00220222A3E3022A04D13C2814BFA1 -:10385000002203229CE3032A0AD140284FF00002F1 -:1038600000F296831A71DA715871987104228FE30D -:10387000042A06D19A7983F84900504098710522AC -:1038800086E3052AADD159791A799142997906D9F9 -:1038900041409971511C197113441872A1E781427A -:1038A00040F0738393F8490005F0DAF8002840F0FF -:1038B0006783DAF8003093F84930C82B00F0DB80DA -:1038C00043D82D2B00F0F18224D8252B00F0CE8296 -:1038D00006D8212B00F02182232B00F0668182E3A1 -:1038E000292B00F0CE822B2B00F0D782272B40F023 -:1038F0007A830020FEF7FAF9FEF772F84C4FA7F82A -:10390000E600FEF76DF8A7F8E800FEF769F8A7F8FB -:10391000EA0032E3332B00F0DC820CD82F2B00F0CE -:10392000EE82312B40F05F83414FC020FEF7DEF97D -:1039300007F18008F9E2412B00F0D382442B00F01C -:103940001683352B40F04F8351E1D02B00F0F381EB -:1039500042D8CC2B00F0798106D8C92B00F00D821B -:10396000CA2B00F0A0803EE3CE2B00F0F88140F29D -:10397000ED81FEF735F8FEF733F82D4FDFF8B8800C -:10398000A7F8D000FEF72CF8A7F8D200FEF728F829 -:10399000D8F800B0A7F8D400FEF722F8ABF8A801D9 -:1039A000FEF71EF8FEF726F8D8F80080FEF718F8A4 -:1039B00000EB80004000A8F85200FEF707F887F8F7 -:1039C0000401FEF703F887F80601FDF7FFFF87F80B -:1039D0000501FDF7FBFFD0E2D42B00F068812DD864 -:1039E000D22B35D040F20782FDF7FAFFA4F8EC00A5 -:1039F000C3E200BFB0210020A00200208802002006 -:103A0000AC210020000C0140FE020020A02100207B -:103A1000F80C0020AF210020A8040020AC040020F6 -:103A2000EFBEADDEF04F00200400FA0500ED00E02F -:103A30000C1A0020480D002018020020EF2B25D082 -:103A4000FA2B00F09681D62B40F0CD82002726E19C -:103A50002B7803F0040303F0FF07002B40F08D8266 -:103A6000FDF7B4FFC94B022883F8540740F269817F -:103A700083F8547765E10027FDF7B2FFC44BD853B4 -:103A80000237102FF8D10122C24B70E1C24FD7F894 -:103A90000080FDF7A5FFA8F856003F68FDF7A0FFDE -:103AA000A7F8540069E2BC4B00271A6898461278C0 -:103AB000022A61D1D8F800B0FDF788FF07F10802AB -:103AC0000BEB820B08F0A2FBB44908F0ABFCCBF87F -:103AD0000400D8F800B0FDF779FF07F10A020BEBFC -:103AE000820B08F093FBAE4908F09CFCCBF8080071 -:103AF000D8F800B0FDF76AFF07F10E020BEB820B5E -:103B000008F084FBA74908F08DFC0137032FCBF8A0 -:103B10000400CFD1072FD8F800B016D1FDF756FF1B -:103B200008F074FB9D4908F07DFCCBF84800D8F8FC -:103B300000B0FDF74BFF08F069FB984908F072FCF4 -:103B4000CBF84C00FDF742FF12E0FDF73FFF0BEB17 -:103B500007031871D8F800B0FDF738FF0BEB070327 -:103B60009873D8F800B0FDF731FF0BEB0703187618 -:103B700001370A2FCED100E2D8F800B0FDF726FFBA -:103B80000BEB07031871D8F800B0FDF71FFF0BEB24 -:103B900007039873D8F800B0FDF718FF0BEB070385 -:103BA00001370A2F1876E7D1E7E1FDF70FFF272845 -:103BB00021D8794B00F11C081B6803EB8808FDF73E -:103BC00005FF794B08F1050703F58A72197A8142DE -:103BD00003D00C339342F9D10DE01B7888F80530FF -:103BE000FDF7F4FE7870FDF7F1FEB87053E0FDF7D5 -:103BF000EDFE0B2804D901200021FEF759F8BCE1A5 -:103C00004FF0060808FB00F0634B00F588701B6856 -:103C100003EB0008FDF7DAFE0328ECD888F80A0069 -:103C2000FDF7D4FE88F80500FDF7D0FE88F8060001 -:103C3000FDF7CCFE88F80700FDF7C8FE88F80800FD -:103C4000FDF7C4FE88F8090097E1584FD7F80080C7 -:103C5000FDF7BCFE88F80000D7F80080FDF7B6FE3F -:103C600088F80100D7F80080FDF7B0FE88F804005E -:103C7000D7F80080FDF7AAFE88F80500D7F8008085 -:103C8000FDF7A4FE88F80600D7F80080FDF79EFE39 -:103C900088F802003F68FDF799FEF8706DE1FDF7C6 -:103CA0009FFE434BD8530237102FF8D165E14FF0F8 -:103CB0000008394F08F12C0B39680291FDF790FE8E -:103CC00002994FEACB021144C880396801920291EF -:103CD000FDF786FE019A0299114408810192FDF7D1 -:103CE0007FFE0728019A02D839680A445073A0F56C -:103CF0007A7292B2B2F57A7F03D83A6802EBCB02BD -:103D000050813F68FDF762FE08F1010807EBCB0325 -:103D1000B8F1080F1873CCD12FE100271E4BD3F850 -:103D20000080FDF753FE08EBC7030137082F83F827 -:103D30006D01F3D121E12B785F0700F11E8102F0C4 -:103D400059FE03F0DDFA07F0CDF816E12B7858079D -:103D500000F11381174B4FF4C8721A800DE12B78D4 -:103D6000590700F10A81144B1A7842F004021A70C4 -:103D700003E12B785A07E4D535E1FDF727FE0E4B1A -:103D80001A78D8B142F002021AE000BF0C1A0020E3 -:103D900062050020040200201802002000002041DB -:103DA0000000C84200007A44780D0108E0030020BA -:103DB000E60D0020A0020020FE02002022F00202F8 -:103DC0001A70FDF703FE8C4B8C4F1870FDF712FE36 -:103DD0003860FDF70FFE7860FDF702FE884B188013 -:103DE000FDF7FEFD874B188094F8063143F002037F -:103DF00084F80631C1E0FDF7E9FD0190FDF7FAFD19 -:103E00000290FDF7F7FD8046FDF7F4FD0746FDF74C -:103E1000E7FDFDF7E5FDFDF7D9FD019A029B9AB993 -:103E2000794A82E80801794B1A8822F010021A8038 -:103E3000774B1A7842F001021A70002F00F09D8033 -:103E4000744BC3F8087198E0102A40F09680724ACB -:103E500082E8080117B16F4BC3F808716E486F4BC9 -:103E60000222011D1A7002F09FFF86E00020FDF77C -:103E70003DFF0023B360FDF7BDFDB3681843B0609C -:103E80007BE00020FDF732FFFDF7AAFDA6F8080150 -:103E9000FDF7A6FDA6F80A016FE00020FDF726FF5A -:103EA000FDF794FD5E4B587167E00020FDF71EFFA3 -:103EB000FDF78CFD86F81801FDF792FDA6F81E01AE -:103EC000FDF78EFDA6F81A01FDF78AFDA6F81C0184 -:103ED00053E00020FDF70AFFFDF778FD86F820018A -:103EE0004BE00020FDF702FF0027FDF76FFD4C4B74 -:103EF0003B440137082F83F81001F6D13DE0002044 -:103F0000FDF7F4FE464F07F14008FDF769FDA7F8FD -:103F1000D401FDF75BFD87F8D601FDF757FD0437A7 -:103F200087F8D3014745F0D127E0FDF759FD00F0B0 -:103F30003F00A7F85601FDF753FDB7F85621800161 -:103F400000F4F8631343A7F85631FDF73FFD000175 -:103F500087F85401FDF73AFD97F8543100F00F004F -:103F6000184387F8540104374745DED105E00020A7 -:103F7000FDF7BCFE012384F80C310020FDF7B6FEEE -:103F8000DAF800309879FDF782FEDAF80030002286 -:103F900083F8482025E494F80C3113B1214A224BD0 -:103FA000DA60224B09F14C0999457FF40DAC2049A8 -:103FB0000B689B0611D51F4BD4F810211B689A1A69 -:103FC000002A0ADB0C4A1278042A06D903F51233B8 -:103FD000104A03F5F873C2F81031174B9B683BB1D8 -:103FE0001648984704E001200021FDF761FEC7E76D -:103FF00007B0BDE8F08F00BF1804002024040020A3 -:104000001604002014040020500C0020500300204F -:10401000FE020020F80C00205C0C0020580C002050 -:104020000C1A00200400FA0500ED00E0E00D00206D -:1040300088020020A02100201C0200200204002091 -:104040002DE9F04F974B91B01B68BBB9964C237884 -:10405000013B042B00F2F086DFE813F00B060B06A1 -:104060000B06DE06C4062068FDF7F5FD8F4B0446FF -:104070001B681B784BB1012B00F0ED80894C206848 -:10408000FDF7EEFD0028EED1E0E72428884D0CD0A6 -:1040900006D80A2800F08E800D2800F08B80C6E03C -:1040A0002A2806D02C2804D0C1E02B706B70AB708E -:1040B000CEE06A782E782A4400217D4BD170EEB98B -:1040C000DA789E74472A19D11A79502A16D15A796A -:1040D000472A07D19A79472A04D1DA79412A01D1AE -:1040E00001229A746A79724B522A07D19A794D2A21 -:1040F00004D1DA79432A04BF02229A74AB7C6C4F54 -:10410000012B02D0022B36D049E0B31E072B46D834 -:10411000DFE803F0040810141C27452C03F0A6FC6C -:1041200068613CE0EA78624B532A38D15A695242BE -:104130005A6134E003F09AFCA86130E0EA785C4B05 -:10414000572A2CD19A6952429A6128E0EB78302B99 -:10415000584B1A788CBF42F0020222F002021A7009 -:104160001DE0002003F0DCFC287718E0002003F0BD -:10417000D7FCE88313E0072E06D0082E0FD10120CC -:1041800003F0CEFC78840AE0012003F0C9FC41F280 -:10419000184358434FF47A72B0FBF2F33B84013674 -:1041A00000232A2C424A2E706B704CD1012182F8D8 -:1041B00024104DE095F82430002B34D03C4BDB78B4 -:1041C000402B04D9A3F137021201D2B202E01B0145 -:1041D00003F0F0022B79A978402B8CBF373B303BA2 -:1041E000DBB21344DBB29942314A1BD1937C012BE1 -:1041F00008D0022B16D1118C2F4B528C19802F4BCB -:104200001A800FE02B4909788E070CD52C4950698C -:10421000086090694860107F2A490870D18B2A4A4B -:10422000118000E00023002285F8242010E06B7844 -:104230001F4A0E2B03D8591C13445170DC7095F89B -:1042400024301B4A1BB991784C40947000E0002345 -:1042500003F0010361E1164B002193F82520082AA1 -:1042600000F25A81DFE802F00B0514324353718DDE -:104270009A00622801D1022207E083F82510B52CAC -:1042800040F04A8193F82520013283F8252043E14C -:10429000032283F8252083F8260083F8270083F87B -:1042A000280039E1A408002084080020A00800208C -:1042B000100E0020FE0200201404002034170020FD -:1042C000240400201804002016040020042283F88F -:1042D000252093F8272093F828100244D2B283F8BF -:1042E00027200A4483F8282083F8290014E10522B6 -:1042F00083F8252093F8272093F828100244D2B29F -:1043000083F827200A4483F82820588504E10621F1 -:1043100083F8251093F8271093F828002144C9B298 -:1043200083F82710014483F82810598D6C4A01EB5B -:104330000424A4B2B4F5007F89BF002154855185BF -:1043400082F8251000229A85E6E093F8272093F85A -:1043500028100244D2B283F827200A4483F8282088 -:104360009A8DC72A03D85E49114481F83000013282 -:1043700092B29A855B8D934240F0CE800722584BD3 -:1043800083E7082283F8252093F82730834200F042 -:10439000C380534A002382F82530BEE083F82510FD -:1043A00093F828104E4A814240F0B68092F82910C6 -:1043B000062947D004D8022912D003292CD0ABE01B -:1043C00012295CD0302940F0A78092F83410454A79 -:1043D000102988BF102111701078434900225CE039 -:1043E0004249506B4860906B0860116C4FF47A70D2 -:1043F00091FBF0F13E48018092F8F8103D4A19B166 -:10440000117841F0020102E0117821F002011170EF -:10441000012283F8F92055E092F8351011F00101DE -:1044200005D092F83420D41E6242624100E00A4670 -:1044300083F8F820002A45D12E4A117821F0020194 -:1044400011703FE092F83B1011F0010105D092F895 -:104450003A20D01E4242424100E00A4683F8F8204A -:1044600022B9244A117821F00201117093F85F10EB -:10447000214A1170B3F85C10204A118022E0516C7F -:104480001F480180916C42F2107091FBF0F11D48C1 -:104490000180012182F8FA1014E0824201F10C013E -:1044A00010DA11F8045C184C155511F8035C174C20 -:1044B000155511F8015C164C15550D78154C155510 -:1044C0000132EAE793F8F930054A2BB392F8FA3053 -:1044D00013B3002382F8F93082F8FA3001231CE08C -:1044E000100E002036170020400E0020240400206B -:1044F00016040020FE020020180400208200002084 -:10450000140400203417002037170020471700201C -:1045100057170020671700200023002B3FF4AEAD93 -:10452000A54BA64E9A68DA6032689A60A44B1A6866 -:1045300042F020021A60A34B1A78012A0CBF002215 -:1045400001221A70A04B1A7891077FF597AD9F4909 -:10455000097804297FF692AD9D49097801F004019C -:1045600001F0FF0011B922F001021A701B78964F7A -:1045700013F0010F974C984D11D180B19B070ED5C8 -:10458000964B28686A6818605A60FEF709F8944BE1 -:104590001B88A4F8FC303B7843F001033B7094F88F -:1045A000FE304FF00509013393FBF9F909EB890956 -:1045B000C9EB03098B4B8C481B7884F8FE9005935C -:1045C000831D03EB890907900023DFF80CE2874A7B -:1045D00053F80E00864F985090FBF7FC02F1080745 -:1045E00043F807C0834F03EB0E0107FB0C0742F2B1 -:1045F000107097FBF0F00691079980B221F8020F36 -:1046000002F1100A03EB830B0490079153F80A00A0 -:1046100059F80B1049F80B70C1EB000808EB0700C4 -:10462000734F4FF0050843F80A0090FBF8F007FBC2 -:104630000C000599183201299850774608D1DDF809 -:1046400010E0AEF10202B2F5797F9CBF06990860D6 -:104650000433082BB9D1DFF87C813068D8F84C31AD -:10466000C01A07F0D3FD644907F0DCFE33684FF051 -:104670007E51C8F84C31814607F0BEFF10B94FF0AB -:104680007E5000E048460CAAC4F85001534B0092FB -:104690000DAA019297E803000CCBFDF73FFF0C9B9E -:1046A00056496422B3FBF2F30D980B80544B90FBF8 -:1046B000F2F21A80444A474E127812F0010208BF03 -:1046C0001A8098F8543108BF0A80002B3AD0D6F8E7 -:1046D00050114FF07E5007F0A5FED6F858318146B4 -:1046E0002868C01A07F096FD494607F0E7FD07F075 -:1046F000ABFFD6F85C211FFA80FA68680FFA8AFAD5 -:10470000801A07F087FD3F4B196807F0D7FD49462F -:1047100007F0D4FD07F098FFB6F9623100B2C21875 -:10472000B6F960310221534492FBF1F293FBF1F3AD -:1047300092B29BB2A6F86621A6F86431A6F862216F -:10474000A6F86031012388F854312F4B79681B8813 -:10475000386803F030031F4E1F4DC8F85C11C8F8CD -:104760005801002B3FF48AAC06F5B873009306F5A8 -:10477000BA730193D6F86821D6F86C31FDF7CEFEF6 -:104780006B68D6F86C01C01A07F044FD1D4B196820 -:1047900007F094FD07F058FFD6F868312A68C6F88C -:1047A0007C019B1AC6F878310E4B1B78012B2DD05B -:1047B000022B00F0F58061E484080020081A002034 -:1047C00088020020FE0D0020FE02002018040020B8 -:1047D000B0210020100E002024040020500C0020E6 -:1047E00018030020580C00200E0F00203C0F002062 -:1047F00080969800806967FF00007A448804002052 -:104800008A0400203000002050030020D6F89C418C -:10481000D6F89031D6F88021D6F8947104F1004092 -:1048200005930492079707F00FFF0746204607F00D -:104830000BFF8C4BD6F850511B68D6F898618A4C08 -:104840000890069609934FF0000ADFF83C9259F859 -:104850001A60A9F1140230463AF8028007F0DAFC37 -:10486000049907F02BFD07F0EFFEC8EB000080B2C3 -:1048700009F128092AF809000FFA80F9484607F0DB -:10488000C9FC059907F01AFD07F0DEFE1FFA80FB50 -:1048900009EB060007F0BEFC079907F00FFD29465B -:1048A00007F00CFD216807F001FC07F0CDFEB842CF -:1048B00004DB089A9042A8BF104600E0384607F093 -:1048C000A9FC206007F0C0FE58441FFA80FB606816 -:1048D00008F13108301A07F09DFC294607F0A2FDC7 -:1048E000099B206102469878D4F80890039207F05B -:1048F0008DFC5E4907F0E2FC01464FF07E5007F068 -:1049000091FD294607F0D2FB0146284607F08AFDB3 -:10491000039A844649461046CDF80CC007F0C4FB04 -:10492000DDF80CC00146604607F0C8FC0146484669 -:1049300007F0BCFB1FFA88F8B8F1620F014620614E -:104940006660A0600ED9069807F0B8FC07F07CFE00 -:10495000474AB0F5FA6FA8BF4FF4FA609042B8BF6B -:10496000104600E00020834440F6B8320FFA8BFB7B -:104970009345A8BF93463F4A0A219345B8BF934643 -:1049800001FB0AF13C4A54F8140B2AF802B03B4AE6 -:104990000AF1020ABAF1040F88503FF46FAB54E7F2 -:1049A000304BD6F870911F68B6F8A451B7F808A03C -:1049B0004FEA59039A4528BF9A462BB29A4502DC22 -:1049C0001FFA8AFA0BE02E49D6F8500107F076FC60 -:1049D00007F03AFE28441FFA80FAA6F8A4A1D8F8F6 -:1049E0007451D8F8A861AE1B3046FDF747FE002889 -:1049F000D8BF404241F293139842CCBF002001201F -:104A0000002843D0304607F005FC1E4907F056FC4D -:104A10000AF04AFB0646484607F0F8FB01463046D6 -:104A200007F04CFC07F010FE80B240F6B83203B23B -:104A30009342A8BF13460F4AA8F8AC019342ACBFFB -:104A4000EB18AB1848F6A042934203DDA3F50C43E4 -:104A5000A03B04E0002BBCBF03F50C43A033C8F817 -:104A6000B03115E0D40300208C0C0020DB0FC940CE -:104A700030F8FFFF48F4FFFFDC030020B40C0020F7 -:104A80000000C842D3023739880F0020C8F8B0515F -:104A9000D4F8B021C2F50C502830049207F0BAFBCC -:104AA000AA4907F00BFC05460AF08AFA0F9028463F -:104AB0000AF0FAFAD4F8C051D4F8B431D4F8B821D5 -:104AC0000E9005F1004007930A9207F0BDFD059096 -:104AD000284607F0B9FDD4F85081D4F8BC410B90BA -:104AE00009949B4C0025504607F094FB0EAB53F8FD -:104AF000151007F0E3FBDFF894B206463BF905001A -:104B000007F088FB0146304607F0CEFA07F09CFD1F -:104B1000904B06B2B6F57A7FA8BF4FF47A769E42E4 -:104B2000B8BF1E46B0B20BF13C0B25F80B0000B22B -:104B300007F070FB0799834607F0C0FB07F084FD80 -:104B400080B208900A99584607F0B8FB414607F032 -:104B5000B5FB216807F0AAFA07F076FD059B98429D -:104B600004DB0B9A9042A8BF104600E0059807F0BE -:104B700051FB8346206060681434301A07F04AFB0A -:104B8000414607F04FFC54F80C3C44F8040C024634 -:104B9000B8780693039207F039FB6F4907F08EFB54 -:104BA00001464FF07E5007F03DFC414607F07EFA8B -:104BB0000146404607F036FC039A844606991046A3 -:104BC000CDF80CC007F070FADDF80CC00146604665 -:104BD00007F074FB0146069807F068FA44F8106C79 -:104BE000014644F8040C44F80C0C099807F066FBE5 -:104BF00007F02AFD089E0644584607F025FD30447C -:104C000040F6B83200B29042A8BF1046534A0A217B -:104C10009042B8BF10466943514AA852514A0235E2 -:104C2000042D41F802B07FF45EAF3B792BB1049BB9 -:104C3000642293FBF2F24C4B1A803B884B4C994513 -:104C40000ED9D4F8A831D4F87401C01AFDF716FDB6 -:104C500042F210730028B8BF404298427FF70EAA74 -:104C6000434B01221A70B4F8FC203F4B1A80FFF727 -:104C700005BA404A116890460F7817B1012F0DD040 -:104C8000ADE0012B00F2AB8062783B4B03EB0213EB -:104C90003A4A59681068FCF7D9FF9DE0374E3068F2 -:104CA000FCF7CFFFB146002800F099802378344DFF -:104CB000022B29D0032B31D0012B40F09080314BB7 -:104CC0001F686B69FB1A632B40F289802B69042BE8 -:104CD00018D8DFF8A480306808EB03135968FCF794 -:104CE000B5FF6B78366808EB03139D6815F8011B58 -:104CF00019B13046FCF7C6FFF8E723696761013355 -:104D000023616CE0022068E06A781B4B306803EB9B -:104D100002135968FCF79AFF03205EE02B7E03B96B -:104D20002F76227E164B012A36D11A697B2A2FD87C -:104D3000D8F800309B782BB9134BD9F80000995C58 -:104D4000FCF7A0FF23690133236125E0D302373943 -:104D5000B40C002018FCFFFFDB0FC94048F4FFFF34 -:104D6000DC0300208C0C0020E40D0020100E00203D -:104D7000580C0020A00800202C080108A4080020DE -:104D800084080020081A00208C0E0108740F0020EF -:104D900000221A6102221A76227E294B022A18D199 -:104DA0001A690F2A13D8D8F80030997859B95B7866 -:104DB000244903EB03130B441A44D9F8000092F87A -:104DC0007D10FCF75FFF23690133236101E00322BB -:104DD0001A76237E022B02D9042005F017FD00234A -:104DE000636029E063680522013363606378012012 -:104DF0000133DBB2B3FBF2F202EB82029B1A637067 -:104E0000114B00221B68A360104B1A70104B1A78CC -:104E100022F002021A700DE00B4B1A68A368D21A36 -:104E200040F6C4139A4207D90A4B05201A6822F0AB -:104E300020021A6005F0EAFC11B0BDE8F08F00BF57 -:104E4000840800208C0E0108081A00201804002095 -:104E5000FE02002088020020084BDA68D10709D43E -:104E6000DA68520708D4DB6813F0100F0CBF042077 -:104E70000320704701207047022070470020024045 -:104E80001E4B2DE9F0431A781D460AB31C4B0778D8 -:104E90001E781C4B93F800C002231B4A03F1010843 -:104EA000D45C344104F00F04BC420CD20B2C0AD861 -:104EB00012F8039012F8088002EB840209EA0C044D -:104EC00008EB042414610233102BE6D100232B706D -:104ED00003788B420FD90C4B93F8400060B10B4A1A -:104EE000890012780B44186902B1400800F5777008 -:104EF00080B2BDE8F0830020BDE8F0830801002007 -:104F00006408002065080020D40F002066080020F7 -:104F100007299ABF024B33F821000020704700BFD9 -:104F2000E4010020024B53F82100C0F3CF0070478A -:104F30008C01002038B5104C0123054684F8403020 -:104F4000FCF702FE636C41F28832C31A9342A364F9 -:104F500084BF002384F84C3094F84C30EDB20F2B12 -:104F60006064E55403D1054B01221A7038BD024A32 -:104F7000013382F84C3038BDD40F002008010020E6 -:104F800010B50446FCF7E0FD0D4B41F288311A6D77 -:104F90001865821A8A425A6584BF002283F8582015 -:104FA00093F85830074A142BD45403D1064B0122EE -:104FB0001A7010BD024A013382F8583010BD00BF8C -:104FC000D40F0020CD010020CC01002010B50446F4 -:104FD000FCF7BAFD164AD36DD065C31AB3F57A6FE4 -:104FE00084BF002382F8603092F8603023B9A82C87 -:104FF0001CD110490B7006E0022B02D10E490C7037 -:1050000001E0242B01D80D49CC540133DBB282F8E6 -:105010006030094A127852000532934206D1044B9F -:10502000002283F86020034B01221A7010BD00BFDC -:10503000D40F0020640100208A01002065010020B7 -:1050400038B50446FCF780FD114B40F6C4115A6E8A -:105050005866821A8A4284BF002283F8682093F837 -:1050600068200AB90F2C11D10A480021017052B1F1 -:10507000094D182A154405F8014C04D1012283F882 -:105080006810027038BD013283F8682038BD00BF57 -:10509000D40F0020090100200A0100202DE9F04F63 -:1050A000064689B00F4615469B462978002900F030 -:1050B000B880252902D001353046B0E06C78302C1C -:1050C00003D002354FF0000903E0AC784FF001093E -:1050D0000335A4F13003092B4FF000081AD8A4F1CE -:1050E0003003DAB2092A07D80A2B13DC0A2202FBA2 -:1050F000083815F8014BF2E7A4F16103052B02D83B -:10510000A4F15703F0E7A4F14103052B02D8A4F161 -:105110003703E9E76C2C03BF2C780122013500220C -:10512000632C66D006D8252C77D0582C3FD0002C85 -:1051300077D0BAE7732C63D002D8642C11D0B4E7CF -:10514000752C02D0782C32D0AFE70BF1040A05ACF5 -:10515000DBF800000A2112B10022234613E02346A7 -:1051600020E00BF1040A05ACDBF8000072B1002866 -:1051700006DA2D238DF8143040420DF1150300E0BE -:1051800023460A210022FDF791F80DE0002806DAF7 -:105190002D238DF8143040420DF1150300E0234615 -:1051A0000A210022FDF75AF8D34600941AE00BF1C9 -:1051B000040303930DF1140ADBF80000102132B14F -:1051C000583C624262415346FDF770F806E0B4F184 -:1051D00058035A425A415346FDF740F8DDF80CB0E7 -:1051E000CDF800A03046394642464B46FDF79AF8C6 -:1051F0005BE730469BF800100BF10404B8470AE067 -:10520000DBF80030304600933946424600230BF16C -:105210000404FDF787F8A34647E730462146B84720 -:1052200043E709B0BDE8F08F124870B50023047859 -:105230001A46D1B28C4209D0057B8D4208D00D4D63 -:105240002D7E8D4208BF02210ED102E0002100E038 -:1052500001210C2505FB0101074D084E1D4495F861 -:105260002C510133755D0D720132032A01D0022BDE -:10527000DFD970BD480000200C1A0020A3210108CE -:1052800070B50546441E14F8011F61B1064E304644 -:1052900009F09BFC0028F6D0861B0448631B3044B1 -:1052A00080F81031EFE770BDBC2A01080C1A00200D -:1052B00030B587B005460C4603A800210C2209F042 -:1052C00050FC2846002107F0B5F920B128462A49AC -:1052D00006F0ECFE03E02846274906F0E5FE2749E4 -:1052E00006F0ECFF07F0B0F9054685EAE570A0EBA3 -:1052F000E57069460A22FDF701F800239D4203701C -:10530000ACBF20232D2368468DF80C3009F06AFCD1 -:10531000012807D130238DF80D308DF80E308DF82F -:105320000F300CE0022805D130238DF80D308DF8B8 -:105330000E3004E0032804BF30238DF80D30694699 -:1053400003A809F035FC03A809F04CFC0338C5B2EA -:105350002A4603A9204609F06FFC00236355204626 -:10536000074909F025FC03A92046294409F020FC3F -:10537000204607B030BD00BF6F12033A00007A44E8 -:10538000682001088A6810B50C6A036814430A692A -:1053900023F4FF4314434A6923F0700314438A69DA -:1053A0001443CA6914434A6A14438A6A2243134362 -:1053B0000360CB6843600B6883604B68C36010BDBB -:1053C00002684FF6FE7313400360002303604360DE -:1053D0008360C3602A4B984222D02A4B984229D03E -:1053E000294B984230D0294B984237D0284B9842CD -:1053F0003ED0284B984206D153F8682C42F47002F4 -:1054000043F8682C7047244B984206D153F87C2C03 -:1054100042F0706243F87C2C7047204B984206D1D2 -:1054200053F8042C42F00F0243F8042C70471C4B35 -:10543000984206D153F8182C42F0F00243F8182C89 -:105440007047184B984206D153F82C2C42F47062E6 -:1054500043F82C2C7047144B984206D153F8402C3B -:1054600042F4704243F8402C7047104B984205D1EB -:1054700053F8542C42F4702243F8542C704700BF68 -:10548000080002401C00024030000240440002407C -:10549000580002406C0002408000024008040240B4 -:1054A0001C040240300402404404024058040240FC -:1054B0001F4B10B55A6802F00C02042A03D0082AC8 -:1054C00004D01C4A14E01C4A126811E05A6859685A -:1054D000C2F38342C90302F1020201D4174906E074 -:1054E000596811F4003F1449096818BF49084A4334 -:1054F00002605968124AC1F30311545C0168E1402B -:1055000041605C68C4F30224145D21FA04F48460F1 -:105510005C68C4F3C224145DE140C1605B68C3F3FE -:1055200081331A44137CB1FBF3F1016110BD00BF5C -:105530000010024000127A001400002000093D0013 -:105540003400002010B50446FFF786FC012806D180 -:105550001CB1FFF781FC013CF8E7052010BD002CD1 -:1055600008BF052010BD0A88F0B54B888F880E89CA -:10557000CD88002A3AD1048C834A24F00104240403 -:10558000240C0484018B048C89B221F0F30141EADC -:105590000616B6B29042A4B246EA070743F00103EA -:1055A00015D002F50062904211D0B0F1804F0ED0BC -:1055B000A2F5983290420AD002F58062904206D05D -:1055C00002F58062904218BF24F00A0401D124F051 -:1055D0000204234307830384038B23F00C031B047F -:1055E0001B0C0383038B9BB21D4344E0042A44D16C -:1055F000048C654A24F010042404240C0484018BD8 -:10560000048C21F440710905090D41EA063189B283 -:1056100041EA07279042A4B2BFB212D002F500625D -:1056200090420ED0B0F1804F0BD0A2F5983290424C -:1056300007D002F58062904203D002F5806290426A -:1056400007D124F0200444EA03139BB243F0100373 -:1056500004E024F0A00443F01003234307830384F1 -:10566000038B23F440631B041B0C0383038B9BB24B -:1056700043EA0525ADB20583F0BD082A018C3ED171 -:1056800021F480710904090C0184818B3E4A89B29E -:1056900021F0F301048C41EA0616B6B29042A4B29E -:1056A00046EA070712D002F5006290420ED0B0F130 -:1056B000804F0BD0A2F59832904207D002F580625D -:1056C000904203D002F58062904207D124F4007426 -:1056D00044EA03239BB243F4807304E024F420647F -:1056E00043F48073234387830384838B23F00C0369 -:1056F0001B041B0C8383838B9BB21D4341E021F46D -:1057000080510904090C0184828B048C22F44072BC -:105710001205120D42EA072242EA06361A4AA4B2DC -:105720009042B6B212D002F5006290420ED0B0F1B3 -:10573000804F0BD0A2F59832904207D002F58062DC -:10574000904203D002F58062904207D124F40052C7 -:1057500042EA033292B242F4805205E047F6FF5229 -:10576000224043F480531A4386830284838B23F4BC -:1057700040631B041B0C8383838B9BB243EA052588 -:10578000ADB28583F0BD00BF002C01401FB50123E1 -:10579000ADF808300023ADF80C30ADF80A30094BF5 -:1057A000ADF804101B7801A9012B08BF0323ADF845 -:1057B000062008BFADF80C30FFF7D5FE05B05DF848 -:1057C00004FB00BF0C06002038B510F80E2C044670 -:1057D00050F8043C52B9012200F80E2C20F80C1CA1 -:1057E000197B18680222BDE83840CFE730F80C2C4E -:1057F00020F80A1C891A89B220F8081C084A10F8F7 -:105800000F0C002502EB4002A2F86A1004F80E5CAF -:105810001868197B2A46FFF7B9FF04F8065C38BD03 -:10582000D40F0020CB78F0B5DA0648BF8A78098813 -:1058300003F00F0548BF154311F0FF0F1DD004689A -:1058400000220127974007EA0106BE4211D19700C6 -:105850004FF00F0C0CFA07FC05FA07F724EA0C04CA -:10586000282B44EA070401D1466102E0482B08BF17 -:1058700006610132082AE4D10460FF291FD9446877 -:10588000002202F108060127B74007EA0106BE42DE -:1058900011D197004FF00F0C0CFA07FC05FA07F72F -:1058A00024EA0C04282B44EA070401D1466102E0F3 -:1058B000482B08BF06610132082AE2D14460F0BDDE -:1058C0002DE9F843574B0C460168013AC3F88210A2 -:1058D0008188A3F88610072A42D8DFE802F0040A7C -:1058E000101822292F35B3F882202280B3F88420A3 -:1058F00013E0B3F884202280B3F8822005E0B3F8E7 -:10590000822052422280B3F88420524205E0B3F84C -:10591000842052422280B3F882206280B3F886301D -:105920001DE0B3F8822052422280B3F8842012E0B6 -:10593000B3F884202280B3F882200CE0B3F88220F0 -:105940002280B3F8842005E0B3F8842052422280FC -:10595000B3F8822052426280B3F886305B42A38063 -:10596000314B1B78002B5AD1B4F9000006F052FCE1 -:105970008046B4F9020006F04DFC0746B4F9040075 -:1059800006F048FC294D06462968404606F096FC7C -:10599000E9688146384606F091FC0146484606F023 -:1059A00085FBA9698146304606F088FC01464846D9 -:1059B00006F07CFB09F03AFB69682080404606F05F -:1059C0007DFC29698146384606F078FC0146484648 -:1059D00006F06CFBE9698146304606F06FFC014633 -:1059E000484606F063FB09F021FBA9686080404649 -:1059F00006F064FC69698046384606F05FFC0146A3 -:105A0000404606F053FB296A0746304606F056FC2E -:105A10000146384606F04AFB09F008FBA080BDE8C5 -:105A2000F88300BFD40F002028000020D8050020F4 -:105A3000074B084A1B7812889A4207D3064A126815 -:105A4000907898428CBF002001207047002070475A -:105A500008040020E40B00200404002010B5194BBA -:105A600093F88820511C83F88810174902F0070228 -:105A70004878164903EB420331F81010A3F88A1056 -:105A800000231846124A9A5A02331044102B80B24F -:105A9000F8D1C00806F0BEFB0E4906F00FFC0E4917 -:105AA00006F0C0FC0D4B04461B68187806F0B2FBEC -:105AB0000146204606F002FC06F0ECFD084B18708B -:105AC00010BD00BFD40F0020C0050020D00500206D -:105AD0005E1000203333534000F07F450404002063 -:105AE00008040020224B70B519684FF47A73B1FB9B -:105AF000F3F1204B20481A78204B214D1B7802F0FF -:105B00002FF8204B20481968204B2E68B1FBF3F189 -:105B100002F026F800241E4BE2B253F8221049B1DD -:105B2000012303FA02F2324202D01A4802F018F8B6 -:105B30000134F0E72A6892070DD5174A1748127802 -:105B400003EB8203196A02F00BF8154B197A11B1B5 -:105B5000144802F005F81448FCF722F9BDE870403B -:105B6000124B1348198800224FF4EF6301F0F8BF7D -:105B7000081A0020080400206A2001088000002084 -:105B80008802002084000020A820010840420F0065 -:105B9000600F0108C6200108B1210020CA200108B9 -:105BA0008C020020D4200108A12601084403002013 -:105BB000D820010870B586B0054609F013F8C0B2C8 -:105BC00008BB044606236343444A03F588731268FE -:105BD00019201344591D4D789A7A454305F561758E -:105BE0005B7900958D78684300F561700190C87805 -:105BF000029009793A4803912146013401F0B0FF3F -:105C00000C2CDFD168E0284609F041F80B285FDC56 -:105C100006267043314B00F588701E68202106442B -:105C20000023681C8DF8173008F0CFFF741D05465F -:105C300058B1451C284609F02AF8032805D89DF8D4 -:105C40001730607101338DF817302846202108F095 -:105C5000BCFF054658B1451C284609F018F80D2828 -:105C600005D870719DF8173001338DF8173028462C -:105C7000611C0DF1170204F085FB202108F0A5FF3F -:105C8000054658B1451C284609F001F80C2805D8EE -:105C90009DF81730E07001338DF817302846202129 -:105CA00008F093FF50B1013008F0F1FF0D2805D83E -:105CB0009DF81730207101338DF817309DF817309B -:105CC000062B09D020460021062208F04AFF03E0F7 -:105CD00004480C2101F044FF06B070BD18020020FA -:105CE0000A21010800220108F0B585B0074608F036 -:105CF00079FFC0B2E0B90446324B04F11C021B68C4 -:105D0000192003EB8203591D8D785A79454305F517 -:105D100061759B790095C978484300F561700190E1 -:105D200021462948013401F01BFF282CE4D146E02C -:105D3000384608F0ACFF27283DDC224B00F11C065A -:105D40001B68781C03EB8606202100238DF80F309A -:105D500008F03BFF751D044658B1441C204608F06E -:105D600096FF152805D870719DF80F3001338DF816 -:105D70000F302046202108F028FF044658B1441C6B -:105D8000204608F084FF0D2805D89DF80F30687074 -:105D900001338DF80F302046A91C0DF10F0204F0DD -:105DA000F1FA9DF80F30042B09D028460021042277 -:105DB00008F0D7FE03E00548282101F0D1FE05B028 -:105DC000F0BD00BF180200202A21010800220108AE -:105DD0003F4A2DE9F84F916840F201130B4040F221 -:105DE00001118B4293460AD13A4B1A7893F80190ED -:105DF0005A70B9EB020918BF4FF0010901E04FF0EA -:105E000001094FF00008344B5FFA88F41B78A34275 -:105E10005CD9324B324E1B68324F23B93B685B89E9 -:105E200026F814304FE03A68072C94BF12F804A00B -:105E3000A246294851469847DBF808300546DB055D -:105E400009D5B9F1000F06D0274B50461B682946EB -:105E50001B68DB699847A5F2EE2240F2DC5392B250 -:105E60009A4288BF3B68DBF8082088BF5D8942F210 -:105E7000010313402BB31D4B1978164B01F003029D -:105E800002EB840293F8620003EB420255801A464B -:105E900020B9032915D9012183F8621002EBC4034C -:105EA00099885D8802EB44020D44D9881B890D4412 -:105EB0001D44ADB2A2F8645004232DB295FBF3F556 -:105EC000ADB226F8145008F101089CE7BDE8F88F40 -:105ED0000C1A0020701000206708002070080020B5 -:105EE000620500200401002008020020EC0B0020C5 -:105EF0002DE9F0411E4C137CA46804F0400C022BE9 -:105F000032D80C265E431B4C03F1010835192F7A59 -:105F1000384226D0335D2BB1012B03D0022B14BFA6 -:105F200003230223144F1E01BC19BCF1000F02D140 -:105F3000BE5D022E15D04E7B277B3740B74210D175 -:105F40004F686668B7420CD38F68A668B74208D816 -:105F5000137094605560D16082F810801046BDE8DF -:105F6000F0815FFA88F3CAE70020BDE8F08100BF46 -:105F70000C1A002048000020AC0F0108094B30B576 -:105F80009D68094B05F480551868084B1C68002370 -:105F90000DB1828800E0A28805495A520233182BBD -:105FA000F6D130BD0C1A0020881800208C18002073 -:105FB000E60D0020F8B50024204BE0B21F78B8426F -:105FC0000CD21F4B33F810101E4B53F820301BB16E -:105FD0000B2801D8DB6898470134EDE71A4B9B6822 -:105FE0005B032AD50025194E2B46EAB2BA4224D2C9 -:105FF000726854689C4218D02046FCF794FBEFF37B -:106000001283502282F3128811494FF0280CA28C7F -:106010000CFB001092B201324262A28ADBB292B251 -:1060200042F00102A28283F3118856F8043F002255 -:106030001B6801351A802346D7E7F8BD842100206C -:10604000862100203C0700200C1A00203807002081 -:10605000BC1800202DE9F04FAF4E85B03778032FE4 -:1060600014D9AE4BAE48B3F90410B0F9042000299E -:10607000B8BF49426FF063035B1A9A4204DB01F137 -:1060800064039342A8BF134683801FE0012F1DD8ED -:10609000A44BA54C1B78013B142B00F2E381DFE8F5 -:1060A00013F09100E101E10168009F00E101E101CD -:1060B0003101E101E101E101E101E101BD00E101A5 -:1060C000E101E101E101E101A301BA01934B97492B -:1060D000B3F806A0924B0968B3F80280B3F80090B9 -:1060E000B3F904B0924C02910025BD4204F11004B2 -:1060F000CED20FFA8AF006F08DF854F8101C06F094 -:10610000DDF803460FFA88F0019306F083F854F89F -:10611000081C06F0D3F8019B0146184605F0C6FF9F -:1061200003460FFA89F0019306F074F854F80C1C3A -:1061300006F0C4F8019B0146184605F0B7FF029A25 -:10614000034692F90000019340420BFB00F006F079 -:1061500061F854F8041C06F0B1F8019B014618469A -:1061600005F0A4FF06F070FA724B23F81500013514 -:10617000BBE702210420FBF77CFE694D0121AF88BB -:1061800078431FFA80F80420FBF773FE6D8800FB4C -:1061900005801FFA80F80420FBF77AFE4044208136 -:1061A00002210520FBF765FE7843012187B2052017 -:1061B000FBF75FFE00FB057087B20520FBF768FE6A -:1061C00038440BE005200121FBF753FE544B9D881A -:1061D000684385B20520FBF75BFE2844608141E1FE -:1061E000554B00201D68FBF753FEDFF8688195F9D9 -:1061F0000630B8F902203227534393FBF7F31844D3 -:1062000020800120FBF744FE95F90E30B8F90020FC -:10621000534393FBF7F73844608023E1474B1B78E7 -:1062200013F0040F464B02D11B689B880BE01968E2 -:106230003A4A0B88B2F9062049889A4203DB914218 -:10624000B4BF0B461346E381E2893A4B3A4F1A80BA -:106250003C4B1B681D7855B30220FBF719FE3A68CA -:10626000B2F91030518A984203DB0BB29842B8BFA2 -:106270000346354909684889C3EB000E334B0FFAD2 -:106280008EFEB3F87C100FFA81FCF44501DA0D4460 -:1062900001E002DD4D1BA3F87C5092F91620B3F902 -:1062A0007C305343642293FBF2F31844A080284BC4 -:1062B0001B88DB050CD5194B1A88D7F80090E280B3 -:1062C00022819A88184F62815B880325A38101E0AF -:1062D000134BF1E709EBC50393F90630B7F90680D4 -:1062E000284608FB03F8642398FBF3F8A7F8068018 -:1062F000FBF7CEFD01354044072DF88007F102077A -:10630000E8D1AFE00D4B1B7813F0040F0C4B23D1F9 -:106310001B689B882CE000BF84210020C60300205E -:10632000E0170020E80300206C000020EC030020B0 -:106330008C0700208621002084180020B021002036 -:106340008C18002090180020941800207010002055 -:1063500050030020080300201968AD4A0B88B2F9E9 -:10636000062049889A4203DB9142B4BF0B4613468C -:10637000E381E289A74BA84D1A80A84B03201B8814 -:106380000121DF0503D5FBF774FDA14F02E0FBF708 -:1063900070FDA34FB7F80280022100FB08F01FFA3E -:1063A00080F90320FBF765FD3F88012100FB079082 -:1063B000E8800420FBF75DFD00FB08F002211FFAD6 -:1063C00080F80420FBF755FD00FB0780288103209F -:1063D000FBF75EFDE3881844E0800420FBF758FDDE -:1063E0002389184420813DE001210420FBF741FD71 -:1063F0008B4D6F88784387B204202781FBF748FDD7 -:106400003844208101210520FBF733FD2D886843A6 -:1064100085B26581DEE6824B0325B3F80490984689 -:1064200028460221FBF725FD00FB09F0012187B278 -:106430002846FBF71EFDC5F106035B0838F813304C -:1064400000FB037087B224F815702846FBF720FD87 -:10645000384424F815000135072DE1D16C4BDA885A -:106460006C4B1A806F4DDFF8E491AB6813F0200F8E -:1064700034D00020FBF70CFD208080460120FBF784 -:1064800007FD694B644F1B6860801A0626D5674B71 -:106490001B681B7813F0020F654B23D0D9F800C09E -:1064A000B3F900109CF90E209CF906C0B3F9023034 -:1064B0004A43CCF1000C03FB0CF3322192FBF1F2C6 -:1064C0006FF0310C92B293FBFCFC9444E04493FBDC -:1064D000F1F1A7F800800A4410447880D9F8001040 -:1064E000002319E0D9F80010B3F902C091F9062091 -:1064F000B3F900300CFB02FC32229CFBF2FCE044BE -:10650000A7F8008091F90E104B4393FBF2F2E3E7FA -:10651000E2520233102B0CD0E05E31F9232001EB64 -:10652000830790427F88F3DB3AB28242A8BF0246DB -:10653000EEE73E4B1B681B785B0704D43549347883 -:10654000088801231BE03B4B00241F780423043FF1 -:10655000FFB25FFA87F84FFA88F2D4420BD4364A7A -:1065600003F10109381932F813105FFA89F9C0B242 -:10657000FCF71BF94B460134042CECD1DEE7A342B7 -:1065800008D231F9132000B28242A8BF104680B26F -:106590000133F4E7294B4FEA44081A68AB6803F467 -:1065A00080550395244D03F01009254BB5F906607D -:1065B000244D1B782F68244D03F00403DBB2D5F87B -:1065C00000C002930023434562D0B2F802A004B297 -:1065D000544505DD0F4CC0EB0A0A1D5B55441D53A5 -:1065E000039D0C4C002D33D07D8931F903A0AE42C0 -:1065F000CBBFBCF802509588B2F802B0BCF800B02E -:10660000AA4503DBDA45B4BF55465D46E55238E09E -:10661000C6030020862100206C00002050030020CB -:10662000E01700200C1A00204C03002098180020CE -:10663000080300200F060020620500208C180020AF -:10664000B021002094180020881800208418002011 -:1066500031F903A01588B2F802B0AA4503DBDA4588 -:10666000B4BF55465D46E55204EB030ABC89A64219 -:1066700007DAB9F1000F01D1148800E09488AAF874 -:106680000040029C14B9044C1C5BCC5202339AE7C4 -:1066900005B0BDE8F08F00BFE60D0020826A816979 -:1066A000436B1144D960416A914203D98A1A5A60F6 -:1066B000816204E001698A1A5A6000228262002223 -:1066C00080F844201A6842F001021A60704700BF47 -:1066D00010B50446204608F085FA10F0FF0F06D1E9 -:1066E0000C4B0D481978BDE8104001F039BA20462E -:1066F00008F0CDFA02280CD8064B0A221870074B76 -:10670000074C02FB0030074B06301860FBF70EFA0F -:10671000E0E710BD440C0020AD2101085C21002001 -:1067200076260108E0030020174B13B51A880446AB -:1067300022F040021204120C1A801A883B2022F028 -:1067400038021204120C1A801A88694692B242F07A -:1067500040021A80062200F097FE9DF800209DF866 -:10676000013043EA022323809DF802209DF8033084 -:1067700043EA022363809DF804209DF8053043EA34 -:106780000223A38002B010BD00300140174B13B5A7 -:106790001A88044622F040021204120C1A801A8849 -:1067A000432022F038021204120C1A801A8869461B -:1067B00092B242F040021A80062200F065FE9DF877 -:1067C00000209DF8013043EA022323809DF8022037 -:1067D0009DF8033043EA022363809DF804209DF86E -:1067E000053043EA0223A38002B010BD003001400F -:1067F00010B5A0F513746379DB074CD594F83832E3 -:1068000013B3236B1868828DC2F34E02828494F80E -:106810003C2222B1B4F842220132A4F84222A279E9 -:10682000197B012A0CBF0222002200F0C3FC0123C5 -:1068300084F83B32002384F8393284F83A3284F801 -:106840003832A4F8403210BD94F83B322046012B78 -:1068500004BF94F8393284F83A32FBF781FF94F898 -:106860003B12236BA27949B9012184F83B128A4279 -:106870001868197B0CBF0222002208E0002184F86E -:106880003B12012A1868197B14BF02220022BDE8BE -:10689000104000F08FBC10BD10B5A0F5127494F834 -:1068A0003C22C2B9A36A616A994229D0591CA069E5 -:1068B000A162C05C2369C0B299424FEA400343F42D -:1068C0000073A4F83E324FF00A0384F83D3228BF2B -:1068D000A262012312E094F93D327BB1B4F83E127A -:1068E00020464B08A4F83E3201F00101FBF74DFFB2 -:1068F00094F83D32013B84F83D3201E084F83C32AB -:1069000094F83832002B4FD194F839320133DBB28E -:10691000092B84F8393204D12046BDE81040FBF73A -:106920001FBF0A2B40D194F83B322BB9B4F8403248 -:1069300043F00103A4F840326379D9071CD5B4F8B9 -:106940004002820501D4C30705D4B4F844320133B0 -:10695000A4F8443210E0E36AC0F347000BB1984753 -:106960000AE0E3696269D054E269E3680132B2FB8C -:10697000F3F103FB1123E361012284F8382294F838 -:106980003B220023012A84F839320DD1A27984F800 -:106990003B32236B012A1868197B14BF02220022A4 -:1069A000BDE8104000F006BC10BD00230F49DAB26C -:1069B000595C4F2903D001330A2BF7D11A460C4BEF -:1069C00083F82C21002283F82D2183F82E214FF407 -:1069D000E132C3F83021C3F83421C3F83821C3F8B9 -:1069E0003C21522283F84021704700BFA3210108B7 -:1069F0000C1A00202DE9F04FD84AD94C85B0106808 -:106A0000516802AB03C3DFF8908300214FF4EF62BB -:106A1000204608F0A6F804F50573C8F80030D14BFD -:106A20000025DFF878A31D7004F25673CAF8003011 -:106A3000032363710223A36040F24C404FF41673AA -:106A4000A4F8F030A4F81C01FA2340F26C70A4F80A -:106A5000F230A4F81E012A231920A4F8EE3084F89D -:106A600025014FF4FA7340F27E40A4F8F630A4F802 -:106A7000D000202340F23A7084F8F430A4F8D20019 -:106A80006E234FF47A7084F80431A4F8D4002B23D9 -:106A900040F27E5084F80531A4F8D600212340F25C -:106AA000EA500126552240F2DC514FF01E0B4FF008 -:106AB000320984F80631A4F8D8004FF4C87340F2C4 -:106AC000B4502270A4F80831A4F81A11A4F8DA001E -:106AD000A4F8DE3084F8EC6084F821B184F82461F5 -:106AE00084F82761A4F8DC90A4F8E0908DE8060013 -:106AF000FFF75BFF40F6AC53A381D8F8003028279E -:106B00001720A57318761F7183F80EB05F7183F894 -:106B10000FB058761D700B20019A1872142058720D -:106B20001875502098776420D8774FF0080E782099 -:106B300083F813E05873DFF868C28B484FF00E0EED -:106B40009A7183F80AE02D224FF05A0E4FF00A0B8B -:106B50001A745A7783F80BE01F73DA7583F8216093 -:106B60009D7683F807905D74DD769D741D7783F8BC -:106B700015B0C3F824C0D86318644FF08240D862BF -:106B80004FF07C5098637948C3F828C05864784A1D -:106B90007848DFF810C200991A635A639864C3F802 -:106BA0004CC084F856E74FF0410EA4F85E1784F805 -:106BB00057E784F85A5784F85B5784F8589784F855 -:106BC000595784F85C579A666B4A0421DA666B4A17 -:106BD00083F858101521D86583F8607083F86170C8 -:106BE0001A6783F87460A3F85450A3F85650A3F8BA -:106BF000525083F864106248FEF742FBD8F8003028 -:106C00004FF44872A3F86221C82283F8A7214FF4F9 -:106C10009662A3F8A82140F2D932A3F8AA2140F63F -:106C2000430283F85F7183F86061A3F8AC2183F8B5 -:106C30005D5183F85E5183F8645183F8A6B11A461A -:106C4000474656464FF47F71A2F866114FF4FA6139 -:106C5000A2F8681102A840F2DC51A2F86A11415D65 -:106C6000013582F86C11082D4FF0FF0182F86D118B -:106C700002F10802E6D1012283F8AE2183F8AF21A8 -:106C800083F8B021C82183F8B6216422A3F8B21199 -:106C9000A3F8B82114214FF4967283F8B411A3F825 -:106CA000BA211E21282283F8B511A3F8BC210023A4 -:106CB000E21810330021C02B1161F9D131480021B5 -:106CC000402207F04EFF00232F49E21859580433A1 -:106CD0000868382BC2F8D401F6D12C480021802254 -:106CE00007F03FFF2A4B294D03F1300E1868596811 -:106CF0002A4603C2083373451546F7D1254DFBF7E5 -:106D0000A9FBFBF7E3FBFBF7BDFB3F6828463946D1 -:106D10004FF4E07207F01CFF394605F5E0704FF4C0 -:106D2000E07207F015FF336805F56372596818685B -:106D300003C2198911801A68C5F896235A68C5F8E4 -:106D40009A231B89A5F89E33012384F82434022357 -:106D500084F8E43505B0BDE8F08F00BFDC0F010812 -:106D60000C1A0020440C00208FC2753DCDCC4C3D48 -:106D70009A99193F0000A040F6287C3F3D0A773FD2 -:106D8000BE210108E01B0020F0060108601B002066 -:106D9000E40F0108E01D002018020020E00300209D -:106DA0000000204000004040F7B50368174C184D24 -:106DB00023600B68174E63600068FBF7F1FB95E8F2 -:106DC0000300154B0196009394E80C00FBF7A6FB1B -:106DD0003668124B60681E606B68114FC01A05F070 -:106DE00019FA104B196805F069FA05F02DFC2268B4 -:106DF0002B687860D31A3B600B4B1E600B4B1B68F3 -:106E0000DA880B4B1A8003B0F0BD00BF780F00206A -:106E100024040020840F0020800F0020C00F0020D9 -:106E2000880F002030000020B80F0020D40300207D -:106E3000B40F00202DE9F043142285B08146884626 -:106E40001B48002107F08DFE02261A4B0027B7428F -:106E500024DA13F8042C0021C8B2013112B1501EFB -:106E60000240F9E71C7AD1B2013214B1611E0C4024 -:106E7000F9E7421A002A0EDD01ACA3F10C0595E8F2 -:106E8000070084E8070093E8070085E8070094E816 -:106E9000070083E8070001370C33D8E7013ED4D15F -:106EA000034A4846414605B0BDE8F043FFF720B825 -:106EB000F01000205400002070B52548037813F02E -:106EC000010F03F004023AD0002A40D103F002017E -:106ED00001F0FF06002932D143F0040303701D4B7B -:106EE0001A881D4B1A801D4B9B6859052FD504200D -:106EF00000F073F901460420FFF79CFF43681A7AFB -:106F0000D20724D55C6814B3154D2B68A34208D171 -:106F100020460121FAF777FD284631464C2207F03A -:106F200020FEEB6CA34212D120460121FAF76BFD43 -:106F3000BDE870400B4800214C2207F012BE32B968 -:106F40000220FF210122BDE87040FAF733BE70BD78 -:106F5000B021002018030020280D00200C1A00206A -:106F6000480D0020940D002038B505460C4600F071 -:106F700034F901462846FFF75DFF28B143681B7AC4 -:106F80001C420CBF0020012038BD38B50B4B054614 -:106F90009B685A050ED5FBF753FA044650B10820FA -:106FA000E9B2FFF7E1FF30B1054B1C78231F5C42CB -:106FB0005C4100E00124204638BD00BF0C1A0020CF -:106FC000B4040020084B5A6882420AD01A698242EF -:106FD00006D0DA69824208BF183302D0002300E0ED -:106FE0000C335972704700BF480000202DE9F34769 -:106FF00006461F464FF41473734345489246C4181F -:10700000804626B9434A2263103AC4F83421424AE2 -:107010000025C250032363714FF480734FF00109C0 -:10702000E3602361D4F8343184F83C5284F8389218 -:1070300084F8395284F84662586804F134029B6837 -:10704000626104F59C72A261E1622562E561A5625C -:107050006562A4F84252A4F84452ADF80430022507 -:10706000102301A9C4F808A0A7718DF806308DF887 -:107070000750FBF7B3FB236B01A958689B688DF899 -:107080000750ADF8043048238DF80630FBF7A6FB17 -:1070900049462046FBF779FB3220FAF77AFD1F4B71 -:1070A000D4F834911B681D46B5FBFAF1B1F5803F69 -:1070B00003D3012DF8D96D08F6E7194A4846B3FB0A -:1070C000F2F289B2D2B200F079FA4FF414735E434F -:1070D000144B06F5127608EB060548F806304846CC -:1070E0002946002203F088FA266B012F14BF0222E2 -:1070F00000223068317B00F05DF80B4B30466B604E -:10710000291D002203F078FA204602B0BDE8F0877E -:1071100004110020101E0108141001088400002032 -:1071200040420F0099680008F167000803460A46CC -:1071300090F84602D96A9B7958E700BF426A10B5B9 -:107140008469A154416A02690131B1FBF2F402FB86 -:1071500014124262426B32B11368DB0708D4BDE8F7 -:107160001040FFF79BBA036DDA6842F08002DA60E4 -:1071700010BD08B540F2E9330D4A1189890709D5D8 -:10718000908140F2E9330A4A1189C9070AD59089EA -:10719000C0B208BD013B9BB2002BEDD1FBF757FB02 -:1071A000FF2008BD013B9BB2002BECD1F6E700BFEE -:1071B000003001401FB50123ADF80830ADF80410D0 -:1071C000002301A9ADF80A30ADF80C30ADF8062067 -:1071D000FEF7C9F905B05DF804FB70B5002206465C -:1071E00030491301585CB04204D00132072AF7D16C -:1071F000002070BD2C4C0B44082E0FCB254684E894 -:107200000F001AD009D8022E0ED0042E15D0012E50 -:1072100046D1264B1B685B683FE0202E3AD0402EBB -:1072200006D0102E3CD11FE0204B1B689B6802E06B -:107230001E4B1B681B6963602FE01D4B1B681B788E -:1072400053B1013B012B0AD9FBF7FAF8002814BF10 -:107250004FF46143002304E04FF4165301E04FF470 -:1072600096436B60AB601BE0124B1B681B7A042BD0 -:1072700016D8DFE803F00808030808000E4B636027 -:10728000A360032304E04FF4E1336360A3600123B0 -:107290006B7305E0054B1B68DB68A360204670BD7F -:1072A000014870BD2C10010854130020E00D00208F -:1072B000F403002004010020A08601000E4B1A7880 -:1072C000552A16D15A88B2F5EF6F12D11A79BE2A13 -:1072D0000FD193F874270020EF2A0CD113F8012B5B -:1072E0005040064A9342F9D1D0F1010038BF002046 -:1072F000704700207047704700F8010878FF0108C8 -:107300004A4B55222DE9F3411A704FF4EF625A802F -:10731000BE221A71EF2283F87427002283F87527A2 -:1073200011461E46B35C0132B2F5EF6F81EA0301EC -:10733000F8D13E4B3E4A83F875173E4B04275A60FE -:1073400002F188325A600020013F17F0FF075DD03C -:10735000384B3422384CDA60C4F309037BB133195B -:1073600003F17843A3F5FC33D3F800804FF40050C9 -:1073700000230193FEF7E6F80428E5D11BE04FF463 -:107380003020FEF7DFF80428DED12A4D4FF43020FC -:107390002B6943F002032B616C612B6943F04003BE -:1073A0002B61FEF7CFF82A6941F6FD7313400428DC -:1073B0002B61D4D0C8E71F4D4FF400502B6943F028 -:1073C00001032B611FFA88F32380FEF7BBF8042822 -:1073D00012D1A31C0193019B4FEA1848A3F8008027 -:1073E0004FF40050FEF7AEF82B6941F6FE721A40DA -:1073F00004282A6106D0A7E72B6941F6FE721A40DD -:107400002A61A1E70D4B04349C42A5D1094B042805 -:107410001A6942F080021A6102D1FFF74FFF10B9DA -:107420000A20FAF7EDFB02B0BDE8F0810C1A00204B -:10743000230167450020024000F8010878FF010899 -:107440008A2802D08E2809D07047094B1B689B06FA -:107450000DD5084B1B7853B9074A03E0054B1B7841 -:107460002BB9064A064B1A60064B2D221A7070473C -:10747000880200208C0400205C04002030040020DE -:1074800098040020A104002070B5184E10237361E9 -:1074900040F080000C461546FFF76BFE144B9B89AD -:1074A0004FF47A737DB1124A1189880706D5FF21FE -:1074B00091810F4A1189C90711D509E05A1E92B26C -:1074C00023B9FBF7C4F91023336170BD1346EAE713 -:1074D000928992B20CB122700134013DE2E75A1E4A -:1074E00092B2002BEDD01346E3E700BF0008014045 -:1074F0000030014070B5054C10250E466561FFF760 -:1075000038FE3046FFF735FE256170BD00080140AA -:1075100008B5284B80211A886B2022F04002120403 -:10752000120C1A801A8822F038021204120C42F04F -:1075300030021A801A8892B242F040021A80FFF795 -:10754000D9FF9620FAF725FB03216820FFF7D2FF29 -:107550009620FAF71EFB03216B20FFF7CBFF0120DB -:10756000FAF70CFB10216A20FFF7C4FF0120FAF79D -:1075700005FB00216C20FFF7BDFF0120FAF7FEFAA2 -:1075800000211920FFF7B6FF0120FAF7F7FA1021C2 -:107590001C20FFF7AFFF0120FAF7F0FA1B2018219B -:1075A000FFF7A8FF0120FAF7E9FA034B01221A704E -:1075B00008BD00BF00300140FC05002013B50446A3 -:1075C000006800F0FFF9236801A81A8892B242F01F -:1075D00001021A80637B00228DF8043001238DF8AC -:1075E00005308DF806208DF8073000F0CDF902B097 -:1075F00010BD2DE9F74FA24F0C463E7C05461146C3 -:10760000006891469B462246731C3B7400F0DAF9F1 -:10761000AB686868ADF8043018238DF8063001A90E -:1076200002238DF80730FBF7D9F82B7B143736018E -:1076300007EB060A2C680C2B00F2F280DFE813F04F -:107640000D00F000F000F0004D00F000F000F00040 -:107650008200F000F000F000B600238C894823F08F -:1076600001031B041B0C2384218CA288238B8442DE -:1076700023F073034FEA03434FEA134389B292B2F4 -:1076800043F0700314D000F50060844210D000F580 -:10769000406084420CD000F58060844208D000F540 -:1076A0008060844204D021F0020141F0030107E030 -:1076B00021F00E0122F4407241F0030142F4807285 -:1076C000A2802383A4F834B02184238B23F0080301 -:1076D0001B041B0C43F0080332E0238C694823F0A1 -:1076E00010031B041B0C2384218CA288238B84424F -:1076F00023F4E6434FEA03434FEA134389B292B2BD -:1077000043F4E04308D000F50060844204D021F047 -:10771000200141F0300107E021F0E00122F4406255 -:1077200041F0300142F48062A2802383A4F838B093 -:107730002184238B23F400631B041B0C43F400639C -:1077400023836DE0238C4F4823F480731B041B0CB0 -:107750002384218CA288A38B844223F073034FEAF5 -:1077600003434FEA134389B292B243F0700308D047 -:1077700000F50060844204D021F4007141F44071AE -:1077800007E021F4606122F4405241F4407142F478 -:107790008052A280A383A4F83CB02184A38B23F061 -:1077A00008031B041B0C43F0080338E0B4F820C0A6 -:1077B000344A2CF4805C4FEA0C4C4FEA1C4CA4F881 -:1077C00020C0B4F820C0A388B4F81C802CF4005C5E -:1077D00028F4E6484FEA08484FEA0C4C4FEA1848AC -:1077E0004FEA1C4C94429BB248F4E0484CF4405C95 -:1077F00003D002F50062944203D123F4804343F4A2 -:107800008043A380A4F81C80A4F840B0A4F820C052 -:10781000A38B23F400631B041B0C43F40063A383BA -:10782000AB7B43B1B4F844306FEA43436FEA534350 -:107830009BB2A4F8443023889BB243F00103238019 -:107840002B7B0C2B14D8DFE803F0071313130A1358 -:1078500013130D131313100004F1340307E004F1A4 -:10786000380304E004F13C0301E004F14003BB51A0 -:107870005046AAF80890CAF8044003B0BDE8F08F5B -:1078800054130020002C01400EB40FB5074906AB7D -:107890000190074A01A80393FDF700FC019B002219 -:1078A0001A7004B05DF804EB03B070476917000864 -:1078B000C72101084B8810B5DC0607D52C4B14797D -:1078C0001B6853F824402B4B43F820404B889B0601 -:1078D00007D5274B54791B6853F82440254B43F8B0 -:1078E00020404B881C070DD5234B0C781B78B3EB3D -:1078F000141F07DB1E4BD4781B6853F824401D4B24 -:1079000043F820404B889B070DD51C4B0C781B7807 -:10791000B3EB141F07DC164B54781B6853F8244054 -:10792000144B43F820404B88DC070ED5144B0C78E1 -:107930001B7804F00F049C4207DC0D4B14781B6885 -:1079400053F824400B4B43F820404B885B070ED57F -:107950000C4B09781B7801F00F01994207DB044BAF -:1079600092781B6853F82220024B43F8202010BD68 -:10797000A8080020E00400209705002095050020BD -:1079800094050020960500200D4B10B5DC680122FF -:10799000E443C4F30224C4F1040402FA04F40178B9 -:1079A000A3F5406324011944E4B281F8004301784F -:1079B000480901F01F018A4043F8202010BD00BF94 -:1079C00000ED00E0254B10B55343254A254C1268C5 -:1079D0000139B2FBF3F20388013AA04289B292B2B4 -:1079E0009BB212D004F50064A0420ED0B0F1804FDB -:1079F0000BD0A4F59834A04207D004F58064A042CF -:107A000003D004F58064A04202D123F070039BB23E -:107A1000154CA04206D004F58064A0421CBF23F49C -:107A200040739BB203800F4B8185984202850FD033 -:107A300003F5006398420BD003F54063984207D0EA -:107A400003F58063984203D003F58063984201D127 -:107A5000002303860123838210BD00BF40420F0034 -:107A600084000020002C014000100040284BF0B59D -:107A70001D6800222748165C1418AB19597801F0CC -:107A8000040101F0FF0371B10132102AF2D100208C -:107A9000F0BD1BB103EB83035B00DBB210F8012BDD -:107AA000303A1344DBB2221A022AF2DC002184426B -:107AB0000AD919B101EB81014900C9B210F8012BB3 -:107AC000303A1144C9B2F2E72E2E14D1601C0022C4 -:107AD0000424067802EB8202AF197F7852007F07F8 -:107AE00092B203D5303A3244013092B2013C14F0E4 -:107AF000FF04EED100E00022074806244143642041 -:107B000000FB02120548B2FBF4F200FB0320F0BDBB -:107B100090000020130E002040420F008096980035 -:107B200030B5002213460D495C5C9CB12E2C04D16B -:107B3000013378B11C1800250D550A246243C95C35 -:107B4000A1F13004092C9CBF303A52180E2B03D8F7 -:107B50000133E8E7104630BD002030BD130E002091 -:107B60000FB407B50A4904AB08680A4953F8042B57 -:107B700009680193FDF792FA074B1868FAF761F864 -:107B80000028F9D003B05DF804EB04B0704700BFE3 -:107B9000A8050020A40500202818002037B58288F9 -:107BA0000446836810060D4606D529494FF4E07057 -:107BB00091F8541700FB0133D10504D525490A205B -:107BC000097800FB013302F03F02042A12D006D8E4 -:107BD000012A0DD0022A2FD193F900102DE0102A8E -:107BE0000AD0202A0AD0082A26D1B3F9001024E0AE -:107BF000197822E0198820E019681EE069461868A3 -:107C0000FDF756FB01461448FFF7AAFFF5B1E068FF -:107C100004F000FB6946FDF74BFB01460F48FFF7F8 -:107C20009FFF206904F0F6FA6946FDF741FB014623 -:107C30000A48FFF795FF09E000210948FFF790FF88 -:107C400025B10848E1682269FFF78AFF03B030BD1B -:107C50000C1A0020440C0020D1200108D02001087B -:107C6000D7210108D32101082DE9F0438DB0054645 -:107C700006F0B8FFC0B2002858D104467F4B00215F -:107C80001E68142207A806F06CFFA500002303A9B4 -:107C900005A80393059377190B7183801A46DFF8C3 -:107CA000F0E1B7F802C03EF8138018EA0C0F0CD0D0 -:107CB0000EF10A0E0DF1300813F80EE002F1010C7E -:107CC000424402F824EC5FFA8CF20133052BE6D132 -:107CD00000231A46DFF8C0E1B7F802C013F80E809F -:107CE00018EA0C0F0CD00EF1060E0DF1300813F847 -:107CF0000EE002F1010C424402F81CEC5FFA8CF237 -:107D00000133062BE6D1735D8DE803001A0907A83D -:107D10005B4903F00F03FFF7B7FD2146594807AA57 -:107D20000134FFF71DFF202CA8D1A3E0284606F060 -:107D3000AEFF1F28044600F3918028462021E4B2BC -:107D400006F043FF1F2C01D94F4888E04B4B471CDE -:107D50001B68002103EB84042046042206F001FF87 -:107D600000254A4B07AE304600210A2215F8039041 -:107D70005FFA85F806F0F5FE0023FA5CF91832B1D7 -:107D80000A2B04D04A4502D0F2540133F5E74A45A4 -:107D900001F1010767D1B8F1020F0DD0B8F1030F5F -:107DA0000CD0B8F1010F0BD0304606F070FF2378ED -:107DB000C0B243EA00100AE0002219E0002226E0E7 -:107DC000304606F064FF237800F00F00184320705F -:107DD00038E00133062B0AD02D4800F115069E5DD0 -:107DE0008E42F6D10344D97B63880B436380013212 -:107DF0000CA9D3B20B4413F8141C19B30023EBE7FE -:107E0000412B1DD0542B08BF04230ED00132D3B216 -:107E10000DF13008434413F8143C9BB1492B01D1B8 -:107E2000002302E0572B07D10123194931F8131021 -:107E300063880B436380E9E7462BE1D10223F4E733 -:107E40000323F2E70135042D8BD10124FAF702FB5D -:107E5000FAF73CFBFAF716FB64B975E70D482021E9 -:107E6000FFF77EFE06E020460021042206F079FEA0 -:107E70000024EBE70DB0BDE8F08300BFDC04002078 -:107E8000C7210108DA210108E6210108B71001081D -:107E90009C100108F4210108AB10010807B5064B3E -:107EA00006480093064B074A1968074BFFF758FE30 -:107EB00003B05DF804FB00BF472201081622010849 -:107EC00088000020322201083E22010810B5074830 -:107ED000F9F766FF0024064B0648E218E15852689D -:107EE0000C34FFF73DFEFC2CF5D110BD4F220108EC -:107EF00084110108652201087FB5044606F072FE70 -:107F0000082824D100231F49E25C096811444978FC -:107F100001F00301022908BF203AE2540133082B83 -:107F2000F1D10025665D1848314606F04EFE28B1B5 -:107F300001356019314606F048FE18B11348F9F7CB -:107F40002FFF1CE0082DEDD12046FDF799F91048D0 -:107F5000F9F726FF00230F4A04A91A4492F81021CA -:107F60000A440949595C0133082B02F80C1CF2D170 -:107F70000023094801A98DF80C30FFF7F1FD04B08A -:107F800070BD00BF90000020BC2A01086D220108CE -:107F90008D2201080C1A0020682201082DE9F04307 -:107FA00089B0044606F01EFEC6B2002E6CD18B4886 -:107FB000F9F7F6FE8A4C2069002104F013FB40BB60 -:107FC000013688483146FFF7CBFD206904A9FDF74B -:107FD0006FF901468448FFF7C3FD606904A9FDF706 -:107FE00067F901468048FFF7BBFDA06904A9FDF7CA -:107FF0005FF901467C48FFF7B3FDE06904A9FDF78E -:1080000057F901467948FFF7ABFD0C2E04F1100437 -:10801000D1D10025764C2F462B464FF00008B045B5 -:1080200004F1100415DA184654F8101C04F03EF858 -:1080300054F80C1C8146284604F038F854F8081C03 -:108040000546384604F032F808F101084B46074669 -:10805000E5E76848019302950397F9F7A1FE00242C -:1080600001ABE058644920F0004004F0E3FA634BB0 -:10807000634A0434002814BF10461846F9F790FEEE -:108080000C2CEDD15F4891E020465F49052206F0B7 -:10809000B1FD38B9524B002203441030C0281A6198 -:1080A000F8D197E020465949042206F0A3FD064680 -:1080B0002046002E40D1202106F087FD002800F048 -:1080C0008980451C284606F08DFD34468046504B7D -:1080D00053F824600EB94F4868E0284631465FFAED -:1080E00088F206F087FD671C20BB3D4B0021C218BB -:1080F0001030C02811619C46F7D1474B002403EB98 -:10810000C702D2F804E09846BEF1000F04D14348FC -:108110003146FFF725FD55E018F837309C42F6DA76 -:1081200023010CEB0305103573440FCB013485E8B4 -:108130000F00F1E73C46CAE706F0A9FD461E0B2EEC -:10814000074643DC2046202106F03FFD054640B1AE -:10815000451C2846F9F7ECFF214B3F01D85101247B -:1081600000E004462846202106F02FFD054640B1D8 -:10817000451C2846F9F7DCFF194B013403EB0613C5 -:1081800058612846202106F020FD054640B1451CD7 -:108190002846F9F7CDFF124B013403EB0613986123 -:1081A0002846202106F011FD18B91D48F9F7F8FD01 -:1081B00010E00130F9F7BCFF094B032C03EB061666 -:1081C000F061F2D11748FFF7E9FE03E016480C21F1 -:1081D000FFF7C6FC09B0BDE8F08300BFAA22010882 -:1081E0000C1A0020D5220108DB22010868220108B0 -:1081F000201A0020DF2201080AD7233CA62201080A -:10820000A2220108A1260108EE220108F422010899 -:1082100080120108F92201083C0701080E23010819 -:108220001E2301087626010858230108F8B50746E1 -:1082300006F0D8FC044638B9194B1A485A791A4B3B -:10824000013A53F8221028E038461849224606F031 -:10825000D1FC60B91648F9F7A3FD164C54F8041F79 -:1082600019B11548FFF77CFCF8E7144805E0002534 -:108270000D4B53F8256026B91148BDE8F840F9F7D1 -:108280008FBD38463146224606F0B4FC0135002841 -:10829000EED1034B0B485D713146BDE8F8405FE419 -:1082A0000C1A002080230108801201086E280108A2 -:1082B000942301087C120108C6200108A1260108A8 -:1082C000F9220108A723010870B5044606F08AFCCC -:1082D00008B91E482EE020461D4906F0FDFC00248A -:1082E0002646254678B12CB1012C06D106F0CFFCEC -:1082F000064602E006F0CBFC054615490020013495 -:1083000006F0EAFCEEE70B2D04D9BDE870401148F9 -:108310000C2125E4012C07DC0F4B294633F91520ED -:108320000E48BDE870401BE4A6F57A73B3F57A7F7A -:1083300003D90B48BDE8704012E40A48294632468A -:10834000FFF70EFC044B23F8156070BDB92301083C -:1083500045260108F3230108E60D00201924010831 -:1083600031240108532401082DE9F743044606F09F -:1083700039FCC0B290B9314C054694F8D711B4F825 -:10838000D42194F8D6312E48009129460135FFF7C3 -:10839000E7FB102D04F10404EFD14BE0204606F07A -:1083A00076FC0F28054636DC2046202106F00DFC21 -:1083B000244FEDB2D7F80090441CAD0000262046B3 -:1083C00006F065FC5FFA86F8B8F1010F83B208D0B9 -:1083D000B8F1020F0BD0B3F5B47F1ED23A685353F5 -:1083E0000AE0FF2B19D83B682B44987004E0FF2B60 -:1083F00013D83B682B44D87020462C2106F0E5FBAF -:10840000044608B1441C02E0B8F1020F05D1013660 -:10841000032ED4D10EE00C4806E009EB0500002144 -:10842000042206F09EFB0948102103B0BDE8F0438A -:10843000FFF796BB03B0BDE8F08300BF0C1A002025 -:108440006C240108A808002080240108E621010806 -:10845000044B1A6942F480421A611A6922F480427C -:108460001A617047001002402DE9F0418CB01D46A2 -:108470009DF848308846012B1746A54B06D19842F7 -:1084800065D10422A3F530531A6101E098425ED110 -:10849000A048A14B87600360A04BA907436103F18B -:1084A000C00383614FF0C003C3600361984B036551 -:1084B00003F104038364C36403F5484303F15403E5 -:1084C0000363A3F11403D3F8D42F436342F480422F -:1084D000C3F8D42FD3F8D02F42F00102C3F8D02F25 -:1084E0004FF002038DF803304FF40073ADF8003005 -:1084F0004FF018038DF8023003D589486946FAF722 -:108500006DF91C232A078DF8023003D5844869468B -:10851000FAF764F94FF48063ADF8003048238DF822 -:108520000230EB0703D57E486946FAF757F90E2368 -:108530008DF804300022012301A88DF805308DF854 -:1085400006208DF80730734CFFF71EFA53E0754B89 -:10855000984240F0D980744B6F4A9F601A60734A0A -:1085600018655A61C0329A61C022DA601A61704A95 -:10857000AE079A64DA646F4BDA6942F48022DA61FA -:108580009A6942F008029A614FF002038DF80330B5 -:108590004FF48063ADF800304FF018038DF80230CF -:1085A00003D565486946FAF719F91C232C078DF89D -:1085B000023003D560486946FAF710F94FF40063BA -:1085C000ADF80030E8074FF048038DF8023003D5CE -:1085D00059486946FAF702F927238DF8043000223A -:1085E000012301A88DF805308DF806208DF807309D -:1085F000FFF7CAF94C4C0026012384F84430266268 -:10860000E661A6626662C4F82C806571A760A671F7 -:10861000204602F009F915F0090F31D0206B00282F -:1086200026D0E36C039601934FF480530A93802382 -:108630000693E368059604932023099363690796DC -:10864000029308960B96FCF7BBFE01A9206BFCF782 -:1086500099FE236B1A6842F001021A60226D918A1A -:1086600089B241F0400191825B689BB2236407E0CC -:10867000236D4FF6DF721A80DA6842F02002DA606A -:1086800015F00A0F2CD0606B28B3A36C0026019361 -:108690004FF480530A938023069323690296049330 -:1086A0001023039305960796089609960B96FCF7F8 -:1086B00087FE606B01A9FCF765FE636B1A6842F0E8 -:1086C00002021A605E605E60236D9A8A92B242F086 -:1086D00080029A8204E0236DDA6842F08002DA6058 -:1086E000236D29079A8992B242F400529A819A8A9C -:1086F00003D592B242F0080203E022F0080212040D -:10870000120C9A82204600E000200CB0BDE8F081F7 -:1087100000380140B0190020BC10010828140020C6 -:1087200000080140004800405C190020A815002006 -:108730000448004000100240000C01402DE9F047C1 -:10874000054606F04FFA304B0446D3F808809A46A7 -:1087500090B92E48F9F724FB2D4B53F8241049B15A -:108760000123A34013EA080F02D02A48FFF7F8F9C3 -:108770000134F1E7284821E028462849224606F03E -:1087800039FA58B92648F9F70BFB264C54F8041F60 -:108790000029EFD01F48FFF7E3F9F7E72B78002611 -:1087A0002D2B03BF013504F1FF344FF001094FF0C9 -:1087B0000009174B53F8267027B91B48BDE8F0474E -:1087C000F9F7EEBA28463946224606F013FAC8B938 -:1087D0000120B040830501D51448EFE7B9F1000F3F -:1087E00003D0F9F7D2FD124804E040EA0800CAF8C5 -:1087F00008001048F9F7D4FA39460F48BDE8F047A9 -:10880000FFF7AEB90136D4E70C1A0020A9240108FD -:10881000D4100108C6200108A12601086E2801080D -:10882000BC240108D0100108D1240108E824010863 -:10883000FC24010806250108682201082DE9F04FF3 -:1088400087B09A468046894616469DF84040FEF716 -:10885000C4FC02AF0546034600F1100E18685968C3 -:108860003A4603C2083373451746F7D12B7B0BB941 -:1088700003960496404602A9FEF7DCFA054640B18D -:108880004368586830B1404602A92A46FDF730FBDC -:10889000F4E72CE0AB6895F800B01F78012F22D1E7 -:1088A00014480094494632465346FFF7DDFD04461E -:1088B0000AE0022F1BD1494623463246FEF796FBBB -:1088C00051460446F9F7B8F95CB10B4B277103EB3D -:1088D0008B03C3F800436B6820465C604146FEF79B -:1088E00071FB204603E0E4D200940448DAE707B0C5 -:1088F000BDE8F08F004800402814002000380140F7 -:1089000037B5254C254DA369284643F48053A36110 -:10891000E36801A943F48053E36018238DF806301F -:10892000A023ADF8043003238DF80730F9F756FF84 -:108930004023ADF8043004230DEB030128468DF8E5 -:108940000630F9F74BFF1023284601A9ADF8043093 -:108950008DF80630F9F742FFE36843F48053E36093 -:10896000E36823F48053E3600D4B1A8802F441520C -:1089700042F4457242F003021A809A8B22F400629C -:108980001204120C9A8307221A821A8892B242F0B9 -:1089900040021A8003B030BD0010024000080140C0 -:1089A00000300140254B37B5DA69254C42F480424E -:1089B000DA611A69204642F480421A6118238DF860 -:1089C00006304FF42043ADF8043001A903238DF89D -:1089D0000730F9F703FF4FF48043ADF80430042368 -:1089E0000DEB030120468DF806304FF48055F9F762 -:1089F000F5FE1023204601A98DF80630ADF804508D -:108A0000F9F7ECFE2561FFF723FD0E4B1A8802F4FF -:108A1000415242F4457242F003021A809A8B22F4CA -:108A200000621204120C9A8307221A821A8892B2E8 -:108A300042F040021A8003B030BD00BF0010024077 -:108A4000000C01400038004008B5FEF759FC02F068 -:108A500049FABDE808400F2014210122F9F7AAB80D -:108A60002DE9F04F692887B0044600F0A38200F298 -:108A700096802E2800F0378562D8242800F00785DC -:108A80002BD8202800F07E82222800F0B383012812 -:108A900040F05A852C20F9F729F90020F9F7F7F86A -:108AA0002046F9F7F4F80020F9F7F1F84320F9F738 -:108AB000EEF84C20F9F7EBF84620F9F7E8F84C20EF -:108AC000F9F7E5F82046F9F7E2F80020F9F7DFF8C2 -:108AD0000020F9F7DCF80024F0E0282800F0DF841B -:108AE00012D8262840F03085924C0320F9F7FEF882 -:108AF000B4F9E600F9F7FDF8B4F9E800F9F7F9F888 -:108B0000B4F9EA0000F029BC2A2800F0D3842C280C -:108B100040F01A85874C0720F9F7E8F894F8180117 -:108B2000F9F7B5F8B4F91E01F9F7E3F8B4F91A0149 -:108B3000F9F7DFF8B4F91C01F9F7DBF800F0C0BC75 -:108B4000642800F0E2801AD8322800F0B9840AD8EC -:108B5000302840F0F984774C8020F9F7C7F804F109 -:108B6000800500F0D6BC342800F06483402840F033 -:108B7000EB840820F9F7BAF8002400F0AABC6628B4 -:108B800000F09881C0F0EE80672800F0CC81682862 -:108B900040F0DA841020F9F7A9F8002402E27328E3 -:108BA00000F0AF8355D86D2800F0178212D86B28DB -:108BB00000F0D78340F2B0835F4C0620F9F796F8B7 -:108BC000B4F90000F9F795F8B4F90200F9F791F853 -:108BD0005A4BC0E36F2800F03082C0F00682702844 -:108BE00000F07682722840F0AF84524C1620F9F7DC -:108BF0007DF80020F9F77DF8B4F9D000F9F779F89D -:108C00004F4DB4F9D200F9F774F8B4F9D400F9F77C -:108C100070F82B68B3F9A801F9F76BF80020F9F7A1 -:108C200068F80020F9F786F82B68B3F952000A2398 -:108C300090FBF3F0F9F75DF894F80401F9F727F8E1 -:108C400094F80601F9F723F894F80501F9F71FF8ED -:108C5000E3E3782800F0738110D8752800F0BE8215 -:108C6000C0F00983762800F08E83772840F06C846A -:108C7000344D00242878F9F739F837E3A42800F0B8 -:108C8000CE8310D8A02840F05F840C20F9F72EF88E -:108C90002D4B1868F9F74EF82C4B1868F9F74AF87D -:108CA0002B4B1868F8E3F02800F0E483FE2840F02E -:108CB0004B840820F9F71AF80024D3E3254B1B68EE -:108CC000185D0134F8F7E3FF042CF7D10020F9F721 -:108CD00010F80024204B185D0134F8F7D8FF0B2C56 -:108CE000F8D100241D4B185D0134F8F7D0FF082C93 -:108CF000F8D10720F8F7CBFF0024194B185D013499 -:108D0000F8F7C5FF072CF8D187E30720094CF8F7DF -:108D1000EDFFE620F8F7BBFF6079F8F7B8FF002019 -:108D2000F8F7B5FF94F82631002B0CBF04200C2077 -:108D3000B2E300BF0C1A0020080300201803002033 -:108D4000180200205A180020E8F7FF1FECF7FF1F59 -:108D5000F0F7FF1F8C000020322201083E2201089C -:108D6000472201080B20F8F7C1FFC34BB3F90000FD -:108D7000F8F7BFFF0020F8F7BCFFC04B1B68C3F338 -:108D8000C000C3F38002800040EA4200C3F3400207 -:108D90001043C3F3401240EAC20003F0100318432B -:108DA000F8F7A7FFB64B1A8812F0010F0CBF00208E -:108DB000022012F0020F0CBF0021042112F0040F58 -:108DC0000CBF0023102312F0400F0CBF00242024FE -:108DD000019312F0100FAB4B02940CBF00244FF420 -:108DE000007412F0200F1B6803940CBF00244FF492 -:108DF000806412F4807F04940CBF00244FF400645C -:108E000002F0080B03F4807A059403F4805903F40C -:108E1000005803F4004C03F4803E03F4003703F4DD -:108E2000802603F4002503F4801403F0C00343EA12 -:108E30000B0343EA0A0343EA090343EA080343EA4C -:108E40000C0343EA0E0E904B4EEA07073E431B7895 -:108E500035432C43C3F38003234303430B4301995E -:108E6000029C0B4303992343049C0B430599234322 -:108E700012F4007F43EA01030CBF00224FF40012FA -:108E80001A43824B00201C780346A3420CD280492F -:108E90005D5C012101FA05F5154218BF994003F107 -:108EA000010318BF0843F0E7F8F744FF794B93F844 -:108EB00054070BE31220F8F719FF774B774C1B8808 -:108EC000B3F5806F22D90025605F082390FBF3F093 -:108ED0000235F8F70EFF062DF6D1714CB4F90000FB -:108EE000F8F707FFB4F90200F8F703FFB4F904003C -:108EF0006C4CF8F7FEFEB4F90000F8F7FAFEB4F98E -:108F00000200F8F7F6FEB4F9040026E2B4F9000016 -:108F1000F8F7EFFEB4F90200F8F7EBFEB4F904003D -:108F2000F8F7E7FED9E71020F8F7E0FE00245E4BE3 -:108F3000185D0134F8F7ABFE102CF8D10FE23820A1 -:108F4000F8F7D4FE0025594E05F12C043368E400EF -:108F50002344B3F90600F8F7CCFE33680135234407 -:108F6000B3F90800F8F7C5FE33682344B3F90A00E3 -:108F7000F8F7BFFE33681C44207BF8F788FE082D05 -:108F8000E1D1ECE10820F8F7B1FE0024474B1B6863 -:108F900003EBC40393F86D010134F8F778FE082C55 -:108FA000F4D1DCE1424B185D0134F8F770FE102C6F -:108FB000F8D1D4E13F4D00242878400000F0FE00B5 -:108FC000F8F794FE2B789C4280F0C9813A4B33F934 -:108FD0001400F8F78EFE0134F4E70620F8F786FE59 -:108FE0000020F8F7A7FE0020B7E10720F8F77EFE83 -:108FF000324B4FF6FF741878F8F749FE304B18687B -:10900000A042A8BF204620EAE07000B2F8F771FE47 -:109010002C4BB3F90000F8F76CFE1E4B93F80C21B3 -:10902000294B18680028B8BF40420AB10A235843A8 -:10903000A042A8BF204600B28FE1244C0720F8F7D9 -:1090400055FE23681878F8F722FE23685878F8F759 -:109050001EFE23681879F8F71AFE23685879F8F786 -:1090600016FE23689879F8F712FE23689878F8F7C7 -:109070000EFE2368D87829E24403002088020020ED -:10908000500300204C030020B02100205A1800207B -:10909000441800200C1A002000000020E8020020E4 -:1090A0003C0300209E0500206C00002018020020D8 -:1090B00086210020670800206205002008040020A7 -:1090C00010040020EE0B00200C040020E003002020 -:1090D000B44D1E20F8F70AFE2B6800241B78022BE3 -:1090E00069D12B68B04903EB8403586A03F0E6F8B2 -:1090F00005F09CFFFA28A8BFFA2020EAE070C0B271 -:10910000F8F7C5FD2B68A94903EB8403186B03F03E -:10911000D5F805F08BFFFA28A8BFFA2020EAE07006 -:10912000C0B2F8F7B4FD2B68A14903EB8403D86BF8 -:1091300003F0C4F805F07AFF6428A8BF642020EA91 -:10914000E070C0B20134F8F7A2FD032CC9D1072C9E -:109150002B681ED1986C944903F0B0F805F066FFB7 -:10916000FA28A8BFFA2020EAE070C0B2F8F78FFD15 -:109170002B688D49D86C03F0A1F805F057FFFA2849 -:10918000A8BFFA2020EAE070C0B2F8F780FD002006 -:109190000BE023441879F8F77AFD2B682344987B79 -:1091A000F8F775FD2B682344187E0134F8F76FFD3E -:1091B0000A2CCCD1D3E02B6823441879F8F767FD4B -:1091C0002B682344987BF8F762FD2B682344187EB4 -:1091D0000134F8F75CFD0A2CEDD1C0E02F20F8F740 -:1091E00085FD744C14F8010F002800F0B880F8F7E2 -:1091F0004EFDF7E7A020F8F779FD0024694B04F154 -:109200001C021B680C2103EB82035D1D6A4A5B791B -:10921000013401FB0323187AF8F739FD6878F8F771 -:1092200036FDA878F8F733FDE878F8F730FD282CFC -:10923000E4D194E04820F8F759FD002506266E4356 -:10924000584B06F588761B6801351E44B07AF8F74E -:109250001EFD7079F8F71BFDB079F8F718FDF0796D -:10926000F8F715FD307AF8F712FD707AF8F70FFD70 -:109270000C2DE3D173E00027012400254F4B1B7810 -:109280009D4222DA4E4BE95C00234B4A03EB020875 -:109290009A5C8A4204D00C33B3F58A7FF5D112E090 -:1092A000D8F8040005F09EFC81460CB9264601E082 -:1092B000074408E04E4506DAD8F80430985DF8F720 -:1092C000E6FC0136F6E70135D8E7002C47D0F8B2C6 -:1092D000F8F70CFD0024D0E7374A99189A5C8242CF -:1092E0000BD00C33B3F58A7FF6D101342B789C4236 -:1092F00035D2334BE05C0023EEE7087AF8F7C7FC81 -:10930000F3E70820F8F7F2FC0124E0B20134F8F7A3 -:10931000BEFC092CF9D122E01020F8F7E7FC294B1C -:10932000294C187800F00200F8F7B1FC274B1878A8 -:10933000F8F7ADFC2068F8F7FDFC6068F8F7FAFC78 -:10934000234BB3F90000F8F7D4FC224BB3F900002B -:10935000F8F7CFFC204BB3F90000F8F7CAFC012066 -:10936000F3E00520F8F7C2FC1C4BB3F90000F8F756 -:10937000C0FC1B4BB3F90000F8F7BBFC194B187885 -:1093800000F00100A2E0F8F721FB06461220F8F7F2 -:10939000ADFC0EB9144B02E0102E29D1134B1D6801 -:1093A0005C6827E018020020000020410000C8424D -:1093B00000007A4423110108780D01085A18002092 -:1093C00044180020FE02002024040020180400207D -:1093D0001604002014040020341700208804002004 -:1093E0008A040020FE0D0020500C00205C0C0020A0 -:1093F000002425463046F8F74AFC2846F8F79AFC40 -:109400002046F8F797FC524B1868F8F793FC0020B9 -:10941000F8F76FFC0020F8F76CFC002056E04D4D8B -:109420000024A8782E4680000130C0B2F8F75EFC18 -:10943000A878F8F72CFCB3789C4290D2464D285D72 -:10944000F8F725FC05F11003185DF8F720FC05F18D -:109450002003185D3035F8F71AFC285DF8F717FC83 -:109460000134E8E73D4B185F0234F8F742FC082C62 -:10947000F8D174E73A4C0420F8F738FC2368B3F9C4 -:109480005600F8F736FC2368B3F9540065E704206A -:10949000F8F72CFC334B9868F8F74CFC5FE7314C3D -:1094A0000420F8F723FCB4F90801F8F722FCB4F91A -:1094B0000A0152E70120F8F719FC2A4B587905E018 -:1094C0000120F8F713FC274B93F82001F8F7DFFB96 -:1094D00045E7244B234493F810010134F8F7D7FBF8 -:1094E000082CF6D13BE74020F8F700FC1D4C04F1B6 -:1094F0004005B4F9D401F8F7FCFB94F8D601F8F76D -:10950000C6FB043494F8D301F8F7C1FBAC42F0D1A8 -:1095100025E7B4F85601043400F03F00F8F7E9FB02 -:10952000B4F85201C0F38410F8F7E3FB94F850014B -:109530000009F8F7ACFB94F8500100F00F00F8F7C1 -:10954000A6FBAC42E5D10AE7002007B0BDE8F08FEA -:10955000000E002034170020371700207817002055 -:10956000180200200C1A0020954B2DE9F74F1B78AC -:10957000013B012B00F22081924B1E78864240F085 -:109580001B81914B1B78022B00F016818F4B904D65 -:1095900013F806808F4B83F800808F4B1A78019266 -:1095A0001AB18E4B33F9160007E08C4A2B6832F95A -:1095B000160003F100432B60404202F02BFE884965 -:1095C00002F030FFDFF838A20446DAF800B00021DC -:1095D000584603F007F80027DFF82C92002859D0EE -:1095E000D9F800B02046594603F024F868B17D4B05 -:1095F0002A687B491A60C9F80040204602F05EFEE6 -:1096000003F022F8784BD880BDE05846394603F085 -:1096100011F8002800F0B780744B1A78002A31D175 -:109620002046296802F040FD4FF07E5102F0E4FF31 -:109630006F4C28B160686F4902F040FE60600FE037 -:109640006D49606802F03AFEDFF8CCA183465146CE -:1096500002F0D2FF10B9C4F804B001E0C4F804A0CD -:10966000624A01231370654B00221B68C9F8007021 -:1096700043449A72019A82F00103574A1370604B77 -:109680001F6080E05F4BCAF800401A68554BFA3201 -:109690005A6078E02046594602F0AEFF48B1584A79 -:1096A0004F491460204602F009FE02F0CDFF4E4BF8 -:1096B000D880534BD9F80090D3F800A048465146C3 -:1096C00002F0F2FC4F4B83461968464B5A688A1ADF -:1096D000002A0BDA4FF07E5102F0ACFF002852D086 -:1096E0002046514602F0A6FF00284CD03D4A48468D -:1096F000116802F09FFF3E4C38B120683E4902F0ED -:10970000DDFD3C492060A06807E058464FF08041ED -:1097100002F090FF28B1A068374902F0CFFDA060A9 -:1097200004E02068334902F0C9FD2060334B2C4926 -:109730002068D3F8009002F0C1FD02F0ABFF09F8F9 -:109740000800A06802F0A6FF019AC84482F0010355 -:10975000214A88F814001370294B1F602A4B1F60A0 -:10976000224B1A780132D2B2032A01D01A700AE0D1 -:1097700000221A701E4B2549586802F09FFD02F026 -:1097800089FF88F80A001EB9174B1A8864321A80BC -:10979000114A13780BB11E4B00E01E4B2B600F4B90 -:1097A00033F9160002F036FD0D4902F03BFE01468A -:1097B000286802F079FC00E0084603B0BDE8F08FAD -:1097C00052030020A4030020B4030020A8060108CF -:1097D00054030020B5030020A50300200803002047 -:1097E000000020418017002078170020A6030020E9 -:1097F000B80300200AD7833FEC51783FB003002024 -:10980000A8030020081A0020AC03002000007A44BE -:109810000000A0410000A0C16F12833A10B50848B3 -:10982000F8F7BEFA074B1C682046F8F70AFA18B991 -:109830000A20F8F7AEF9F7E7034A044BDA6010BDE7 -:10984000B52501085C1800200400FA0500ED00E0D1 -:1098500008B50548F8F7A4FAFDF7CCF8FDF750FD78 -:10986000BDE80840FFF7DABFC125010808B5074881 -:10987000F8F796FA064A002313729363054A1370A9 -:10988000FCF77CFBBDE80840FFF7C8BFD7250108FF -:1098900080170020AF21002008B50448F8F780FAAF -:1098A000FDF72EFDBDE80840FFF7B8BF032601080D -:1098B0002DE9F04F002487B00746039191460493A9 -:1098C00082462546022DDFF878814FEA450607D10A -:1098D00003984379B8F904001B3343435B1148E014 -:1098E0004D4B38F9151033F9153003EB4101C9F12F -:1098F0000003994203DB4945B4BF0B464B46474939 -:10990000049A31F906B0915FCBEB030303EB010B33 -:10991000F8F7FCFB98B1424B58465B5D029302F0AE -:1099200079FC404902F07EFD029B01461846FFF794 -:109930001BFE3C4902F0C2FC02F086FE83463A4B15 -:109940001988C80711D403988A07037938F90600E3 -:1099500003F11B0300FB03F34FEA231309D57A7CC1 -:1099600002FB0BFB03EB2B2303E0FB7903FB0BF365 -:109970001B112E4A2E49905F042290FBF2F0181A18 -:109980007B5D9AF80AC0434305932A4B6258B3F8AB -:1099900000B001350BFB00F3DB120CFB0323264A5E -:1099A000B3F5001FA8BF4FF400139342B8BF13468E -:1099B000635022494FEA1B1B62584FF6FF7C821A04 -:1099C000BCFBFBFC0CFB02FC605001F1180B01F12D -:1099D0000C0054F8008054F80B204FEAAC1C44F8FB -:1099E00000C042449AF81400624401924243059830 -:1099F000121202EBE012243102EB6333032D44F820 -:109A00000B808B530AF1010A04F104047FF45AAF6E -:109A100007B0BDE8F08F00BFA4210020080300209C -:109A20006011010800002041500300203C03002089 -:109A3000DC0C0020440300200000E0FFBC170020E5 -:109A4000C60300202DE9F04F89B00793914B069291 -:109A5000B3F90220B3F90030002AB8BF5242002BFC -:109A6000B8BF5B4200249A42B8BF1A4603900592E1 -:109A70002646A14627460494A0462546DFF844A280 -:109A8000BAF8003099075AD0022D58D0814BDDF832 -:109A900018B0F25E804BF35E03EB4202CBF10003A1 -:109AA0009A4203DB5B469A42B8BF13467B4ADDF815 -:109AB0001CC036F902B03CF90620CBEB030303EBE4 -:109AC000020BF8F723FB90B1754B584615F803804D -:109AD00002F0A0FB734902F0A5FC01464046FFF7E7 -:109AE00043FD704902F0EAFB02F0AEFD83460399A4 -:109AF0006423CA7902FB0BF292FBF3F2CB7E6FF088 -:109B0000040101FB03F8424505DB03EB83039A42A2 -:109B1000B4BF90469846644A42F21071A3585B4421 -:109B20008B42A8BF0B4661498B42B8BF0B46A3507E -:109B3000039A92F811B00BFB03F31B130493BAF8CA -:109B4000003003F00302012A01D1022D3ED1584911 -:109B5000504A895FB75EDDF80CB0564A81EAE17081 -:109B6000A0EBE170B0F5206F1BF805C054F802902F -:109B70001DDC022D15D05020784390FBFCFC042006 -:109B800091FBF0F1C1EB0C0CE1444B48B9F57A5F65 -:109B9000A8BF4FF47A598145ACBF42F804901051E8 -:109BA00007E087EAE770A0EBE7706428E3DD0021B7 -:109BB0001151404AA1587D2291FBF2F9039A2A449F -:109BC000927A02FB09F9402299FBF2F99A0716D51D -:109BD000022D14D0DDF814C0DDF810B00CFB07F333 -:109BE0000CFB09F0CCF5FA7101FB083301FB0B010A -:109BF0004FF4FA7293FBF2F391FBF2F108E0DB070A -:109C000001D5022D02D149463B4601E00499434665 -:109C1000274ADFF8B4B0B25A04200FFA82FC15F8D4 -:109C20000BB09CFBF0FA0BFB0AFB6FF04F0A9BFB9F -:109C3000FAFA9A44214BCDF804A036F903A0F25267 -:109C4000CAEB0C0C9CFBF0FC03F1120A981D225885 -:109C500054F80AB044F800C019489344285CCDF881 -:109C600008B0E34444F80A2000FB0BF2202092FBEA -:109C7000F0F2DDF804C08A1A0135063B6244032D78 -:109C8000F25204F1040406F102067FF4F7AE09B0C3 -:109C9000BDE8F08FC6030020A421002008030020A7 -:109CA0006011010800002041480C0020F0D8FFFF9F -:109CB0003C030020DC0C002080C1FFFFE6170020E1 -:109CC0000C0D002050030020060D00202DE9F04F60 -:109CD00089B007937A4B814618880491059202F067 -:109CE00095FA784902F0EAFA002403904F46254697 -:109CF0002646022EDFF80CA20BD10499BAF9040013 -:109D00004B790A33584302F085FA6F4902F08AFB17 -:109D100044E06E4B3AF90520EB5E05991A444B423C -:109D20009A4203DB0B469A42B8BF1346684AAA5EC2 -:109D30009B1A079A505F184402F06CFA654902F0CA -:109D400071FB8046F8F7E2F928B1634B4146985D14 -:109D5000FFF70AFC8046614B1A88D10705D54046BB -:109D6000D9F8441002F0AAFA18E004993AF905006B -:109D70000B7901921433584302F04CFA524902F025 -:109D800051FB019A8346930709D5D9F848104046FC -:109D900002F094FA0146584602F088F98346504A88 -:109DA000505F02F037FA4F4AD16802F087FA8246D4 -:109DB0005146584602F078F9396A804602F07EFA38 -:109DC000DFF844B106900399404602F077FAF96A49 -:109DD00002F074FA54F80B1002F068F94249804618 -:109DE00002F00AFC38B94046404902F023FC20B199 -:109DF000DFF8F88001E0DFF8F0804BF80480DFF84E -:109E00000CB1504654F80B1002F04EF944F80BA078 -:109E1000034603994FF07E50029302F003FB029B2E -:109E20000146184602F04AFA0BF10C03E2580BF116 -:109E3000180B54F80B10824610460192029302F060 -:109E400035F9514602F032F9019A029B44F80B2091 -:109E500044F803A0264902F0E5FAB96B02F02EFAA5 -:109E60002449824602F0C8FB38B95046224902F024 -:109E7000E1FB20B1DFF880A001E0DFF878A00698D0 -:109E8000414602F013F9514602F00EF905F0CEF802 -:109E90001A4BB0F57A7FA8BF4FF47A709842B8BFDA -:109EA00018460136164B032EE85204F1040405F15E -:109EB000020507F104077FF41CAF09B0BDE8F08F7D -:109EC00044030020BD37863500004842A42100200D -:109ED0000803002000002041601101085003002009 -:109EE0003C0300201C02002000007AC300007A43DB -:109EF00000004040000096C30000964318FCFFFF9E -:109F0000E0170020C6030020E80C00200418002001 -:109F10002DE9F047704B86B01A789946DFF8C88172 -:109F200092B90123D8F80000022189F80030FDF72A -:109F300049F8D8F80030694A6948C2F8A830F7F7FC -:109F40002FFF6848F7F72CFFD8F80000F7F788FED6 -:109F5000002800F0BE80644B604C1868F7F77BFE69 -:109F60000928014601D03F284FD14FF0000AA56BC8 -:109F70005E4F56462DB15E4839682A4604F03AFED7 -:109F800010B9BA4606B93E465A4B0C379F42F1D338 -:109F9000CEB13768DAF800E02B46F85C1EF8031003 -:109FA000814201D0A3630EE05A1C41B92D2B06D883 -:109FB000A2632344202022441872117203E04C490A -:109FC00058541346E9E7A36B0BB1564512D04A48E3 -:109FD000F7F7E6FE564509D856F80C0BF7F7E0FE02 -:109FE000D8F800000921F7F74DFEF3E73D48F7F7F1 -:109FF000D7FE0025A36B9D42A6D23D4BD8F80000AA -:10A00000595DF7F73FFE0135F4E7A36B33B9042838 -:10A010003BD104F10800FFF729FC5AE00C2801D1DC -:10A0200036488CE70A2901D00D2949D13448F7F781 -:10A03000B7FEA36BE21800231372227A232A17D0EB -:10A040000493304B2A4E009303A8284915220C2371 -:10A05000039604F020FE054638B1006804F0C2FD06 -:10A060000130AB683044984702E02748F7F798FE84 -:10A070001F480021302204F074FD0023A36399F8E7 -:10A080000030002B7FF45DAF23E00C28C8D07F297F -:10A0900003D159E72F2B3FF657AFA1F12002D2B2DF -:10A0A0005E2A3FF651AF13B920293FF44DAF5A1C39 -:10A0B000A263D8F800001C442172F7F7E3FD43E7E0 -:10A0C0007F29E7D1013BA363002223441A720F4882 -:10A0D00038E706B0BDE8F087AF21002080170020E8 -:10A0E0000A260108422601085C1800208411010894 -:10A0F0008817002080120108472601084C26010815 -:10A10000A1260108B3190008572601087326010883 -:10A110001F4B13B51A886B2022F040021204120C58 -:10A120001A801A88802122F038021204120C42F0A0 -:10A1300030021A801A88062492B242F040021A8035 -:10A14000FDF7D8F99620F7F724FD75200DF10701EA -:10A150000122FDF799F99DF80730682B04D0013CE6 -:10A1600014F0FF04EED110E00C200DF107010122E4 -:10A17000FDF78AF99DF80730142B06D3182B02D966 -:10A18000543B062B01D8012000E0002002B010BD96 -:10A19000003001402DE9F041002407462546104BD0 -:10A1A0003946E65804EB0308304604F057FD58B131 -:10A1B0000C483146FDF7D4FC40460021FDF7EEFC8B -:10A1C0000948FDF7CDFC01351434B4F52F6FE6D105 -:10A1D00025B90648BDE8F041F7F7E2BDBDE8F081DA -:10A1E000DC120108D3260108A12601087726010800 -:10A1F0002DE9F74F044604F0F5FC054620B101288F -:10A2000018D123782A2B15D15548F7F7C9FD00241A -:10A21000544B5548E618E158FDF7A2FC3046294654 -:10A22000FDF7BCFC14345148F7F7BAFDB4F52F6FB5 -:10A23000EED192E020463D2104F0C7FC002800F05A -:10A240008780034613F8012C202A01D1013BF9E74E -:10A25000451C2846C4EB030A04F019FD8346284632 -:10A26000F7F766FF0026054614237343DFF8F490E2 -:10A2700053F8097003EB0908384604F0B3FC0346B1 -:10A280001A4620463946019304F0B4FC019B00288D -:10A2900055D15FFA8AF29A4251D1D8F80C0001F0F8 -:10A2A000B9FF0146284602F0BBF9002845D0D8F88E -:10A2B000100001F0AFFF0146284602F0A7F9002880 -:10A2C0003BD0B8F804309B064FF0140303FB06960E -:10A2D000B28858BF5D4614062946B36806D524489F -:10A2E0004FF4E07490F8540704FB0033D00504D514 -:10A2F00020480A24007804FB003302F03F02042ABD -:10A300000BD004D8013A012A0CD819700AE0102A9F -:10A3100005D0202A05D0082A04D1198002E019604E -:10A3200000E01D6039461448FDF71AFC3046002154 -:10A3300003B0BDE8F04FFDF731BC104803E0013633 -:10A340008C2E91D10E4803B0BDE8F04FF7F728BD31 -:10A35000204603B0BDE8F04F1CE703B0BDE8F08F26 -:10A360008F260108DC120108D3260108A126010866 -:10A370000C1A0020440C0020A4260108AF26010876 -:10A380007726010870B50E462021154604F01DFC05 -:10A390000446B8B1441C204604F079FCB0F5617F56 -:10A3A00005DB40F634039842A8BF184601E04FF49D -:10A3B00061701923A0F5617090FBF3F030702B7879 -:10A3C00001332B702046202104F0FFFB0446B8B176 -:10A3D000441C204604F05BFCB0F5617F05DB40F6D1 -:10A3E00034039842A8BF184601E04FF46170192366 -:10A3F000A0F5617090FBF3F070702B7801332B7037 -:10A40000204670BD104B043033F91030B3F5617F36 -:10A4100005DB40F633029342A8BF134601E04FF438 -:10A42000617308781922504300F28330984208DAA9 -:10A430004878504300F283309842B4BF0020012096 -:10A4400070470020704700BF620500202DE9F04FE3 -:10A45000624C23686249581C0A78894602F0FF0C56 -:10A460000AB10346F6E7277A667AA57AE16823609F -:10A47000E0461FFA88F213B21F2B00F3938059496C -:10A4800001EB8300C278807831F82310C0F1FF001F -:10A4900080B2002861D0C0F1FF0050433C23B1FBE3 -:10A4A000F3FA0012BAF1050F5AD8DFE80AF0030BED -:10A4B0001A283846161A4E43C5B2B6FBF3F62E4498 -:10A4C000F6B248E0B1FBF3F703FB1717BFB2C5B212 -:10A4D000C7F13C07101A4743B7FBF3F72F44164662 -:10A4E00029E0B1FBF3F503FB1515C7B2ADB2101AA5 -:10A4F0004543B5FBF3F53D44EDB2164630E0B1FB04 -:10A50000F3F603FB1616B6B2C7B2C6F13C06101A34 -:10A510004643B6FBF3F63E441546F6B220E0B1FBE7 -:10A52000F3F703FB1717C6B2BFB2101A4743B7FBC6 -:10A53000F3F737441546FFB212E0B1FBF3F503FB26 -:10A540001515ADB2C6B2C5F13C05101A4543B5FBB1 -:10A55000F3F53544EDB2174602E0154616461746A8 -:10A560004FEA072A4AEA064A4AEA050A172301215E -:10A5700099400CF1170211EA0A0FC3EB02021A49C3 -:10A580000CBF0920112092B213F1FF338854EED290 -:10A590000CF1180C08F101081FFA8CFC1FFA88F85E -:10A5A000124966E7012389F80030114BE28040F23E -:10A5B0002A3227726672A572E160A4F804C05A605C -:10A5C0000C4A00219184118889B241F00101118067 -:10A5D0001A6842F001021A60BDE8F08F2C180020C2 -:10A5E000AE210020E0040020AC0800203418002038 -:10A5F0006C00024000040040F8B50468054620469F -:10A600000E461746F8F78FF8032845D82B7B9B0892 -:10A610009AB246B94FF0020C0CFA03F3A18989B241 -:10A6200021EA0303A3810A2101FB00211B4B43F80C -:10A630002160043143F8217046B12A7B022592083B -:10A6400005FA02F2A1890A4392B2A281282202FBF2 -:10A65000003000F12002EFF31286502383F31288BA -:10A660000023C1180D6915B115600A69043204335D -:10A67000102BF6D100231360F3B283F31188036A21 -:10A6800023B1A3899BB243F0010304E0A38923F023 -:10A6900001031B041B0CA381F8BD00BFBC180020E4 -:10A6A00038B5114B114D1A78114C29688AB12269BD -:10A6B0000244914217D300201870F7F774FA2B6800 -:10A6C00023610C4B1A780AB1013A1A7001232375E1 -:10A6D00038BD2269C832914205D301201870F7F7BE -:10A6E00062FA2B68236138BD430D0020081A002050 -:10A6F0002C180020CE02002037B5214D8DF80730F0 -:10A700006B7D8DF8062002AA8DF804008DF80510E7 -:10A710001A4412F8042C443AD2B20F2A29D8194903 -:10A72000022B31F8124003D814B12046FFF7B8FFCE -:10A730006B7D134A022B09D9134B19681369091B46 -:10A740008B4203D200235375104A13702B7D012BCB -:10A7500000D09CB96B7D022B02D8094A0133537596 -:10A760000B4B00202875187003B0BDE83040F7F798 -:10A770001ABA022B4FF0C804D7D9D9E703B030BDBD -:10A780002C18002062110108081A0020CE020020B7 -:10A79000430D002030B585B004AC002524F8025DDF -:10A7A0000091ADF8060021461020F7F70DFB9DF84B -:10A7B00006002146F7F708FB9DF807002146F7F74A -:10A7C00003FB9DF800002146F7F7FEFA9DF8010013 -:10A7D0002146F7F7F9FA9DF802002146F7F7F4FA57 -:10A7E0009DF803002146F7F7EFFA9DF80E00294681 -:10A7F000C043C0B2F7F7E8FA024B1A68024B1A607E -:10A8000005B030BD081A0020C80400200449054BDB -:10A810000968002218701A6159611A76704700BFE2 -:10A82000081A00208408002070B5046D4279A389BD -:10A8300002F0040123F400531B041B0C0546866838 -:10A8400086B0A38101F0FF0021B14FF480604FF486 -:10A85000005100E0014612F0010F14BF0423002351 -:10A8600012F0020F1CBF43F008039BB212F0080F56 -:10A87000228A18BF0C2392B222F440521143218243 -:10A88000A28992B222F4B05222F00C021043034388 -:10A890009BB2A381A38A01A823F440731B041B0C61 -:10A8A000A382FAF705FE1949049A039B8C4208BF5C -:10A8B0001346A2891921594312B2002AB4BF760067 -:10A8C000B600B1FBF6F16423B1FBF3F212011009FB -:10A8D00003FB1011A08900B2002806DAC90032314A -:10A8E000B1FBF3F303F0070305E009013231B1FBDB -:10A8F000F3F303F00F031A4392B22B6D22819A896E -:10A9000092B242F400529A8106B070BD0038014004 -:10A91000417189E7816087E770B5064600240A4BDC -:10A92000E518AA8816420AD0E1580848FDF718F938 -:10A9300028460021FDF732F90548F7F731FA1434BB -:10A94000B4F52F6FEBD170BDDC120108CF260108E2 -:10A95000A1260108F7B5294B1B78042B48D14020CC -:10A96000F7F766F8044670B12046F7F76AF918B9A8 -:10A970000A20F7F70EF9F7E7214B20461B68196903 -:10A98000F7F764F90AE01E4B21461B6800901A692C -:10A9900040200323FDF752FF044648B3194D2868B1 -:10A9A00041798B0703D441F00201F7F745F9164BC3 -:10A9B00008221A612868F7F753F958B1114B124E63 -:10A9C000082718687761F7F746F901462046F7F738 -:10A9D00059F937612046F7F743F90028EAD02046B5 -:10A9E0002E68F7F738F901463046F7F74BF9E1E7FB -:10A9F000064803B0BDE8F040F7F7D2B9840800205C -:10AA000080080020A4080020000C0140D92601087D -:10AA10002DE9F743124C814604F1980894F84A60F6 -:10AA2000C6B9D9F804200025009501202946032342 -:10AA3000FDF704FF074620B97EB94FF49642012680 -:10AA4000F1E7204629464C2204F08BF801232760C9 -:10AA500084F84A304C344445E0D103B0BDE8F0837B -:10AA6000480D0020F7B5524B524C2360FAF7DCFB3F -:10AA70000120FCF78AFA002800F084804E4BFF2169 -:10AA800018461622256804F06CF8002202704B4A22 -:10AA90000121126803469707817504D5417003218F -:10AAA000817502218170560704D5997D481C9875DF -:10AAB0000320585412F00A0F0CD09A7D04219954A7 -:10AAC000511CC9B205205854D11C02329975D2B21A -:10AAD000062199543A4FBA68900604D5997D481CCE -:10AAE000987507205854110608D5997D09205854A7 -:10AAF000881C01319875C9B20A20585479790829FF -:10AB000001D00E2904D1997D481C98750B2058540A -:10AB1000997D4FF00C0E481CC0B212F0040F264E67 -:10AB2000987503F801E003D00231B175102131545A -:10AB3000997D97F84571481CC0B24FF0120E002F56 -:10AB40000CBF002702F001071B4E987503F801E0C7 -:10AB50001FB10231B17513213154997D1427481C5E -:10AB6000C0B298755F549305134E03D50231152377 -:10AB7000B175335413480021982203F0F2FF2846A0 -:10AB8000FFF746FF0220FCF700FA70B10220F6F74B -:10AB90004FFF2568084C0146A06130B90090AA68B3 -:10ABA00002200323FDF74AFEA06103B0F0BD00BF01 -:10ABB000381B0020E00D00204418002088020020EF -:10ABC0000C1A0020480D0020A94B2DE9F7431B78F3 -:10ABD000002B00F08181F7F7E1FBA64E05463378A4 -:10ABE000834200F07981A44C23681B78002800F090 -:10ABF000EF8063BB0420F6F71BFFA04F01463860CF -:10AC0000DFF8848290B143794FF4165188F81C30F4 -:10AC10008368C8F82030F7F719F838680221F7F789 -:10AC20000BF838680421FCF7CDF910E0944B0420B0 -:10AC30001B684FF416529B7800930223FDF7FEFD2C -:10AC40004379386088F81C308368C8F8203023685E -:10AC50001F78012F33D10420F6F7EAFEDFF8448293 -:10AC60000146C8F80000DFF82092A0B143794FF404 -:10AC7000964189F824308368C9F82830F6F7E6FF52 -:10AC8000D8F800003946F6F7D7FFD8F800000421BD -:10AC9000FCF798F913E000903B4604204FF49642ED -:10ACA000FDF7CCFD4379C8F8000089F824308368AB -:10ACB000C9F828300379022B04BF724B1F70236838 -:10ACC0001F78022F41D10420F6F7B2FE6E4C0146E8 -:10ACD000E06288B143794FF4964184F8303083685C -:10ACE0006363F6F7B3FFE06A3946F6F7A5FFE06A5B -:10ACF0000421FCF767F90CE000903B4604204FF478 -:10AD00009642FDF79BFD4379E06284F8303083681A -:10AD10006363E76A5D4C94F84A30022B09D094F8DB -:10AD20009620022A00F0D6801BB14C34002A18BFAE -:10AD30000024574B1C6044B1204600214C2203F0F4 -:10AD400010FF0223276084F84A30F7F779FB0028C8 -:10AD500000F0BE804F4F3B78002B40F0B9800820B8 -:10AD6000F6F766FE4C4C0146206090B1464B4279A6 -:10AD70004FF4614183F838208268DA63F6F766FFA2 -:10AD800020680821F6F758FF20680821FCF71AF917 -:10AD90009EE0424B08201B684FF461429B78009371 -:10ADA0000346FDF74BFD206040B1012342793B7023 -:10ADB000354B83F838208268DA6389E0384B1B789A -:10ADC000002B00F0858004233B70FFF74BFE7FE0F3 -:10ADD00083B92A4FDFF8B080386898F81C10F6F76E -:10ADE0002BFF3868D8F82010F6F730FF38680421B8 -:10ADF000F6F709FE23681B78012B10D1294FDFF8E5 -:10AE00008880386898F82410F6F716FF3868D8F864 -:10AE10002810F6F71BFF38680421F6F7F4FD2368C5 -:10AE20001B78022B0DD1184CE06A94F83010F6F71D -:10AE300003FFE06A616BF6F709FFE06A0421F6F7A9 -:10AE4000E2FDF7F7FDFA002842D0124F3B7813F0ED -:10AE5000FB0F3DD0124B104C1B782BB32068082100 -:10AE6000F6F7D1FD04233B70FFF7FCFD2EE000BF99 -:10AE7000F0030020F1030020F4030020F803002079 -:10AE80001C0400209D05002044180020480D0020CF -:10AE9000A4040020B4040020B8040020E00B00202B -:10AEA000D60B002090040020DFF83480206898F84A -:10AEB0003810F6F7C1FE2068D8F83C10F6F7C6FE49 -:10AEC00020680821F6F79FFD04233B7000232360D0 -:10AED000357001E04C342CE703B0BDE8F08300BFCF -:10AEE000441800202DE9F041FCF7E8F910B90A20D8 -:10AEF000F6F786FEAF4C4FF4EF622046AE4903F002 -:10AF000027FE94F854374FF4E072022B84BF0023DD -:10AF100084F8543794F85437A84E02FB034303F5E2 -:10AF2000057393F850203360022A84BF002283F80F -:10AF3000502093F85030A24A13700A2202FB0343B8 -:10AF4000A04A03F256731360A36842F201021A404A -:10AF50003AB944F208021A401AB9964A43F4005327 -:10AF60009360A368DA0703D54FF40050F7F70DFAA2 -:10AF7000A3685B0409D50820F7F707FA4FF40050DF -:10AF8000F7F703FA0120F7F700FAA3681F0706D5C1 -:10AF90004FF40050F7F7F9F90120F7F7F6F9A36835 -:10AFA0009D040ED54FF40040F7F7EFF94FF4006021 -:10AFB000F7F7EBF94FF48030F7F7E7F94020F7F7B0 -:10AFC000E4F9A368580603D54FF48030F7F7DDF9AC -:10AFD0007D4D7E4B2F461D60FAF726F97C4B05F11F -:10AFE0001C0201201A60FCF7F8F801460120FBF76B -:10AFF00021FF002849D00220FCF7EFF8014602208B -:10B00000FBF718FF002840D02020FCF7E6F80146A7 -:10B010002020FBF70FFFA368190601D5002834D0C4 -:10B020001020FCF7DAF801461020FBF703FFA368B5 -:10B030001A0700D548B30420FCF7CFF801460420D6 -:10B04000FBF7F8FE30B90820FCF7C7F801460820E6 -:10B05000FBF7F0FEA3685B0503D400231A461946EC -:10B0600009E00028F9D110E079B90121C00708D41E -:10B070000C33242B0BD057481844007A8507F5D59C -:10B08000F2E70132D2B2022AF2D9FBF78EFCF6F7D0 -:10B090004DFD514D514B32681D60514B101D1860D4 -:10B0A00002F175010023A846CD5C55B901EB030EF2 -:10B0B0009EF802C09EF803E0F44502D2494B1D7091 -:10B0C00002E00433A02BEFD1474B48490B604849BD -:10B0D00050330B601178474B012903D0022903D06C -:10B0E000454902E0454900E045491960454B02F5F4 -:10B0F000D9721A60F7F772FA3668434B06F5D372C5 -:10B100001A60424B00229A80414B424A424D1360E2 -:10B1100006F5B3722A60A3F122026A602E333F4A19 -:10B1200006F5D771EB6006F5D87311606B61C5F851 -:10B1300008802F61B4F8F00001F068F8E861B4F815 -:10B14000F20001F063F896F8583005F118022B76FA -:10B1500096F8743028626B7694F82531C5F83480FF -:10B1600085F824302E4BB6F862011A60331DAB62AD -:10B170002C4B06F160021A6006F16403EB6206F2E2 -:10B180005D132B6301F046F80146274801F04AF9A8 -:10B19000264901F093F8264B26491860F06D01F01E -:10B1A0008DF801464FF07C5001F03CF9224B1860BD -:10B1B000BDE8F0810C1A002000F8010818020020F8 -:10B1C000440C0020E00300201C1B00200401002090 -:10B1D000E00D002048000020DC1A00203C0C00207C -:10B1E000400C00202C000020001B00203402002016 -:10B1F000F40300207C000020459A0008B198000864 -:10B20000CD9C0008D4030020041A00205008002020 -:10B21000041B0020A402002084180020EC0300205E -:10B22000D802002034030020000061444C3D0F444C -:10B23000D0030020DB0F49402403002010B5044652 -:10B24000204603F0CFFC10F0FF0F07D10B4B0C484A -:10B2500093F85417BDE81040FCF782BC204603F079 -:10B2600016FD022808D8054B064C83F85407FCF756 -:10B2700047F8FFF737FEE3E710BD00BF0C1A0020C8 -:10B28000B1210108762601082DE9F04F844985B0E7 -:10B29000054603F06FFC8349002828460CBF0124B3 -:10B2A000072403F067FC80490028284608BF0224D1 -:10B2B00003F060FC002808BF0424E10740F1BE80D1 -:10B2C0007A48FCF74DFC0020FCF7E8FD784F794800 -:10B2D000FCF746FC7848FCF743FC7A79774B013A57 -:10B2E000774853F82210FCF73BFC3869002101F045 -:10B2F00079F900285CD13D460646D5F8108000213A -:10B30000404601F06FF900284ED101366D483146B4 -:10B31000D5F814B0D5F818A0D5F81C90FCF720FC8F -:10B320004046002101F068F910B16748FCF718FCAD -:10B3300069464046F9F7BCFF01466448FCF710FC3B -:10B340005846002101F058F910B15F48FCF708FC9D -:10B3500069465846F9F7ACFF01465C48FCF700FC2B -:10B360005046002101F048F910B15748FCF7F8FBAE -:10B3700069465046F9F79CFF01465448FCF7F0FB3C -:10B380004846002101F038F910B14F48FCF7E8FBBE -:10B3900069464846F9F78CFF01464D48FCF7E0FB4B -:10B3A0000C2E05F11005A8D14A48711CFCF7D8FBFA -:10B3B0004948FCF7D5FB494DD7F8088055F8041FDC -:10B3C00019B14748FCF7CCFBF8E70D46454B53F85D -:10B3D000256056B10123AB4013EA080F03D0424861 -:10B3E0003146FCF7BDFB0135F0E74048FCF7B8FB00 -:10B3F00031467B1893F8103104AA13443C4A8A5C06 -:10B400000131082903F8102CF3D10023694639488B -:10B410008DF80830FCF7A4FB3748FCF7A1FB374850 -:10B42000FCF722FC3648FCF79BFB3448FCF79CFFFA -:10B430003448FCF795FB4020FFF76EFAA2071AD5B7 -:10B440003148FCF78DFB3148FCF78AFB2B48FFF7AE -:10B45000F5FE2F48FCF784FB2848FAF745FC2D48F9 -:10B46000FCF77EFB2548FAF7A5FB2648FCF778FB9E -:10B470008020FFF751FA63070FD52748FCF770FBD0 -:10B480002648FCF76DFB1D48FBF722F91D48FCF729 -:10B4900067FB4FF48070FFF73FFA05B0BDE8F08F0F -:10B4A000F9280108EA2F01080029010806290108E6 -:10B4B0000C1A00201429010826290108801201080D -:10B4C000322901083D29010845260108D12001083B -:10B4D000682201084529010857290108D0100108F0 -:10B4E00067290108D410010875290108822901087B -:10B4F000BC2A01088E29010897290108762601082F -:10B50000A3290108A1260108B1290108C4290108BD -:10B51000D2290108DC290108EB290108FC290108CE -:10B5200001480249F7F7BCB8000800403419002070 -:10B5300001480249F7F7B4B8000400400C19002094 -:10B540004FF080400149F7F7ABB800BFE418002086 -:10B5500001480249F7F7A4B8002C0140BC180020AC -:10B5600001480249F7F79CB8002C0140BC180020A4 -:10B5700038B5204CD4F8F0301D88ADB2AA0618D5E5 -:10B58000D4F8CC201AB1988880B2904711E09B88FB -:10B59000D4F8BC20D4F8B410DBB28B54D4F8BC205F -:10B5A000D4F8AC300132B2FBF3F103FB1123C4F841 -:10B5B000BC302B061DD5D4F8C820D4F8C4100D4BD0 -:10B5C0008A4210D0D3F8B800D3F8F010805C013272 -:10B5D000C0B28880D3F8B010B2FBF1F001FB1022AA -:10B5E000C3F8C82038BDD3F8F030DA6822F0800202 -:10B5F000DA6038BDBC1800200F4BD3F84421118805 -:10B60000090618D5D3F81C11D3F8180181420ED0C1 -:10B61000D3F80C01405C0131C0B29080D3F8042112 -:10B62000B1FBF2F002FB1011C3F81C117047D36894 -:10B6300023F08003D3607047BC1800200C480D4BEA -:10B640004FF400525A60D0F828214FF6FE7311686B -:10B650000B401360D0F81821D0F81C319A4202D068 -:10B66000F430FBF71BB8012380F83831704700BF76 -:10B67000BC18002000000240084A13689B020BD54A -:10B68000074B0021197007494FF6FE730868034005 -:10B690000B604FF400135360704700BF000002407E -:10B6A000AE2100206C00024010B50C4B1A785107F7 -:10B6B00013D50B4C22F004021A70A3685B050CD55D -:10B6C000FFF782FA04200121FBF74EFC28B104F5B4 -:10B6D0009670BDE81040FFF79BB910BDB021002067 -:10B6E0000C1A002070B5F6F705F838B3144C237A1D -:10B6F0000BB9A38070BD134D2E78C6F38000F6F70A -:10B700000BF890B1104B46F002061A680F4B5189A6 -:10B710002E7019805189598052899A800C4A12687A -:10B720005288DA80E3880133E380F5F7CFFF10B960 -:10B730002B785B0702D4BDE87040B5E770BD00BF51 -:10B7400050080020B02100204C0800206205002095 -:10B75000041A00200F4B1A6842F001021A6059685F -:10B760000D4A0A405A601A6822F0847222F480322C -:10B770001A601A6822F480221A605A6822F4FE02C3 -:10B780005A604FF41F029A60044B4FF000629A60B7 -:10B79000704700BF001002400000FFF800ED00E01D -:10B7A000024B1A6801321A60704700BF081A002065 -:10B7B00008B5084BB3F8D80093F87C270023D9B21A -:10B7C000914204D2044921F813000133F7E7FAF754 -:10B7D000F1FBFEE7081A00208621002081F00041DD -:10B7E00002E000BF83F0004330B54FEA41044FEA66 -:10B7F000430594EA050F08BF90EA020F1FBF54EA01 -:10B80000000C55EA020C7FEA645C7FEA655C00F09C -:10B81000E2804FEA5454D4EB5555B8BF6D420CDD6D -:10B820002C4480EA020281EA030382EA000083EAF0 -:10B83000010180EA020281EA0303362D88BF30BD90 -:10B8400011F0004F4FEA01314FF4801C4CEA1131E6 -:10B8500002D0404261EB410113F0004F4FEA033345 -:10B860004CEA133302D0524263EB430394EA050FD0 -:10B8700000F0A780A4F10104D5F1200E0DDB02FA3F -:10B880000EFC22FA05F2801841F1000103FA0EF2D3 -:10B89000801843FA05F359410EE0A5F120050EF199 -:10B8A000200E012A03FA0EFC28BF4CF0020C43FACA -:10B8B00005F3C01851EBE37101F0004507D54FF0D7 -:10B8C000000EDCF1000C7EEB00006EEB0101B1F527 -:10B8D000801F1BD3B1F5001F0CD349085FEA30006D -:10B8E0004FEA3C0C04F101044FEA445212F5800F78 -:10B8F00080F09A80BCF1004F08BF5FEA500C50F115 -:10B90000000041EB045141EA050130BD5FEA4C0CF7 -:10B91000404141EB010111F4801FA4F10104E9D180 -:10B9200091F0000F04BF01460020B1FA81F308BF77 -:10B930002033A3F10B03B3F120020CDA0C3208DD43 -:10B9400002F1140CC2F10C0201FA0CF021FA02F11E -:10B950000CE002F11402D8BFC2F1200C01FA02F18E -:10B9600020FA0CFCDCBF41EA0C019040E41AA2BFB3 -:10B9700001EB0451294330BD6FEA04041F3C1CDA7B -:10B980000C340EDC04F11404C4F1200220FA04F09B -:10B9900001FA02F340EA030021FA04F345EA030145 -:10B9A00030BDC4F10C04C4F1200220FA02F001FA07 -:10B9B00004F340EA0300294630BD21FA04F0294689 -:10B9C00030BD94F0000F83F4801306BF81F4801122 -:10B9D0000134013D4EE77FEA645C18BF7FEA655C95 -:10B9E00029D094EA050F08BF90EA020F05D054EA67 -:10B9F000000C04BF1946104630BD91EA030F1EBF6C -:10BA00000021002030BD5FEA545C05D1400049416F -:10BA100028BF41F0004130BD14F580043CBF01F562 -:10BA2000801130BD01F0004545F0FE4141F4700148 -:10BA30004FF0000030BD7FEA645C1ABF1946104623 -:10BA40007FEA655C1CBF0B46024650EA013406BF24 -:10BA500052EA033591EA030F41F4002130BD00BFE3 -:10BA600090F0000F04BF0021704730B54FF48064A0 -:10BA700004F132044FF000054FF0000150E700BF21 -:10BA800090F0000F04BF0021704730B54FF4806480 -:10BA900004F1320410F0004548BF40424FF000016D -:10BAA0003EE700BF42004FEAE2014FEA31014FEAB0 -:10BAB00002701FBF12F07F4393F07F4F81F06051FF -:10BAC000704792F0000F14BF93F07F4F704730B56E -:10BAD0004FF4607401F0004521F0004120E700BF01 -:10BAE00050EA010208BF704730B54FF000050AE088 -:10BAF00050EA010208BF704730B511F0004502D589 -:10BB0000404261EB41014FF4806404F132045FEA8A -:10BB1000915C3FF4DCAE4FF003025FEADC0C18BF2F -:10BB200003325FEADC0C18BF033202EBDC02C2F125 -:10BB3000200300FA03FC20FA02F001FA03FE40EAB7 -:10BB40000E0021FA02F11444C1E600BF70B54FF0B7 -:10BB5000FF0C4CF4E06C1CEA11541DBF1CEA135599 -:10BB600094EA0C0F95EA0C0F00F0DEF82C4481EA01 -:10BB7000030621EA4C5123EA4C5350EA013518BF21 -:10BB800052EA033541F4801143F4801338D0A0FB0E -:10BB900002CE4FF00005E1FB02E506F00042E0FBBB -:10BBA00003E54FF00006E1FB03569CF0000F18BFC1 -:10BBB0004EF0010EA4F1FF04B6F5007F64F5407469 -:10BBC00004D25FEA4E0E6D4146EB060642EAC621FC -:10BBD00041EA55514FEAC52040EA5E504FEACE2E69 -:10BBE000B4F1FD0C88BFBCF5E06F1ED8BEF1004F6C -:10BBF00008BF5FEA500E50F1000041EB045170BDE8 -:10BC000006F0004646EA010140EA020081EA03012B -:10BC1000B4EB5C04C2BFD4EB0C0541EA045170BD27 -:10BC200041F480114FF0000E013C00F3AB8014F1A1 -:10BC3000360FDEBF002001F0004170BDC4F10004EA -:10BC4000203C35DA0C341BDC04F11404C4F120056B -:10BC500000FA05F320FA04F001FA05F240EA0200C6 -:10BC600001F0004221F0004110EBD37021FA04F6FC -:10BC700042EB06015EEA430E08BF20EAD37070BDB6 -:10BC8000C4F10C04C4F1200500FA04F320FA05F015 -:10BC900001FA04F240EA020001F0004110EBD37017 -:10BCA00041F100015EEA430E08BF20EAD37070BD87 -:10BCB000C4F1200500FA05F24EEA020E20FA04F360 -:10BCC00001FA05F243EA020321FA04F001F000410F -:10BCD00021FA04F220EA020000EBD3705EEA430E80 -:10BCE00008BF20EAD37070BD94F0000F0FD101F0AF -:10BCF0000046400041EB010111F4801F08BF013CE8 -:10BD0000F7D041EA060195F0000F18BF704703F025 -:10BD10000046520043EB030313F4801F08BF013DAC -:10BD2000F7D043EA0603704794EA0C0F0CEA135568 -:10BD300018BF95EA0C0F0CD050EA410618BF52EA22 -:10BD40004306D1D181EA030101F000414FF0000028 -:10BD500070BD50EA410606BF1046194652EA430636 -:10BD600019D094EA0C0F02D150EA013613D195EAAA -:10BD70000C0F05D152EA03361CBF104619460AD1F2 -:10BD800081EA030101F0004141F0FE4141F47001FC -:10BD90004FF0000070BD41F0FE4141F4780170BDEC -:10BDA00070B54FF0FF0C4CF4E06C1CEA11541DBF51 -:10BDB0001CEA135594EA0C0F95EA0C0F00F0A7F853 -:10BDC000A4EB050481EA030E52EA03354FEA013180 -:10BDD00000F088804FEA03334FF0805545EA131393 -:10BDE00043EA12634FEA022245EA111545EA10655B -:10BDF0004FEA00260EF000419D4208BF964244F1F2 -:10BE0000FD0404F5407402D25B084FEA3202B61A10 -:10BE100065EB03055B084FEA32024FF480104FF4E4 -:10BE2000002CB6EB020E75EB030E22BFB61A754658 -:10BE300040EA0C005B084FEA3202B6EB020E75EBEB -:10BE4000030E22BFB61A754640EA5C005B084FEA53 -:10BE50003202B6EB020E75EB030E22BFB61A754620 -:10BE600040EA9C005B084FEA3202B6EB020E75EB2B -:10BE7000030E22BFB61A754640EADC0055EA060EEC -:10BE800018D04FEA051545EA16754FEA06164FEA2F -:10BE9000C30343EA52734FEAC2025FEA1C1CC0D1DB -:10BEA00011F4801F0BD141EA00014FF000004FF068 -:10BEB000004CB6E711F4801F04BF01430020B4F129 -:10BEC000FD0C88BFBCF5E06F3FF6AFAEB5EB030CE1 -:10BED00004BFB6EB020C5FEA500C50F1000041EBDE -:10BEE000045170BD0EF0004E4EEA113114EB5C04AB -:10BEF000C2BFD4EB0C0541EA045170BD41F480117E -:10BF00004FF0000E013C90E645EA060E8DE60CEA85 -:10BF1000135594EA0C0F08BF95EA0C0F3FF43BAFA2 -:10BF200094EA0C0F0AD150EA01347FF434AF95EA59 -:10BF30000C0F7FF425AF104619462CE795EA0C0F3D -:10BF400006D152EA03353FF4FDAE1046194622E70A -:10BF500050EA410618BF52EA43067FF4C5AE50EAE4 -:10BF600041047FF40DAF52EA43057FF4EBAE12E7D4 -:10BF70004FEA410212F5001215D211D56FF4787311 -:10BF8000B3EB625212D94FEAC12343F0004343EAB4 -:10BF9000505311F0004F23FA02F018BF404270478F -:10BFA0004FF00000704750EA013005D111F0004019 -:10BFB00008BF6FF0004070474FF00000704700BFAF -:10BFC0004A0011D212F5001211D20DD56FF4787318 -:10BFD000B3EB62520ED44FEAC12343F0004343EA6D -:10BFE000505323FA02F070474FF00000704750EAB8 -:10BFF000013002D14FF0FF3070474FF00000704722 -:10C000004FEA4102B2F1E04324BFB3F5001CDCF17A -:10C01000FE5C0DD901F0004C4FEAC0024CEA5070B2 -:10C02000B2F1004F40EB830008BF20F001007047E1 -:10C0300011F0804F21D113F13872BCBF01F00040E4 -:10C04000704741F480114FEA5252C2F11802C2F116 -:10C05000200C10FA0CF320FA02F018BF40F0010097 -:10C060004FEAC1234FEAD32303FA0CFC40EA0C0049 -:10C0700023FA02F34FEA4303CCE77FEA625307D186 -:10C0800050EA01331EBF4FF0FE4040F440007047BD -:10C0900001F0004040F0FE4040F40000704700BF57 -:10C0A00080F0004002E000BF81F0004142001FBF6D -:10C0B0005FEA410392EA030F7FEA226C7FEA236C76 -:10C0C0006AD04FEA1262D2EB1363C1BFD21841406B -:10C0D00048404140B8BF5B42192B88BF704710F001 -:10C0E000004F40F4000020F07F4018BF404211F0A4 -:10C0F000004F41F4000121F07F4118BF494292EA0C -:10C10000030F3FD0A2F1010241FA03FC10EB0C0037 -:10C11000C3F1200301FA03F100F0004302D54942C4 -:10C1200060EB4000B0F5000F13D3B0F1807F06D371 -:10C1300040084FEA310102F10102FE2A51D2B1F169 -:10C14000004F40EBC25008BF20F0010040EA03005E -:10C150007047490040EB000010F4000FA2F101020B -:10C16000EDD1B0FA80FCACF1080CB2EB0C0200FA95 -:10C170000CF0AABF00EBC25052421843BCBFD040E3 -:10C180001843704792F0000F81F4000106BF80F45D -:10C1900000000132013BB5E74FEA41037FEA226C20 -:10C1A00018BF7FEA236C21D092EA030F04D092F0EB -:10C1B000000F08BF0846704790EA010F1CBF00201F -:10C1C000704712F07F4F04D1400028BF40F000407C -:10C1D000704712F100723CBF00F50000704700F09C -:10C1E000004343F0FE4040F4000070477FEA2262C3 -:10C1F00016BF08467FEA23630146420206BF5FEA94 -:10C20000412390EA010F40F4800070474FF0000393 -:10C2100004E000BF10F0004348BF40425FEA000C5A -:10C2200008BF704743F0964301464FF000001CE002 -:10C2300050EA010208BF70474FF000030AE000BF58 -:10C2400050EA010208BF704711F0004302D5404296 -:10C2500061EB41015FEA010C02BF84460146002008 -:10C2600043F0B64308BFA3F18053A3F50003BCFA23 -:10C270008CF2083AA3EBC25310DB01FA02FC6344D0 -:10C2800000FA02FCC2F12002BCF1004F20FA02F2D7 -:10C2900043EB020008BF20F00100704702F12002CA -:10C2A00001FA02FCC2F1200250EA4C0021FA02F22B -:10C2B00043EB020008BF20EADC7070474FF0FF0C30 -:10C2C0001CEAD0521EBF1CEAD15392EA0C0F93EA2B -:10C2D0000C0F6FD01A4480EA010C400218BF5FEACD -:10C2E00041211ED04FF0006343EA501043EA511140 -:10C2F000A0FB01310CF00040B1F5000F3EBF49003A -:10C3000041EAD3715B0040EA010062F17F02FD2A3D -:10C310001DD8B3F1004F40EBC25008BF20F0010020 -:10C32000704790F0000F0CF0004C08BF49024CEA37 -:10C33000502040EA51207F3AC2BFD2F1FF0340EAC9 -:10C34000C250704740F400004FF00003013A5DDC3A -:10C3500012F1190FDCBF00F000407047C2F100027B -:10C36000410021FA02F1C2F1200200FA02FC5FEA68 -:10C37000310040F1000053EA4C0308BF20EADC70B2 -:10C38000704792F0000F00F0004C02BF400010F424 -:10C39000000F013AF9D040EA0C0093F0000F01F0D1 -:10C3A000004C02BF490011F4000F013BF9D041EAF3 -:10C3B0000C018FE70CEAD15392EA0C0F18BF93EAF5 -:10C3C0000C0F0AD030F0004C18BF31F0004CD8D11F -:10C3D00080EA010000F00040704790F0000F17BFA6 -:10C3E00090F0004F084691F0000F91F0004F14D0EC -:10C3F00092EA0C0F01D142020FD193EA0C0F03D144 -:10C400004B0218BF084608D180EA010000F0004046 -:10C4100040F0FE4040F40000704740F0FE4040F421 -:10C42000400070474FF0FF0C1CEAD0521EBF1CEAC0 -:10C43000D15392EA0C0F93EA0C0F69D0A2EB0302DE -:10C4400080EA010C49024FEA402037D04FF0805378 -:10C4500043EA111143EA10130CF000408B4238BF3D -:10C460005B0042F17D024FF4000C8B4224BF5B1A4B -:10C4700040EA0C00B3EB510F24BFA3EB510340EA99 -:10C480005C00B3EB910F24BFA3EB910340EA9C0047 -:10C49000B3EBD10F24BFA3EBD10340EADC001B01B7 -:10C4A00018BF5FEA1C1CE0D1FD2A3FF650AF8B425B -:10C4B00040EBC25008BF20F0010070470CF0004C68 -:10C4C0004CEA50207F32C2BFD2F1FF0340EAC25093 -:10C4D000704740F400004FF00003013A37E792F054 -:10C4E000000F00F0004C02BF400010F4000F013AB2 -:10C4F000F9D040EA0C0093F0000F01F0004C02BFAD -:10C50000490011F4000F013BF9D041EA0C0195E715 -:10C510000CEAD15392EA0C0F08D142027FF47DAFAE -:10C5200093EA0C0F7FF470AF084676E793EA0C0F9E -:10C5300004D14B023FF44CAF08466EE730F0004C9C -:10C5400018BF31F0004CCAD130F000427FF45CAF2C -:10C5500031F000437FF43CAF5FE700BF4FF0FF3C9A -:10C5600006E000BF4FF0010C02E000BF4FF0010CED -:10C570004DF804CD4FEA40024FEA41037FEA226CB6 -:10C5800018BF7FEA236C11D001B052EA530C18BFD8 -:10C5900090EA010F58BFB2EB030088BFC81738BF3D -:10C5A0006FEAE17018BF40F0010070477FEA226C2B -:10C5B00002D15FEA402C05D17FEA236CE4D15FEA27 -:10C5C000412CE1D05DF8040B704700BF844608465B -:10C5D0006146FFE70FB5FFF7C9FF002848BF10F11C -:10C5E000000F0FBD4DF808EDFFF7F4FF0CBF012061 -:10C5F00000205DF808FB00BF4DF808EDFFF7EAFFEB -:10C6000034BF012000205DF808FB00BF4DF808EDA5 -:10C61000FFF7E0FF94BF012000205DF808FB00BF9A -:10C620004DF808EDFFF7D2FF94BF012000205DF820 -:10C6300008FB00BF4DF808EDFFF7C8FF34BF01202D -:10C6400000205DF808FB00BF4FEA4002B2F1FE4F48 -:10C650000FD34FF09E03B3EB12620DD94FEA0023C4 -:10C6600043F0004310F0004F23FA02F018BF40429D -:10C6700070474FF00000704712F1610F01D1420284 -:10C6800005D110F0004008BF6FF0004070474FF038 -:10C690000000704742000ED2B2F1FE4F0BD34FF0B4 -:10C6A0009E03B3EB126209D44FEA002343F0004328 -:10C6B00023FA02F070474FF00000704712F1610F4B -:10C6C00001D1420202D14FF0FF3070474FF000001D -:10C6D000704700BF73B96AB9002908BF0028BCBF02 -:10C6E00000204FF00041C4BF6FF000414FF0FF3019 -:10C6F00000F03CB882B0EC462DE9005000F006F89E -:10C70000DDF804E002B00CBC704700BF2DE9704FAB -:10C71000089E14461D468046894600F029F804FB11 -:10C7200001F3A4FB00AB00FB05329344B8EB0A080D -:10C7300069EB0B09C6E90089BDE8708F2DE9704FE0 -:10C74000089E14461D468046894600F061F900FBAC -:10C7500005F5A0FB04AB04FB0154A344B8EB0A08A5 -:10C7600069EB0B09C6E90089BDE8708F704700BF0F -:10C7700000292DE9F00FC0F2A1800024002BC0F2A7 -:10C780009880154606460F46002B3FD18A4258D95D -:10C79000B2FA82F34BB1C3F1200201FA03F720FA97 -:10C7A00002F29D4000FA03F61743290CB7FBF1F2A1 -:10C7B00001FB1277A8B200FB02F34FEA164C4CEAD9 -:10C7C0000747BB4209D97F1902F1FF3C80F0058180 -:10C7D000BB4240F20281023A2F44FF1AB7FBF1F349 -:10C7E00001FB137100FB03F0B6B246EA0141884237 -:10C7F00008D9491903F1FF3780F0F180884240F2EF -:10C80000EE80023B43EA0242002303E08B420AD956 -:10C8100000231A461046194614B1404261EB41010B -:10C82000BDE8F00F7047B3FA83F8B8F1000F40F09D -:10C8300088808B4202D3824200F2E28000230122F0 -:10C84000E8E712B90123B3FBF2F5B5FA85F2002A45 -:10C850003AD17F1B280C1FFA85FC0123B7FBF0F1AE -:10C8600000FB11770CFB01F24FEA164848EA074734 -:10C87000BA4207D97F1901F1FF3802D2BA4200F259 -:10C88000C4804146BF1AB7FBF0F200FB12700CFBEC -:10C8900002FCB6B246EA0040844507D9401902F1CD -:10C8A000FF3702D2844500F2AE803A4642EA0142A6 -:10C8B000B0E7E443524263EB430362E7404261EB7B -:10C8C00041014FF0FF3459E79540C2F1200927FAA2 -:10C8D00009F126FA09F99740280CB1FBF0F800FBA2 -:10C8E00018111FFA85FC0CFB08F349EA07094FEA07 -:10C8F000194747EA01418B4206FA02F608D949195D -:10C9000008F1FF327AD28B4278D9A8F10208294483 -:10C91000C91AB1FBF0F300FB13170CFB03F21FFA6B -:10C9200089F949EA0747BA4207D97F1903F1FF316C -:10C9300060D2BA425ED9023B2F44BF1A43EA084391 -:10C940008CE7C8F1200225FA02F103FA08FC27FA65 -:10C9500002F320FA02F207FA08F741EA0C0C4FEA58 -:10C960001C49B3FBF9F109FB11331FFA8CFA0AFBDE -:10C9700001FB17433A0C42EA03439B4505FA08F0D2 -:10C9800008D913EB0C0301F1FF3235D29B4533D9A3 -:10C9900002396344CBEB0303B3FBF9F209FB123317 -:10C9A0000AFB02FABFB247EA0347BA4508D917EBB8 -:10C9B0000C0702F1FF331BD2BA4519D9023A67447A -:10C9C00042EA0145A5FB0001CAEB07078F424FF081 -:10C9D00000030AD305D02A461CE76246FDE63B4623 -:10C9E00010E706FA08F68642F5D26A1E002311E720 -:10C9F0001A46E5E70B46A0E71146CBE7904687E7E6 -:10CA00004346424606E7023A50E702392F4439E7E7 -:10CA10002DE9F00F144605460E46002B43D18A42FD -:10CA200053D9B2FA82F757B1C7F1200620FA06F6B9 -:10CA300001FA07F302FA07F400FA07F51E43210C86 -:10CA4000B6FBF1F201FB1266A0B200FB02F32F0C61 -:10CA500047EA0646B34209D9361902F1FF3780F09A -:10CA6000FD80B34240F2FA80023A2644F61AB6FB41 -:10CA7000F1F301FB136100FB03F0ADB245EA0141A4 -:10CA8000884208D9091903F1FF3680F0E98088420D -:10CA900040F2E680023B43EA024200231046194678 -:10CAA000BDE8F00F70478B424CD8B3FA83F6002EE6 -:10CAB0004FD18B4202D3824200F2DD80BDE8F00FFD -:10CAC0000023012210461946704712B90124B4FB15 -:10CAD000F2F4B4FA84F2002A40F08280091B260C9A -:10CAE000A7B20123B1FBF6F006FB101107FB00F221 -:10CAF0004FEA154C4CEA01418A4207D9091900F165 -:10CB0000FF3C02D28A4200F2C8806046891AB1FB1B -:10CB1000F6F206FB121107FB02F7ADB245EA01453A -:10CB2000AF4208D92C1902F1FF3180F09B80A74257 -:10CB300040F29880023A42EA004210461946BDE8A7 -:10CB4000F00F704700231A4610461946BDE8F00F53 -:10CB50007047C6F1200522FA05F703FA06F421FA18 -:10CB600005F301FA06FB20FA05F53C434FEA1448A9 -:10CB7000B3FBF8FC08FB1C331FFA84F909FB0CFA21 -:10CB800045EA0B0B4FEA1B4545EA03439A4502FA77 -:10CB900006F204D91B190CF1FF356FD3AC46CAEB72 -:10CBA0000303B3FBF8F508FB153309FB05F91FFA7E -:10CBB0008BFB4BEA0347B94504D93F1905F1FF3315 -:10CBC00062D31D4645EA0C4CACFB0223C9EB0707B8 -:10CBD0009F424FF000054AD346D062462B465DE7A0 -:10CBE0009440C2F1200921FA09FC914020FA09F988 -:10CBF000260CBCFBF6F806FB18CCA7B207FB08F323 -:10CC000049EA01094FEA194141EA0C4C634500FA2F -:10CC100002F509D91CEB040C08F1FF323BD2634545 -:10CC200039D9A8F10208A444C3EB0C0CBCFBF6F301 -:10CC300006FB13C107FB03F21FFA89F949EA014118 -:10CC40008A4207D9091903F1FF3022D28A4220D93A -:10CC5000023B2144891A43EA084343E73A4605E781 -:10CC6000334618E70A4666E7B0409042B5D20CF169 -:10CC7000FF32002312E7334632460FE79A458DD93B -:10CC8000ACF1020C23448AE7B9459AD9023D274406 -:10CC900098E70346DEE79046C6E70238214435E7C9 -:10CCA0001C481D49026800608A4200F01D80002176 -:10CCB00000F004B8194B5B58435004311848194B25 -:10CCC00042189A42FFF4F6AF174A00F003B8002367 -:10CCD00042F8043B154B9A42FFF4F9AFFEF73AFDD8 -:10CCE00000F036F8FFF7FEBF114E124830601248D0 -:10CCF000016821F070610160410201600F4C182051 -:10CD000020600F490F4808600F48D0F800D04068F5 -:10CD100000470000F04F0020EFBEADDE50370108A5 -:10CD200000000020FC00002000010020CC21002099 -:10CD3000181002400900000004000140140C0140DA -:10CD4000000C01404434434400F0FF1FFFF7FEBFD6 -:10CD50002DE9804893B0F3F7DBF9DFF850928E4C61 -:10CD6000D9F8086000232370330740F1E780636837 -:10CD70001B7A042B00F2E080DFE803F00303058A4E -:10CD8000B100237AD9E0627A834B002A00F0D48084 -:10CD900000225A7293F82020170700F1CD80D97A2B -:10CDA0009A7A01F0070042EA00225A621A7B02F0E6 -:10CDB0003F00400140EAD1019962597B890041EA74 -:10CDC00092119A7B02F0010041EA8021D962D97B5D -:10CDD00001F00F00C00140EA52021A631A7C02F00F -:10CDE0007F00000140EA11115963597C490041EA72 -:10CDF000D212997C01F0030042EA40229A63DA7C65 -:10CE000002F01F00800140EA9101D963197DC90039 -:10CE100041EA5212997D1A645A7D01F0070042EAF4 -:10CE200000225A64DA7D02F03F00400140EAD1015D -:10CE30009964197E890041EA92115A7E02F001003C -:10CE400041EA8021D964997E01F00F00C00140EAD7 -:10CE500052021A65DA7E02F07F00000140EA1111E9 -:10CE60005965197F490041EAD212597F01F0030048 -:10CE700042EA40229A659A7F02F01F00800140EA50 -:10CE80009101D965D97FC90041EA52121A6651E071 -:10CE900094F86420404B002A4ED0002283F864208E -:10CEA00093F86620012A47D193F88A20102A84BF7C -:10CEB000102283F88A2094F88A10384A0023D8B2C6 -:10CEC000884202F1020235D212F8010C12F8025C1B -:10CED00040EA0525324840F823500133EFE794F843 -:10CEE000CC202D4B42B3002283F8CC2093F8CD20E8 -:10CEF000A82A21D193F8E050F5B9274901EB450361 -:10CF000093F8D00093F8D13003EB0020FEF7A8FD92 -:10CF10001DA3D3E90023FEF743FF1DA3D3E900239C -:10CF2000FEF760FCFFF74CF81E4B43F82500013577 -:10CF3000082DE2D1012300E000232370750408D5F9 -:10CF400094F8043123B1144B002283F80421012307 -:10CF5000237023783BB1F00505D50F4BD3F808318A -:10CF60001B681B689847104D23782A6833B90A4B11 -:10CF7000D3F80C31D31ADB43DB0F00E00123BBB144 -:10CF8000F5F76EFC28E000BF9A9999999999194094 -:10CF900000000000007077400001002068010020C0 -:10CFA0008C010020E4010020A02100200C1A0020A8 -:10CFB000D4F810315A1CC4F810212BB9D9F8083014 -:10CFC000190601D5F7F73CF8D4F81031012B03DD31 -:10CFD000A44B0022C3F81021F4F7B6FDB9F80C30C9 -:10CFE00028602BB1D4F81421821A002AC0F23786A7 -:10CFF00018449C4D99F80530C4F81401059305F5C3 -:10D000009670D4F82031D4F81861984705F59670D9 -:10D01000014694F83221F8F753FC934B1B88002B00 -:10D0200000F09880D5F834314FF000081B7805F5F2 -:10D030009C75049347468C4BB3F800A08B4BBAF514 -:10D040007A7F03D1002243F808202A61884AD05F02 -:10D0500053F80820024443F80820FFF7DBF82A6958 -:10D060000132012A2A6104D1002368602860AB6084 -:10D070002AE0D5F800C002926146CDF80CC00190BC -:10D08000FFF712F8029A83461046FFF7C3F80146ED -:10D090005846FFF7C7F9DDF80CC001466046FFF7B8 -:10D0A00005F8019B02461146686018460292FEF799 -:10D0B000FBFF01465846FFF701F9A968FEF7F6FFA6 -:10D0C000029AE8602A60A860694A002302F1540BC2 -:10D0D000BAF1010FBB5227F80B30DFF88CA12CD12D -:10D0E0002869012807DD0138FFF794F80146E86850 -:10D0F000FFF798F900E0002002F066F80346049874 -:10D1000058B10193FFF786F8019B01461846FFF7D7 -:10D1100091FA10B14FF47A731AE0544B4FF47A72CB -:10D1200058F803300A2003F5FA7393FBF2F32BF857 -:10D1300007300F210122F4F73DFD0237062F08F1D9 -:10D14000040805F114057FF476AFBAF80030013B0E -:10D15000AAF800300023434D05F5967205F5C0711D -:10D16000985A595A411A99520233062BF3D1D5F8DD -:10D17000883113F0020300F0F282D5F8903105F502 -:10D18000CC70984705F5CC70014695F89E21F8F7CC -:10D1900097FBB5F8A03105F5CC77002B44D00022E1 -:10D1A000D5F8A40113462F4D37F902C0B5F8A011E8 -:10D1B00005F5D47EB1F5C87F04BF00214EF80310F9 -:10D1C0005EF80310274D61444EF80310043300212C -:10D1D0000C2BB952815202F10202E4D1B5F8A03110 -:10D1E000012B1CD1D5F8A8314FF4C872C83393FB7A -:10D1F000F2F30380D5F8AC31C83393FBF2F34380EC -:10D20000D5F8B031C83393FBF2F21A4B1B88D21A0F -:10D210008280A6F85410A6F85610FBF715FCB4F857 -:10D22000A031013BA4F8A031D9F808305A0740F1E9 -:10D230008680B4F8B4210B4B322A1DD1D3F8A42137 -:10D240001188A3F8B61151889288A3F8B811A3F8F1 -:10D25000BA21B6F85420A3F8BC21B6F85620A3F89A -:10D26000BE210BE000010020AC2100207402002050 -:10D270002C02002000000020002A3ED00021D4F81B -:10D28000A4510A46C14837F901C0B0F8B43100F5DD -:10D29000E07E322B04BF00234EF802305EF802001D -:10D2A000BA4B60444EF80200043200200C2A785237 -:10D2B000685201F10201E5D1B3F8B421012A17D176 -:10D2C00083F8CD21052283F8CE21B3F8B62183F867 -:10D2D000CC012A80B3F8B8216A80B3F8BA21AA80B9 -:10D2E000B3F8BC21B3F8BE31A6F85420A6F85630E6 -:10D2F000B4F8B431013BA4F8B43194F8CF21A34B76 -:10D30000EAB1D3F8C001D3F8A4113225002290FB72 -:10D31000F5F083F8CF210880D3F8C40190FBF5F035 -:10D320004880D3F8C83193FBF5F5994B1B88ED1A6B -:10D330008D80A6F85420A6F85620FBF785FBD4F87C -:10D34000A431B4F898111A8800268A1AA4F89821F2 -:10D35000B4F89A115A88B3468A1AA4F89A219B887D -:10D36000B4F89C21D31AA4F89C31F4F7EDFBD4F85F -:10D37000D0310546C31A18460493FEF747FFD4F888 -:10D38000D4110690FEF79AFFD4F8D881C4F8D05192 -:10D3900098F80090079035467E4F785FFEF73AFF89 -:10D3A0000799FEF78BFF09A98851B9F1000F2BD01F -:10D3B0004846FEF72FFF01464FF07E50FFF732F848 -:10D3C0000346194607F1B00A4FF07E500193FEF76D -:10D3D0006BFE56F80A10FEF771FF07F16C0102466A -:10D3E000485F0292FEF716FF019BBC371946FEF715 -:10D3F00065FF029A01461046FEF758FE4AF80600FD -:10D40000FFF722F9785304E007F1BC036C37EA5BBD -:10D41000EA52614F0436EB5F0235062D03FB03BB76 -:10D42000BAD15B4D642303FB0BFB2B8807F108008B -:10D430005B439BFBF3FBABF1490B09A91FFA8BFB89 -:10D44000F4F742FDBBF13B0FD8F8046010D9B4F9F2 -:10D45000FC01FEF7DFFED4F8F86101463046FFF725 -:10D46000E9F84A4F94F8FE3160B343F008032BE02B -:10D470004FF07E513046FEF719FE01464FF07E50C8 -:10D48000FEF7D0FF4FF0000A8146DFF818B13046B2 -:10D490005BF81A10FEF712FF034637F90A000193F2 -:10D4A000FEF7B8FE019B01461846FEF7FFFD494610 -:10D4B000FEF704FF4BF81A000AF1020ABAF1060F50 -:10D4C000E3D1C4E723F008033146D4F8F40187F828 -:10D4D000FE3101F077FE0746C4F80002D4F8F001EF -:10D4E000D4F8F8A100F10046D4F8F4010146FEF7A3 -:10D4F000E5FE514681465046FEF7E0FE01464846AD -:10D50000FEF7D4FD01F060FE0146304601F05AFE00 -:10D5100022490646C4F804023846FEF7CFFE01F061 -:10D5200085FD1E49A4F808023046FEF7C7FE01F04B -:10D530007DFDD4F88831A4F80A021B0736D51848B7 -:10D5400009A9F4F7C1FCD8F808504FF07E512846DD -:10D55000FEF7ACFD01464FF07E50FEF763FFDFF8AB -:10D5600048A081460AF10C0BDAF804102846FEF7B1 -:10D57000A5FE0021FEF79AFD4946FEF79FFE4AF8F8 -:10D58000040FDA45F0D106484DE000BF000100204D -:10D59000000000202C020020E80200204C3D0F4437 -:10D5A0000C030020F002002008030020DFF8B093F5 -:10D5B00009A909F10400F4F787FC6868D5F808A008 -:10D5C0000146FEF77BFE514683465046FEF776FE47 -:10D5D00001465846FEF76AFDED6882462946284610 -:10D5E000FEF76CFE01465046FEF760FD01F0ECFDD3 -:10D5F00000210546FEF7F6FFA0B9D9F80400294638 -:10D60000FEF710FF2946C9F80400D9F80800FEF714 -:10D6100009FF2946C9F80800D9F80C00FEF702FFF7 -:10D62000C9F80C00C948F4F707FDC949A4F8180265 -:10D630000698FEF743FE06F10046054607F100474F -:10D64000B4F918020D960C97FEF7E4FDC14900F1FC -:10D650000040FEF733FE0E90B4F9E801FEF7DAFD64 -:10D660000F90B4F9EA01FEF7D5FD1090B4F9EC0182 -:10D67000FEF7D0FD0CA911900FA8F4F725FC98F83F -:10D680000130B54E012B18D1B44B1B785F070ED477 -:10D69000D6F81C32402093FBF0F0181AFEF7BAFDC2 -:10D6A0001199FEF703FDFEF7CFFFC6F81C02D4F870 -:10D6B0001C32402093FBF0F001E0A94B1888FEF7E4 -:10D6C000A9FD01461198FEF7EFFCD4F82412119041 -:10D6D0002846FEF7EBFC01462846FEF7A3FED4F8E9 -:10D6E0002062054631461198FEF7DEFC01462846C9 -:10D6F000FEF7E4FD01463046FEF7D8FC0646C4F8C6 -:10D7000020020F98D4F8287201F090FCD4F834521B -:10D710002978F4F72BFE3844C4F828021098D4F87E -:10D720002C7201F083FC2978F4F720FE3844C4F809 -:10D730002C023046D4F8307201F078FC6978F4F7A6 -:10D7400015FE884B049D1A6838442A441A60D4F8A0 -:10D750003832C4F830020133C4F8383205E0A5F895 -:10D760009831A5F89A31A5F89C31B4F82C21059E82 -:10D77000A4F83C22B4F82E21012E774BA4F83E22C7 -:10D780000ED1B3F94212B3F9302102EB4102032169 -:10D7900092FBF1F292B2A3F84022A3F8422203E0F6 -:10D7A000B3F83021A3F84022F4F7CEF96E4B6A4D5E -:10D7B0001860D4F84832C4F84802C31AA4F84432B6 -:10D7C000F5F748FDD4F84C3213F4801300F08D8047 -:10D7D000B5F85032180600F1ED80604B1B78590700 -:10D7E00070D595F852225E4B12B195F853223AB19A -:10D7F0000022C4F8542201221A74002284F8532211 -:10D800001B7CD4F81851032B95F80080524E05F17B -:10D81000040784F8523206D1384606F516714C22B8 -:10D8200001F096F944E0012B07D106F51670394650 -:10D830004C2201F08DF9002302E0022B02D10123DA -:10D8400086F8A432012384F8A53284F8A632002396 -:10D85000C4F8A832C4F8AC32444A94F8A432C4F8EC -:10D86000B07213441B7C424A1D4484F8B532C4F89C -:10D870005422287984F8B482FEF7CCFC3D49FEF7A7 -:10D88000D1FDC4F8B802A87BFEF7C4FC3A49FEF704 -:10D89000C9FDC4F8BC02287EFEF7BCFC3749FEF780 -:10D8A0000DFDC4F8C002FEF7F5FE00232876AB7329 -:10D8B000B4F8503243F08003A4F85032012384F8C6 -:10D8C000C43277E00026D5F854023146FEF78AFECE -:10D8D000074600286ED1FBF7B7F8214B0122C5F8A7 -:10D8E000546285F852721A7464E0B5F8509219F0D7 -:10D8F000800F54D095F85222194F511E012941D85A -:10D900001D49D5F8BC02FEF7D9FCFEF7C3FED5F8D9 -:10D91000B06295F8B5821A49B04488F80A00D5F883 -:10D92000C002FEF7CBFCFEF7B5FE88F81400307895 -:10D93000FEF770FC0146FEF7B9FBFEF7ABFEB37ACB -:10D94000B0703373337DB37522E000BF0400002054 -:10D95000BD37863535FA8E3C00010020B02100200D -:10D9600000000020A8210020A02100209806010826 -:10D970000000A0410000204100007A445555553F69 -:10D980009A99993F032A03D185F85232012301E085 -:10D990003B7C013329F080093B74A4F85092A24BE0 -:10D9A0001B785A0706D494F8C4321BB19F4B01224E -:10D9B00083F85322D4F818819C4D98F86471002F95 -:10D9C0004FD0B5F850329B074BD0D5F8F001D5F8C1 -:10D9D000F4B10146FEF772FC594682465846FEF7FE -:10D9E0006DFC01465046FEF761FBD5F8F8618246B2 -:10D9F00031463046FEF762FC01465046FEF756FBC4 -:10DA0000B5F8CC9201F0E0FB01463046FEF70AFD86 -:10DA100087490646FEF7FAFDF8B9304601F082FB69 -:10DA2000D5F8D012FEF74AFC01F000FBB0F5617F9B -:10DA3000A8BF4FF46170FEF7EDFB7E49FEF7F2FCE4 -:10DA400001F032FB05463846FEF7E4FB2946FEF7B7 -:10DA500035FC01F0EBFA80B200E000204844A4F865 -:10DA6000CC02D4F88831714D9F0640F18380B5F81F -:10DA7000503203F03003002B7CD095F8FE31DE07E6 -:10DA800078D5B5F91802FEF7C5FB6B49FEF716FC11 -:10DA9000064601F009FB8146304601F091FAD5F8BF -:10DAA000D432074693F803A0B5F9DE02634EBAF10B -:10DAB000000F31D0B5F8DA32CAF100051FFA83FB46 -:10DAC0001BB2C01AF4F7DAFDA84203DB5045A8BF29 -:10DAD000504600E02846B4F8D8328344B4F9DC025A -:10DAE0009AB21BB21FFA8BFBC01AA4F8DAB20292E8 -:10DAF000F4F7C4FDA842029A03DB5045B4BF0546C3 -:10DB000055461544ADB2A4F8D8520FFA8BF0FEF783 -:10DB100081FB824628B204E0FEF77CFB8246B5F921 -:10DB2000DC02FEF777FB394605465046FEF7C6FB9A -:10DB3000494683462846FEF7C1FB01465846FEF794 -:10DB4000B3FA3F49FEF76EFCFEF77EFD4946308092 -:10DB50005046FEF7B3FB394681462846FEF7AEFB3A -:10DB600001464846FEF7A2FA3549FEF75BFCFEF790 -:10DB70006BFD7080334B344D1E6808F1040008F1D2 -:10DB80005403D4F8E012B5F8F620B047F8F762FA7B -:10DB9000D4F8E432002B60D0244B93F8E832013BF8 -:10DBA000142B55D8DFE803F00B5454275754541F57 -:10DBB00054545454542F5454545454272F00D4F8CC -:10DBC000EC325B782BB1214B00205989F4F7EDFD45 -:10DBD00043E0154B1B7803F0040303F0FF00002B18 -:10DBE000F1D10146F2E7194D0020E988F4F7DDFD97 -:10DBF00001202989EAE7154D00202989F4F7D5FD90 -:10DC000001206989E2E7114D0020E988F4F7CDFD94 -:10DC100001202989F4F7C9FD02206989F4F7C5FDBF -:10DC20000320A989D2E700BFB02100200001002015 -:10DC30008FC2753CEFB6B04435FA8E3CA42100206B -:10DC4000000020417C0000200C1A00206C00002005 -:10DC5000AB68980601D5F4F7B3FDF8F7ABF9C64BFE -:10DC60001B78002B40F0F484C44FBB68590540F189 -:10DC7000EF8494F8F032C24D002B00F0E984F4F701 -:10DC80008DFB002800F0E48495F8F132002B00F0C1 -:10DC9000DF84D5F8F4321B78002B40F03282D5F8BF -:10DCA000F802F3F7DDFF002840F02B82DFF8F08266 -:10DCB000D5F8FC22D8F800309A1A7C2A40F221824A -:10DCC000C5F8FC3295F80033013385F8003305467A -:10DCD00005F12400AA4EC0B2F4F794F806F5F473E7 -:10DCE00033F91500FEF796FAA64B81461888FEF721 -:10DCF00091FA01464846FEF795FBA349FEF7DEFA86 -:10DD0000FEF7A2FC013500B2F4F7A8F8032DDFD12D -:10DD10003020F4F777F80020F4F7A0F8F4F780F853 -:10DD200096F8005315F0030520D1D6F8FC2241F2F5 -:10DD300088339A420BD91020F4F764F82846F4F798 -:10DD40008DF82120F4F75EF82846F4F787F81420C0 -:10DD5000F4F758F8B4F91802F4F780F81C20F4F737 -:10DD600051F80020F4F77AF8F4F75AF894F80033F1 -:10DD7000834D5A0740F09F810220F4F743F8B5F92C -:10DD800002030A2390FBF3F0F4F768F80320F4F79A -:10DD900039F87E4B1B7813F0040F4FF0050304D0C5 -:10DDA000B5F9CC0290FBF3F005E0D5F804235289D5 -:10DDB000B2FBF3F000B2F4F751F8BB689B077FD5D4 -:10DDC000734D94F808232B7840F63401B2FBF3F23C -:10DDD0004A432A21B2FBF1F2B4F80A13062091FB60 -:10DDE000F3F703FB17173F01BFB247EA0227BFB2A1 -:10DDF000C2F303221743F4F705F838B2F4F72EF80C -:10DE0000B4F80A232B78013292B292FBF3F103FBB0 -:10DE10001123A4F80A3394F808336E255D431523C3 -:10DE200095FBF3F53A204FF06409F3F7EBFFB5FBF0 -:10DE3000F9F73846F4F712F83B20F3F7E3FF09FB54 -:10DE4000175080B20A27053090FBF7F000B2F4F7C4 -:10DE500005F82820F3F7D6FFD4F80C03484E90FBC2 -:10DE6000F7F000B2F3F7FAFF0420F3F7CBFFD4F892 -:10DE70000433D6F810035D894FF6FF739842A8BFAC -:10DE8000184620EAE070C5B1281AFDF7F9FD002216 -:10DE9000404BFDF75BFE064628460F46FDF7F0FDBA -:10DEA00002460B4630463946FDF77AFFFEF760F82A -:10DEB0004845A8BF484620EAE07000B2F3F7CEFF1D -:10DEC000D4F888312E4D9F0640F1898095F8FE31B7 -:10DED0009E071AD51120F3F795FFB5F81403FDF747 -:10DEE000CFFD23A3D3E90023FDF730FE00222A4B08 -:10DEF000FDF77AFCFEF73CF800B2F3F7AFFF19200C -:10DF0000F3F780FF0020F3F7A9FF94F8FE31B4F88F -:10DF1000165313F0020F08BF00250120F3F772FF1C -:10DF200028B2F3F79BFF0920F3F76CFF0020F3F70B -:10DF300095FF1A4B94F818531B88B3F5967F0BD9AD -:10DF40000F4A92F8002302F00F02072A04D842F287 -:10DF50000F75AB42B8BF1D460520F3F753FFD4F849 -:10DF60001C335B7BF3B928B237E000BFAFF300800E -:10DF70007B14AE47E17A843FAF2100200C1A0020C9 -:10DF8000000100200000002000007A44B0210020A1 -:10DF900080000020000059400000E03F8200002087 -:10DFA000081A0020A5F12000FDF76AFDD0A3D3E9EF -:10DFB0000023FDF7F5FEFEF723F800210546FEF7E6 -:10DFC0001BFB10B14FF03F4101E04FF07C51284660 -:10DFD000FEF76CF8FEF738FB00B2F3F73FFFD4F81A -:10DFE000883198060ED4C44B0021D3F81C536868BE -:10DFF000FEF7F8FA00285CD1A8680021FEF7F2FAD3 -:10E00000002856D194F8FE21BB4B910703D493F816 -:10E010002023012A07D10123D4F82463D4F82853FC -:10E0200084F820330FE0D3F81C53B4496868FEF736 -:10E0300045F9FEF709FBB1490646A868FEF73EF927 -:10E04000FEF702FB05460FA93046F4F7CFF913207F -:10E05000F3F7D8FEBDF93C00F3F700FF1B20F3F700 -:10E06000D1FEBDF93E00F3F7F9FE2320F3F7CAFE17 -:10E07000002EACBF4E205320F3F7F0FE0FA9284628 -:10E08000F4F7B4F91220F3F7BDFEBDF93C00F3F745 -:10E09000E5FE1A20F3F7B6FEBDF93E00F3F7DEFE0B -:10E0A0002220F3F7AFFE002DACBF45205720F3F739 -:10E0B000D5FEF3F7B5FE94F80033282B21D18E4B13 -:10E0C0000022D8F8007083F800234FF47A73B7FB6E -:10E0D000F3F73C251720F3F795FEB7FBF5F6B6FBF3 -:10E0E000F5F005FB1060000200B2F3F7B7FE182050 -:10E0F000F3F788FE05FB167000B2F3F7AFFEF3F7F7 -:10E100008FFED4F8F4327C4D1B78012B40F0248133 -:10E11000F3F71AFDD5F82C33794AC31A9342064611 -:10E1200040F2A98095F80823002385F84E2385F84E -:10E130004423D5F80C2385F8323385F8343385F839 -:10E140004F3385F845330A2392FBF3F285F84C23CD -:10E15000121285F84D23D5F8102392FBF3F385F8BE -:10E16000503395F8FE211B1285F8513395F818337A -:10E17000920785F8763303D42D2385F8773378E03A -:10E18000042B8CBF3323322385F877335D48D4F8D2 -:10E190002453DFF878C195FBF0F70CFB07584FF0DC -:10E1A000060E0EFB08F8584B07EB870798FBF3F9B0 -:10E1B00003FB198807EB87074FFA89F9D4F828136E -:10E1C00009EB8707BFB291FBF0F084F866733F0A52 -:10E1D00084F867730CFB00170EFB07F7ED0F84F84C -:10E1E000655397FBF3F503FB1573642293FBF2F37E -:10E1F00084F86D331B12C90F84F86E33B4F81433EE -:10E2000084F86A1324214B4398FBF2F893FBF2F253 -:10E21000B4F8883384F86323C2F3072284F86423B4 -:10E2200084F86F33B4F816231B0A84F870330A237A -:10E23000B2FBF3F300EB800003F5FA739BB26DB20F -:10E2400000EB800005EB800084F871331B0A80B27C -:10E2500084F87233B4F88A3384F8688384F86B03E3 -:10E260004FEA2828000A84F8698384F86C0384F84C -:10E270007833C4F82C6394F88C331F4D5BB9D5F810 -:10E280009003F3F7EDFC95F89D34002B40F02B84C0 -:10E29000012800F23084D4F89823174D002A5BD06F -:10E2A00095F88C733FB1D5F89C3340F6B731F31A2B -:10E2B0008B420BD850E00123D5F89003022185F85A -:10E2C0008C33F3F7B9FC85F8A07343E095F8A133DC -:10E2D000F3B9D5F890030121C5F8983385F88C334C -:10E2E000F3F7AAFCF3F7C1FC34E000BFAFF3008002 -:10E2F000CDCCCCCCCCCCFC3F000100208096184B80 -:10E300003F0D03008096980040420F00806967FF30 -:10E31000013BDBB285F8A13395F8A01395F8A20371 -:10E3200043B901304B1C85F8A20385F8A033D5F81A -:10E3300090030DE0134613F8012B0130114485F8CA -:10E34000A203D5F8900385F8A013C5F898331146B9 -:10E35000F3F798FCC4F89C63D4F8F432AE4D1B7804 -:10E36000022B1BD1D5F8A433C3B1C5F8A8331B6861 -:10E37000AA4AC5F8AC33D5F8B0331344987CFAF701 -:10E380006FFBD5F8A8339879F3F781FCD5F8B03353 -:10E390000133092B88BF0023C5F8B033F4F750F8D8 -:10E3A000002800F0558194F8B433013B012B00F2B2 -:10E3B0004F81994D9A4ED5F8B803F3F751FCE8B167 -:10E3C000D5F8B803F3F747FC95F8BC2333687E2AE9 -:10E3D00010D102221B2885F8B423C5F8C03305D01C -:10E3E0000D2803D0342801D0672803D18A4901239E -:10E3F00081F8C433884A82F8BC03DAE73368D5F879 -:10E40000C02341F658319A1A8A4203D9032385F86A -:10E41000B4331DE1D5F8C8239B1A042B40F21881B0 -:10E4200095F8C433002B00F0138195F8CC237D4B75 -:10E4300033F8120018B985F8CC034FF4036094F850 -:10E44000CC33B0F5C06F03F10103DBB2724D84F839 -:10E45000CC334AD019D8B0F5007F43D006D8B0F5F8 -:10E46000807F6AD0B0F5887F67D0F1E0B0F5806F2B -:10E4700072D0B0F5826F00F0B180B0F5047F40F04B -:10E48000E78095F808335321DCE0B0F5006F2FD01A -:10E490000CD8B0F5E26F56D0B0F5E46F59D0B0F5B6 -:10E4A000E06F40F0D580B5F9E8114EE0B0F5036FAC -:10E4B00007D0B0F5046F42D0B0F5026F40F0C880CD -:10E4C000B4E0D5F888319F0640F1C28095F8FE315E -:10E4D0009E0740F1BD80B5F81433242159436423CD -:10E4E000123133E0D5F80C13ADE0D5F81013AAE0E3 -:10E4F000D5F88821910640F1AB8095F8FE2192076E -:10E5000040F1A680DB0709D5D5F828130029BCBF48 -:10E51000494241F0804141F0004106E0D5F8241322 -:10E520000029BCBF494241F080414FF40060FCF734 -:10E5300031F9002384F8C4338AE0002183E0B5F97F -:10E54000183264217EE0B5F9EA112C2391FBF3F136 -:10E5500079E0B5F9EC11F8E795F8CD3342F2107196 -:10E560000133DBB2032B85F8CD3384BF012385F85B -:10E57000CD3394F8CD3359432B4B1B78DF0748BF7D -:10E5800001319E0748BF02315807B5F8503248BFE5 -:10E590000431DA0748BF0A319F0748BF14311E060D -:10E5A00048BF2831D80548BF28315A0748BF6431D1 -:10E5B0001F0748BFC8319E0548BF01F5C8719806BE -:10E5C00048BF01F57A71DA0648BF01F5FA615B06CA -:10E5D00048BF01F57A614FF4806034E0D5F88811C6 -:10E5E00011F0200612D095F8FE3113F0020F0CBF87 -:10E5F00000214FF47A7113F0010F0CBF00234FF488 -:10E60000FA63194495F8183319441CE03146FCF7B5 -:10E61000C1F885F8C4631BE00001002098060108DA -:10E62000081A0020D01D0108B0210020D5F888313B -:10E630009F060DD595F8FE319E0709D5B5F816331E -:10E640004FF47A715943FCF7A5F8002385F8C433D9 -:10E65000DFF8E8B2DBF80830DD037EF57EAB94F836 -:10E66000CE33A84E002B3EF478ABA74B1B78002B83 -:10E670007EF473ABF3F768FAD6F8D033D6F8D873D4 -:10E68000C31A6FEA0309D6F8D433C71BC31AFF4372 -:10E690006FEA030AFF0F05464FEAD9794FEADA7AA3 -:10E6A00037B9BAF1000F03D1B9F1000F3EF455AB01 -:10E6B0004FF00008DFF84CC25FFA88F6604690F829 -:10E6C00060349E423BD29149DCF8DC33B2000968E9 -:10E6D00013446244C2F8E0135988C8050BD48B0573 -:10E6E0002AD58B4B1B785E0754BF8A4B8A4B1B681D -:10E6F000C2F8E03320E01946884A30460193CDF84D -:10E700000CC0F9F7D7F8DDF80CC0019BBCF850221B -:10E7100012F0400F03D030461946814A0AE09007B4 -:10E7200003D5304619467F4A04E0D10704D57E4A16 -:10E7300030461946F9F7BEF808F10108BAE79E001D -:10E740000023B3421FD06F49D1F8DC231A4452880A -:10E75000520516D501F57872D0580890B1F96804C1 -:10E760007821A0F57A7048434FF47A7190FBF1F06C -:10E7700000F22B1040F2671190FBF1FE01FB1E012D -:10E7800099520433DDE767B305F5C333A033C4F80A -:10E79000D83394F886345B4E1BBB86F88734DBF89D -:10E7A00008309B0705D5F7F743F910B1012386F828 -:10E7B0008734D4F88834534E1B689B68984728B137 -:10E7C00096F8873443F0020386F88734504B1B7861 -:10E7D00013F0050F05D194F8873443F0040384F84F -:10E7E000873494F8872422B9464B93F88634002B5B -:10E7F0004DD094F8861411F0010FA1F10C001AD13C -:10E80000032906D8414B434E12F0040F18BF33467C -:10E8100000E03E4B0439072904D8444912F0010FA7 -:10E8200018BF0B46C0B2032810D8414912F0020F9E -:10E8300018BF0B460AE0C0B2032806D8334B36494E -:10E8400012F0020F18BF0B4600E0304B0021DFF83A -:10E85000B4E0764696F86004CEB2B0420CD9DEF849 -:10E86000DC03B60030444088000603D518687644BF -:10E87000C6F8E0030131EAE78FB14AB194F8862483 -:10E88000204B0132D2B2142A07D1002205E037B161 -:10E8900094F88634002BF1D101E083F88624BAF194 -:10E8A000000F23D0B4F9C832B4F9C6223221002AAD -:10E8B000B8BF5242002BB8BF5B4293FBF1F392FB0F -:10E8C000F1F1DBB2C9B28B4238BF0B46194A0BB12A -:10E8D00092FBF3F22A44C4F8D42394F88C24094B15 -:10E8E0000AB9012200E0002283F88C2494F88C24D9 -:10E8F000044B22B9104AC3F89024002028E0034AB0 -:10E90000F9E700BF00010020AE210020CC1D010866 -:10E91000B021002098060108A4060108B4060108E9 -:10E92000BA060108C0060108C60601089C060108CF -:10E93000A0060108400D0300CC0601080C1A0020B7 -:10E94000D3F8DC1394000E197688760607D40130CC -:10E950007C4BC2B293F860149142F1D89FE0B3F9B6 -:10E96000C662192E21DD11F8227093F894E407F0A5 -:10E970000F0CF445D3F8906408DC93F895E4BEEBF3 -:10E98000171F03DC23443468C3F8E0436D4B11F8D0 -:10E99000224093F896C404F00F0EE6452DDB93F861 -:10E9A0009574B7EB141F28DC22E0193625DA11F82C -:10E9B000227093F894E407F00F0CF445D3F89064B8 -:10E9C00008DC93F897E4BEEB171F03DB234434689D -:10E9D000C3F8E0435B4B11F8224093F896C404F06F -:10E9E0000F0EE64509DB93F89774B7EB141F04DBB1 -:10E9F000346803EB8203C3F8E043524BB3F9C842D7 -:10EA0000192C21DD11F8227093F8946407F00F0E91 -:10EA1000B645D3F8904409DC93F895E4BEEB171F94 -:10EA200004DC276803EB8203C3F8E07311F822309B -:10EA300003F00F01B1428ADC424F97F89714B1EB13 -:10EA4000131F84DB3B4624E0193480DA11F822706E -:10EA500093F8966407F00F0EB645D3F8904409DB9F -:10EA600093F895E4BEEB171F04DC276803EB8203E1 -:10EA7000C3F8E07311F8223003F00F01B142FFF642 -:10EA800066AF304E96F89714B1EB131FFFF65FAFE9 -:10EA9000334603EB82022368C2F8E03357E7B9F14B -:10EAA000000F1CD093F8992493F8981405F543456A -:10EAB0008818013890FBF2F402FB140083F89B14D1 -:10EAC000013183F89A0491FBF2F002FB10125035E9 -:10EAD000D2B2C3F8D05383F89C2483F89824FBF770 -:10EAE000B5FCFEF73AB900283FF4D5ABD5F8900352 -:10EAF000F3F7B1F822E00228134F03D0F3F7B5F88B -:10EB0000012303E07A7C22B1C5F894637B74FFF79C -:10EB1000C2BBD5F89433F31AB3F57A6FFFF4BBABED -:10EB20000123D5F890037B74F3F795F80746D5F8E1 -:10EB30009003F3F790F8802F7FF4ADABF8F780FCEB -:10EB4000FFF7A9BB0001002000000020AFF3008008 -:10EB500010B50023934203D0CC5CC4540133F9E7D1 -:10EB600010BD02440346934202D003F8011BFAE7AA -:10EB7000704700000D4B70B51D680022845C2B1996 -:10EB80005B7803F00303012B8B5C08BF2034EE1885 -:10EB9000767806F00306012E08BF2033E41A02D16E -:10EBA0000132002BEAD1204670BD00BF900000204A -:10EBB00010B50446224613780134002BFAD1CC5C00 -:10EBC000D4540133002CFAD110BDC9B2024610F85A -:10EBD000013B1BB18B42F9D1104670470029FBD095 -:10EBE00018467047034613F8012B002AFBD1181A68 -:10EBF000013870470F4BF0B51E680023934215D0C3 -:10EC0000C55C7419647804F00304012CCC5C08BF63 -:10EC1000203537197F7807F00307012F08BF20340C -:10EC20002D1B04D10133002CE8D100E0002528463B -:10EC3000F0BD00BF9000002010B5034632B111F8BE -:10EC4000014B013A03F8014B002CF7D11A449342CF -:10EC500003D0002103F8011BF9E710BD30B503789C -:10EC60000BB1044604E00B78002B18BF002030BD28 -:10EC700022461078013438B10023C85C28B1D55C35 -:10EC80008542F5D10133F8E730BD104630BD002193 -:10EC90000A2200F001B92DE9F04E82468B461F464C -:10ECA000144612B90020BDE8F08E002BFAD00026E1 -:10ECB000A642F7D2A5196D0807FB05B9504649468B -:10ECC000089B9847002802DB03D06E1C25462C4683 -:10ECD000EEE74846BDE8F08E174B2DE9F0411D6880 -:10ECE0000646AC6D0F46FCB9502000F0E3F8A8656D -:10ECF0008460AB6D046044601C61DC60AB6D9C6142 -:10ED00005C61AB6DDC629C62AB6D5C631C63AB6D84 -:10ED1000DC639C63AB6D5C641C64AB6DDC649C6405 -:10ED2000AB6D1C77AB6D5C6230463946AA6D012332 -:10ED3000BDE8F04100F002B8F4000020F0B508B9D9 -:10ED4000106828B3044614F8015B0F4617F8016BEE -:10ED50003EB1B542FAD10BB12046F3E7146003701F -:10ED6000F0BD4DB915602846F0BD17F8016BAE42F5 -:10ED700007D0002EF9D11C46234613F8015B0F463D -:10ED8000F3E715B10021217000E02B461360F0BDC0 -:10ED9000F0BD000084463F482DE9F04FD0F80080D8 -:10EDA0000E46344614F8015B08EB0500407800F08D -:10EDB000080000F0FF0708B12646F2E72D2D03D129 -:10EDC000B41C7578012703E02B2D04BF7578B41CA3 -:10EDD00033F010000DD1302D08D1207800F0DF0085 -:10EDE000582851D165781023023402E0002B08BF67 -:10EDF0000A23002F0CBF6FF0004A4FF0004ABAFB05 -:10EE0000F3F903FB19AA0026304608EB050B9BF823 -:10EE100001B01BF0040F01D0303D0BE01BF0030BE1 -:10EE20001BD0BBF1010F14BF4FF0570B4FF0370B46 -:10EE3000CBEB05059D4210DAB6F1FF3F0AD04845FD -:10EE400006D801D1554503DC03FB0050012601E043 -:10EE50004FF0FF3614F8015BD7E7731C0CD1002F7D -:10EE60004FF022030CBF6FF000404FF00040CCF891 -:10EE700000302AB9BDE8F08F07B1404242B106B177 -:10EE8000611E1160BDE8F08F002B08BF0823B0E7BA -:10EE9000BDE8F08F9000002030B51346044A0546C7 -:10EEA0000C46106829462246BDE83040FFF772BF85 -:10EEB000F4000020024B0146186800F003B800BFC0 -:10EEC000F400002070B5CD1C25F0030508350C2D8D -:10EED00038BF0C25002D06463FDB8D423DD3214B2C -:10EEE0001C6818462146A1B10B685B1B0ED40B2B86 -:10EEF00003D90B60CC18CD501FE08C4202D1626860 -:10EF000002601AE04B6863600C4616E00C464968E4 -:10EF1000E9E7154C23681BB9304600F027F820605C -:10EF20002946304600F022F8431C014615D0C41C87 -:10EF300024F0030484420AD1256004F10B00231D50 -:10EF400020F00700C31A0BD05A42E25070BD304681 -:10EF5000611A00F00BF80130EED10C233360002071 -:10EF600070BD00BFC0210020BC21002038B5064C78 -:10EF7000002305460846236000F008F8431C02D130 -:10EF8000236803B12B6038BDC8210020094A1368EB -:10EF900063B118446946884202D810601846704729 -:10EFA000054B0C221A604FF0FF307047034B136083 -:10EFB000EFE700BFC4210020C8210020CC210020A1 -:10EFC00000B5194A20F00043934283B0014617DD93 -:10EFD000B3F1FF4F04DBFDF767F803B05DF804FB06 -:10EFE000694600F037FB00F00302012A00980199FE -:10EFF00011D0022A0AD09AB1012201F0EFF8ECE711 -:10F00000002100F0EFFC03B05DF804FB00F0EAFC27 -:10F0100000F10040E1E701F0E1F800F10040DCE739 -:10F0200000F0E0FCD9E700BFD80F493F30B5C0F38E -:10F03000C754A4F17F031E2B83B0014620DC581C6B -:10F040001BDB162B4FEAD17509DDC1F3160040F426 -:10F050000000963CA04005B1404203B030BD114BCA -:10F0600053F825402046FDF721F8019001982146EC -:10F07000FDF71AF820F0004333B9002003B030BD8B -:10F08000FDF7E2FA03B030BDC0F31604C0F3C75079 -:10F0900044F40004C0F1960024FA00F0002DDCD006 -:10F0A000DAE700BF3C33010800B51D4A20F00043F9 -:10F0B000934283B0014618DDB3F1FF4F04DBFCF748 -:10F0C000F3FF03B05DF804FB694600F0C3FA00F0FB -:10F0D0000300012818D002280ED0D0B10098019961 -:10F0E00000F080FC00F10040EBE70021002201F07D -:10F0F00075F803B05DF804FB00980199012201F056 -:10F100006DF800F10040DCE70098019900F06AFC1E -:10F11000D7E700980199012201F060F8D1E700BF1C -:10F12000D80F493F70B58AB0054600F09BF8224CD5 -:10F13000064694F90030013303D0284601F02CFA3A -:10F1400010B930460AB070BD284601F0DBF94FF027 -:10F150007E51FDF76FFA0028F3D0184901220023F1 -:10F160002846009208930191FCF79CFC02460B464E -:10F170001348CDE90423CDE9022301F0A7F894F95F -:10F180000030CDE90601022B0BD0684601F09CF857 -:10F1900038B1089B53B9DDE90601FCF731FF0AB02D -:10F1A00070BD01F073FA21230360F2E701F06EFAFB -:10F1B000089B0360EFE700BFF8000020443301081C -:10F1C0004C33010800F0B6B970B58AB0054600F0BE -:10F1D000B5FB224C064694F90030013308D028468E -:10F1E00001F0DAF920B128460021FDF705FA10B93F -:10F1F00030460AB070BD1A49012200232846019109 -:10F2000000920893FCF74EFC2478CDE90401CDE987 -:10F2100002017CB900220023CDE90623684601F0F3 -:10F2200053F888B1089BA3B9DDE90601FCF7E8FEB5 -:10F230000AB070BD0020002102460B46FCF7B0FD6D -:10F24000022CCDE90601E9D101F020FA2123036067 -:10F25000E8E701F01BFA089B0360E5E7F8000020EF -:10F2600050330108F8B520F00043B3F17E5F044647 -:10F2700010D008DCB3F17C5F11DAB3F10C5F00F35E -:10F2800084809D48F8BD0146FCF70EFF0146FDF75E -:10F29000C9F8F8BD002840F3CD800020F8BD002853 -:10F2A000C0F2CA8001464FF07E50FCF7FDFE4FF0E1 -:10F2B0007C51FDF703F8044600F040FB8F490646F9 -:10F2C0002046FCF7FBFF8E49FCF7F0FE2146FCF7D9 -:10F2D000F5FF8C49FCF7E8FE2146FCF7EFFF8A4971 -:10F2E000FCF7E4FE2146FCF7E9FF8849FCF7DCFE69 -:10F2F0002146FCF7E3FF8649FCF7D8FE2146FCF7E0 -:10F30000DDFF844905462046FCF7D8FF8249FCF71B -:10F31000CBFE2146FCF7D2FF8049FCF7C7FE214611 -:10F32000FCF7CCFF7E49FCF7BFFE2146FCF7C6FF89 -:10F330004FF07E51FCF7BAFE01462846FDF772F801 -:10F340003146FCF7BBFF26F47F6525F00F05074625 -:10F3500029462846FCF7B2FF01462046FCF7A4FEEA -:10F36000294604463046FCF7A1FE01462046FDF73B -:10F3700059F801463846FCF799FE01462846FCF745 -:10F3800095FE0146FCF792FEF8BD0146FCF796FF9C -:10F390005A490546FCF792FF5949FCF787FE294672 -:10F3A000FCF78CFF5749FCF77FFE2946FCF786FFE8 -:10F3B0005549FCF77BFE2946FCF780FF5349FCF7D3 -:10F3C00073FE2946FCF77AFF5149FCF76FFE294688 -:10F3D000FCF774FF4F4906462846FCF76FFF4E497D -:10F3E000FCF762FE2946FCF769FF4C49FCF75EFE1C -:10F3F0002946FCF763FF4A49FCF756FE2946FCF70D -:10F400005DFF4FF07E51FCF751FE01463046FDF79F -:10F4100009F801462046FCF751FF01464148FCF738 -:10F4200043FE01462046FCF73FFE01463E48FCF7FE -:10F430003BFEF8BD3D48F8BD4FF07E51FCF736FE6F -:10F440004FF07C51FCF73AFF2C490446FCF736FF9D -:10F450002B49FCF72BFE2146FCF730FF2949FCF72E -:10F4600023FE2146FCF72AFF2749FCF71FFE214611 -:10F47000FCF724FF2549FCF717FE2146FCF71EFF89 -:10F480002349FCF713FE2146FCF718FF06462046E9 -:10F4900000F054FA1F4905462046FCF70FFF1E49AD -:10F4A000FCF702FE2146FCF709FF1C49FCF7FEFDB4 -:10F4B0002146FCF703FF1A49FCF7F6FD2146FCF74D -:10F4C000FDFE4FF07E51FCF7F1FD01463046FCF7A2 -:10F4D000A9FF2946FCF7F2FE1249FCF7E5FD0146BB -:10F4E0002846FCF7E3FD0146FCF7E0FD0146104825 -:10F4F000FCF7DAFDF8BD00BFDB0FC93F08EF11389C -:10F50000047F4F3A4611243DA80A4E3E90B0A63ED5 -:10F51000ABAA2A3E2EC69D3D6133303F2D57014098 -:10F5200039D119406821A233DA0FC93FDB0F4940B6 -:10F53000DA0F494021F00042B2F1FF4FF8B504461E -:10F5400014DC20F00045B5F1FF4F06460EDCB1F1AA -:10F550007E5F3AD08F1707F0020747EAD07755B998 -:10F56000022F2FD0032F2FD13148F8BD0846214656 -:10F57000FCF79CFDF8BDFAB1B2F1FF4F29D0B5F10F -:10F58000FF4F19D0AA1AD2153C2A19DC002938DB02 -:10F590002046FCF747FF00F0B5FF00F09DFE012F6D -:10F5A0002CD0022F22D0002F2FD02249FCF77EFD35 -:10F5B0002149FCF779FDF8BD002E15DB1F48F8BD89 -:10F5C0001E48ECE71C48F8BDF8BDBDE8F84000F067 -:10F5D00083BEB5F1FF4F19D0022FF3D0032FC3D054 -:10F5E000012F1BD00020F8BD1548F8BD1149FCF7CC -:10F5F0005DFD01461048FCF757FDF8BD00F10040E5 -:10F60000F8BD3C32C4DA0020C9E7F8BD022F0CD0A7 -:10F61000032F08D0012F04D00A48F8BD4FF0004056 -:10F62000F8BD0948F8BD0948F8BD0948F8BD00BF54 -:10F63000DB0F49C02EBDBB33DB0F4940DB0FC93F99 -:10F64000DB0FC9BFDB0F493FDB0F49BFE4CB16C05F -:10F65000E4CB16402DE9F04FAB4A20F00044944231 -:10F6600089B006460D4664DDA84A94421CDC002899 -:10F67000A74940F3EC80FCF717FDA64B24F00F04DC -:10F680009C42064664D0A449FCF70EFD0146286062 -:10F690003046FCF709FDA049FCF706FD0123686030 -:10F6A000184609B0BDE8F08F9C4A944262DDB4F17F -:10F6B000FF4F46DAE715863FA4EBC7542046FCF718 -:10F6C000C3FFFCF7A7FD0346014620460593FCF760 -:10F6D000EBFC4FF08741FCF7F1FD8046FCF7B4FFEF -:10F6E000FCF798FD0146044640460694FCF7DCFC16 -:10F6F0004FF08741FCF7E2FD00210790FCF772FF15 -:10F70000002800F0C58020460021FCF76BFF002890 -:10F7100014BF0123022382480221019000913A463E -:10F7200005A8294600F022FA002EC0F2A780034661 -:10F7300003E00022286000234A60184609B0BDE8B3 -:10F74000F08F0146FCF7B0FC002368602860F4E706 -:10F750007449FCF7A9FC74490446FCF7A5FC014672 -:10F7600028602046FCF7A0FC6F49FCF79DFC0123B4 -:10F770006860E2E700F0C6FE6C490746FCF79EFDB4 -:10F780004FF07C51FCF792FCFCF75EFF8246FCF7E1 -:10F7900041FD5F498346FCF791FD01463846FCF781 -:10F7A00083FC5D4980465846FCF788FDBAF11F0F7F -:10F7B00081464946404618DC5D4B0AF1FF3253F85A -:10F7C000223024F0FF029A420FD0FCF76DFC07466E -:10F7D0002F6039464046FCF767FC4946FCF764FC5D -:10F7E000002E686056DB5346A7E7FCF75DFCE31587 -:10F7F000C0F3C7529A1A082A0746E9DD4949584614 -:10F800000393FCF75BFD074639464046FCF74CFC8A -:10F81000044621464046FCF747FC3946FCF744FCC9 -:10F82000414907465846FCF749FD3946FCF73CFC80 -:10F83000814649462046FCF737FC039BC0F3C7527C -:10F840009B1A192B074641DC2860A046C1E7FCF74C -:10F850002DFC304B24F00F049C42064623D02E4949 -:10F86000FCF724FC014628603046FCF71DFC2A49C1 -:10F87000FCF71CFC4FF0FF3368605EE795E80C0076 -:10F8800003F1004102F1004243422A60696054E7FB -:10F89000032340E707F1004700F100402F60686054 -:10F8A000CAF1000349E71F49FCF700FC1E49044662 -:10F8B000FCF7FCFB014628602046FCF7F5FB1A49E3 -:10F8C000FCF7F4FB4FF0FF33686036E71949584600 -:10F8D000FCF7F4FC074639462046FCF7E5FB80467A -:10F8E00041462046FCF7E0FB3946FCF7DDFB1249B8 -:10F8F00004465846FCF7E2FC2146FCF7D5FB81465E -:10F900004946404661E700BFD80F493FE3CB164068 -:10F91000800FC93FD00FC93F43443537800F49435B -:10F92000D83301080044353708A3852E84F9223FD7 -:10F930005833010800A3852E32318D2420F0004277 -:10F94000B2F1FF4FF8B5044603462DD25AB3002852 -:10F950003DDBB2F5000F4FEAE0502CD37F38C3F304 -:10F960001603C20743F4000348BF5B0000274010A2 -:10F970005B003E4619244FF08072B5189D4202DCB0 -:10F980005B1BAE181744013C4FEA43034FEA520297 -:10F99000F3D113B107F001031F447F1007F17C5727 -:10F9A00007EBC050F8BDF8BD0146FCF787FC2146C7 -:10F9B000FCF77CFBF8BD14F400020FD15B001902C8 -:10F9C00002F10102FAD5C2F101021044C6E7014674 -:10F9D000FCF76AFB0146FCF725FDF8BD0122104447 -:10F9E000BCE700BF2DE9F84320F00046B6F1485FC0 -:10F9F00005460F4649DAFCF727FE002800F09D80F7 -:10FA000029462846FCF75AFC4E490446FCF756FCAA -:10FA10004D49FCF74BFB2146FCF750FC4B49FCF7EA -:10FA200043FB2146FCF74AFC4949FCF73FFB2146D2 -:10FA3000FCF744FC4749FCF737FB2146FCF73EFC4A -:10FA40004549FCF733FB2146FCF738FC804620464D -:10FA50004FF07C51FCF732FC414606462046FCF74D -:10FA60002DFC394604462846FCF728FC0146204672 -:10FA7000FCF71AFB01463046FCF716FB01464FF037 -:10FA80007E50FCF711FBBDE8F8830146FCF716FC3D -:10FA90002C490446FCF712FC2B49FCF707FB2146D6 -:10FAA000FCF70CFC2949FCF7FFFA2146FCF706FCA1 -:10FAB0002749FCF7FBFA2146FCF700FC2549FCF737 -:10FAC000F3FA2146FCF7FAFB2349FCF7EFFA21464B -:10FAD000FCF7F4FB214B80469E42B8DD204B9E4252 -:10FAE00027DC06F17F4631464FF07E50FCF7DCFA0A -:10FAF000814620464FF07C51FCF7E0FB3146FCF795 -:10FB0000D3FA414606462046FCF7D8FB3946044660 -:10FB10002846FCF7D3FB01462046FCF7C5FA014610 -:10FB20003046FCF7C1FA01464846FCF7BDFABDE88D -:10FB3000F883DFF834900B4EDBE74FF07E50BDE8E2 -:10FB4000F88300BF4ED747ADF6740F317CF2933483 -:10FB5000010DD037610BB63AABAA2A3D9999993E6F -:10FB60000000483F0000903E0000383F2DE9F04F74 -:10FB7000DFB00B93013B0293D31E48BF131DB84C5B -:10FB800006466898DB1054F8204023EAE3730C9390 -:10FB9000DB4302EBC30308940693089C029B0C9A78 -:10FBA0001D190991C3EB02071DD4699C3D4404EB68 -:10FBB000870901354FF0000822AC0AE059F8080027 -:10FBC000FCF728FB0137AF4244F8080008F10408AD -:10FBD00009D0002FF2DA01370020AF4244F80800C4 -:10FBE00008F10408F5D1089A002AC0F2DF82089AC9 -:10FBF0000B9B02F101089C0022AF4FEA88082744C2 -:10FC00000025029A002AC0F2F28105EB070B4FF0A3 -:10FC100000094FF0000A56F809005BF8041DFCF7D4 -:10FC20004DFB01465046FCF741FA09F10409A14594 -:10FC30008246F0D14AA840F805A004354545E0D1F8 -:10FC4000089A0EAB03EB82030D9391464FEA8903AA -:10FC50000793079A5EAB1344B9F1000F53F850AC09 -:10FC600023DD0DF134084AAF174490440DAD4FF039 -:10FC70006E515046FCF722FBFCF7E6FCFCF7CAFA93 -:10FC80004FF087418346FCF719FB01465046FCF7CD -:10FC90000BFAFCF7D9FC594645F8040F57F8040D48 -:10FCA000FCF704FA45458246E1D15046069900F03A -:10FCB0008DFC4FF078510546FCF700FB00F026FC68 -:10FCC0004FF08241FCF7FAFA01462846FCF7ECF9BE -:10FCD0000546FCF7B9FC8246FCF79CFA014628462B -:10FCE000FCF7E2F9069A8046002A40F3678109F1A1 -:10FCF000FF310EA850F82130C2F1080043FA00F29B -:10FD000002FA00F01B1A06989244C0F1070743FA62 -:10FD100007F70EA840F82130002F32DDB9F1000FAF -:10FD20000AF1010A40F375810EAB079A1946114496 -:10FD3000002507E0C2F5807012B143F8040C0125DC -:10FD40008B420BD053F8042B002DF3D0C2F1FF02ED -:10FD50008B4243F8042C4FF00105F3D1069B002B96 -:10FD60000DDD012B00F03281022B08D109F1FF33A8 -:10FD70000EA951F8232002F03F0241F82320022F60 -:10FD800070D040460021FCF72DFC002800F0838055 -:10FD9000089A09F1FF35AA420DDC079A0EAB0D98BF -:10FDA0001344002253F8041D834242EA0102F9D1B0 -:10FDB000002A40F0E481089B0EA85A1E50F8223019 -:10FDC000002B40F0F18100EB8202012352F8041D68 -:10FDD00001330029FAD04B4499450A933DDADDF806 -:10FDE0002CA022AACA44DDF8308002EB8A02C84463 -:10FDF000C9EB0309131D03920593699A079B4FEA08 -:10FE000089094AAF02EB8808CDF810901F440025FD -:10FE100058F8040FFCF7FEF9029B039A002B50518F -:10FE20004FF0000B13DBDDF814A04FF00009AA44DB -:10FE300056F809005AF8041DFCF740FA01465846E6 -:10FE4000FCF734F909F10409A1458346F0D1049A7D -:10FE50000435954247F804BFDAD1DDF82890F5E67D -:10FE6000F036010841464FF07E50FCF71DF9804600 -:10FE7000002D86D006994FF07E5000F0A7FB01467A -:10FE80004046FCF711F9804640460021FCF7AAFBEA -:10FE900000287FF47DAF069B40465942CDF808A06C -:10FEA00000F094FB4FF087410446FCF7B9FB0028B3 -:10FEB00000F07F814FF06E512046FCF7FFF9FCF710 -:10FEC000C3FBFCF7A7F94FF087410546FCF7F6F9AD -:10FED00001462046FCF7E8F8FCF7B6FB0EAB43F80A -:10FEE00029002846FCF7B0FB069C09F101050834FF -:10FEF0000EA9069441F8250006994FF07E5000F0B7 -:10FF000065FB002D04464FDB6E1C4FEA8508C6EBEF -:10FF1000867A0DF138094AABC1444FEA8A0A9844FF -:10FF20004FF0000B59F80B00FCF774F92146FCF771 -:10FF3000C5F94FF06E5148F80B002046FCF7BEF9AA -:10FF4000ABF1040BD3450446ECD1DFF88C92DDF81D -:10FF500020A00024B34603950497BAF1000FB8BF60 -:10FF6000002515DB00263746002501E0A7420FDCFF -:10FF700058F8061059F80600FCF7A0F90146284683 -:10FF8000FCF794F80137BA45054606F10406EDDAA8 -:10FF90005EA800EB84030134A345A8F1040843F8EC -:10FFA000A05CDAD1039D049F689C032C00F298802A -:10FFB000DFE814F0CB009C009C00310010D109F167 -:10FFC000FF330EA951F823703F12A5E609F1FF3364 -:10FFD0000EA850F8232002F07F0240F82320CEE63E -:10FFE0004FF07C51FCF71CFB58B90746C9E64FF0AF -:10FFF000000A4AA840F805A0043545457FF401AE43 -:020000040801F1 -:100000001EE6B9F1000F4FF002070AF1010A3FF7AF -:100010008BAE0025A2E6002D40F3DC804FEA850B75 -:100020005EAB36AE05F1FF3A5B4406EB8A0A53F845 -:10003000A08C54465B4635AABB462F4600E0C84616 -:1000400054F804594146284601920093FCF72EF8D3 -:10005000814649462846FCF727F84146FCF726F832 -:10006000019AC4F804909442A060009BE7D13D46F9 -:10007000012D5F469B4640F3AD805EAB9B445BF831 -:10008000A04C00E044465AF8049921464846FCF743 -:100090000DF8804641464846FCF706F82146FCF735 -:1000A00005F85645CAF80480CAF80800EAD16C1C65 -:1000B00006EB84040020083654F8041DFBF7F6FF15 -:1000C000B442F9D1002F7ED0369A379B099C00F1BB -:1000D000004002F1004203F10043A060226063602F -:1000E000029A02F007005FB0BDE8F08F002DB8BFA4 -:1000F00000200ADB36AE6C1C002006EB840454F8AA -:10010000041DFBF7D3FFB442F9D1002F35D000F125 -:100110000043099C014623603698FBF7C5FF002D7C -:1001200008DD36AC04EB850554F8041FFBF7BEFF71 -:10013000AC42F9D10FB100F10040099A5060029A27 -:1001400002F007005FB0BDE8F08F002D39DB6C1CBA -:1001500036AE002006EB840454F8041DFBF7A6FF1E -:10016000B442F9D10FB100F10040099A1060029A2F -:1001700002F007005FB0BDE8F08F0346C9E7069ABA -:100180000EAC54F82530083ACDF808A00692002BA2 -:100190007FF4B2AE04EB850353F8041D013D083A29 -:1001A0000029F9D00692A7E6012314E60B9B9C00D8 -:1001B00046E52046FCF748FA0EAA4D4642F82900CB -:1001C0009AE60020CEE7099C369A379BA060226011 -:1001D000636085E7002075E7FC3601082DE9F843E8 -:1001E00020F00043B3F1485F04460F46904603DA1F -:1001F000FCF72AFA002857D021462046FCF75EF883 -:1002000021460546FCF75AF8294906462846FCF7D8 -:1002100055F82849FBF748FF2946FCF74FF82649CF -:10022000FBF744FF2946FCF749F82449FBF73CFF5C -:100230002946FCF743F82249FBF738FF8146B8F11D -:10024000000F22D038464FF07C51FCF737F8494672 -:1002500080463046FCF732F801464046FBF724FF63 -:100260002946FCF72BF83946FBF71EFF15490546D2 -:100270003046FCF723F801462846FBF717FF0146F6 -:100280002046FBF711FFBDE8F88349462846FCF7F6 -:1002900015F80C49FBF708FF3146FCF70FF821462B -:1002A000FBF704FFBDE8F8832046BDE8F88300BFF4 -:1002B000D3C92E2F342FD7321BEF3836010D5039CA -:1002C0008988083CABAA2A3E0020704700200149DB -:1002D000704700BF0000F87F2DE9F04120F0004595 -:1002E000B5F1A14F0446064608DBB5F1FF4F6FDCC0 -:1002F000002840F3A0806F48BDE8F0816E4B9D421E -:1003000077DCB5F1445F68DB4FF0FF3721462046CC -:10031000FBF7D4FF01468046FBF7D0FF674905464F -:10032000FBF7CCFF6649FBF7C1FE2946FBF7C6FF8A -:100330006449FBF7BBFE2946FBF7C0FF6249FBF7A8 -:10034000B5FE2946FBF7BAFF6049FBF7AFFE294629 -:10035000FBF7B4FF5E49FBF7A9FE4146FBF7AEFF92 -:100360005C4980462846FBF7A9FF5B49FBF79CFEEA -:100370002946FBF7A3FF5949FBF796FE2946FBF7F1 -:100380009DFF5749FBF790FE2946FBF797FF55491C -:10039000FBF78AFE2946FBF791FF7B1C014640468E -:1003A0004CD0FBF783FE2146FBF788FF4E4B4F4DA9 -:1003B00053F82710FBF778FE2146FBF775FE014640 -:1003C00055F82700FBF770FE002E30DBBDE8F0810A -:1003D0000146FBF76BFEBDE8F0814549FBF766FE81 -:1003E0004FF07E51FCF726F900288DD02046BDE85D -:1003F000F08100F087F83F4B04469D4229DCA3F5CD -:10040000D0039D4244DC0146FBF750FE4FF07E5185 -:10041000FBF74AFE4FF0804105462046FBF746FEBB -:1004200001462846FBF7FEFF002704466EE700F171 -:100430000040BDE8F0813048BDE8F081FBF736FEB2 -:100440002146FBF73BFF01462046FBF72DFEBDE8AA -:10045000F0812A4B9D4214DC4FF07F51FBF724FEC4 -:100460004FF07F5105462046FBF728FF4FF07E51A5 -:10047000FBF71CFE01462846FBF7D4FF0227044683 -:1004800044E701461E48FBF7CDFF032704463DE73E -:100490004FF07E51FBF708FE4FF07E510546204697 -:1004A000FBF704FE01462846FBF7BCFF0127044684 -:1004B0002CE700BFDB0FC93FFFFFDF3ED769853C5C -:1004C00059DA4B3D356B883D6E2EBA3D2549123EBB -:1004D000ABAAAA3E21A215BD6BF16E3D95879D3D4D -:1004E000388EE33DCDCC4C3E283701083837010823 -:1004F000CAF24971FFFF973FDB0FC9BFFFFF1B40E7 -:10050000000080BF20F00040704700BF2DE9F0419F -:1005100020F00047FD0D7F3D162D064613DC002D13 -:1005200080461BDB194F2F41074214D01849FBF7B7 -:10053000BDFD0021FCF77EF868B1002E1BDB28EA28 -:100540000700BDE8F081B7F1FF4F04D30146FBF788 -:10055000ADFDBDE8F0813046BDE8F0810C49FBF708 -:10056000A5FD0021FCF766F80028F4D0002E08DB7A -:100570000020BDE8F0814FF4000343FA05F5A844DC -:10058000DDE7002FE7D00348BDE8F081FFFF7F00E3 -:10059000CAF24971000080BF30F0004001D1022052 -:1005A0007047A0F50003B3F1FE4F01D2042070475D -:1005B000054B421E9A4201D803207047B0F1FF4319 -:1005C00058425841704700BFFEFF7F0038B530F0F9 -:1005D0000044024603460D4614D0B4F1FF4F0DD23D -:1005E000B4F5000F0FD3E40D2C44FE2C2EDC002CB0 -:1005F0001DDD23F0FF4343EAC45038BD0146FBF73D -:1006000055FD38BD38BD4FF09841FBF757FE194BEB -:1006100002469D4207DBC0F3C7540346193CE3E79B -:10062000154800F02DF81449FBF748FE38BD14F1C9 -:10063000160F13DA4CF250339D421146F0DD0F488D -:1006400000F01EF80D49FBF739FE38BD11460B4886 -:1006500000F016F80949FBF731FE38BD04F1190026 -:1006600023F0FF4343EAC0504FF04C51FBF726FE06 -:1006700038BD00BFB03CFFFF6042A20DCAF2497115 -:1006800001F0004120F0004008437047014B18681A -:10069000704700BFF4000020780000FF000000FF5A -:1006A0003C0000FFF00000FF0001746564666D6AA5 -:1006B00069736C67010B020D0A03050B030D0A0336 -:1006C0000A0B040D0A03080B040D0A031E0000FFA9 -:1006D0004A0100FF2C0100FF0E0100FFD20000FFC5 -:1006E000B40000FF960000FF5A0000FF0000FFFF6B -:1006F000CC1D0108EC0601089C060108CC06010887 -:10070000A0060108E806010898060108E4060108A9 -:10071000E0060108DC060108A4060108D806010865 -:10072000D4060108D006010800000000000C0140BA -:1007300008001002000C0140040014020000000038 -:100740000000000003010000240D01080400000067 -:10075000E40C010804000000A40C010802010000E0 -:10076000840C0108000100000000000006000000E9 -:10077000240C010806000000C40B01080101000060 -:100780000000000004000000840B010806000000C7 -:10079000240B010808000000A40A0108080000005A -:1007A000240A010808000000A40901080101000052 -:1007B0000000000000010000000000000001000037 -:1007C00000000000040000006409010806000000A9 -:1007D00004090108000100000000000002010000FF -:1007E000E408010801010000000000000000000012 -:1007F00000000000CA080108B008010896080108B6 -:100800007C0801085D17000819170008F516000894 -:10081000CD160008BD160008E5B600084917000807 -:100820006D1600083D1700082F1700080000000093 -:1008300000C20100B01E0108D31E01080100000023 -:1008400000E10000E81E01080A1F01080200000084 -:10085000009600001E1F0108401F01080300000051 -:10086000004B0000541F0108761F0108040000001F -:10087000802500007626010876260108000106037F -:100880000703080409040A040B0401040204030416 -:1008900004040504FFFF0002010202020302040235 -:1008A000050206030703080409040A040B04FFFFFA -:1008B000000106030703080309030A030B030103EE -:1008C0000203030304030503FFFF00020102020207 -:1008D00003020402050206030703080309030A03CF -:1008E0000B03FFFF0000803F00000000000000003D -:1008F000000080BF0000803F0000000000000000FA -:100900000000803F0000803F000080BF0000803F6B -:10091000000080BF0000803F000080BF000080BF5B -:100920000000803F0000803F0000803F0000803FCB -:100930000000803F0000803F0000803F000080BF3B -:10094000000080BF0000803F0000000000000000A9 -:10095000000000000000803F0000000000000000D8 -:10096000000000000000803F000000000000803F09 -:100970000000803F0000803F000080BF000080BF7B -:10098000000000000000803F000000000000803FE9 -:10099000000080BF0000803F0000803F000080BF5B -:1009A000000000800000803F0000803F000000BF8A -:1009B0000000803F0000803F000000BF000080BFBB -:1009C0000000803F0000803F000080BF0000003F2B -:1009D0000000803F0000803F0000003F0000803F9B -:1009E0000000803F0000803F0000003F000080BF0B -:1009F000000080BF0000803F000080BF000000BFFB -:100A0000000080BF0000803F000000BF0000803F6A -:100A1000000080BF0000803F0000803F0000003FDA -:100A2000000080BF0000803FF704353FF70435BF6A -:100A30000000803F0000803FF70435BFF70435BF5A -:100A40000000803F0000803FF70435BFF704353FCA -:100A50000000803F0000803FF704353FF704353F3A -:100A60000000803F0000803F00000000000080BFC9 -:100A7000000080BF0000803F000080BF0000000039 -:100A8000000080BF0000803F000000000000803FA9 -:100A9000000080BF0000803F0000803F0000000099 -:100AA000000080BF0000803F000080BF0000803F4A -:100AB000000080BF0000803F000080BF000080BFBA -:100AC0000000803F0000803F0000803F0000803F2A -:100AD0000000803F0000803F0000803F000080BF9A -:100AE000000080BF0000803F000080BF0000803F0A -:100AF0000000803F0000803F000080BF000080BFFA -:100B0000000080BF0000803F0000803F0000803F69 -:100B1000000080BF0000803F0000803F000080BFD9 -:100B20000000803F0000803F000000BFD0B35D3F69 -:100B30000000803F0000803F000000BFD0B35DBFD9 -:100B40000000803F0000803F0000003FD0B35D3FC9 -:100B5000000080BF0000803F0000003FD0B35DBFB9 -:100B6000000080BF0000803F000080BF0000000048 -:100B7000000080BF0000803F0000803F00000000B8 -:100B80000000803F0000803F000000000000803F28 -:100B9000000080BF0000803F000080BF000080BFD9 -:100BA000000000000000803F000000000000803FC7 -:100BB0000000803F0000803F0000803F000080BFB9 -:100BC000000000000000803FD0B35DBF0000003F88 -:100BD0000000803F0000803FD0B35DBF000000BF39 -:100BE000000080BF0000803FD0B35D3F0000003FA9 -:100BF0000000803F0000803FD0B35D3F000000BF99 -:100C0000000080BF0000803F00000000000080BFA7 -:100C10000000803F0000803F000000000000803F97 -:100C2000000080BF0000803F00000000A8AAAA3F8B -:100C30000000803F0000803F000080BFB0AA2ABFB4 -:100C4000000080BF0000803F0000803FB0AA2ABFA4 -:100C5000000080BF0000803F00000000A8AAAA3F5B -:100C6000000080BF0000803F000080BFB0AA2ABF04 -:100C70000000803F0000803F0000803FB0AA2ABFF4 -:100C80000000803F0000803F0000803F0000000027 -:100C9000000000000000803F000080BF0000000056 -:100CA000000000000000803F000080BF0000803F87 -:100CB000000080BF0000803F000080BF000080BFB8 -:100CC0000000803F0000803F0000803F0000803F28 -:100CD0000000803F0000803F0000803F000080BF98 -:100CE000000080BF0000803F000000000000803F47 -:100CF000000080BF0000803F000080BF00000000B7 -:100D00000000803F0000803F0000803F00000000A6 -:100D10000000803F0000803F00000000000080BF16 -:100D2000000080BF0000803F00000000A8AAAA3F8A -:100D3000000000000000803F000080BFB0AA2ABF72 -:100D4000000000000000803F0000803FB0AA2ABFE2 -:100D50000000000001000102000103000104000185 -:100D60000500010600010700010800010900010A51 -:100D700000010B00010C010300000000AF1F01087F -:100D80000000000001000000B41F01080100000085 -:100D900002000000BB1F0108020000000300000069 -:100DA000C41F01080300000004000000CA1F01085E -:100DB0000500000005000000CF1F0108060000002C -:100DC00006000000D91F010807000000070000000E -:100DD000E21F01080800000008000000EB1F0108E6 -:100DE0000900000009000000F41F01080A000000CB -:100DF0000A000000FE1F01080B0000000B000000AD -:100E0000082001080C0000000C000000122001085E -:100E10000D0000000D0000001A2001080E00000067 -:100E20000E000000222001080F0000000F0000004B -:100E30002A200108100000001000000033200108E3 -:100E400011000000110000003A200108120000000B -:100E500012000000442001081300000013000000ED -:100E60004C20010814000000140000005720010865 -:100E700015000000150000006120010816000000A8 -:100E80001600000000000000FF000000B56206012F -:100E90000300F00500FF19B56206010300F003002E -:100EA000FD15B56206010300F00100FB11B56206F5 -:100EB000010300F00000FA0FB56206010300F00222 -:100EC00000FC13B56206010300F00400FE17B562D2 -:100ED000060103000102010E47B56206010300018D -:100EE00003010F49B56206010300010601124FB567 -:100EF00062060103000112011E67B56206080600C2 -:100F0000C80001000100DE6A00B562061608000391 -:100F10000703000000000031E501B5620616080075 -:100F200003070300510800008A4102B56206160853 -:100F3000000307030004E00400199D03B5620616D0 -:100F40000800030703000002020035EF04B5620643 -:100F50001608000307030080010000B2E80000004B -:100F600083210108882101088C2101089F210108A3 -:100F700091210108972101089B2101080000000030 -:100F8000762601083F210108472101084F21010869 -:100F9000572101085E21010869210108712101081A -:100FA000792101087E2101080000000000000000F6 -:100FB0008025000000C201000600000001000000C2 -:100FC0008025000000C201000700000002000000B0 -:100FD00080250000004B0000090000001E1E646414 -:100FE00064646464220046022100820120004302FE -:100FF00010000101000049020100880102004C02BA -:101000001200840111009001110090011100A00153 -:101010001100A001D7170008F517000811180008E3 -:101020002D7100083D180008491800080200000052 -:101030008025000000C20100000000002000000028 -:101040008025000000C201000100000040000000F7 -:101050008025000000C20100000000000100000027 -:101060008025000000C20100000000001000000008 -:101070008025000000C20100000300000400000001 -:1010800080250000004B0000000000000800000068 -:1010900000E1000000E100000004000040008000CA -:1010A000000100020004495746415401020408109F -:1010B000204E45535755442C3A3A00003D710008E4 -:1010C000A51700087317000815A90008C117000824 -:1010D00011A900080F250108162501081B25010884 -:1010E0002C25010836250108412501084C25010859 -:1010F0009721010857250108912101086025010861 -:101100006A250108A6240108782501088825010818 -:101110008F25010898250108A2250108AA250108A4 -:1011200000000000524F4C4C3B50495443483B593F -:1011300041573B414C543B506F733B506F73523B94 -:101140004E6176523B4C4556454C3B4D41473B56D4 -:10115000454C3B00472201083E220108322201088B -:1011600000019001C800C800C800C800C800C8003D -:10117000C800C80064000000C800C800C800C8005B -:1011800032000000FF26010808270108B55B0008AF -:101190002C27010830270108E95C000846270108D0 -:1011A0004B2701089D7F00085F270108652701087C -:1011B00069830008CE2501087627010851980008A8 -:1011C000932701089827010889B20008C72701085A -:1011D000762601086D980008CC270108D42701085D -:1011E0003D870008E8270108EC27010895A10008C1 -:1011F000FF2701080E28010855A900082828010822 -:1012000076260108CD7E00082D2801083128010826 -:10121000697C00084028010844280108F97E00087C -:1012200059270108602801082D8200087328010849 -:1012300079280108C9820008EA2F010894280108CA -:101240003DB20008A328010894280108D1660008CF -:10125000AF280108B428010899980008F022010875 -:10126000C4280108F1A10008F2280108E6280108B5 -:10127000E55A0008B02D0108762601089D7E000879 -:101280000E2A0108122A0108182A01081E2A01083C -:10129000212A0108282A01082B2A0108302A0108DE -:1012A0003C2A01083F2A0108452A01084C2A010866 -:1012B000562A0108602A0108692A0108772A0108CC -:1012C000832A01088A2A0108902A01089D2A010818 -:1012D000A82A0108B52A010800000000D12A010847 -:1012E00044000000181A002000000000282300001D -:1012F000DA2A0108410000001A1A0020000000004C -:1013000001000000E82A010844000000261B00201C -:10131000B0040000A4060000EF2A01084400000009 -:10132000281B002000000000D0070000F92A010857 -:10133000440000002A1B002000000000D00700002D -:10134000032B0108420000002C1B002000000000BD -:1013500012000000102B0108420000002D1B00208D -:1013600001000000FF0000001B2B010842000000EC -:101370002E1B00200000000001000000302B01089F -:1013800044000000DC1A002000000000D00700002C -:101390003D2B010844000000DE1A00200000000080 -:1013A000D00700004A2B010844000000E01A00208A -:1013B00000000000D0070000562B01084400000088 -:1013C000E21A002000000000D0070000662B010890 -:1013D00044000000E41A002000000000D0070000D4 -:1013E000772B010844000000E61A002000000000EE -:1013F000D0070000822B010844000000E81A0020FA -:1014000000000000D0070000972B010844000000F6 -:10141000EA1A002032000000007D0000A62B01081F -:1014200044000000EC1A002032000000F20100002D -:10143000B52B0108410000002F1B00200000000018 -:1014400001000000C22B010841000000301B0020F9 -:101450000000000001000000D52B01084100000041 -:10146000311B002000000000B4000000E12B010847 -:1014700041000000321B002000000000640000005A -:10148000ED2B010842000000331B0020FFFFFFFF8F -:1014900001000000032C010841000000381B00205F -:1014A00000000000090000001A2C010841000000A3 -:1014B000391B00200000000009000000312C010849 -:1014C000410000003A1B002000000000090000005D -:1014D000482C0108410000004C1B00203000000097 -:1014E0007E000000592C0108500000003C1B002029 -:1014F000B004000000C20100662C0108500000008A -:10150000401B0020B004000000C20100732C010841 -:1015100050000000441B00200000000000C2010039 -:10152000802C010850000000481B0020B00400007F -:1015300000C20100992C010841000000341B00206A -:101540000000000001000000A62C0108410000007E -:10155000351B00200000000004000000B42C01082E -:1015600041000000361B00200000000001000000C8 -:10157000C42C010881000000281C0020000000008D -:10158000C8000000CE2C010881000000321C0020A1 -:1015900000000000C8000000D82C010881000000F5 -:1015A0003C1C002000000000C8000000E22C0108E4 -:1015B00081000000291C002000000000C80000007D -:1015C000ED2C010881000000331C00200000000009 -:1015D000C8000000F82C0108810000003D1C00201C -:1015E00000000000C8000000032D01088100000079 -:1015F0002A1C002000000000C80000000D2D01087A -:1016000081000000341C002000000000C800000021 -:10161000172D0108810000003E1C00200000000082 -:10162000C8000000212D010884000000D21D002008 -:1016300000000000D00700002F2D010881000000ED -:10164000D61D00200000000001000000442D01080C -:1016500084000000D81D00200A000000D007000010 -:10166000522D010884000000DA1D00200A0000004D -:10167000D0070000602D010881000000D51D00206A -:1016800000000000640000006E2D01084100000011 -:10169000241B00200000000003000000802D010832 -:1016A00041000000501B002000000000030000006B -:1016B000932D010841000000511B00200000000094 -:1016C00001000000A42D010841000000521B002071 -:1016D0000000000001000000B82D010860000000BB -:1016E000541B0020A6FFFFFF5A000000D02D010868 -:1016F00060000000581B00204CFFFFFFB4000000FA -:10170000E82D0108410000005C1B002000000000E3 -:1017100001000000012E0108410000005D1B0020B7 -:1017200000000000010000000C2E01084400000031 -:101730001A1B002000000000204E00001D2E010892 -:1017400041000000101B002000000000FF0000000E -:10175000282E010841000000111B00200A00000093 -:10176000320000003E2E010841000000121B002044 -:101770000A00000032000000542E0108440000005E -:10178000141B00200100000010270000682E010833 -:1017900044000000161B002000000000720600003C -:1017A0007D2E010841000000181B002000000000F1 -:1017B000010000009B2E010841000000EE1A0020ED -:1017C0000000000008000000A62E010841000000F3 -:1017D000EF1A00200000000008000000B02E0108F1 -:1017E00041000000F01A0020000000000800000086 -:1017F000BA2E010848000000F21A00204CFFFFFF3B -:1018000068010000CB2E010848000000F41A0020F7 -:101810004CFFFFFF68010000DD2E010848000000BA -:10182000F61A00204CFFFFFF68010000ED2E0108B2 -:1018300044000000021B002064000000840300003C -:10184000032F010844000000FA1A002000000000E5 -:10185000000100000C2F010841000000001B0020C7 -:1018600000000000800000001C2F01084400000060 -:10187000FC1A002064000000E80300002D2F01087E -:1018800044000000FE1A002064000000E80300008D -:101890003F2F0108810000007F1D00200100000093 -:1018A000FA000000512F010881000000801D002077 -:1018B0000000000001000000482F01088100000026 -:1018C0007D1D00200000000020000000662F0108A0 -:1018D000810000007E1D0020000000006400000068 -:1018E000732F010881000000841D0020000000000B -:1018F000960000008D2F010884000000821D00204A -:101900000100000084030000A72F0108420000002E -:10191000F81A0020FFFFFFFF01000000BD2F0108A3 -:1019200082000000CE1D0020FFFFFFFF010000002D -:10193000CB2F010882000000CF1D00200000000016 -:1019400001000000DD2F010881000000701C002054 -:101950000000000002000000F22F01080101000059 -:101960006221002000000000FA000000FA2F0108A8 -:10197000010100006321002000000000640000005D -:101980000230010801010000642100200000000075 -:10199000640000000A3001080101000065210020F8 -:1019A0000000000064000000133001080101000085 -:1019B00066210020000000006400000023300108C0 -:1019C0000101000067210020000000006400000009 -:1019D0002C300108010100006821002000000000F7 -:1019E0006400000035300108040100006A21002075 -:1019F000E8030000D0070000443001088100000027 -:101A0000C61D002000000000C8000000533001087F -:101A100081000000C71D002000000000C800000079 -:101A20006630010884000000C81D0020E8030000A3 -:101A3000D00700007830010884000000CA1D002093 -:101A400064000000D00700008A3001088400000014 -:101A5000CC1D002064000000B80B00009C30010881 -:101A600081000000D01D002000000000FF000000E9 -:101A7000A930010841000000F91A00200000000010 -:101A800009000000B630010881000000781C002029 -:101A900000000000FA000000C530010881000000CD -:101AA000801C00200000000064000000D430010809 -:101AB00081000000811C0020000000006400000084 -:101AC000E2300108A00000007C1C002001000000A2 -:101AD00014000000F230010881000000941C002076 -:101AE0000000000001000000013101088800000032 -:101AF000761C0020D4FEFFFF2C01000010310108ED -:101B000088000000741C0020D4FEFFFF2C010000A0 -:101B10001E31010881000000841C0020000000002C -:101B2000300000002C310108A0000000881C0020BB -:101B300000000000010000003B310108A00000008F -:101B40008C1C00200000000001000000473101084B -:101B5000A0000000901C0020000000000100000018 -:101B60005331010888000000721C0020B0B9FFFF4B -:101B7000504600006331010881000000201C002055 -:101B80000000000002000000723101088100000026 -:101B9000251C002000000000C80000007A31010868 -:101BA000810000002F1C002000000000C800000081 -:101BB000D52E010881000000391C00200000000023 -:101BC000C80000008231010881000000241C0020B0 -:101BD00000000000C80000008931010881000000F9 -:101BE0002E1C002000000000C8000000C42E0108C8 -:101BF00081000000381C002000000000C800000028 -:101C00009031010881000000261C00200000000027 -:101C1000C80000009631010881000000301C00203F -:101C200000000000C8000000E72E0108810000004D -:101C30003A1C002000000000C80000009C31010890 -:101C4000A0000000481C002000000000640000000C -:101C5000A5310108A0000000541C00200000000075 -:101C600064000000AE310108A0000000601C0020EC -:101C70000000000064000000B7310108A00000006F -:101C8000441C00200000000064000000BF31010877 -:101C9000A0000000501C00200000000064000000B4 -:101CA000C7310108A00000005C1C002000000000FB -:101CB00064000000CF310108A00000004C1C00208F -:101CC0000000000064000000D6310108A000000000 -:101CD000581C00200000000064000000DD310108F5 -:101CE000A0000000641C0020000000006400000050 -:101CF000E4310108A00000006C1C0020000000007E -:101D00000A000000F2310108A0000000681C002059 -:101D1000000000000A000000FE3101088100000000 -:101D2000271C002000000000C80000000432010849 -:101D300081000000311C002000000000C8000000ED -:101D40000A320108810000003B1C00200000000056 -:101D5000C800000010320108810000002B1C002088 -:101D600000000000C80000001832010881000000D7 -:101D7000351C002000000000C800000020320108CF -:101D8000810000003F1C002000000000C80000008F -:101D900028320108810000002D1C002000000000F6 -:101DA000C80000002E32010881000000371C00200E -:101DB00000000000C800000034320108810000006B -:101DC000411C002000000000C800000000000000CE -:101DD000300810020002000100060008000810018F -:101DE0004008000710072007000410042008000026 -:101DF00000080040000C014040000000001E0028C8 -:101E000000040040000C014020000000041D0028D8 -:101E100000040040000C014001000000081D0028E3 -:101E200000040040000C0140020000000C1D0028CE -:101E3000000000400008014001000000001C0028D4 -:101E4000000000400008014002000000041C0028BF -:101E500000080040000C0140000200000C1E0118A8 -:101E600000080040000C014000010000081E01189D -:101E700000080040000C014080000000041E011812 -:101E8000002C01400008014000010000001B011867 -:101E900000040040000C014010000000001D01186B -:101EA000000000400008014004000000081C011868 -:101EB00024505542582C34312C312C303030332CB6 -:101EC000303030312C3131353230302C302A314500 -:101ED0000D0A0024504D544B3235312C31313532FE -:101EE00030302A31460D0A0024505542582C3431E6 -:101EF0002C312C303030332C303030312C353736DB -:101F000030302C302A32440D0A0024504D544B32CC -:101F100035312C35373630302A32430D0A00245003 -:101F20005542582C34312C312C303030332C303059 -:101F300030312C33383430302C302A32360D0A0010 -:101F400024504D544B3235312C33383430302A3212 -:101F5000370D0A0024505542582C34312C312C3086 -:101F60003030332C303030312C31393230302C306D -:101F70002A32330D0A0024504D544B3235312C3166 -:101F8000393230302A32320D0A00303132333435B2 -:101F9000363738394142434445464748494A4B4C15 -:101FA0004D4E4F505152535455565758595A00415F -:101FB000524D3B00414E474C453B00484F52495A19 -:101FC0004F4E3B004241524F3B004D41473B004882 -:101FD000454144465245453B004845414441444AF9 -:101FE0003B0043414D535441423B0043414D545209 -:101FF00049473B0047505320484F4D453B00475011 -:102000005320484F4C443B00504153535448525581 -:102010003B004245455045523B004C45444D4158DC -:102020003B004C45444C4F573B004C4C49474854AF -:10203000533B0043414C49423B00474F5645524EAB -:102040004F523B004F53442053573B0054454C459F -:102050004D455452593B004155544F54554E453B04 -:1020600000534F4E41523B002E0053797374656DFF -:1020700020557074696D653A202564207365636F1F -:102080006E64732C20566F6C746167653A2025640A -:10209000202A20302E315620282564532062617476 -:1020A00074657279290D0A004350552025644D4806 -:1020B0007A2C2064657465637465642073656E733F -:1020C0006F72733A20002573200041434348573A0A -:1020D000202573002E2563004379636C65205469C5 -:1020E0006D653A2025642C20493243204572726F79 -:1020F00072733A2025642C20636F6E6669672073C3 -:10210000697A653A2025640D0A0061646A72616E1D -:1021100067652025752025752025752025752025C6 -:10212000752025752025750D0A00617578202575A7 -:102130002025752025752025752025750D0A00415F -:1021400044584C333435004D505536303530004D01 -:102150004D413834357800424D41323830004C53CF -:102160004D333033444C4843004D505536303030B9 -:10217000004D5055363530300046414B45004E6FCE -:102180006E65004759524F00414343004241524F50 -:1021900000534F4E415200475053004750532B4D70 -:1021A000414700004F20100443024001087261744F -:1021B0006570726F66696C652025640D0A00414583 -:1021C0005452313233340025752C25753A25733A33 -:1021D000257300202564202564006C656420257526 -:1021E0002025730D0A005061727365206572726F4D -:1021F000720D0A00496E76616C6964206C6564201A -:10220000696E6465783A206D757374206265203C50 -:102210002025750D0A00436C65616E666C69676800 -:10222000742F2573202573202F20257320282573D4 -:1022300029004465632020372032303134003232A7 -:102240003A31323A3530003232376238396500413E -:102250007661696C61626C6520636F6D6D616E643F -:10226000733A0D0A0025730925730D0A004D757325 -:102270007420626520616E79206F72646572206FD0 -:10228000662041455452313233340D0A0043757291 -:1022900072656E742061737369676E6D656E743AF2 -:1022A00020004E4709004F4B0900437573746F6D52 -:1022B000206D697865723A200D0A4D6F746F72094E -:1022C00054687209526F6C6C0950697463680959DB -:1022D00061770D0A002325643A090025730900532C -:1022E000616E69747920636865636B3A0900726591 -:1022F000736574006C6F616400496E76616C69642B -:10230000206D6978657220747970650D0A004C6FD4 -:1023100061646564202573206D69780D0A00577229 -:102320006F6E67206E756D626572206F66206172D8 -:1023300067756D656E74732C206E656564732069B6 -:1023400064782074687220726F6C6C20706974639A -:1023500068207961770D0A004D6F746F72206E7579 -:102360006D626572206D757374206265206265749C -:102370007765656E203120616E642025640D0A004A -:1023800043757272656E74206D697865723A2025A6 -:10239000730D0A00417661696C61626C65206D693C -:1023A000786572733A20004D6978657220736574A0 -:1023B00020746F2025730D0A0055736167653A0D0F -:1023C0000A6D6F746F7220696E646578205B766148 -:1023D0006C75655D202D2073686F77205B6F7220B0 -:1023E0007365745D206D6F746F722076616C7565B6 -:1023F0000D0A004E6F2073756368206D6F746F72E5 -:102400002C207573652061206E756D626572205B8E -:10241000302C2025645D0D0A004D6F746F722025ED -:1024200064206973207365742061742025640D0A2B -:1024300000496E76616C6964206D6F746F722076EE -:10244000616C75652C20313030302E2E32303030BA -:102450000D0A0053657474696E67206D6F746F7236 -:1024600020256420746F2025640D0A00636F6C6F53 -:10247000722025752025642C25752C25750D0A00E4 -:10248000496E76616C696420636F6C6F7220696E4F -:102490006465783A206D757374206265203C202550 -:1024A000750D0A004343334400456E61626C6564F8 -:1024B0002066656174757265733A200041766169C2 -:1024C0006C61626C652066656174757265733A2033 -:1024D00000496E76616C6964206665617475726529 -:1024E000206E616D650D0A00534F4E415220756E8E -:1024F000617661696C61626C650D0A0044697361A3 -:10250000626C65642000456E61626C6564200052F7 -:10251000585F50504D005642415400494E464C4978 -:102520004748545F4143435F43414C0052585F5317 -:10253000455249414C004D4F544F525F53544F50F8 -:1025400000534552564F5F54494C5400534F465424 -:1025500053455249414C004641494C534146450080 -:1025600054454C454D455452590043555252454EE1 -:10257000545F4D455445520052585F504152414CB2 -:102580004C454C5F50574D0052585F4D53500052D0 -:102590005353495F414443004C45445F53545249AF -:1025A0005000444953504C4159004F4E4553484FF9 -:1025B00054313235000D0A5265626F6F74696E676F -:1025C00000526573657474696E6720746F2064656A -:1025D0006661756C7473000D0A4C656176696E678F -:1025E00020434C49206D6F64652C20756E736176B5 -:1025F0006564206368616E676573206C6F73742E09 -:102600000D0A00536176696E67000D0A456E7465A8 -:1026100072696E6720434C49204D6F64652C2074AD -:102620007970652027657869742720746F2072653A -:102630007475726E2C206F72202768656C70270D80 -:102640000A000D0A2320000D1B5B4B001B5B324A66 -:102650001B5B313B314800556E6B6E6F776E2063AC -:102660006F6D6D616E642C20747279202768656CC3 -:1026700070270008200800556E6B6E6F776E20760D -:1026800061726961626C65206E616D650D0A00435F -:10269000757272656E742073657474696E67733ACF -:1026A000200D0A0025732073657420746F20005676 -:1026B000616C75652061737369676E6D656E7420FA -:1026C0006F7574206F662072616E67650D0A007306 -:1026D0006574202573203D20004572726F723A2088 -:1026E000456E61626C6520616E6420706C75672058 -:1026F000696E204750532066697273740D0A006139 -:10270000646A72616E67650073686F772F736574B2 -:102710002061646A7573746D656E742072616E6792 -:1027200065732073657474696E67730061757800F2 -:1027300073686F772F736574206175782073657483 -:1027400074696E677300636D6978006465736967A7 -:102750006E20637573746F6D206D697865720063A8 -:102760006F6C6F7200636F6E666967757265206368 -:102770006F6C6F727300726573657420746F206480 -:10278000656661756C747320616E64207265626F3A -:102790006F740064756D70007072696E7420636F81 -:1027A0006E666967757261626C65207365747469C1 -:1027B0006E677320696E2061207061737461626C52 -:1027C0006520666F726D0065786974006665617476 -:1027D000757265006C697374206F72202D76616C60 -:1027E000206F722076616C006765740067657420E5 -:1027F0007661726961626C652076616C75650067EF -:102800007073706173737468726F7567680070615C -:1028100073737468726F7567682067707320746F64 -:102820002073657269616C0068656C70006C65642A -:1028300000636F6E666967757265206C656473000E -:102840006D6170006D617070696E67206F662072D7 -:1028500063206368616E6E656C206F7264657200E0 -:102860006D69786572206E616D65206F72206C698C -:102870007374006D6F746F72006765742F73657485 -:10288000206D6F746F72206F75747075742076612F -:102890006C756500696E64657820283020746F203F -:1028A0003229007261746570726F66696C650073BD -:1028B000617665007361766520616E642072656281 -:1028C0006F6F74006E616D653D76616C7565206F2C -:1028D0007220626C616E6B206F72202A20666F72AC -:1028E000206C6973740073686F77207379737465F3 -:1028F0006D20737461747573006D6173746572001B -:102900007261746573000D0A232076657273696FB6 -:102910006E0D0A000D0A232064756D70206D6173C1 -:102920007465720D0A000D0A23206D697865720DB9 -:102930000A006D697865722025730D0A00636D6960 -:102940007820256400636D6978202564203020306C -:10295000203020300D0A000D0A0D0A232066656123 -:10296000747572650D0A0066656174757265202D57 -:1029700025730D0A00666561747572652025730DF7 -:102980000A000D0A0D0A23206D61700D0A006D61A9 -:10299000702025730D0A000D0A0D0A23206C656452 -:1029A0000D0A000D0A0D0A2320636F6C6F720D0A69 -:1029B000000D0A232064756D702070726F66696C5B -:1029C000650D0A000D0A232070726F66696C650D33 -:1029D0000A000D0A23206175780D0A000D0A2320D4 -:1029E00061646A72616E67650D0A000D0A232064D6 -:1029F000756D702072617465730D0A000D0A2320D5 -:102A00007261746570726F66696C650D0A0054526C -:102A100049005155414450005155414458004249E4 -:102A20000047494D42414C00593600484558360050 -:102A3000464C59494E475F57494E47005934004864 -:102A400045583658004F43544F5838004F43544F61 -:102A5000464C415450004F43544F464C415458004B -:102A6000414952504C414E450048454C495F313236 -:102A7000305F4343504D0048454C495F39305F4417 -:102A8000454700565441494C3400484558364800A3 -:102A900050504D5F544F5F534552564F004455417F -:102AA0004C434F505445520053494E474C45434FB9 -:102AB0005054455200435553544F4D0041455254D4 -:102AC000313233343536373861626364656667683E -:102AD000006C6F6F7074696D6500656D665F61761F -:102AE0006F6964616E6365006D69645F7263006D38 -:102AF000696E5F636865636B006D61785F636865CD -:102B0000636B00727373695F6368616E6E656C00FE -:102B1000727373695F7363616C6500696E7075745D -:102B20005F66696C746572696E675F6D6F6465007E -:102B30006D696E5F7468726F74746C65006D617836 -:102B40005F7468726F74746C65006D696E5F636F3B -:102B50006D6D616E640033645F6465616462616EB3 -:102B6000645F6C6F770033645F6465616462616E9B -:102B7000645F686967680033645F6E65757472616D -:102B80006C0033645F6465616462616E645F746885 -:102B9000726F74746C65006D6F746F725F70776DB7 -:102BA0005F7261746500736572766F5F70776D5FD9 -:102BB000726174650072657461726465645F6172EC -:102BC0006D0064697361726D5F6B696C6C5F7377C4 -:102BD0006974636800736D616C6C5F616E676C65CE -:102BE00000666C6170735F73706565640066697818 -:102BF000656477696E675F616C74686F6C645F644D -:102C000069720073657269616C5F706F72745F31B5 -:102C10005F7363656E6172696F0073657269616C81 -:102C20005F706F72745F325F7363656E6172696F3C -:102C30000073657269616C5F706F72745F335F738C -:102C400063656E6172696F007265626F6F745F6356 -:102C50006861726163746572006D73705F62617543 -:102C6000647261746500636C695F6261756472614E -:102C70007465006770735F6261756472617465008A -:102C80006770735F706173737468726F7567685F84 -:102C90006261756472617465006770735F70726FF2 -:102CA0007669646572006770735F736261735F6DEC -:102CB0006F6465006770735F6175746F5F636F6EDB -:102CC000666967006770735F706F735F700067702D -:102CD000735F706F735F69006770735F706F735FAE -:102CE00064006770735F706F73725F7000677073FA -:102CF0005F706F73725F69006770735F706F73727C -:102D00005F64006770735F6E61765F7000677073F9 -:102D10005F6E61765F69006770735F6E61765F6496 -:102D2000006770735F77705F726164697573006EBE -:102D300061765F636F6E74726F6C735F68656164F8 -:102D4000696E67006E61765F73706565645F6D695B -:102D50006E006E61765F73706565645F6D617800AB -:102D60006E61765F736C65775F7261746500736521 -:102D70007269616C72785F70726F766964657200F7 -:102D800074656C656D657472795F70726F76696475 -:102D900065720074656C656D657472795F737769CF -:102DA0007463680074656C656D657472795F696ED3 -:102DB00076657273696F6E006672736B795F6465B6 -:102DC0006661756C745F6C617474697475646500B8 -:102DD0006672736B795F64656661756C745F6C6F46 -:102DE0006E676974756465006672736B795F636F93 -:102DF0006F7264696E617465735F666F726D617422 -:102E0000006672736B795F756E69740062617474C9 -:102E10006572795F6361706163697479007662617C -:102E2000745F7363616C6500766261745F6D617875 -:102E30005F63656C6C5F766F6C746167650076626A -:102E400061745F6D696E5F63656C6C5F766F6C74E7 -:102E50006167650063757272656E745F6D65746538 -:102E6000725F7363616C650063757272656E745F27 -:102E70006D657465725F6F6666736574006D756C01 -:102E800074697769695F63757272656E745F6D6589 -:102E90007465725F6F757470757400616C69676ECC -:102EA0005F6779726F00616C69676E5F6163630071 -:102EB000616C69676E5F6D616700616C69676E5F09 -:102EC000626F6172645F726F6C6C00616C69676ED7 -:102ED0005F626F6172645F706974636800616C69DE -:102EE000676E5F626F6172645F796177006D6178B0 -:102EF0005F616E676C655F696E636C696E61746952 -:102F00006F6E006779726F5F6C7066006D6F726FC5 -:102F10006E5F7468726573686F6C64006779726F56 -:102F20005F636D70665F666163746F72006779726C -:102F30006F5F636D70666D5F666163746F72006171 -:102F40006C745F686F6C645F6465616462616E6419 -:102F500000616C745F686F6C645F666173745F635B -:102F600068616E6765007961775F6465616462615D -:102F70006E64007468726F74746C655F636F7272F4 -:102F8000656374696F6E5F76616C756500746872F5 -:102F90006F74746C655F636F7272656374696F6E72 -:102FA0005F616E676C65007961775F636F6E7472E5 -:102FB0006F6C5F646972656374696F6E00796177C5 -:102FC0005F646972656374696F6E007472695F75BE -:102FD0006E61726D65645F736572766F00646566BD -:102FE00061756C745F726174655F70726F66696C35 -:102FF000650072635F726174650072635F6578700B -:103000006F007468725F6D6964007468725F6578E0 -:10301000706F00726F6C6C5F70697463685F72616F -:103020007465007961775F72617465007470615FC7 -:1030300072617465007470615F627265616B706F5C -:10304000696E74006661696C736166655F64656C66 -:103050006179006661696C736166655F6F66665F62 -:1030600064656C6179006661696C736166655F7443 -:1030700068726F74746C65006661696C7361666513 -:103080005F6D696E5F75736563006661696C73611E -:1030900066655F6D61785F757365630067696D6212 -:1030A000616C5F666C616773006163635F68617226 -:1030B0006477617265006163635F6C70665F66610F -:1030C00063746F720061636378795F6465616462E1 -:1030D000616E64006163637A5F6465616462616EFE -:1030E00064006163637A5F6C70665F6375746F66BA -:1030F00066006163635F756E61726D656463616CC8 -:10310000006163635F7472696D5F70697463680006 -:103110006163635F7472696D5F726F6C6C00626192 -:10312000726F5F7461625F73697A65006261726F6A -:103130005F6E6F6973655F6C7066006261726F5F6E -:1031400063665F76656C006261726F5F63665F6184 -:103150006C74006D61675F6465636C696E6174694E -:103160006F6E007069645F636F6E74726F6C6C6514 -:103170007200705F706974636800695F706974637E -:103180006800705F726F6C6C00695F726F6C6C00CE -:10319000705F79617700695F79617700705F70694E -:1031A0007463686600695F70697463686600645F71 -:1031B00070697463686600705F726F6C6C6600693A -:1031C0005F726F6C6C6600645F726F6C6C6600702F -:1031D0005F7961776600695F7961776600645F791E -:1031E000617766006C6576656C5F686F72697A6F8F -:1031F0006E006C6576656C5F616E676C6500705F14 -:10320000616C7400695F616C7400645F616C740070 -:10321000705F6C6576656C00695F6C6576656C00E7 -:10322000645F6C6576656C00705F76656C00695FE5 -:1032300076656C00645F76656C000020202020209D -:103240002020202028282828282020202020202056 -:103250002020202020202020202020881010101046 -:10326000101010101010101010101004040404049A -:1032700004040404041010101010101041414141C6 -:1032800041410101010101010101010101010101AE -:1032900001010101010110101010101042424242C0 -:1032A000424202020202020202020202020202027E -:1032B00002020202020210101010200000000000A2 -:1032C00000000000000000000000000000000000FE -:1032D00000000000000000000000000000000000EE -:1032E00000000000000000000000000000000000DE -:1032F00000000000000000000000000000000000CE -:1033000000000000000000000000000000000000BD -:1033100000000000000000000000000000000000AD -:10332000000000000000000000000000000000009D -:103330000000000000000000000000000000004B42 -:10334000000000CB61636F736600000000000000A6 -:103350007371727466000000000FC93F000F49408E -:1033600000CB9640000FC9400053FB4000CB1641F4 -:1033700000ED2F41000F49410031624100537B4174 -:10338000003A8A4100CB9641005CA34100EDAF4179 -:10339000007EBC41000FC94100A0D5410031E2418F -:1033A00000C2EE410053FB4100F20342003A0A42E0 -:1033B0000083104200CB164200141D42005C2342E1 -:1033C00000A5294200ED2F4200363642007E3C42E5 -:1033D00000C74242000F4942A2000000F90000006D -:1033E000830000006E0000004E000000440000005A -:1033F0001500000029000000FC000000270000006C -:1034000057000000D1000000F5000000340000006B -:10341000DD000000C0000000DB00000062000000D2 -:1034200095000000990000003C00000043000000EF -:103430009000000041000000FE000000510000006C -:1034400063000000AB000000DE000000BB000000D5 -:10345000C500000061000000B7000000240000006B -:103460006E0000003A000000420000004D00000025 -:10347000D2000000E000000006000000490000004B -:103480002E000000EA00000009000000D10000004A -:10349000920000001C000000FE0000001D00000063 -:1034A000EB0000001C000000B1000000290000003B -:1034B000A70000003E000000E800000082000000BD -:1034C00035000000F50000002E000000BB000000E9 -:1034D0004400000084000000E90000009C0000009F -:1034E0007000000026000000B40000005F00000033 -:1034F0007E00000041000000390000009100000043 -:10350000D6000000390000008300000053000000D6 -:1035100039000000F40000009C000000840000005E -:103520005F0000008B000000BD000000F9000000FB -:10353000280000003B0000001F000000F800000011 -:1035400097000000FF000000DE0000000500000002 -:10355000980000000F000000EF0000002F000000A6 -:10356000110000008B0000005A0000000A0000005B -:103570006D0000001F0000006D000000360000001C -:103580007E000000CF00000027000000CB000000FC -:1035900009000000B70000004F00000046000000D6 -:1035A0003F000000660000009E0000005F00000079 -:1035B000EA0000002D000000750000002700000058 -:1035C000BA000000C7000000EB000000E5000000AA -:1035D000F10000007B0000003D000000070000003B -:1035E00039000000F70000008A00000052000000CF -:1035F00092000000EA0000006B000000FB000000E9 -:103600005F000000B10000001F0000008D000000FE -:103610005D000000080000005600000003000000EC -:103620003000000046000000FC0000007B000000AD -:103630006B000000AB000000F0000000CF000000B5 -:10364000BC000000200000009A000000F400000010 -:10365000360000001D000000A9000000E30000008B -:1036600091000000610000005E000000E600000024 -:103670001B00000008000000650000009900000029 -:10368000850000005F00000014000000A0000000A2 -:1036900068000000400000008D000000FF000000F6 -:1036A000D8000000800000004D0000007300000002 -:1036B00027000000310000000600000006000000A6 -:1036C0001500000056000000CA0000007300000052 -:1036D000A8000000C900000060000000E200000037 -:1036E0007B000000C00000008C0000006B000000A8 -:1036F0000400000007000000090000000000C93FAE -:103700000000F0390000DA370000A2330000842EF8 -:103710000000502B0000C2270000D0220000C41F70 -:103720000000C61B000044176937AC316821223302 -:10373000B40F14336821A2333863ED3EDA0F493FEA -:083740005E987B3FDA0FC93FE0 -:083748002890FF7F0100000042 -:10375000000100000000803F0000000000000000A9 -:103760000101000000127A000000000000000000CB -:10377000010203040607080901000000010100001E -:103780000000803F00000000010203040102030466 -:1037900006070809020406080000000000000000F7 -:1037A0000000000001000000000000000000000018 -:1037B000020000000000000000000000DC05DC0545 -:1037C000DC05DC05DC05DC05DC05DC05459A0008CC -:1037D00003000F2700A24A04A4240108A42401081E -:1037E0003A32010800000000000000000000000064 -:1037F00000000000000000000000000000000000C9 -:10380000000000008A210108000000000000000004 -:1038100000000000000000000000000000000000A8 -:103820000000000000000000000000000000000098 -:103830000000000000000000000000000000000088 -:0C384000000000009400002001000000C7 -:0400000508000000EF -:00000001FF diff --git a/obj/cleanflight_CJMCU.hex b/obj/cleanflight_CJMCU.hex deleted file mode 100644 index a751dee717..0000000000 --- a/obj/cleanflight_CJMCU.hex +++ /dev/null @@ -1,3927 +0,0 @@ -:020000040800F2 -:1000000000500020C98B0008758C00082977000873 -:10001000758C0008758C0008758C000800000000C5 -:10002000000000000000000000000000758C0008C7 -:10003000758C000800000000758C00081977000816 -:10004000758C0008758C0008758C0008758C00088C -:10005000758C0008758C0008758C0008758C00087C -:10006000758C0008758C0008758C0008758C00086C -:10007000758C0008758C000881760008758C000866 -:10008000758C0008758C0008758C0008758C00084C -:10009000758C0008758C0008758C0008758C00083C -:1000A000758C000895750008758C0008A57500080A -:1000B000857500087575000865750008C976000823 -:1000C000C1760008C5760008BD760008758C00086A -:1000D000758C00083D760008B5750008758C000821 -:1000E000758C0008758C0008758C000800000000F5 -:1000F0000000000000000000000000000000000000 -:0C01000000000000000000005FF808F1A3 -:100110002DE9F04F674B684C99B023600023636072 -:1001200005F0D2FF18B903F02DFE05F0EFFF03F044 -:100130001FFA00230893614C09930A934FF4E013CC -:100140000B9323685E4943F480338A7B2360A36961 -:10015000894643F01003A361236803F40033099335 -:10016000089B01330893099B1BB9089BB3F5A06F4B -:10017000F2D12168514B11F4003101D0022315E076 -:10018000186840F0010018600891236803F002032A -:100190000993089B01330893099B1BB9089BB3F58E -:1001A000A06FF2D12368980739D501230A93454BF4 -:1001B000454E1968454F41F010011960196821F04A -:1001C00003011960196841F00201196063686360F6 -:1001D00063686360636843F4806363603C4B1968E1 -:1001E00021F0704119603B49B161616821F47C11D3 -:1001F0006160196841F000411960FB6823F4004315 -:10020000FB60BB68190449BF334B4FF4E013B36183 -:100210004FF480130B930A9B012B01D117E0FEE7EB -:10022000022B18D16AB10B9BB3F5801F02D14FF49A -:10023000A01305E00B9BB3F5E01F02D14FF40013B0 -:100240000B9362680B9B134343F4803302E06368B3 -:1002500043F460136360236843F080732360226873 -:10026000164B9201FBD55A6822F003025A605A6875 -:1002700042F002025A606368104A03F00C03082B34 -:100280000693F8D15168154B01F00C01042903D0F5 -:10029000082904D00F4A00E0B2691A602AE05168C8 -:1002A0005068C1F38341C50301F102011AD40C4A1D -:1002B0001EE000BF5D23000808050020001002407A -:1002C000A40F002000200240100000200010014078 -:1002D0000410014000127A00001BB70080000020CB -:1002E00000093D00526812F4003FB26918BF52087D -:1002F000514319606268DFF848A3C2F30312324425 -:1003000092F81CB01A6818AD22FA0BFBC3F800B0C3 -:10031000BB4B4FF00008CAF80C30A369B94843F052 -:100320000103A361636A43F080736362A36943F0CE -:100330001C03A3614FF6FF7325F82C3D29468DF869 -:10034000368002F04FFBB048294602F04BFB2946AD -:10035000AE4802F047FBAE4B28465A6842F00072A6 -:100360005A6006F027FC0D9BAA4AAB48B3FBF2F398 -:100370004FF47A728360BBFBF2FBA84B0BF1FF32A8 -:100380005A60F0228AF823200722C3F808806420EC -:100390001A6001F0D4FEA022A14841460AF0B9FD3E -:1003A000E369424643F00703E361A36943F4006352 -:1003B00043F00C03A361984B4FF0000803F10C01CC -:1003C00002F8018001320E2AF5D1FF229A76DA7600 -:1003D0001A775A77934B4FF0100A0FCB85E80F002E -:1003E000A3690D9843F01003A361A3690EA943F01C -:1003F0001003A3614FF400533B614FF480433B6112 -:1004000002F0F0FA10A90F9802F0ECFA404606F05C -:10041000F7FE854FD9F808B041460BF40063524609 -:10042000384605930AF075FD042302223B7007212C -:1004300001231BF4004F8DF832208DF83380ADF886 -:1004400030A0BB70F97008D01220ADF830003B71BD -:100450007B71BB71F971904600E0984669480CA920 -:1004600001F092FB059B93B1022367480CA9ADF8FC -:10047000303001F089FB092301223B73BA7308F184 -:100480000103072287F80D80FA735FFA83F8636926 -:10049000664843F001036361A369DFF890A143F468 -:1004A0000073A36106F00FFB614B00240D93614BB9 -:1004B000B8F1010F0E930CBF2346802312934FF423 -:1004C000807313934FF4806314932023294615936C -:1004D00050464FF4005316930F94CDF8408011947A -:1004E000179406F0D2FADAF80030B8F1010F43F0B1 -:1004F0000103CAF80030504B98BF00215A6888BFEA -:10050000012122F4702222F4807242EA01225A6010 -:1005100099684A4A20460A4042F4602242F00202A8 -:100520009A60D96A08F1FF3221F47001D2B241EA2F -:100530000252DA62012339188A78002A5AD03A5CCA -:100540005C1C092A91F803E0E4B23B4911D9A2F1FD -:100550000A0505EB45054FF0070C0CFA05FC0EFAF1 -:1005600005FED1F80C8028EA0C0C4CEA0E05CD6093 -:100570000EE002EB42054FF0070C0CFA05FC0EFAF8 -:1005800005FED1F8108028EA0C0C4CEA0E050D612E -:10059000062B29490ED8013B03EB83034FF01F0EB6 -:1005A0000EFA03FE9A404D6B25EA0E0545EA02035A -:1005B0004B6320E00C2B0ED8073B03EB83034FF07B -:1005C0001F0E0EFA03FE9A400D6B25EA0E0545EA52 -:1005D00002030B630FE00D3B03EB83034FF01F0E91 -:1005E0000EFA03FE9A40CD6A25EA0E0545EA02039B -:1005F000CB6200E01C460430102823D023469AE743 -:100600000005FA0500080140000C014000100140FF -:100610000000014040420F000805002010E000E00B -:10062000580E002098CB0008DC0300200800024090 -:100630004C240140EC03002000240140FDF7F1FFB1 -:1006400000ED00E0A84B9A6842F480729A609A68C4 -:1006500042F001029A609A6842F008029A60996832 -:10066000A14A0807FBD4936843F0040393609E4AB1 -:10067000936813F00403FAD19168B9F8E60041F4E5 -:10068000A0019160994A50B9B2F9E83033B9B2F992 -:10069000EA30D3F1010338BF002300E0034613F032 -:1006A000010340F0898086F82C3000B207F0F6FC98 -:1006B0008F4907F047FD8D4E0546B6F9E80007F073 -:1006C000EDFC8B4907F03EFD0446B6F9EA0007F061 -:1006D000E5FC874907F036FD804628460AF048FECB -:1006E000064628460AF0B8FE074620460AF040FEB5 -:1006F000054620460AF0B0FE044640460AF038FEA1 -:10070000814640460AF0A8FE31468046484607F03A -:1007100019FD31468346404607F014FD49460590D1 -:10072000384607F00FFD41460790384607F00AFDAE -:1007300029468246484607F005FD6E490862414653 -:1007400005F1004007F0FEFC6A4A214650629462BF -:10075000079807F0F7FC0146059807F0EBFB654B9F -:100760002146D862504607F0EDFC0146584607F096 -:10077000DFFB60490863294607F1004007F0E2FC0F -:100780005C4A21465063584607F0DCFC014650465F -:1007900007F0CEFB574B21469863059807F0D2FC33 -:1007A0000146079807F0C6FB5249C8632846314600 -:1007B00007F0C8FC4F4A10644F4DDFF860912B687A -:1007C0004A4C43F00A032B60D9F800304B4E49489D -:1007D000B3F852B00023B4F8EE8094F8ED703370A3 -:1007E000436406F0F7FC002800F00781444B454ABB -:1007F000B8F1BB0F1A60444A444E5A60444ADA606A -:1008000001D9012312E0B8F1610F01D902230DE0F3 -:10081000B8F1290F01D9032308E0B8F1130F01D96A -:10082000042303E0B8F1090F07D9052386F82D301A -:100830002B6843F001032B600CE00623F6E7092F39 -:100840000ED097B1334B1B78002B40F08180002FE6 -:100850007AD01F46304B0022022F1A70EFD104E0ED -:100860002B6823F002032B60ECE7DFF888804FF061 -:1008700000094146C1F8449006F0ACFC0028E1D0E4 -:1008800006210DAB68200A4606F0C2FD9DF8373000 -:100890009DF839C003F001035B000CF0010C43EA42 -:1008A0008C0C9DF8353003F001035CEA030A09D093 -:1008B000BAF1010F02D188F8489034E0BAF1020F82 -:1008C0000BD12DE00CAB68200C21012206F0A0FD1D -:1008D0009DF8303013F00F0301D105208EE0042B7A -:1008E0001ED188F848A01EE000240140A40F00207B -:1008F00035FA8E3C080500200C0200204E02002034 -:1009000038020020F97000085F6F00081000002016 -:1009100090C1793D5D160020B6020020340200200F -:10092000012388F84830B04BB04A1A60B04A5A6088 -:10093000B04A92F84820002A14BF6E226F221A7221 -:10094000AD4B02221A707DE72B6823F002032B6067 -:100950002B680DF1600823F004032B60002308F8D6 -:100960002C3D1E200A210122434606F051FD18B1FC -:100970009DF83430482B03D02B6823F008032B60FC -:1009800094F8E2300BB19D4A137094F8E3300BB148 -:100990009B4A137094F8E4300BB19A4A13702B6899 -:1009A000990702D5904B1B689847974B914F1B684E -:1009B00098472B6813F0080F1CD00FFA8BF34FF0F9 -:1009C000640A93FBFAF94846049307F067FB049B1B -:1009D00083460AFB193000B207F060FB8B4907F031 -:1009E000B1FB0146584607F0A5FA894907F0AAFB72 -:1009F000F86405E00023FB6402E0032001F0E8FB5B -:100A0000844B4FF480425A614FF400521A614FF008 -:100A10000A0A9946D9F80C30192083F48043C9F8A2 -:100A20000C30D9F80C300AF1FF3A83F40053C9F8BE -:100A30000C3001F084FB192001F081FB1AF0FF0A51 -:100A4000DFF8D0B1E6D14FF40053CBF810304FF4BB -:100A50008043CBF81030704BDFF8E8A11B6893F9A6 -:100A60000C0007F01BFB6D4907F06CFB0AF080FCE3 -:100A70008346BAF8000007F011FB594607F062FB05 -:100A80000AF0ACFC664B1880BAF8000007F006FBD1 -:100A90000146644807F00AFC634907F007FC5A4B1B -:100AA00038655E49D86807F04DFB604907F04AFB9E -:100AB0005F4B627918605F4B5F491A705F4B01EBC7 -:100AC000C202527C7B655E4B1A60A268920644BFEC -:100AD00001221A602B681B0740F1FF804FF480430E -:100AE000C9F81430322001F02AFB002111221E2007 -:100AF00006F0B6FA012160221E2006F0B1FA642049 -:100B000001F01DFB4FF0000A404606F029FBD346DA -:100B10004FF00A0C5346022101221E200493CDF807 -:100B20000CC006F09DFA322001F009FB404606F0A9 -:100B300017FBBDF93410BDF93600049BBDF9382010 -:100B40000B448842B8BF014692449142B8BF0A465E -:100B500012F5805F8344DDF80CC00BDDD9F80C2062 -:100B6000BCF1010C82F48042C9F80C20D3D10121E0 -:100B7000059101E0002005901E200021122204931F -:100B800006F06EFA049B4FF00A0C022101221E208F -:100B90000493CDF80CC006F063FA322001F0CFFACE -:100BA000404606F0DDFABDF93410BDF93600049B6D -:100BB000BDF938205B1A8842B8BF0146C2EB0A0A69 -:100BC0009142B8BF0A4612F5805FC0EB0B0BDDF80F -:100BD0000CC039DDD9F80C20BCF1010C82F4804244 -:100BE000C9F80C20D1D131E0A40200204947000807 -:100BF000216F0008080500205D1600204E0200202D -:100C0000B60200205A160020380200208988883C4D -:100C10000000204100100140F002002035FA8E3C17 -:100C2000140300200AE81C4100401C46BD378635ED -:100C3000EC0200200005002098CB0008B40F002033 -:100C4000FC0400200000002000220592DFF8CCC147 -:100C50001846CDF80CC007F021FA0146674807F0A6 -:100C600025FB20F000403063584607F017FA014694 -:100C7000624807F01BFB20F000407063504607F00D -:100C80000DFA01465E4807F011FB20F00040B0630A -:100C9000002170221E2006F0E3F9012120221E20EF -:100CA00006F0DEF9022100221E2006F0D9F96420A8 -:100CB00001F045FA059BDDF80CC03BB94FF07E53BF -:100CC000CCF83030CCF83430CCF838304FF48043A6 -:100CD000C9F810304B4B01221A704B4E4B4BB346A8 -:100CE000336005F029FE3068494B0590FF21184616 -:100CF00016220AF00EF9002202702A68DFF814E1C9 -:100D0000012112F0020F8EF80010734604D04170DA -:100D10000321197002218170550704D519784D1CE3 -:100D20001D700325455412F00A0F0CD01A780421C7 -:100D30008154511CC9B205254554D11C0232197089 -:100D4000D2B206218154A268910604D519784D1CAF -:100D50001D70072545546179082901D00E2904D159 -:100D600019784D1C1D700B25455419784D1CEDB29A -:100D70001D700C234354530705D5264B02311970BF -:100D8000234B10215955234B12261978465494F8B9 -:100D900041614D1CEDB2002E0CBF002602F0010691 -:100DA0001D7026B102311970194913264E5596054A -:100DB00004D51A78511C1970152383541648002144 -:100DC00098220AF0A6F8144D05F1980A95F84A30D1 -:100DD000002B30D1059999464A68002603230096D6 -:100DE0000120314606F0DAF80346C8B9B9F1000F20 -:100DF00024D14FF496424FF00109EEE700406F46D0 -:100E000001C05E462C020020B8040020CC10002057 -:100E1000BF040020BE0400201804002010000020A1 -:100E2000284631464C2204930AF073F8049B2B6049 -:100E3000012385F84A304C355545C7D1B64BDBF810 -:100E40000020197A02290AD0187D022806D08D07C1 -:100E500005D400F0020000F0FF0108B10C3359681E -:100E6000AE4DA96531B9009102209268032306F0C6 -:100E700095F8A8654046002114220AF04AF86379E3 -:100E80000E2B01D0082B02D101238DF83F30A3682F -:100E9000A348C3F38041C3F340028DF83A10A1493F -:100EA0008DF83920C3F380128DF83B200968C3F315 -:100EB00040328DF83420C3F3C03200318DF8362033 -:100EC000C3F3C02218BF01218DF83720C3F30042BD -:100ED0008DF83C208DF83D1003F0010201688DF87B -:100EE000352091F8B011B4F8E000C1F380018DF81D -:100EF0003E10ADF84200B4F8DE104FF47A70ADF851 -:100F00004400D804ADF8401004D5874BB3F8DA306C -:100F1000ADF84430B1F5FA7F84BF0023ADF844301A -:100F2000B4F81A318149ADF8463094F8223185F889 -:100F30005C30002385F85D304B709DF83F30002B0E -:100F400014BF0223002302B10133794A4FF0000895 -:100F500002EB8303D3F8C830C1460593059931F8F5 -:100F600008304FF6FF718B42DAB20AD195F85D3046 -:100F700085F85F306F4B1F78162F40F03F810024BB -:100F80002EE16D4C9DF838104FEA021A544419B105 -:100F9000911E012940F20F819DF8361011B1012AEE -:100FA00000F009811B0A022B05D19DF8341000299D -:100FB00008BF002303E0012B08BF9DF835309DF8E2 -:100FC0003D1039B19DF83F1021B9A2F10801012966 -:100FD00098BF04239DF83E1031B19DF83F1019B918 -:100FE000043A032A40F2D080012B39D1FF2387F83D -:100FF000A43087F8A530A3680026E27B6068ADF8CE -:1010000030300CA9022387F8A860C7F8B4408DF8E7 -:1010100033308DF8322087F860607E66BE66FE66EB -:10102000C7F8A06087F8A66087F8A76001F0DAFC2F -:10103000414A217B52F80A00324600F079FC2046F2 -:1010400005F004F93D4B3E49C7F8B8303D4BC7F8B1 -:10105000C060C7F8BC3020460A1D03F091FBAAE02F -:10106000022B36D15FFA89F21C20424336494FF0F9 -:10107000000B8E18012086F8019086F802B086F8E1 -:101080000AB08854A168E27B6068ADF83010F46063 -:101090000CA98DF832208DF8333001F0A3FC264BDB -:1010A000217B53F80A005A4600F042FC204605F026 -:1010B000CDF8264BC6F818B03361254B2046736136 -:1010C00006F1100106F1140203F05AFB09F10109BF -:1010D00071E0032B56D19DF83A20BDF8443032B16F -:1010E00095F85E60204608214FF6FF723CE0BDF89F -:1010F000402095F85E60B2F5FA7F2FD91549204659 -:10110000B1FBF2F292B2082105F052FA05EB860625 -:10111000C6F88801104B2EE01000002008050020C2 -:1011200034020020FC040020A40F002065050020EC -:1011300098CB00080005002058DE0008CD170008F5 -:10114000C0050020A9180008B00500202D1B0008CC -:101150009D17000800127A00C9180008934920461C -:10116000B1FBF2F292B2012105F022FA05EB8606FC -:101170008F4BC6F88801C36095F85E30013385F85F -:101180005E3018E0042B16D1BDF84230874A204665 -:1011900092FBF3F20121BDF8463092B297F85D6000 -:1011A00005F006FA97F85D3007EB86060133C6F8BE -:1011B000B80187F85D3008F10208B8F11C0F7FF420 -:1011C000CDAED3E67B4E98E80F00264486E80F00AC -:1011D000794B10341A78C02C02F101021A7008D031 -:1011E0006B6D0021185903EB040807F03FF9002844 -:1011F000E8D0724EB368D9041DD418E070486E4A26 -:1012000000EBC70393F810E0D3F814C082F800E0B5 -:10121000BCF1000FEDD000247445EADA654E2301DD -:101220001E4463440FCB013486E80F00F4E7082F17 -:10123000644C28D129E0604B93F80090B9F1010F7C -:10124000F5D9614C4FF00008C84504F11004EEDAFE -:1012500054F8100C4FF07C5106F074FF4FF07C51A5 -:1012600044F8100C54F8140C06F06CFF4FF07C514D -:1012700044F8140C54F80C0C06F064FF08F1010853 -:1012800044F80C0CE0E70E2F03D1237843F0100351 -:1012900002E0237823F01003237005F0ABF84B4AEB -:1012A0004B484C494C4B02604C48C5F89C3201609D -:1012B0000023B6F81A01C5F89812A5F8A23285F8ED -:1012C000A432C5F8A822464958520233242BFAD139 -:1012D000444B1A60B3681A0740F1B680374B0022BE -:1012E00093F81831042B00F2A980DFE803F0030320 -:1012F0002A4F9300012B4FF003013B4A08D185F898 -:10130000AC12072185F8AE3285F8AD120C2308E047 -:10131000022385F8AC32002385F8AE3285F8AD1291 -:101320000723137000230093102001232F494FF44B -:10133000E13205F033FE2E4BC5F8B002C5F8B432E9 -:1013400078E001232B4A2C4900931020052305F057 -:1013500025FEC5F8B8020746B6F81A0106F09EFE4B -:10136000264906F0EFFE264906F0E2FD07F0D6F822 -:101370000023244A98500433402BFAD1224B1022E8 -:10138000C5F8B432184B381C1A7054E0009201238F -:101390004FF4E13210201D4905F000FE1C4BC5F84A -:1013A000BC02C5F8B432102242E000BF40420F0038 -:1013B000B9180008E006002034160020A40F002011 -:1013C00098CB00081A020020E8060020A40700209D -:1013D0000C040020B410002070CC0008FC00002099 -:1013E0006203002000020020D5040020B51F000881 -:1013F00039150008A0860100C9200008CDCCCC3FDB -:101400000000B0441C010020ED1500085120000828 -:10141000DD150008009201234FF4E1321020384915 -:1014200005F0BCFD374BC5F8C002C5F8B432082240 -:10143000354B1A70003018BF012028B9082001F080 -:101440004EFA0023C5F8B432B2682F4B12F4804F25 -:1014500004D0082119702D49C5F8B41242F20101D7 -:10146000114002F0010002F4005741B1284AC5F8CA -:10147000B4220FB108221A7008B10C221A701A781F -:10148000043A5A7000F07CFD224B18607379052BEA -:1014900003D1214B4FF4C8721A80204B4FF47A725B -:1014A0001A80237843F0080323701D4B1A7822F02A -:1014B00002021A70B3689B071ED51A4B1A4A1C46C3 -:1014C0001A6000F065FC282000F039FE069A013A07 -:1014D0000692F6D12168154B48781D780246012303 -:1014E000954203D30133082B0244F9D1104A1370FB -:1014F0008A7853430F4A138019B0BDE8F08F00BFBC -:1015000001200008C9150008D5040020191600089C -:10151000251600085C030020B802002058160020A1 -:101520005C160020D0030020A8100020CD0300206E -:101530007C000020CE0300201E4B2DE9F0431A78DA -:101540001D460AB31C4B07781E781C4B93F800C04D -:1015500002231B4A03F10108D45C344104F00F0458 -:10156000BC420CD20B2C0AD812F8039012F8088057 -:1015700002EB840209EA0C0408EB04241461023330 -:10158000102BE6D100232B7003788B420FD90C4B24 -:1015900093F8400060B10B4A890012780B44186937 -:1015A00002B1400800F5777080B2BDE8F0830020FA -:1015B000BDE8F08300010020B4070020B50700203B -:1015C000CC070020B607002007299ABF024B33F84A -:1015D00021000020704700BFDC010020024B53F8BF -:1015E0002100C0F3CF0070478401002008B5074BED -:1015F00053F8210006F04EFD054906F0A3FD05490C -:1016000006F098FC06F08AFF80B208BD1C0100209D -:101610000000203F00005C44014B33F8110070478C -:1016200062030020024B03EB4101B1F84200704716 -:10163000CC070020032810B5114B0FD8114A1268AF -:1016400094888C420AD2D2888A4207D9012202FAAF -:1016500000F093F85A20104383F85A0093F85A3058 -:101660000F2B0CD1064B002283F85A20064B998889 -:1016700008B2142802DD1439998010BD9A8010BD7B -:10168000CC070020E4080020A4070020024B9A8821 -:1016900001329A80704700BFA4070020074B1A68E8 -:1016A000074B1178B3F9040053780B4403EB830321 -:1016B0009842D4BF00200120704700BFE4080020FA -:1016C000A4070020064BB3F90400064B1B681B78E7 -:1016D00003EB83039842D4BF00200120704700BF72 -:1016E000A4070020E408002010B50446FFF7EAFF35 -:1016F000002814BF2046002000F0010010BD024B5E -:1017000001221A72704700BFA4070020014B187A0B -:10171000704700BFA4070020034BB3F90400D0F1C9 -:10172000010038BF00207047A4070020014B0022B1 -:101730009A807047A4070020016B0346C26810B569 -:10174000406941B1196C541A005D013918BF0A464D -:10175000C0B21A6410BD196A405C0131B1FBF2F4E9 -:1017600002FB1412C0B21A6210BD026B03691AB1F7 -:101770005168013B026C02E0C169026A013B881AB0 -:101780001840C0B27047436B13B190F844007047E3 -:10179000826A436AD31A58425841704710F80A3C8B -:1017A0000133DBB20A2B00F80A3C0CD910F8123CCA -:1017B00033B910F8131C044A02EB4102A2F842307C -:1017C000002300F80A3C7047CC070020334A10B5CC -:1017D000136C90681944081A40F68C239842916063 -:1017E000D060516013463CD9127893F945108A4273 -:1017F0000BD1111F082908D893F84610182901D8D1 -:10180000013103E083F8442002E0002183F8461010 -:1018100093F944108A421CD1204991F84710C1B174 -:10182000002191421E4806DA03EB8104246920F866 -:1018300011400131F5E7511E00EB410116308142A4 -:1018400003D0002421F8024FF9E716490878013047 -:10185000087083F84520002201211A7083F8471090 -:1018600010BD92F84710B9B1A0F2EF2440F2DA515E -:101870008C4208D811780B2905D80B1D0131117045 -:1018800042F8230010BD002283F847209918043243 -:101890000020302A0861F9D110BD00BF6805002082 -:1018A0000E080020E8090020024B1A6C0132114496 -:1018B0001964704768050020024B53F820301B68FC -:1018C0001980704790060020074BA1F57A7153F8F4 -:1018D00020304FF47A701A681B894B4393FBF0F366 -:1018E0009BB21380704700BF9006002038B50C688B -:1018F0000546204609F04EFB214602462868BDE811 -:10190000384009F04FBB094BDA68D10709D4DA68CF -:10191000520708D4DB6813F0100F0CBF042003201B -:101920007047012070470220704700BF002002402E -:101930007C4B70B51B78012B0CBF0325002599BB90 -:10194000048C24F001042404240C0484038B048CF0 -:101950009BB223F0F30343F0010343EA0515724BF6 -:10196000A4B2984215D003F50063984211D0B0F1AB -:10197000804F0ED0A3F5983398420AD003F58063C8 -:10198000984206D003F58063984218BF24F00A04F9 -:1019900001D124F0020444F00104224305830284AF -:1019A000038B23F00C033AE004293FD1048C5E4BF7 -:1019B00024F010042404240C0484018B048C21F4EE -:1019C00040710905090D41F480719842A4B241EAC1 -:1019D000053512D003F5006398420ED0B0F1804F68 -:1019E0000BD0A3F59833984207D003F58063984253 -:1019F00003D003F58063984207D124F0200444F01B -:101A0000100444EA021292B204E024F0A00444F06C -:101A10001004224305830284038B23F440631B04D8 -:101A20001B0C0383038B9BB2038370BD0829018CBD -:101A300037D121F480710904090C0184838B048C53 -:101A40009BB223F0F30343F0010343EA0515364B41 -:101A5000A4B2984212D003F5006398420ED0B0F1C0 -:101A6000804F0BD0A3F59833984207D003F58063DD -:101A7000984203D003F58063984207D124F40074A0 -:101A800044F4807444EA022292B204E024F4206414 -:101A900044F48074224385830284838B23F00C03F7 -:101AA00038E021F480510904090C0184838B068CF1 -:101AB00023F440731B051B0D43F4807343EA053583 -:101AC000194BB6B2984212D003F5006398420ED07B -:101AD000B0F1804F0BD0A3F59833984207D003F5AF -:101AE0008063984203D003F58063984207D126F4BF -:101AF000005646F4805646EA023292B205E047F6B6 -:101B0000FF54344044F48054224385830284838B01 -:101B100023F440631B041B0C8383838B9BB283835E -:101B200070BD00BF64050020002C014038B510F8DE -:101B30000E2C044650F8043C52B9012200F80E2C39 -:101B400020F80C1C197B18680222BDE83840EFE62B -:101B500030F80C2C20F80A1C891A89B220F8081CCD -:101B6000084A10F80F0C002502EB4002A2F84210C0 -:101B700004F80E5C1868197B2A46FFF7D9FE04F8B2 -:101B8000065C38BDCC070020CB78F0B5DA0648BF3C -:101B90008A78098803F00F0548BF154311F0FF0F3D -:101BA0001DD0046800220127974007EA0106BE42C3 -:101BB00011D197004FF00F0C0CFA07FC05FA07F74C -:101BC00024EA0C04282B44EA070401D1466102E010 -:101BD000482B08BF06610132082AE4D10460FF29BE -:101BE0001FD94468002202F108060127B74007EA1E -:101BF0000106BE4211D197004FF00F0C0CFA07FC02 -:101C000005FA07F724EA0C04282B44EA070401D15B -:101C1000466102E0482B08BF06610132082AE2D182 -:101C20004460F0BD2DE9F843564B0C460168013A7B -:101C3000D9658188A3F86010072A42D8DFE802F04E -:101C4000040A101822292F35B3F85C202280B3F83B -:101C50005E2013E0B3F85E202280B3F85C2005E03C -:101C6000B3F85C2052422280B3F85E20524205E075 -:101C7000B3F85E2052422280B3F85C206280B3F851 -:101C800060301DE0B3F85C2052422280B3F85E2041 -:101C900012E0B3F85E202280B3F85C200CE0B3F8C9 -:101CA0005C202280B3F85E2005E0B3F85E2052424B -:101CB0002280B3F85C2052426280B3F860305B420D -:101CC000A380314B1B78002B5AD1B4F9000006F0E9 -:101CD000E5F98046B4F9020006F0E0F90746B4F9E8 -:101CE000040006F0DBF9294D06462968404606F057 -:101CF00029FAE9688146384606F024FA0146484642 -:101D000006F018F9A9698146304606F01BFA01462B -:101D1000484606F00FF909F061FB696820804046EB -:101D200006F010FA29698146384606F00BFA01469A -:101D3000484606F0FFF8E9698146304606F002FAA7 -:101D40000146484606F0F6F809F048FBA9686080AD -:101D5000404606F0F7F969698046384606F0F2F920 -:101D60000146404606F0E6F8296A0746304606F086 -:101D7000E9F90146384606F0DDF809F02FFBA080AE -:101D8000BDE8F883CC0700203C0000202805002097 -:101D900010B5194B93F86220511C83F86210174953 -:101DA00002F007024878164903EB420331F810109D -:101DB000A3F8641000231846124A9A5A02331044BA -:101DC000102B80B2F8D1C00806F068F90E4906F071 -:101DD000B9F90E4906F06AFA0D4B04461B681878EB -:101DE00006F05CF90146204606F0ACF906F096FBD9 -:101DF000084B187010BD00BFCC070020DC0300208A -:101E0000EC030020300800203333534000F07F45BE -:101E1000D0030020CD030020034B1B68DA79511C4E -:101E2000D9711344187A7047B004002010B5FFF739 -:101E3000F3FF0446FFF7F0FF04EB002080B210BD73 -:101E4000F0B5137C012B29D80C255D43144C0133CC -:101E500005EB040C9CF8086030421DD02D5D1DB1CF -:101E6000012D14BF022501250E4C4E7B04EB0514F9 -:101E7000277B3740B7420FD14F686668B7420BD314 -:101E80008F68A668B74207D815709460C2F804C07E -:101E9000D16013741046F0BDDBB2D3E70020F0BD73 -:101EA0001000002030D100082DE9F0478278C67874 -:101EB0001E4BC2F1640802EB820C54425FFA88F8B0 -:101EC0004FEA4C0CC6F16409A4B203F11807A5B29D -:101ED00028B2002804DC002D14BF1546012500E0BF -:101EE000454600FB00FA6D430AFB06FA9AFBF5F53E -:101EF0004D4468434FF00A0A90FBFAF0604480B208 -:101F000058800D88B1F802A000B2C5EB0A0A00FBA8 -:101F10000AF04FF47A7A90FBFAF0054423F8025F56 -:101F20000A34BB42A4B2D2D1BDE8F087AA03002094 -:101F300010B544780078002303FB03F1193961439D -:101F400001F6C4115943414340F6C41291FBF2F12A -:101F5000034A22F813100133072BEDD110BD00BF47 -:101F60008C03002010B5044C2068FFF7E1FF2068C7 -:101F70000249BDE8104097E7880300207410002054 -:101F800010B5094A094913688C6812689342F8D160 -:101F9000074A106811684FF47A725043001BB0FB77 -:101FA000F1F002FB030010BDA00F002010E000E0E4 -:101FB0001005002038B5104C0123054684F8403048 -:101FC000FFF7DEFF636F41F28832C31A9342A367C3 -:101FD00084BF002384F87C3094F87C30EDB20F2B62 -:101FE0006067E55403D1054B01221A7038BD024ADF -:101FF000013382F87C3038BDCC070020000100207E -:1020000010B50446FFF7BCFF0E4B41F28831D3F800 -:102010008020C3F88000821A8A42C3F8842084BFDB -:10202000002283F8882093F88830074A142BD45470 -:1020300003D1064B01221A7010BD024A013382F807 -:10204000883010BDCC070020C5010020C40100204D -:1020500010B50446FFF794FF174AD2F88C30C2F847 -:102060008C00C31AB3F57A6F84BF002382F89030D6 -:1020700092F8903023B9A82C1CD110490B7006E0BF -:10208000022B02D10E490C7001E0242B01D80D491E -:10209000CC540133DBB282F89030094A12785200F6 -:1020A0000532934206D1044B002283F89020034B63 -:1020B00001221A7010BD00BFCC0700205C01002077 -:1020C000820100205D01002038B50446FFF758FF6B -:1020D000124B40F6C411D3F89420C3F89400821A2E -:1020E0008A4284BF002283F8982093F898200AB986 -:1020F0000F2C11D10A480021017052B1094D182A44 -:10210000154405F8014C04D1012283F8981002709F -:1021100038BD013283F8982038BD00BFCC070020BD -:10212000010100200201002038B50446FFF728FF16 -:102130000546FFF725FF401BA042FAD338BD10B576 -:1021400004462CB14FF47A70FFF7EEFF013CF8E73C -:1021500010BD2DE9F04106460F4690460025EBB232 -:10216000434512D20024E3B2B34209D2084B3846A9 -:10217000DA68013482F40052DA60FFF7E0FFF2E738 -:102180003C20FFF7DCFF0135E9E7BDE8F08100BF47 -:10219000001001400B490B7813F0010F03F004020B -:1021A0000AD072B9980707D443F004030B70064BAA -:1021B0001A88064B1A8070471AB90220FF210122A3 -:1021C000C7E770475C16002030030020C6030020DC -:1021D00040F2DB1568430C4C08B54FF48043636153 -:1021E0004FF400532361851EE368284683F480433F -:1021F000E360E36883F40053E360FFF7A0FF192076 -:10220000FFF79DFFF0E700BF0010014008B503682D -:102210001B68984708BD064B10B504462146186850 -:10222000FFF7F4FF034B1B689A7954409C7110BD73 -:10223000B4040020B004002038B5044624200D4624 -:10224000FFF7E9FF4D20FFF7E6FF002C084C0CBF1D -:102250003E202120FFF7DFFF2368002228469A71E5 -:10226000FFF7D9FF236893F84900BDE83840D2E76B -:10227000B004002001460020DEE7F8B50E4E0F4CFA -:102280000F4DC1B20746306884F89910FFF7BEFFC2 -:102290002B6894F899109A7930684A409A71C7F37C -:1022A000072184F89910FFF7B1FF2B6894F8991073 -:1022B0009A794A409A71F8BDB4040020CC070020F6 -:1022C000B0040020F8B51B4D1B4C1C4F0646C1B294 -:1022D000286884F89A10FFF799FF3B6894F89A10E1 -:1022E0009A7928684A409A71C6F3072184F89A10AF -:1022F000FFF78CFF3B6894F89A109A7928684A4057 -:102300009A71C6F3074184F89A10FFF77FFF3B6884 -:1023100094F89A109A7928684A409A71310E84F894 -:102320009A10FFF773FF3B6894F89A109A794A4025 -:102330009A71F8BDB4040020CC070020B00400203E -:1023400010B5441E14F8011F21B1034B1868FFF7A4 -:102350005DFFF7E710BD00BF60050020014B186866 -:1023600054E700BF20090020054B1B6803EBC000A9 -:1023700090F9063019420CBF01204FF0FF30704732 -:10238000E80800200A4B1A6802EBC002D379FF2B41 -:1023900007D008490978994203D9074A32F813004F -:1023A00004E00728D4BF908840F2DC5000B27047A8 -:1023B000E8080020D5040020620300202DE9F04F3A -:1023C0000C68836889B0D0F800A0D0F80480064675 -:1023D000204603938B4608F0CBFF0746204609F0C2 -:1023E0003BF8DBF804408146204608F0C1FF054673 -:1023F000204609F031F8DBF8082004461046019227 -:1024000008F0B6FF019A8346104609F025F83946D0 -:102410000290584605F096FE39460490029805F061 -:1024200091FE59460590484605F08CFE02990690AB -:10243000484605F087FE29460790584605F082FE7B -:102440000146504605F07EFE21468346069805F07B -:1024500079FE0146059805F06DFD0146404605F000 -:1024600071FE0146584605F065FD214683460498F5 -:1024700005F068FE0146079805F05AFD01460398ED -:1024800005F060FE0146584605F054FD30600299A3 -:1024900005F1004005F056FE0146504605F052FE9B -:1024A00021468346079805F04DFE0146049805F045 -:1024B0003FFD0146404605F045FE0146584605F001 -:1024C00039FD21468346059805F03CFE01460698F5 -:1024D00005F030FD0146039805F034FE01465846EC -:1024E00005F028FD21467060504605F02BFE294678 -:1024F000044609F1004005F025FE0146404605F07E -:1025000021FE0146204605F015FD394604462846C1 -:1025100005F018FE0146039805F014FE014620461A -:1025200005F008FDB06009B0BDE8F08F2DE9F84F67 -:102530002E4E04463768384608F01AFF05463846DE -:1025400008F08AFF76688046304608F011FF83461F -:10255000304608F081FFD4F80490064629464846E4 -:1025600005F0F0FDA76882464146384605F0EAFDD1 -:102570000146504605F0DCFC21688246584605F0CD -:10258000E1FD41460446484605F0DCFD314605F0D4 -:10259000D9FD0146204605F0CDFC314604463846BB -:1025A00005F0D0FD294605F0CDFD0146204605F099 -:1025B000C1FC0146504608F0DDFF0D4905F0C2FDA3 -:1025C0000C4905F073FE0C4B196805F0B3FC0B4980 -:1025D00005F06CFE08F002FF83B21A0444BF00F558 -:1025E000B4739BB218B2BDE8F88F00BF1803002087 -:1025F0000000E144DB0F4940540500200000204169 -:10260000034B1A78510744BF22F004021A70704736 -:102610005C16002070B5FFF755F838B3144C237AD8 -:102620000BB9A38070BD134D2E78C6F38000FFF761 -:102630005BF890B1104B46F002061A680F4B5189B7 -:102640002E7019805189598052899A800C4A1268DB -:102650005288DA80E3880133E380FFF71FF810B96E -:102660002B785B0702D4BDE87040C9E770BD00BF9E -:10267000A40700205C160020A007002062030020B1 -:10268000E40800202DE9F04102780346202A00F1F9 -:102690000100F9D0092AF7D02D2A02D10346414D75 -:1026A00004E02B2A08BF03464FF07E551E46002447 -:1026B000334616F8012BA2F13007F9B209290DD8DB -:1026C0003949204605F03EFD0446384605F0E6FC53 -:1026D0000146204605F02EFC0446E9E72E2A17D1D4 -:1026E000314F334616F8010B3038C2B2092A0FD8E1 -:1026F00005F0D4FC394605F0D9FD0146204605F029 -:1027000019FC29490446384605F01CFD0746E8E750 -:102710001A7802F0DF02452A38D15A782D2A02D1E0 -:102720000233012604E02B2A14BF013302330026B2 -:10273000013B002713F8012F303AD1B2092903D801 -:102740000A2101FB0727F5E7B7F59A7F28BF4FF469 -:102750009A77B8464FF07E51B8F1070F07D908466F -:10276000124905F0EFFCA8F108080146F4E707F06C -:10277000070737B108460C4905F0E4FC013F014664 -:10278000F7E72EB1204605F091FD04E04FF07E51B1 -:10279000204605F0D7FC0146284605F0D3FCBDE8ED -:1027A000F08100BF000080BF0000204120BCBE4C73 -:1027B000F0B50124B0FBF4F58D4201D34C43F9E7A9 -:1027C0000026DCB1B0FBF4F504FB1500B4FBF1F41A -:1027D0001EB9002D01DC002CF3D1092D03F10107F6 -:1027E0005FFA85FC04DD002A0CBF5725372500E081 -:1027F000302565441D7001363B46E2E71C70F0BD94 -:10280000F0B50124B0FBF4F58D4201D34C43F9E758 -:102810000026DCB1B0FBF4F504FB1500B4FBF1F4C9 -:102820001EB9002D01DC002CF3D1092D03F10107A5 -:102830005FFA85FC04DD002A0CBF5725372500E030 -:10284000302565441D7001363B46E2E71C70F0BD43 -:1028500070B50646B6FBF2F40846154614B120469C -:10286000FFF7F6FF05FB1464024B1B5D00F8013B0C -:1028700070BD00BF38DF00082DE9F041069C002B39 -:1028800006460F460CBF4FF020084FF03008234695 -:1028900013F8011B09B9154603E0002AFBDD013AD4 -:1028A000F6E7002D04DD30464146B847013DF8E724 -:1028B00014F8011B11B13046B847F9E7BDE8F081C3 -:1028C00080EAE073A3EBE0738B4206DB002801DDB6 -:1028D000401A704702D00844704700207047034BED -:1028E0009A6822EA00009860704700BFA40F002099 -:1028F0002DE9F041038A87890446BFB20D461F4087 -:10290000002F36D0B7FA87F34FF00042DA40D243B7 -:1029100091B21B3B21821740042BF1D8DFE803F072 -:10292000221F1C1903006B6A33B103F1FF38002327 -:102930001FFA88F86B6203E0B4F82C801FFA88F85D -:102940002E6A002EDCD033683046414698477668C0 -:10295000F7E72868A18E08E06868218F05E0A8687D -:10296000A18F02E0E868B4F84010036889B2984784 -:10297000C6E7BDE8F0810C4B800A98420CD003D822 -:10298000B0F5801F0ED00BE0084B984206D04933BB -:10299000984205D1002070470220704703207047FD -:1029A000FE20704701207047010010000200100057 -:1029B000044B53F820301BB107289CBF1B681980BB -:1029C000704700BFC006002010B5054C00202188CC -:1029D000FFF7EEFF61880120BDE81040E8E700BF87 -:1029E000620000202DE9F0410F88002347FA03F22E -:1029F000D2072BD58A7803F0070512F0100F18BF05 -:102A000091F803C002F00F0618BF46EA0C06AD00AD -:102A10004FF00F0C0CFA05FC06FA05F5DC0850F82F -:102A20002480282A28EA0C0C45EA0C0540F824509A -:102A300005D101229A40C46824EA020205E0482A2E -:102A400004D101229A40C4682243C2600133102B92 -:102A5000CCD1BDE8F08100BF08B503F057FB00F012 -:102A600087FDBDE808400F2014210122FFF771BB4C -:102A7000A04A2DE9F04F13689F4903F59C439F4DF1 -:102A800020330B60AB6885B013F4807F174604D009 -:102A90009B4B1B681B681B699847AB6842F201049B -:102AA0001C405CB9974E337873B1954B1B681B681B -:102AB0001B68984703F00EFC347005E0924B1A78BF -:102AC00001321A7003F006FCAB68DA0405D58F4BAF -:102AD0001B68DB0701D4FFF793FD8D4B3C6818683A -:102AE000037C83B18B4A013B32F91300A0F57A7065 -:102AF000B0F57A7FA8BF4FF47A7020EAE07005F055 -:102B0000CDFA85492FE0AA68170435D57E4A516869 -:102B1000611A002930DB04F59C41203151607F4966 -:102B20004E797F4931F81660417CB6B296FBF1F0E0 -:102B3000117A013101F00F0111720A4450721846E6 -:102B4000784A9A5C01331044102B80B2F8D100B25D -:102B500090FBF3F000B26428A8BF642020EAE07084 -:102B600005F09CFA704905F0A1FB704905F0EAFAFE -:102B700005F0D4FC6E4B1880AB68DE0510D56D4BAC -:102B80009C426D4C08D923681B681B6A984718B98A -:102B900023681B685B6A984723681B685B699847D2 -:102BA000AA68564BD404B5F8DC100AD55948B3F8D6 -:102BB0001A31B0F90620581A82420ADD19448A42B5 -:102BC00005E05449B3F81C31B1F906209A42C0F22D -:102BD000C1830122002395F823A195F82411B5F8AB -:102BE0001C41B5F81E619B464A4F4FEA9B0BF85EAD -:102BF0000233A042C4BF6BF07F0B5FFA8BFBB04285 -:102C0000B8BF4BF0400B082BEED13F4C637E5B45C9 -:102C100004D1A37EF92B03D8013300E00023A3766F -:102C2000464B84F819B093F80080384F9946B8F1B4 -:102C3000000F14D13B68D80707D582B9404B1B78E9 -:102C4000DB070CD5FFF7A6FA09E03D4B1B785E07C2 -:102C500005D511B1FFF7D4FC01E0002AFAD0A37E1C -:102C60002949142B374E40F0A280354B1AF1000A47 -:102C70001B7818BF4FF0010A03F0040303F0FF02B2 -:102C800093B1B8F1000F00F09280BBF15F0F02D159 -:102C9000FFF7B6FC8BE0BAF1000F00F08880BBF1C3 -:102CA0007D0F40F08480F3E7BBF1570F0BD1264B2B -:102CB0004FF47A721A80254B1B6813F0080376D103 -:102CC000234A138073E0AB68580749D5BBF15A0F0C -:102CD00046D1204B187818B11A7001221E4B54E0CF -:102CE000CA7E1E4B82F00102CA760AB104224CE071 -:102CF00006224AE05016002004020020A40F002003 -:102D000000020020F80000206808002004040020D1 -:102D1000FC0000206203002000007A44DC03002055 -:102D2000EC030020710800200000C84200C07F446E -:102D3000D8040020404B4C00B00700204C0000207D -:102D40005C16002034020020581600200C020020DF -:102D500030030020E5020020E7020020E602002008 -:102D6000BBF15D0F00F09C82BBF15B0F00F09A821B -:102D7000BBF15E0F0BD1032295E2BBF1A70F40F030 -:102D8000B282AE4B1A7842F004021A700FE0BBF127 -:102D9000560F01D1FFF760FE99F80030002B00F0CC -:102DA0009982BBF16F0F40F08E82FFF7F3F9AB68A9 -:102DB0005B0732D5E37EA3B1A14B1B78580710D532 -:102DC000A048A14BB0F90620B3F81C319A4208DDA7 -:102DD0003B6813F0010304D19C4A322111809C4AC4 -:102DE000D3763B68D9030AD59A4B1A782AB99A4AFE -:102DF000127812B9954A3221118001220CE0964BCB -:102E00001A7852B18E4A127802F0040202F0FF01E1 -:102E10001AB91970914B01221A70D6F8009000234C -:102E200009F1750A3B6009F1770698460AF1020339 -:102E300003EB080113F808204B7816F8010C9A42AE -:102E40000AD2314602F080FA30B116F8023C012273 -:102E50009A403B6813433B6008F10408B8F1A00FA7 -:102E600006F10406E2D17E4B1B7843B13B68DFF8E4 -:102E7000088213F0020F7B4E40F0A18196E109F227 -:102E80001512019209F58B769846019A16F8010CF5 -:102E9000531C03EB080113F808204B789A4229D2FF -:102EA000314602F051FA28B396F802C030796E4BE1 -:102EB0000CF1FF3C4FF00C090CEB4C0C09FB00F93A -:102EC0009C44634B96F803B003F11C0A0AEB09011A -:102ED0004A6862450ED000220AF809B08A600122D1 -:102EE00002FA00F093F84C20C1F804C022EA000076 -:102EF00083F84C0008F10608B8F1480F06F1060601 -:102F0000C3D15A4B5A4A1E68D2F800A0DFF86C8130 -:102F10004FF000099B46D8F80030002B00F03D81AF -:102F20001978002900F03981D8F80420C2EB0A0290 -:102F3000002A0CDB0AF5FA72C8F80420012202FA12 -:102F400009F294F84C0020EA020284F84C2018F8A8 -:102F5000040C5A780430C0B2002A40F0E580394AA7 -:102F600032F910000190B5F81A01019A00F1C80C6D -:102F7000624501DD9B7814E0019AC838824202DA8A -:102F80009B785B420DE0012303FA09F394F84C208F -:102F900022EA030384F84C300AF5FA73C8F80430C7 -:102FA000FBE094F84C2042FA09F2D20700F1F580D8 -:102FB000002B304ACCBF02200120013910700A29B1 -:102FC00000F2E380DFE801F0060F1B28315C6E8021 -:102FD000929CA60032781344FA2BA8BFFA2323EA66 -:102FE000E373337007E072781344642BA8BF642343 -:102FF00023EAE37373703046FEF79AFFC5E0F27878 -:1030000030461344642BA8BF642323EAE373F370B0 -:10301000216DFEF749FFB8E032791344642BA8BF55 -:10302000642323EAE3733371AFE072791344642BB2 -:10303000A8BF642323EAE3737371A6E01A02002099 -:103040005C16002062030020A40F0020CC020020A8 -:1030500068080020E4020020E5020020E7020020CA -:103060005B160020C403002050D100088803002014 -:10307000A00F0020E60200200C020020880800209B -:10308000616D4A781A44C82AA8BFC82222EAE272AF -:103090004A700A781344C82BA8BFC82323EAE373F5 -:1030A0000B7072E0616DCA7A1A44C82AA8BFC822A0 -:1030B00022EAE272CA728A7A1344C82BA8BFC823D4 -:1030C00023EAE3738B7260E0616D4A7D1A44C82A7B -:1030D000A8BFC82222EAE2724A750A7D1344C82BAF -:1030E000A8BFC82323EAE3730B754EE0626D9178A5 -:1030F0000B44C82BA8BFC82323EAE373937044E0B2 -:10310000626D117B0B44C82BA8BFC82323EAE3736D -:1031100013733AE0626D917D0B44C82BA8BFC8239E -:1031200023EAE373937530E0012A2ED19B784FF4A4 -:10313000966292FBF3F38F4A32F91000B0F5617F8B -:1031400005DB40F633029042B8BF024601E04FF47F -:103150006172A2F5617292FBF3F3DBB2864A581CEE -:103160000C29107011D194F858209A420DD0042BDC -:10317000824A28BF02230A2184F8583001FB032326 -:103180000633CBF80030FEF7EDFE012303FA09F316 -:1031900094F84C20134384F84C3009F10109B9F13B -:1031A000040F08F10C087FF4B6AE5FE6AB68D805F3 -:1031B00014D5734B1B681B689B68984770B1D8F88F -:1031C00000309B070AD5338813F001020CD16D49FA -:1031D00043F00103E26522660B8006E0338801229A -:1031E00023F00103338000E000223B68590710D52B -:1031F0007AB1328822F0010102F0020289B292B261 -:10320000318052B9E26522665E4A41F002011180C6 -:1032100003E0328822F00202328032885A4912F0EA -:10322000030F4FF4804014BF48610861D8F80010C4 -:1032300011F00A0F21D0DF0609D554070AD442F055 -:1032400004023280514A1188514A118002E022F072 -:10325000040232809806328806D5510607D44949BF -:1032600042F040020A8002E022F0400232805A0618 -:1032700003D5464A1188474A118013F4006F3388FA -:1032800014BF43F4807323F4807333806B79082B6D -:1032900001D00E2B6AD1338823F04003338065E0E0 -:1032A000012200E002225FFA82F808F1FF3385F87C -:1032B0006C3602F02BFF00F05BF902202821424619 -:1032C000FEF747FF73E5BAF1000F03D0BBF17E0FA5 -:1032D0003FF46BADBBF1970F7FF44FAD2E4B4FF426 -:1032E000C8721A8063E50023BBF1BB0F039301D1C1 -:1032F000022304E0BBF1B70F04D14FF6FE73ADF823 -:103300000E300CE0BBF1BE0F01D1022305E0BBF192 -:10331000BD0F7FF44CAD4FF6FE73ADF80C30336843 -:10332000BDF80C10B3F854200A44A3F85420BDF89B -:103330000E10B3F856200A44A3F8562002F0E6FE19 -:1033400000F016F90F2014210122FEF702FF0023DE -:10335000A3762CE5114B00220021DA651A665A6625 -:103360009A66DA6619675967996733E405B0BDE86C -:10337000F08F00BF62030020E60200200C16002040 -:10338000B0070020C40300200010014030030020DB -:10339000DA040020C6030020B802002068080020DC -:1033A00000230E49DAB2595C4F2903D001330A2BAE -:1033B000F7D11A460A4B83F82821002283F82921E5 -:1033C0004FF4E132C3F82C21C3F83021C3F8342183 -:1033D000C3F83821522283F83C2170475DDF000892 -:1033E000A40F002007B5064B06480093064B074A7A -:1033F0001968074B02F055FD03B05DF804FB00BFF0 -:1034000091DD000867DF0008840000207CDD0008F3 -:1034100088DD000810B50446204607F0BBFD10F01B -:10342000FF0F06D10C4B0D481978BDE8104002F093 -:1034300038BD204607F003FE02280CD8064B0A22AE -:103440001870074B074C02FB0030074B0630186022 -:10345000FEF788FDE0E710BDC008002083DF00080C -:103460000C160020B9E1000888030020234B70B53A -:1034700019684FF47A73B1FBF3F1214B21481A78A4 -:10348000214B224D1B7802F00CFD214B214819687D -:10349000214B2E68B1FBF3F102F003FD00241F4B1A -:1034A000E2B253F8221049B1012303FA02F2324288 -:1034B00002D01B4802F0F5FC0134F0E72A689207BD -:1034C0000DD5184A1848127803EB8203196A02F0E6 -:1034D000E8FC164B197A11B1154802F0E2FC1548C8 -:1034E000FEF72EFFBDE87040134B14481A88144BAA -:1034F00092B219884FF4D26302F0D3BCA00F00201F -:10350000CD03002094DF00087C0000200C02002086 -:1035100080000020D2DF000840420F0074D1000874 -:10352000F0DF00085D160020F4DF0008A402002090 -:10353000FEDF0008D5E50008BC04002002E000081A -:103540006003002010B50748FEF7FAFE0024064B82 -:1035500006481A19E15852680C3402F0A2FCD82C23 -:10356000F5D110BD34E00008C0D100084AE00008E1 -:103570002DE9F84302F0A8FD10B90A20FEF728FE55 -:10358000A64D4FF4D2622846A54907F0B9FC95F83C -:103590006C364FF4DA72022B84BF002385F86C3648 -:1035A00095F86C369F4E02FB035303F5A87393F80E -:1035B00050203360022A84BF002283F8502093F801 -:1035C0005030994A13700A2202FB0353974A03F2C0 -:1035D0006E631360AB6842F201021A403AB944F2DA -:1035E00008021A401AB98D4A43F400539360AB683D -:1035F000DB0703D54FF40050FFF771F9AB685F04A8 -:1036000009D50820FFF76BF94FF40050FFF767F971 -:103610000120FFF764F9AB681C0706D54FF4005092 -:10362000FFF75DF90120FFF75AF9AB6898040ED552 -:103630004FF40040FFF753F94FF40060FFF74FF9E4 -:103640004FF48030FFF74BF94020FFF748F9784CF2 -:10365000784B27461C6003F06FF9774B04F1180292 -:1036600001201A6003F008F90146012002F0F4FC81 -:10367000002849D0022003F0FFF80146022002F0A2 -:10368000EBFC002840D0202003F0F6F80146202073 -:1036900002F0E2FCAB68190601D5002834D01020F6 -:1036A00003F0EAF80146102002F0D6FCAB681A07D6 -:1036B00000D548B3042003F0DFF80146042002F0EF -:1036C000CBFC30B9082003F0D7F80146082002F0FF -:1036D000C3FCAB685B0503D400231A46194609E016 -:1036E0000028F9D110E079B90121C00708D40C33C2 -:1036F000182B0BD051481844007A8407F5D5F2E70F -:103700000132D2B2022AF2D9FFF74AFEFEF72AFCB2 -:103710004B494C4B366819604B4B06F10409C3F812 -:10372000009006F1750200238846D15C39B9D018A3 -:103730008478C078844202D2444B197002E004338A -:10374000A02BF2D1424A434B1A603278424B012AF5 -:1037500003D0022A03D0414A02E0414A00E0414A34 -:10376000414C1A6006F5D3732360404B00229A80C7 -:103770003F4B404A06F5D771136006F5B37262609D -:10378000A3F12202A2602E333B4A236106F5D873CF -:103790001160A361C4F80C806761B5F8F00004F013 -:1037A00079FC2062B5F8F20004F074FC96F8583009 -:1037B00004F11C02237796F874306062637795F801 -:1037C0002531C4F82C9084F828302C4BC4F838806C -:1037D0001A602B4B06F160021A6006F16403236342 -:1037E00006F25D136363B6F8620104F057FC01460C -:1037F000244804F05BFD244904F0A4FC234B244935 -:103800001860F06D04F09EFC01464FF07C5004F00F -:103810004DFD204B1860BDE8F88300BFA40F0020C9 -:1038200000F8000834020020C008002088030020AF -:10383000B4100020FC000020B8040020100000207C -:1038400074100020B8080020BC0800204C000020A4 -:10385000981000205002002074000020F949000850 -:103860005D4C0008D54D0008E4080020A4070020A6 -:103870009C100020BC02002004050020F002002063 -:103880004C030020000061444C3D0F44F80400202C -:10389000DB0F49403C03002010B50446204607F0EA -:1038A00079FB10F0FF0F07D10B4B0C4893F86C1607 -:1038B000BDE8104002F0F5BA204607F0C0FB022830 -:1038C00008D8054B064C83F86C0602F01FFCFFF786 -:1038D0004FFEE3E710BD00BFA40F002087DF000804 -:1038E000B9E100082DE9F04F7F4985B0054607F0A2 -:1038F00019FB7E49002828460CBF0124072407F045 -:1039000011FB7B490028284608BF022407F00AFB68 -:10391000002808BF0424E10740F1B380754802F095 -:10392000C0FA0020FFF75EFD734F744802F0B9FA49 -:10393000734802F0B6FA7A79724B734803EB82034C -:10394000D3F8201102F0ADFA3869002104F08EFDA1 -:1039500000285CD13D460646D5F81080002140463F -:1039600004F084FD00284ED1013668483146D5F870 -:1039700014B0D5F818A0D5F81C9002F092FA404681 -:10398000002104F07DFD10B1614802F08AFA694619 -:10399000404602F0F7FF01465E4802F082FA5846C0 -:1039A000002104F06DFD10B1594802F07AFA694621 -:1039B000584602F0E7FF0146564802F072FA5046B8 -:1039C000002104F05DFD10B1514802F06AFA694629 -:1039D000504602F0D7FF01464E4802F062FA4846D0 -:1039E000002104F04DFD10B1494802F05AFA694631 -:1039F000484602F0C7FF0146474802F052FA0C2E33 -:103A000005F11005A8D14548711C02F04AFA444856 -:103A100002F047FA434DD7F8088055F8041F19B152 -:103A2000414802F03EFAF8E70D46404B53F8256056 -:103A300056B10123AB4013EA080F03D03C4831468E -:103A400002F02FFA0135F0E73A4802F02AFA31463F -:103A50007B1893F8103104AA1344374A8A5C013169 -:103A6000082903F8102CF3D10023344869468DF857 -:103A7000083002F016FA324802F013FA402002F041 -:103A8000D7F9A2071AD52F4802F00BFA2E4802F0F8 -:103A900008FA2E48FFF700FF2D4802F002FA2B48E3 -:103AA00002F0B8F82B4802F0FCF9284802F026F999 -:103AB000234802F0F6F9802002F0BAF963070FD527 -:103AC000254802F0EEF9254802F0EBF91F48FFF710 -:103AD000A1FC1B4802F0E5F94FF4807002F0A8F950 -:103AE00005B0BDE8F08F00BF52E00008C9EC000847 -:103AF00059E000085FE00008A40F00206DE0000816 -:103B00007FE0000874D100088BE0000896E0000810 -:103B100088E10008FBDF00084DE000089EE0000897 -:103B2000B0E00008F0D20008C0E00008F4D20008BD -:103B3000CEE00008DBE0000841E50008E7E000080F -:103B4000D5E50008F0E0000803E10008B9E100084D -:103B500011E100081BE100082AE100083BE1000830 -:103B60002DE9F047784B86B01A789A46DFF8EC9149 -:103B7000BAB901238AF80030744BD9F8002059688B -:103B8000914204D019690C33914218BF00230221DD -:103B900059726F4B6F48DA63FEF7D2FB6E48FEF73F -:103BA000CFFBD9F8000003685B689847002800F055 -:103BB000C7806A4B664C186803689B689847092859 -:103BC000014601D03F2853D14FF00008266C644FC6 -:103BD00045462EB163483968324607F0E3F910B91B -:103BE000B84605B93D46604B0C379F42F1D3EDB165 -:103BF000D5F800E0D8F800C0236C55481EF80370D3 -:103C00001CF80310B94211D15A1C51B92D2B08D8F8 -:103C1000026403442027024483F8447082F844106D -:103C200004E0234483F844702264E5E7236C0BB17D -:103C3000454512D04D48FEF783FB454509D855F858 -:103C40000C0BFEF77DFBD9F800000921FEF7DEFA28 -:103C5000F3E74148FEF774FB0026236C9E42A0D296 -:103C6000404BD9F80000995DFEF7D0FA0136F4E731 -:103C7000236C33B904283DD104F1440002F0D6FB93 -:103C80005EE00C2801D13A4886E70A2901D00D29C7 -:103C90004CD13848FEF754FB236CE218002382F81D -:103CA000443094F84420232A17D00493324B2D4EED -:103CB000009303A82A4912220C23039607F0C3F9A4 -:103CC000054638B1006807F065F90130AB6830444B -:103CD000984702E02948FEF733FB224800213022B2 -:103CE00007F017F9002323649AF80030002B7FF4C3 -:103CF00055AF25E00C28C6D07F2903D151E72F2BE3 -:103D00003FF64FAFA1F12002D2B25E2A3FF649AF93 -:103D100013B920293FF445AF5A1C2264D9F800009A -:103D20001C4484F84410FEF771FA3AE77F29E6D183 -:103D3000013B23640022234483F8442010482EE7EB -:103D400006B0BDE8F08700BF5B1600201000002021 -:103D5000E40800204DE1000885E10008600500202E -:103D6000C0D100082809002098D200088AE1000884 -:103D70008FE10008D5E50008ED1800089AE1000879 -:103D8000B6E100082DE9F04FBB4ABC4C85B0106885 -:103D9000516802AB03C3DFF8089300214FF4D262ED -:103DA000204607F0B6F804F5A873C9F80030B44B04 -:103DB0000025DFF8F0B21D7004F26E63CBF800301E -:103DC00003236371A3604FF41673A4F8F030FA2351 -:103DD000A4F8F2302A23A4F8EE304FF4FA73A4F8D2 -:103DE000F630202384F8F4306E2384F804312B233A -:103DF00084F80531212384F806314FF4C873A4F800 -:103E0000083140F24C43A4F81C3140F26C73A4F822 -:103E10001E31192384F8253140F27E43A4F8D030B6 -:103E200040F23A73A4F8D2304FF47A73A4F8D43045 -:103E300040F27E53A4F8D63040F2EA53A4F8D830CA -:103E400040F2B45301273226552240F2DC514FF0A4 -:103E50001E0AA4F8DA304FF47A532270A4F81A112B -:103E6000A4F8DE3084F8EC7084F821A184F8247181 -:103E700084F82771A4F8DC60A4F8E0608DE80600FF -:103E8000FFF78EFA40F6AC53A381D9F800304FF01B -:103E900028081720A573187683F80EA083F80FA0C2 -:103EA00058761D7083F8048083F805800B20019AF2 -:103EB0001872142058721875502098776420D8779B -:103EC0004FF0080E782083F813E05873DFF8D8C15C -:103ED0006C484FF00E0E9A7183F80AE02D224FF0D5 -:103EE0005A0E4FF00A0A1A74DE715A7783F80BE003 -:103EF000DA7583F821709D765D74DD769D741D778B -:103F000083F815A083F80C80C3F824C0D863186424 -:103F10004FF08240D8624FF07C5098635A48C3F803 -:103F200028C05864594A5A48DFF880C100991A637A -:103F30005A639864C3F84CC084F86EE64FF0410EA3 -:103F400084F87066A4F8761684F86FE684F87256E2 -:103F500084F8735684F8715684F874569A664D4AFC -:103F60000421DA664C4A83F858101521D86583F885 -:103F70007470A3F85450A3F85650A3F8525083F825 -:103F8000608083F8618083F864101A67434802F008 -:103F90005BFCD9F800604FF44873A6F86231C8237F -:103FA00086F8A7314FF49663A6F8A83140F2D933CA -:103FB000A6F8AA3140F6430386F86071A6F8AC3142 -:103FC00086F85D5186F85E5186F85F8186F8645107 -:103FD00086F8A6A133465F464FF47F72A3F86621A8 -:103FE0004FF4FA62A3F8682102A940F2DC52A3F868 -:103FF0006A214A5D013583F86C21082D4FF0FF02DC -:1040000083F86D2103F10803E6D1012386F8AE3170 -:1040100086F8AF3186F8B0310023E2181033002162 -:10402000C02B164D1161F8D1314605F541704FF4A2 -:10403000DA7206F065FF314605F597604FF4DA72E3 -:1040400006F05EFF3B6805F5CF625968186803C249 -:10405000198922F8021B1968C5F88216596851603F -:104060001B891381012385F85433022385F8083511 -:1040700005B0BDE8F08F00BF44D30008A40F0020B6 -:10408000C00800208FC2753DCDCC4C3D9A99193F98 -:104090000000A040F6287C3F3D0A773FBAE10008C7 -:1040A000340200208803002000002040000040402F -:1040B00008B50548FEF744F9FFF764FE02F026F85C -:1040C000BDE8084002F0DFB8C3E100082DE9F04F79 -:1040D000AE4E85B03778032F14D9AD4BAD48B3F948 -:1040E0000410B0F904200029B8BF49426FF06303FF -:1040F0005B1A9A4204DB01F164039342A8BF1346A2 -:1041000083801FE0012F1DD8A34BA44C1B78013BDB -:10411000142B00F2DF81DFE813F09100DD01DD01F7 -:1041200068009F00DD01DD012F01DD01DD01DD0102 -:10413000DD01DD01BD00DD01DD01DD01DD01DD01B0 -:104140009F01B601924B9649B3F806A0914B0968BE -:10415000B3F80280B3F80090B3F904B0914C029127 -:104160000025BD4204F11004CED20FFA8AF003F00C -:1041700095FF54F8101C03F0E5FF03460FFA88F092 -:10418000019303F08BFF54F8081C03F0DBFF019B45 -:104190000146184603F0CEFE03460FFA89F001935C -:1041A00003F07CFF54F80C1C03F0CCFF019B01468C -:1041B000184603F0BFFE029A034692F900000193ED -:1041C00040420BFB00F003F069FF54F8041C03F0BD -:1041D000B9FF019B0146184603F0ACFE04F078F9E4 -:1041E000714B23F815000135BBE702210420FEF7CF -:1041F000BBF8684D0121AF8878431FFA80F804208E -:10420000FEF7B2F86D8800FB05801FFA80F80420E5 -:10421000FEF7B8F84044208102210520FEF7A4F8FB -:104220007843012187B20520FEF79EF800FB057058 -:1042300087B20520FEF7A6F838440BE005200121DF -:10424000FEF792F8534B9D88684385B20520FEF730 -:1042500099F8284460813DE1544B00201D68FEF729 -:1042600091F8DFF8608195F90630B8F9022032271D -:10427000534393FBF7F3184420800120FEF782F8A4 -:1042800095F90E30B8F90020534393FBF7F7384403 -:1042900060801FE1464B1B7813F0040F454B02D1A1 -:1042A0001B689B880BE01968394A0B88B2F9062015 -:1042B00049889A4203DB9142B4BF0B461346E3811F -:1042C000E289394B394F1A803B4B1B681D7845B347 -:1042D0000220FEF757F83A68B2F91030518A984236 -:1042E00003DB0BB29842B8BF0346344909684889DA -:1042F000C3EB000E274B0FFA8EFED9880FFA81FC14 -:10430000F44501DA0D4401E001DD4D1BDD8092F939 -:104310001620B3F906305343642293FBF2F318449A -:10432000A080274B1B88DB050CD5194B1A88D7F8C2 -:104330000090E28022819A88184F62815B88032571 -:10434000A38101E0134BF1E709EBC50393F90630B4 -:10435000B7F90680284608FB03F8642398FBF3F8B6 -:10436000A7F80680FEF70EF801354044072DF880C7 -:1043700007F10207E8D1ADE00D4B1B7813F0040FF5 -:104380000C4B21D11B689B882AE000BF341600200B -:104390009A03002058090020000500206200002038 -:1043A00004050020E006002036160020E808002062 -:1043B0005C160020F0080020F4080020F808002017 -:1043C000C4030020200300201968AD4A0B88B2F90D -:1043D000062049889A4203DB9142B4BF0B4613463C -:1043E000E381E289A74BA84D1A80A84B03201B88C4 -:1043F0000121DF0503D5FDF7B7FFA14F02E0FDF76F -:10440000B3FFA34FB7F80280022100FB08F01FFAA8 -:1044100080F90320FDF7A8FF3F88012100FB0790EA -:10442000E8800420FDF7A0FF00FB08F002211FFA3E -:1044300080F80420FDF798FF00FB07802881032007 -:10444000FDF7A0FFE3881844E0800420FDF79AFF01 -:104450002389184420813DE001210420FDF784FFD9 -:104460008B4D6F88784387B204202781FDF78AFF40 -:104470003844208101210520FDF776FF2D8868430F -:1044800085B26581E2E6824B0325B3F80490984635 -:1044900028460221FDF768FF00FB09F0012187B2E1 -:1044A0002846FDF761FFC5F106035B0838F81330B5 -:1044B00000FB037087B224F815702846FDF762FFF1 -:1044C000384424F815000135072DE1D16C4BDA880A -:1044D0006C4B1A806F4DDFF8E491AB6813F0200F3E -:1044E00034D00020FDF74EFF208080460120FDF7EC -:1044F00049FF694B644F1B6860801A0626D5674BDD -:104500001B681B7813F0020F654B23D0D9F800C04D -:10451000B3F900109CF90E209CF906C0B3F90230E3 -:104520004A43CCF1000C03FB0CF3322192FBF1F275 -:104530006FF0310C92B293FBFCFC9444E04493FB8B -:10454000F1F1A7F800800A4410447880D9F80010EF -:10455000002319E0D9F80010B3F902C091F9062040 -:10456000B3F900300CFB02FC32229CFBF2FCE0446D -:10457000A7F8008091F90E104B4393FBF2F2E3E7AA -:10458000E2520233102B0CD0E05E31F9232001EB14 -:10459000830790427F88F3DB3AB28242A8BF02468B -:1045A000EEE73E4B1B681B785B0704D43549347833 -:1045B000088801231BE03B4B00241F780423043FA1 -:1045C000FFB25FFA87F84FFA88F2D4420BD4364A2A -:1045D00003F10109381932F813105FFA89F9C0B2F2 -:1045E000FEF7E6F94B460134042CECD1DEE7A3429A -:1045F00008D231F9132000B28242A8BF104680B21F -:104600000133F4E7294B4FEA44081A68AB6803F416 -:1046100080550395244D03F01009254BB5F906602C -:10462000244D1B782F68244D03F00403DBB2D5F82A -:1046300000C002930023434562D0B2F802A004B246 -:10464000544505DD0F4CC0EB0A0A1D5B55441D5354 -:10465000039D0C4C002D33D07D8931F903A0AE426F -:10466000CBBFBCF802509588B2F802B0BCF800B0DD -:10467000AA4503DBDA45B4BF55465D46E55238E04E -:104680009A0300203616002062000020C403002098 -:1046900058090020A40F002004040020FC0800207A -:1046A000200300206705002062030020F00800209E -:1046B0005C160020F8080020EC080020E808002024 -:1046C00031F903A01588B2F802B0AA4503DBDA4538 -:1046D000B4BF55465D46E55204EB030ABC89A642C9 -:1046E00007DAB9F1000F01D1148800E09488AAF824 -:1046F0000040029C14B9044C1C5BCC5202339AE774 -:1047000005B0BDE8F08F00BFDC0400200C4B07B5FE -:104710001B68196819B10B4A9069014391619A8825 -:104720009868ADF8042002228DF8072004220DEBD2 -:1047300002018DF80620FEF755F903B05DF804FB81 -:104740004C0500200010024010B50A4C23681BB134 -:10475000FFF7DCFF00232360074B1B7813B1012B0D -:1047600003D010BD4FF4006201E04FF48052034BC0 -:104770001A8010BD4C0500205005002000000020CC -:10478000F8B50468054620460E461746FEF7F3F8CE -:10479000032845D82B7B9B089AB246B94FF0020CF0 -:1047A0000CFA03F3A18989B221EA0303A3810A2148 -:1047B00001FB00211B4B43F82160043143F82170B9 -:1047C00046B12A7B0225920805FA02F2A1890A4322 -:1047D00092B2A281282202FB003000F12002EFF306 -:1047E0001286502383F312880023C1180D6915B176 -:1047F00015600A6904320433102BF6D100231360CC -:10480000F3B283F31188036A23B1A3899BB243F007 -:10481000010304E0A38923F001031B041B0CA38103 -:10482000F8BD00BF580E002070B5046D4279A38911 -:1048300002F0040123F400531B041B0C0546866898 -:1048400086B0A38101F0FF0021B14FF480604FF4E6 -:10485000005100E0014612F0010F14BF04230023B1 -:1048600012F0020F1CBF43F008039BB212F0080FB6 -:10487000228A18BF0C2392B222F4405211432182A3 -:10488000A28992B222F4B05222F00C0210430343E8 -:104890009BB2A381A38A01A823F440731B041B0CC1 -:1048A000A38202F087F91949049A039B8C4208BF3E -:1048B0001346A2891921594312B2002AB4BF7600C7 -:1048C000B600B1FBF6F16423B1FBF3F2120110095B -:1048D00003FB1011A08900B2002806DAC9003231AA -:1048E000B1FBF3F303F0070305E009013231B1FB3B -:1048F000F3F303F00F031A4392B22B6D22819A89CE -:1049000092B242F400529A8106B070BD0038014064 -:10491000417189E7816087E730B51049104A0C780A -:10492000104B84B19C6815680444A54214D31268E6 -:1049300000209A600C4A0870117809B10139117091 -:1049400001221A7330BD98681468C830844203D3BA -:104950001268012008709A6030BD00BF1104002069 -:10496000A00F002058090020E602002037B51D4D99 -:104970008DF807306B7B8DF8062002AA8DF80400B5 -:104980008DF805101A4412F8042C443AD2B20F2ABA -:1049900009D81549022B31F8124008D894B12046A5 -:1049A000FFF7BAFF0EE0022B4FF0C804F7D90F4B08 -:1049B0001A68AB68121B934204D20A4A002353734D -:1049C0000B4A13702B7B012B00D04CB96B7B022B55 -:1049D00002D8044A01335373064A00232B73137021 -:1049E00003B030BD580900204CD30008A00F0020B0 -:1049F000E6020020110400202DE9F04F8BB009934E -:104A00008A4B0792B3F90220B3F90030002AB8BFED -:104A10005242002BB8BF5B429A42B8BF1A46844B41 -:104A200003921B88814603F00302069203F0020200 -:104A300003F0010392B205930023089219461E4623 -:104A4000184604931F461A46069C002C41D0022AA1 -:104A50003FD0764C079F0D5F7C426D00A54203DB83 -:104A60003C46A542B8BF2C46724DDDF824A031F972 -:104A700005C03AF90150CCEB040404EB050C99F89D -:104A80000750642405FB0CF595FBF4F599F81B40E1 -:104A90006FF004076743BD4205DB04EB8404A542C5 -:104AA000B4BF2F462746644D5C59644442F2107CE3 -:104AB0006445A8BF6446DFF898C16445B8BF644642 -:104AC0005C5199F811506C4324130494069C012CFA -:104AD0003BD05A4D55486D5E594C85EAE576A6EBBC -:104AE000E576B6F5206F085E19F802C053F8048029 -:104AF0001DDC022A15D05026464396FBFCFC0426FA -:104B000095FBF6F5C5EB0C0CE0444E4EB8F57A5F1C -:104B1000A8BF4FF47A58B045ACBF44F80380E650C4 -:104B200007E080EAE076A6EBE076642EE3DD002580 -:104B3000E550434C1E597D2496FBF4F609EB020424 -:104B4000A47A6643402496FBF4F6089CB4B1022A8A -:104B500068D0DDF80CA0DDF810B00AFB00F40AFB09 -:104B600006F8CAF5FA7505FB074405FB0B854FF4FB -:104B7000FA7C94FBFCF495FBFCF506E0059C002C0C -:104B800050D0022A4ED0049D3C46DFF8B0C04FF012 -:104B9000040B31F80CC00FFA8CF898FBFBFADFF825 -:104BA000B4B012F80BB00BFB0AFA6FF04F0B9AFB84 -:104BB000FBFAA244CDF804A0DFF89CA0042431F94C -:104BC0000AB021F80AC0CBEB08080AF1080C98FBE0 -:104BD000F4F80AF114041C5953F80CB00AF1140A41 -:104BE000A34453F80C40C34443F80A40164CDDF884 -:104BF00004A0145D013204FB0BFB20249BFBF4FB9F -:104C0000CBEB050B114DDA44032A43F80C8021F855 -:104C100005A003F1040301F102017FF415AF0BB00D -:104C2000BDE8F08F35460446AFE700BF9A03002089 -:104C3000C403002020030020C408002054030020E7 -:104C4000CC08002080C1FFFFA803002058090020E5 -:104C5000F0D8FFFFA2030020680900202DE9F04FE3 -:104C600089B00793524B0291B3F904300192039338 -:104C7000504B06461B8803F0010103F002039BB270 -:104C800004934D4B0691B3F800A04FF6FF714FEA25 -:104C90001A13B1FBF3F1002305911D461946022DAD -:104CA00008D1029FDDF80CC07C791B340CFB04F4A6 -:104CB000641129E03E4C019A31F9048057424FEAD1 -:104CC0004804BC4203DB1746BC42B8BF27463B4CF6 -:104CD000DDF81CC00C5F3F1B3CF901403A19069CF3 -:104CE0007CB9029C277907F11B0408FB04F4049F9C -:104CF00024114FB190F811C00CFB02F704EB2724EC -:104D000002E0C479544324112D4FDFF8C48031F9F7 -:104D100007C004279CFBF7FCCCEB040C0AFB0CF44B -:104D200096F80AB053F80870E4120BFB0474254F90 -:104D3000B4F5001FA8BF4FF40014BC42B8BF3C46F6 -:104D4000214F10F80590DA5943F8084043F807C09E -:104D5000C2EB0C0809FB0CF9DDF814C001350CFBA3 -:104D600008F807F10C0C1837DA5953F80CB04FEA71 -:104D7000A818934453F80C20C344DA51377D032D0F -:104D800007FB0BF74FEA272707EBE91707EB64341C -:104D90000E4F43F80C80CC5306F1010601F10201DD -:104DA00003F104037FF47BAF09B0BDE8F08F00BFCF -:104DB0009A030020C4030020600300202003002089 -:104DC000540300200000E0FF88090020580900205B -:104DD000CC0800202DE9F04F89B00793714B814634 -:104DE00018880492039103F055F96F4903F0AAF96A -:104DF000029002994FF07E5003F058FA002406907A -:104E00004E462546A046B8F1020F684B0BD10399D8 -:104E1000B3F904004A790A32504303F03FF9644978 -:104E200003F044FA35E0049A5F5F53429F4203DB8C -:104E300013469F42B8BF3B465E4AAA5E9B1A079A3A -:104E4000505F184403F02AF95B4903F02FFA5B4BDB -:104E50008346B3F800A01AF0010F04D0D9F844102B -:104E600003F070F915E0039B18791430784303F0D0 -:104E700015F94F4903F01AFA1AF0020F074609D044 -:104E8000D9F84810584603F05DF90146384603F05A -:104E900051F807464A4BDFF84CB1585F03F0FEF873 -:104EA000484BD96803F04EF982465146384603F024 -:104EB0003FF8316A074603F045F9029905903846F4 -:104EC00003F040F9F16A03F03DF954F80B1003F0D8 -:104ED00031F83D49074603F0D3FA30B938463B492B -:104EE00003F0ECFA10B1394F00E0374F4BF8047083 -:104EF000DFF8F4B0504654F80B1003F019F844F8FA -:104F00000BA0069903F01EF90BF10C03E2580BF10C -:104F1000180B54F80B10824610460192009303F0D0 -:104F200009F8514603F006F8019A009B44F80B205B -:104F300044F803A0264903F0B9F9B16B03F002F974 -:104F40002449824603F09CFA38B95046224903F0BE -:104F5000B5FA20B1DFF880A001E0DFF878A005986D -:104F6000394602F0E7FF514602F0E2FF06F036FA5A -:104F70001A4BB0F57A7FA8BF4FF47A709842B8BF49 -:104F8000184608F10108164BB8F1030FE85204F176 -:104F9000040405F1020506F104067FF434AF09B0FC -:104FA000BDE8F08F60030020BD3786359A030020EE -:104FB000000048422003002000002041C4030020DC -:104FC000540300203802002000007AC300007A4316 -:104FD00000004040000096C30000964318FCFFFF0D -:104FE00058090020D8080020AC090020F0B5934CE7 -:104FF000934A23689D8AADB2E9B211F0010F36D011 -:10500000198821F400610904090C1980198889B2F2 -:1050100041F480611980002182F86810894908787C -:105020008949B8B192F8690018B988480078FF2812 -:1050300010D1012082F8690085480078022804D147 -:10504000188880B240F400601880097841F00101AE -:10505000198216E1097801F0FE0119827B4B1B7859 -:10506000FF2B00F00E81FF2382F8683009E18F07E3 -:1050700040D5BFF35F8F76490878C0B2012816D1BA -:10508000704D2D789DB192F8695085B1198821F441 -:1050900080610904090C1980BFF35F8F198B19888F -:1050A00082F86A0089B241F4007119801DE0188B02 -:1050B000BFF35F8F087802280CD16248007848B1AE -:1050C00092F8690030B1198821F480610904090C53 -:1050D0001980D0E00978032907D15A49097821B10C -:1050E00092F86910002940F0C680998889B241F48D -:1050F0008061C5E04E0764D5012182F86A105149EC -:10510000097800293ED092F8691000293AD0504918 -:1051100092F8680009784F4D022919881FD921F4A7 -:1051200080610904090C19801F8A2E68C1B2FFB280 -:1051300040B23754188880B240F4007018808B1C3D -:1051400082F86830236828681D8A013149B2EDB2BF -:105150004554998889B241F4806199802CE089B2E4 -:1051600041F4007119801E8A2D68C1B2F6B240B2B6 -:105170002E541B8A481C40B2DBB203312B5482F8F8 -:10518000681019E092F8691011B93349097851B1E2 -:10519000198889B241F40071198092F8683001339E -:1051A00082F8683008E0198889B241F4807119806A -:1051B000234B012183F8691021680B88D805FCD4A2 -:1051C0005FE001F0400101F0FF06214809B32149E9 -:1051D000B3F810C00F6892F868105FFA8CFCCDB27B -:1051E0006E1C49B2F6B207F801C082F86860077811 -:1051F00076B2F11C8F4205D1998821F480610904AF -:10520000090C99800378B3423BD1023582F868508B -:1052100037E0290635D592F868104DB26F1C1FD0C3 -:105220000E4E01313668C9B2755D82F86810EDB274 -:105230001D82007849B2884223D11CE0500E002024 -:1052400068090020430E0020400E0020410E00207F -:105250004C0E0020480E0020420E0020440E00207C -:10526000144982F868600978C9B21982124909782C -:1052700009B9017829B9998821F480610904090CD8 -:1052800099800E4B92F9681018780D4B421C914290 -:105290000FD1002283F8692093F86A3033B1226875 -:1052A000938823F440731B041B0C9380054B00224E -:1052B0001A70F0BD410E0020430E00204C0E00205D -:1052C000680900204D0E002070B50E4620211546BD -:1052D00005F053FE0446B8B1441C204605F0AFFE6D -:1052E000B0F5617F05DB40F634039842A8BF18464D -:1052F00001E04FF461701923A0F5617090FBF3F0A9 -:1053000030702B7801332B702046202105F035FEBC -:105310000446B8B1441C204605F091FEB0F5617F0B -:1053200005DB40F634039842A8BF184601E04FF46D -:1053300061701923A0F5617090FBF3F070702B7809 -:1053400001332B70204670BD104B043033F9103000 -:10535000B3F5617F05DB40F633029342A8BF1346E5 -:1053600001E04FF4617308781922504300F2833052 -:10537000984208DA4878504300F283309842B4BF2C -:105380000020012070470020704700BF620300200A -:105390000D4B0278D9684378C943C1F30221C1F1AA -:1053A000040103FA01F1094B0901C9B21A4482F858 -:1053B000001302780120510902F01F0200FA02F2E4 -:1053C00043F82120704700BF00ED00E000E100E05D -:1053D000F8B5074605F0DEFD044638B91A4B1B4800 -:1053E0005A791B4B013A53F8221028E038461949E4 -:1053F000224605F0D7FD60B91748FCF7A1FF174C0E -:1054000054F8041F19B1164800F04BFDF8E7154891 -:1054100005E000250E4B53F8256026B91248BDE87B -:10542000F840FCF78DBF38463146224605F0BAFDFC -:1054300001350028EED1044B0C485D713146BDE8C2 -:10544000F84000F02EBD00BFA40F002056E5000874 -:1054500098D200085FE300086AE5000894D20008CB -:10546000F0DF0008D5E500087DE5000892E50008BA -:1054700037B582880446836810060D4606D529494B -:105480004FF4DA7091F86C1600FB0133D10504D5A6 -:1054900025490A20097800FB013302F03F02042A63 -:1054A00012D006D8012A0DD0022A2FD193F900106C -:1054B0002DE0102A0AD0202A0AD0082A26D1B3F9D2 -:1054C000001024E0197822E0198820E019681EE015 -:1054D0006946186801F056FA0146144800F0E1FCEC -:1054E000F5B1E06802F0DAFD694601F04BFA0146D9 -:1054F0000F4800F0D6FC206902F0D0FD694601F0AB -:1055000041FA01460A4800F0CCFC09E000210948B4 -:1055100000F0C7FC25B10848E168226900F0C1FC31 -:1055200003B030BDA40F0020C0080020FBDF00083E -:10553000FADF0008A8E50008A4E500082DE9F0411D -:10554000002407462546104B3946E65804EB03086D -:10555000304605F05BFD58B10C48314600F0A1FC27 -:1055600040460021FFF784FF094800F09AFC01350E -:105570001434B4F5166FE6D125B90648BDE8F041FC -:10558000FCF7DEBEBDE8F0811CD400087BE8000813 -:10559000D5E50008ABE500082DE9F74F044605F016 -:1055A000F9FC054620B1012818D123782A2B15D102 -:1055B0005548FCF7C5FE0024544B5548E618E15801 -:1055C00000F06FFC30462946FFF752FF1434514873 -:1055D000FCF7B6FEB4F5166FEED192E020463D2101 -:1055E00005F0CBFC002800F08780034613F8012C5F -:1055F000202A01D1013BF9E7451C2846C4EB030AE8 -:1056000005F01DFD83462846FDF73CF800260546BB -:1056100014237343DFF8F49053F8097003EB09087F -:10562000384605F0B7FC03461A4620463946019332 -:1056300005F0B8FC019B002855D15FFA8AF29A4226 -:1056400051D1D8F80C0002F029FD0146284602F09D -:105650002BFF002845D0D8F8100002F01FFD0146AE -:10566000284602F017FF00283BD0B8F804309B060C -:105670004FF0140303FB0696B28858BF5D4614062C -:105680002946B36806D524484FF4DA7490F86C06BE -:1056900004FB0033D00504D520480A24007804FB1D -:1056A000003302F03F02042A0BD004D8013A012A49 -:1056B0000CD819700AE0102A05D0202A05D0082A33 -:1056C00004D1198002E0196000E01D6039461448D9 -:1056D00000F0E7FB3046002103B0BDE8F04FFFF7D4 -:1056E000C7BE104803E00136782E91D10E4803B0B2 -:1056F000BDE8F04FFCF724BE204603B0BDE8F04FF4 -:105700001CE703B0BDE8F08FC3E500081CD4000817 -:105710007BE80008D5E50008A40F0020C0080020A1 -:10572000D8E50008E3E50008ABE500087FB50446CE -:1057300005F030FC082824D100231F49E25C0968E9 -:105740001144497801F00301022908BF203AE254CC -:105750000133082BF1D10025665D1848314605F06C -:105760000CFC28B101356019314605F006FC18B172 -:105770001348FCF7E5FD1CE0082DEDD1204601F0B3 -:1057800063F81048FCF7DCFD00230F4A04A91A4413 -:1057900092F810210A440949595C0133082B02F898 -:1057A0000C1CF2D10023094801A98DF80C3000F03F -:1057B00078FB04B070BD00BF8800002041E5000800 -:1057C00003E6000823E60008A40F00204DE00008CF -:1057D0002DE9F04389B0044605F0DCFBC6B2002E8B -:1057E0006CD18B48FCF7ACFD8A4C2069002102F09B -:1057F0003DFE40BB01368848314600F052FB20692F -:1058000004A901F0BFF80146844800F04AFB606932 -:1058100004A901F0B7F80146804800F042FBA069F6 -:1058200004A901F0AFF801467C4800F03AFBE069BA -:1058300004A901F0A7F80146794800F032FB0C2ECC -:1058400004F11004D1D10025764C2F462B464FF0A1 -:105850000008B04504F1100415DA184654F8101C7D -:1058600002F068FB54F80C1C8146284602F062FBEB -:1058700054F8081C0546384602F05CFB08F10108A4 -:105880004B460746E5E76848019302950397FCF706 -:1058900057FD002401ABE058644920F0004002F0BD -:1058A0000DFE634B634A0434002814BF10461846AB -:1058B000FCF746FD0C2CEDD15F4891E020465F4996 -:1058C000052205F06FFB38B9524B0022034410301B -:1058D000C0281A61F8D197E020465949042205F002 -:1058E00061FB06462046002E40D1202105F045FBF5 -:1058F000002800F08980451C284605F04BFB344603 -:105900008046504B53F824600EB94F4868E0284653 -:1059100031465FFA88F205F045FB671C20BB3D4B22 -:105920000021C2181030C02811619C46F7D1474BA6 -:10593000002403EBC702D2F804E09846BEF1000F42 -:1059400004D14348314600F0ACFA55E018F837303E -:105950009C42F6DA23010CEB0305103573440FCBA0 -:10596000013485E80F00F1E73C46CAE705F067FB24 -:10597000461E0B2E074643DC2046202105F0FDFA8B -:10598000054640B1451C2846FCF77CFE214B3F01F3 -:10599000D851012400E004462846202105F0EDFA04 -:1059A000054640B1451C2846FCF76CFE194B0134F6 -:1059B00003EB061358612846202105F0DEFA054660 -:1059C00040B1451C2846FCF75DFE124B013403EB49 -:1059D000061398612846202105F0CFFA18B91D4812 -:1059E000FCF7AEFC10E00130FCF74CFE094B032C39 -:1059F00003EB0616F061F2D11748FFF7E9FE03E06A -:105A000016480C2100F04DFA09B0BDE8F08300BF44 -:105A100040E60008A40F00206BE6000871E60008CD -:105A20004DE00008B80F002075E600080AD7233CB7 -:105A30003CE6000838E60008D5E5000884E60008E2 -:105A40008AE6000898D200087DE50008A8CB000887 -:105A50008FE600089FE60008B9E10008D9E60008D3 -:105A60002DE9F047054605F095FA324B0446D3F888 -:105A700008809A4690B93048FCF762FC2F4B53F8E7 -:105A8000241049B10123A34013EA080F02D02C4887 -:105A900000F007FA0134F1E72A4821E028462A49B4 -:105AA000224605F07FFA58B92848FCF749FC284CF3 -:105AB00054F8041F0029EFD0214800F0F2F9F7E76D -:105AC0002B7800262D2B03BF013504F1FF344FF056 -:105AD00001094FF00009194B53F8267027B91D48EA -:105AE000BDE8F047FCF72CBC28463946224605F0B5 -:105AF00059FAE8B90120B040020601D51648EFE78F -:105B0000830501D51548EBE7B9F1000F03D0FCF789 -:105B1000E6FE134804E040EA0800CAF8080011480D -:105B2000FCF70EFC39461048BDE8F04700F0B9B963 -:105B30000136D0E7A40F002001E70008F4D20008E6 -:105B4000F0DF0008D5E500085FE3000814E700086F -:105B5000F0D2000829E7000840E7000852E70008F3 -:105B600066E7000870E700084DE0000870B50446DD -:105B700005F010FA08B9204830E020461F4905F02A -:105B800083FA00242646254678B12CB1012C06D193 -:105B900005F055FA064602E005F051FA05461749A8 -:105BA0000020013405F070FAEEE70B2D05D9BDE8B1 -:105BB000704013480C2100F074B9012C08DC114B23 -:105BC000294633F915201048BDE8704000F069B946 -:105BD000A6F57A73B3F57A7F04D90C48BDE8704016 -:105BE00000F05FB90A482946324600F05AF9054BE1 -:105BF00023F8156070BD00BF79E7000888E1000850 -:105C0000B3E70008DC040020D9E70008F1E700084A -:105C100013E80008F0B585B0074605F0BBF9C0B23F -:105C2000E0B90446324B04F11C021B68192003EB57 -:105C30008203591D8D785A79454305F561759B7925 -:105C40000095C978484300F56170019021462948C4 -:105C5000013400F026F9282CE4D146E0384605F05E -:105C6000EEF927283DDC224B00F11C061B68781C4E -:105C700003EB8606202100238DF80F3005F07DF917 -:105C8000751D044658B1441C204605F0D8F9152866 -:105C900005D870719DF80F3001338DF80F30204614 -:105CA000202105F06AF9044658B1441C204605F04D -:105CB000C6F90D2805D89DF80F30687001338DF8AE -:105CC0000F302046A91C0DF10F02FFF7FDFA9DF8D9 -:105CD0000F30042B09D028460021042205F019F9C1 -:105CE00003E00548282100F0DCF805B0F0BD00BF56 -:105CF000340200202CE8000841E8000870B586B0A6 -:105D0000054605F047F9C0B208BB044606236343C5 -:105D1000444A03F58873126819201344591D4D78BD -:105D20009A7A454305F561755B7900958D786843EE -:105D300000F561700190C878029009793A480391A2 -:105D40002146013400F0ADF80C2CDFD168E0284684 -:105D500005F075F90B285FDC06267043314B00F522 -:105D600088701E68202106440023681C8DF81730B7 -:105D700005F003F9741D054658B1451C284605F089 -:105D80005EF9032805D89DF81730607101338DF84E -:105D900017302846202105F0F0F8054658B1451C7B -:105DA000284605F04CF90D2805D870719DF817307C -:105DB00001338DF817302846611C0DF11702FFF7EB -:105DC00083FA202105F0D9F8054658B1451C28462C -:105DD00005F035F90C2805D89DF81730E07001332F -:105DE0008DF817302846202105F0C7F850B1013052 -:105DF00005F025F90D2805D89DF8173020710133DD -:105E00008DF817309DF81730062B09D02046002159 -:105E1000062205F07EF803E004480C2100F041F86A -:105E200006B070BD3402002057E8000841E80008C1 -:105E300070B5064600240A4BE518AA8816420AD017 -:105E4000E158084800F02DF828460021FFF710FB24 -:105E50000548FCF775FA1434B4F5166FEBD170BD34 -:105E60001CD4000877E80008D5E50008426A10B5A0 -:105E70008469A154416A02690131B1FBF2F402FB69 -:105E800014124262426B32B11368DB0708D4BDE8DA -:105E9000104000F0E1BD036DDA6842F08002DA6084 -:105EA00010BD0FB42DE9F04F684A89B012AB1668E7 -:105EB000674A53F8045B176804939B4629780029C6 -:105EC00000F0B880252902D001353046B0E06C786A -:105ED000302C03D002354FF0000903E0AC784FF0CE -:105EE00001090335A4F13003092B4FF000081AD83B -:105EF000A4F13003DAB2092A07D80A2B13DC0A22EC -:105F000002FB083815F8014BF2E7A4F16103052BF9 -:105F100002D8A4F15703F0E7A4F14103052B02D8FE -:105F2000A4F13703E9E76C2C03BF2C78012201357B -:105F30000022632C66D006D8252C77D0582C3FD071 -:105F4000002C77D0BAE7732C63D002D8642C11D020 -:105F5000B4E7752C02D0782C32D0AFE70BF1040AED -:105F600005ACDBF800000A2112B10022234613E041 -:105F7000234620E00BF1040A05ACDBF8000072B107 -:105F8000002806DA2D238DF8143040420DF1150358 -:105F900000E023460A210022FCF732FC0DE0002835 -:105FA00006DA2D238DF8143040420DF1150300E080 -:105FB00023460A210022FCF7FBFBD34600941AE09B -:105FC0000BF1040303930DF1140ADBF80000102118 -:105FD00032B1583C624262415346FCF711FC06E084 -:105FE000B4F158035A425A415346FCF7E1FBDDF83D -:105FF0000CB0CDF800A03046394642464B46FCF77F -:106000003BFC5BE730469BF800100BF10404B847FB -:106010000AE0DBF800303046009339464246002360 -:106020000BF10404FCF728FCA34647E73046214661 -:10603000B84743E7074B186803681B69984700286F -:10604000F8D009B0BDE8F04F04B070470C0500204F -:106050000805002020090020F0B5142285B007466D -:106060000E461648002104F054FF154B00241A7AFE -:10607000E0B2013412B1511E0A40F9E71C7DD1B2E1 -:10608000013214B1611E0C40F9E7421A002A0DDDFD -:1060900093E8070001AD85E807000A4C94E8070083 -:1060A00083E8070095E8070084E80700034A3846BC -:1060B000314605B0BDE8F040FBF7C2BED409002070 -:1060C000100000201C0000200E4B1A78552A16D113 -:1060D0005A88B2F5D26F12D11A79BE2A0FD193F82D -:1060E0008C260020EF2A0CD113F8012B5040064AD1 -:1060F0009342F9D1D0F1010038BF00207047002051 -:106100007047704700F8000890FE00084A4B55227F -:106110002DE9F3411A704FF4D2625A80BE221A71EF -:10612000EF2283F88C26002283F88D2611461E4626 -:10613000B35C0132B2F5D26F81EA0301F8D13E4B74 -:106140003E4A83F88D163E4B04275A6002F188328E -:106150005A600020013F17F0FF075DD0384B342212 -:10616000384CDA60C4F309037BB1331903F1784387 -:10617000A3F57843D3F800804FF400500023019337 -:1061800000F062FD0428E5D11BE04FF4302000F060 -:106190005BFD0428DED12A4D4FF430202B6943F0FB -:1061A00002032B616C612B6943F040032B6100F00B -:1061B0004BFD2A6941F6FD73134004282B61D4D0AE -:1061C000C8E71F4D4FF400502B6943F001032B61CA -:1061D0001FFA88F3238000F037FD042812D1A31C96 -:1061E0000193019B4FEA1848A3F800804FF4005038 -:1061F00000F02AFD2B6941F6FE721A4004282A613C -:1062000006D0A7E72B6941F6FE721A402A61A1E782 -:106210000D4B04349C42A5D1094B04281A6942F065 -:1062200080021A6102D1FFF74FFF10B90A20FBF775 -:10623000CFFF02B0BDE8F081A40F00202301674525 -:106240000020024000F8000890FE000813B501226B -:1062500004460021006800F057F9236801A81A8855 -:1062600092B242F001021A80637B00228DF8043062 -:1062700001238DF805308DF806208DF80730FFF7E3 -:1062800087F802B010BD10B50848FCF759F8084B64 -:106290001C68236820461B69984718B90A20FBF739 -:1062A0004EFFF6E7034A044BDA6010BD81E80008B0 -:1062B000600500200400FA0500ED00E008B5044880 -:1062C000FCF73EF8FFF722FFBDE80840DBE700BF20 -:1062D0008DE800083F4A2DE9F84F916840F201131C -:1062E0000B4040F201118B4293460AD13A4B1A7D82 -:1062F00093F815905A75B9EB020918BF4FF00109D0 -:1063000001E04FF001094FF00008344B5FFA88F4C8 -:106310001B78A3425CD9324B324E1B68324F23B9F3 -:106320003B685B8926F814304FE03A68072C94BF2D -:1063300012F804A0A246294851469847DBF80830D5 -:106340000546DB0509D5B9F1000F06D0274B5046AD -:106350001B6829461B68DB699847A5F2EE2240F2CC -:10636000DC5392B29A4288BF3B68DBF8082088BFB2 -:106370005D8942F2010313402BB31D4B1978164B74 -:1063800001F0030202EB840293F8760003EB420271 -:10639000D5821A4620B9032915D9012183F8761030 -:1063A00002EBC403198BDD8A02EB44020D44598BC6 -:1063B0009B8B0D441D44ADB2A2F8785004232DB23E -:1063C00095FBF3F5ADB226F8145008F101089CE7EF -:1063D000BDE8F88FA40F0020D4090020D5040020C8 -:1063E000BC07002062030020FC0000200002002007 -:1063F00068080020094B30B59D68094B05F48055AD -:106400001868084B1C6800230DB1828800E0A28840 -:1064100005495A520233182BF6D130BDA40F002083 -:10642000EC080020F0080020DC04002008B5074834 -:10643000FBF786FF064A00231370064A1360064ADC -:106440001370FFF7D7FFBDE808401CE794E8000889 -:1064500028090020240900205B160020F8B500243C -:10646000224BE0B21F78B8420CD2214B33F8101007 -:10647000204B53F820301BB10B2801D8DB6898471C -:106480000134EDE71C4B9B685B0304D41B4B4FF4BA -:1064900080421A61F8BD0025194E2B46EAB2BA4275 -:1064A000F4D2726854689C4218D02046FCF763FA14 -:1064B000EFF31283502282F3128812494FF0280C16 -:1064C000A28C0CFB001092B201324262A28ADBB2B3 -:1064D00092B242F00102A28283F3118856F8043F7F -:1064E00000221B6801351A802346D7E734160020A6 -:1064F0003616002090060020A40F00200010014056 -:106500008C060020580E0020254B10B55343254A19 -:10651000254C12680139B2FBF3F20388013AA0421C -:1065200089B292B29BB212D004F50064A0420ED0A0 -:10653000B0F1804F0BD0A4F59834A04207D004F5F9 -:106540008064A04203D004F58064A04202D123F00D -:1065500070039BB2154CA04206D004F58064A042A3 -:106560001CBF23F440739BB203800F4B818598427C -:1065700002850FD003F5006398420BD003F540630A -:10658000984207D003F58063984203D003F58063F7 -:10659000984201D1002303860123838210BD00BFEE -:1065A00040420F0080000020002C014000100040FD -:1065B0002DE9F74FA24E0C46377805461146006884 -:1065C00091469B4622467B1C06F8043BFFF79CFF46 -:1065D000AB686868ADF8043018238DF8063001A95F -:1065E00002238DF80730FCF7FDF92B7B3F0106EB0A -:1065F000070A2C680C2B00F2F280DFE813F00D0084 -:10660000F000F000F0004D00F000F000F00082001B -:10661000F000F000F000B600238C8A4823F001035C -:106620001B041B0C2384218CA288238B844223F01F -:1066300073034FEA03434FEA134389B292B243F024 -:10664000700314D000F50060844210D000F5406063 -:1066500084420CD000F58060844208D000F5806050 -:10666000844204D021F0020141F0030107E021F04F -:106670000E0122F4407241F0030142F48072A280C4 -:106680002383A4F834B02184238B23F008031B0454 -:106690001B0C43F0080332E0238C6A4823F01003FC -:1066A0001B041B0C2384218CA288238B844223F49B -:1066B000E6434FEA03434FEA134389B292B243F4ED -:1066C000E04308D000F50060844204D021F02001AE -:1066D00041F0300107E021F0E00122F4406241F096 -:1066E000300142F48062A2802383A4F838B0218470 -:1066F000238B23F400631B041B0C43F400632383EC -:106700006DE0238C4F4823F480731B041B0C2384FF -:10671000218CA288A38B844223F073034FEA0343A6 -:106720004FEA134389B292B243F0700308D000F5E8 -:106730000060844204D021F4007141F4407107E00C -:1067400021F4606122F4405241F4407142F48052DD -:10675000A280A383A4F83CB02184A38B23F0080378 -:106760001B041B0C43F0080338E0B4F820C0354A82 -:106770002CF4805C4FEA0C4C4FEA1C4CA4F820C06F -:10678000B4F820C0A388B4F81C802CF4005C28F472 -:10679000E6484FEA08484FEA0C4C4FEA18484FEADF -:1067A0001C4C94429BB248F4E0484CF4405C03D04B -:1067B00002F50062944203D123F4804343F4804302 -:1067C000A380A4F81C80A4F840B0A4F820C0A38B38 -:1067D00023F400631B041B0C43F40063A383AB7B13 -:1067E00043B1B4F844306FEA43436FEA53439BB27A -:1067F000A4F8443023889BB243F0010323802B7B11 -:106800000C2B14D8DFE803F0071313130A13131328 -:106810000D131313100004F1340307E004F13803DF -:1068200004E004F13C0301E004F14003F35150465D -:10683000AAF80890CAF8044003B0BDE8F08F00BF82 -:10684000640A0020002C014070B50546441E14F86F -:10685000011F61B1064E304604F08FFB0028F6D0D0 -:10686000861B0448631B304480F81031EFE770BD8D -:1068700041E50008A40F002070B500220646284913 -:106880001301585CB04204D00132072AF7D100202E -:1068900070BD244D0B4405F1C404102E0FCB84E8C9 -:1068A0000F002B4617D007D8012E0DD0022E34D161 -:1068B0001D4B1B689B680BE0202E27D0402E2CD14F -:1068C000194B1B681B6903E0174B1B685B6820E0D2 -:1068D000C5F8C8301DE0154A1268127A042A1CD87F -:1068E000DFE802F00A0A030A0A00114AC5F8C820C4 -:1068F000C5F8CC20032206E04FF4E132C5F8C820E9 -:10690000C5F8CC20012283F8D12006E0064B1B6895 -:10691000DB68C5F8CC30204670BD064870BD00BFAE -:106920006CD30008640A0020B8040020FC0000209A -:10693000A0860100280B00200F4970B500230C78B9 -:106940001A46D8B2844205D00D7B854208BF01208B -:106950000CD100E000200C2505FB0010074D084E6F -:10696000154495F828510132755D05720133052BE8 -:1069700001D0012AE5D970BD10000020A40F00202D -:106980005DDF000830B587B005460C4603A800213E -:106990000C2204F0BEFA2846002101F08FFD20B140 -:1069A00028462A4901F0C6FA03E02846274901F0A3 -:1069B000BFFA274901F0C6FB01F08AFD054685EACA -:1069C000E570A0EBE57069460A22FBF741FF002362 -:1069D0009D420370ACBF20232D2368468DF80C30F8 -:1069E00004F0D8FA012807D130238DF80D308DF846 -:1069F0000E308DF80F300CE0022805D130238DF8D1 -:106A00000D308DF80E3004E0032804BF30238DF8DC -:106A10000D30694603A804F0A3FA03A804F0BAFAFB -:106A20000338C5B22A4603A9204604F0DDFA002344 -:106A300063552046074904F093FA03A920462944E8 -:106A400004F08EFA204607B030BD00BF6F12033A43 -:106A500000007A44C0E80008826A8169436B1144EF -:106A6000D960416A914203D98A1A5A60816204E06E -:106A700001698A1A5A6000228262002280F844204A -:106A80001A6842F001021A6070478A6810B50C6AF1 -:106A9000036814430A6923F4FF4314434A6923F04B -:106AA000700314438A691443CA6914434A6A14433D -:106AB0008A6A224313430360CB6843600B68836098 -:106AC0004B68C36010BD02684FF6FE73134003604D -:106AD0000023036043608360C3602A4B984222D046 -:106AE000294B984229D0294B984230D0284B9842C4 -:106AF00037D0284B98423ED0274B984206D153F8C6 -:106B0000682C42F4700243F8682C7047234B98427B -:106B100006D153F87C2C42F0706243F87C2C70470D -:106B20001F4B984206D153F8042C42F00F0243F851 -:106B3000042C70471B4B984206D153F8182C42F096 -:106B4000F00243F8182C7047174B984206D153F8BF -:106B50002C2C42F4706243F82C2C7047134B984253 -:106B600006D153F8402C42F4704243F8402C704751 -:106B70000F4B984205D153F8542C42F4702243F83D -:106B8000542C7047080002401C00024030000240B4 -:106B900044000240580002406C0002408000024065 -:106BA000080402401C040240300402404404024035 -:106BB000580402401F4B10B55A6802F00C02042A18 -:106BC00003D0082A04D01C4A14E01C4A126811E0C1 -:106BD0005A685968C2F38342C90302F1020201D420 -:106BE000174906E0596811F4003F1449096818BFB5 -:106BF00049084A4302605968124AC1F30311545CC0 -:106C00000168E14041605C68C4F30224145D21FA2C -:106C100004F484605C68C4F3C224145DE140C16084 -:106C20005B68C3F381331A44137CB1FBF3F1016158 -:106C300010BD00BF0010024000127A0028000020A2 -:106C400000093D004D00002010B50446FAF75BFE38 -:106C5000012806D11CB1FAF756FE013CF8E70520E1 -:106C600010BD002C08BF052010BD00BF2DE9F0416C -:106C70001D46A04B8CB09842884617465AD19E4C70 -:106C80009E4BA26023609E4B20656361C033A3616D -:106C9000C023E36023619B4BA907A364E36403F56E -:106CA000484303F154032363A3F11403D3F8D42F0F -:106CB000636342F48042C3F8D42FD3F8D02F42F05C -:106CC0000102C3F8D02F4FF002038DF803304FF4C8 -:106CD0000073ADF800304FF018038DF8023003D583 -:106CE00089486946FBF77EFE1C232A078DF802308F -:106CF00003D585486946FBF775FE4FF48063ADF810 -:106D0000003048238DF80230EB0703D57E486946F2 -:106D1000FBF768FE0E238DF804300022012301A842 -:106D20008DF805308DF806208DF80730724CFEF78F -:106D30002FFB52E0754B984240F0D880744B6F4A5D -:106D40009F601A60C022DA601A61724A18655A613F -:106D5000C0329A61704AAE079A64DA646F4BDA699E -:106D600042F40032DA615A6942F001025A614FF08E -:106D700002038DF803304FF00403ADF800304FF0FC -:106D800018038DF8023003D55F486946FBF72AFEE9 -:106D90001C232C078DF8023003D55B486946FBF7AE -:106DA00021FE0823ADF80030E8074FF048038DF8C6 -:106DB000023003D554486946FBF714FE26238DF8AC -:106DC00004300022012301A88DF805308DF806203B -:106DD0008DF80730FEF7DCFA4D4C0026012384F8CD -:106DE00044302662E661A6626662C4F82C80657152 -:106DF000A760A6712046FDF717FD15F0090F31D0E9 -:106E0000206B002826D0E36C039601934FF4805347 -:106E10000A9380230693E36805960493202309933D -:106E200063690796029308960B96FFF74CFE01A93B -:106E3000206BFFF72AFE236B1A6842F001021A60EA -:106E4000226D918A89B241F0400191825B689BB2C8 -:106E5000236407E0236D4FF6DF721A80DA6842F090 -:106E60002002DA6015F00A0F2CD0606B28B3A36CF7 -:106E7000002601934FF480530A93802306932369DD -:106E80000296049310230393059607960896099695 -:106E90000B96FFF718FE606B01A9FFF7F6FD636B19 -:106EA0001A6842F002021A605E605E60236D9A8A80 -:106EB00092B242F080029A8204E0236DDA6842F0D6 -:106EC0008002DA60236D29079A8992B242F4005257 -:106ED0009A819A8A03D592B242F0080203E022F026 -:106EE00008021204120C9A82204600E000200CB026 -:106EF000BDE8F081003801404C0F0020DCD30008D1 -:106F0000380B0020043801400008014000440040D4 -:106F1000F80E0020B80C002004440040001002408D -:106F200013B5062204466B463B21682000F070FA38 -:106F30009DF800209DF8013043EA022323809DF84C -:106F400002209DF8033043EA022363809DF8042069 -:106F50009DF8053043EA0223A38002B010BD13B5AB -:106F6000062204466B464321682000F051FA9DF842 -:106F700000209DF8013043EA022323809DF802207F -:106F80009DF8033043EA022363809DF804209DF8B6 -:106F9000053043EA0223A38002B010BD2DE9F04F73 -:106FA00087B099460746884615469DF840B0FFF7DA -:106FB00063FC02AE0446034600F1100E18685968DF -:106FC000324603C2083373451646F7D1237B0BB90B -:106FD00003950495384602A9FFF73EF8044608B920 -:106FE000002031E04368586828B1384602A922469B -:106FF000FAF726FFF2E7A36894F800A01E781EB9FE -:10700000CDF800B0124804E0012E1DD11148CDF892 -:1070100000B04B4641462A46FFF728FE03460028AB -:10702000DED00D4A067102EB8A02C2F800036268E4 -:1070300050600A4842689A4204D002690C309A4271 -:1070400018BF00204772184607B0BDE8F08F00BF98 -:107050000038014000440040380B002010000020A0 -:1070600013B5244B4000C0B283F8080302ACD3F838 -:10707000180383F8091304F8012D0021012283F875 -:107080000A23C3F80C4383F80B13C3F8104383F8A7 -:10709000142383F8152383F8161348B382889205C6 -:1070A00015D40288D4050DD447F2305201888905E1 -:1070B00002D5013AFAD113E092B1028892B242F4B9 -:1070C00080720280828892B242F44072828047F2DB -:1070D000305293F8151311B1013AFAD100E012B908 -:1070E00000F086F904E0034B93F8160380F00100EA -:1070F00002B010BD380B002010B5174C23681BB12F -:10710000FDF704FB002323606B2180226820FFF73A -:10711000A7FF6420FBF713F8192100226820FFF76E -:107120009FFF6B2103226820FFF79AFF372102227D -:107130006820FFF795FF094B1A211A786820FFF79E -:107140008FFF1B2118226820FFF78AFFBDE810403F -:1071500068201C21102283E74C0500203D00002000 -:1071600037B50622044603216B461E2000F050F975 -:107170009DF801309DF80000154D43EA002000B253 -:1071800000F08CFF296800F0DDFF01F0A1F99DF807 -:10719000033020809DF8020043EA002000B200F096 -:1071A0007DFFA96800F0CEFF01F092F99DF805304F -:1071B000A0809DF8040043EA002000B200F06EFFBA -:1071C000696800F0BFFF01F083F9608003B030BD53 -:1071D0004000002007B52320FAF7B1FF6820752191 -:1071E00001220DF1070300F013F928B19DF8070003 -:1071F000B0F168035842584103B05DF804FB00BF8A -:107200002DE9F04F1421012834BF0646012601FB69 -:1072100006F3DFF8D8A1DFF8C0B10AEB03025AF891 -:1072200003301069CBF80030694B15891E70694B2B -:10723000B2F80A80DC6989B02043546848EA05073F -:10724000D8610222276120468DF80E1003A9019310 -:10725000ADF80C708DF80F20FBF7C4FB019B4FF0CD -:1072600008099B46A268154203D10A20FAF75CFF81 -:10727000F8E70A206561FAF757FF25610A20FAF757 -:1072800053FFB9F10109EDD1C4F814800A20FAF7CF -:107290004BFF65610A20FAF747FF25610A20FAF7DC -:1072A00043FF0222C4F8108020468DF80F2003A966 -:1072B0001C228DF80E20ADF80C70FBF793FB464BAB -:1072C000464A1C689442DBF8102008D142F40012B0 -:1072D000CBF81020DBF8102022F4001207E042F473 -:1072E0008002CBF81020DBF8102022F48002CBF8CB -:1072F0001020A38803A823F440731B041B0CA38055 -:1073000023889BB243F001032380A588FFF752FC3A -:1073100025F03F050599324A2D04B1FBF2F22D0C00 -:107320001543ADB2A5802388012523F001031B047A -:107330001B0C23802B4B03A8B1FBF3F34FF4967186 -:107340004A439BB24FF47A71002B92FBF1F208BFD3 -:107350000123013292B243F400432284A3832388A1 -:107360009BB243F001032380238823F4816323F03D -:1073700002031B041B0C23804FF48043238114233E -:1073800003FB06A6737B00248DF80C308DF80D40AE -:107390008DF80E408DF80F50FDF7FAFF337B9DF806 -:1073A0000F208DF80C308DF80D408DF80E401AB17D -:1073B00003A8FDF7EDFF07E0590903F01F039D4007 -:1073C000094A203142F8215009B0BDE8F08F00BFD2 -:1073D000540E002000100240500E002000540040C7 -:1073E00040420F00804F120000E100E0F4D300089B -:1073F00008B5054B1A88013292B21A80034B1878EF -:10740000FFF7FEFE002008BDBC040020540E002043 -:1074100010B54000204CC0B220702048204C0170B4 -:10742000204800210170012020701F4C23601F4C58 -:1074300023601F4B1A701F4B1F4A107019701F4991 -:107440000868194630B383889C0515D40388DB058A -:107450000DD447F230530488A40502D5013BFAD17C -:1074600012E08BB103889BB243F48073038083885E -:107470009BB243F44073838047F23053107810B1CD -:10748000013BFBD100E013B9BDE81040B0E708783C -:1074900080F0010010BD00BF400E0020410E002012 -:1074A000430E0020420E0020480E0020440E002013 -:1074B0004C0E00204E0E00204D0E0020500E0020DD -:1074C000244A13B513681446998A89B20191019927 -:1074D00011F4706F02D0204A01211170019A12F448 -:1074E000E06F2AD01A8B9A8822F480621204120C60 -:1074F0009A80019A910520D41A8892051DD41A8881 -:10750000D0050FD51A88D105FCD41A8892B242F45E -:1075100000721A801A889205FCD4104B1878FFF775 -:107520006FFE0AE01A8892B242F400721A809A88BA -:1075300022F440721204120C9A802268938A23F477 -:1075400070631B041B0C9382054B00221A7002B05F -:1075500010BD00BF500E00204E0E0020540E002023 -:107560004D0E002001480249FBF7C2B90008004057 -:10757000D00E002001480249FBF7BAB900040040D0 -:10758000A80E00204FF080400149FBF7B1B900BFC1 -:10759000800E002001480249FBF7AAB9002C0140E7 -:1075A000580E002001480249FBF7A2B9002C014007 -:1075B000580E002038B5204CD4F8F0301D88ADB2FC -:1075C000AA0618D5D4F8CC201AB1988880B2904772 -:1075D00011E09B88D4F8BC20D4F8B410DBB28B54F3 -:1075E000D4F8BC20D4F8AC300132B2FBF3F103FB89 -:1075F0001123C4F8BC302B061DD5D4F8C820D4F80C -:10760000C4100D4B8A4210D0D3F8B800D3F8F01054 -:10761000805C0132C0B28880D3F8B010B2FBF1F0C8 -:1076200001FB1022C3F8C82038BDD3F8F030DA6867 -:1076300022F08002DA6038BD580E00200F4BD3F8DC -:1076400044211188090618D5D3F81C11D3F8180164 -:1076500081420ED0D3F80C01405C0131C0B2908061 -:10766000D3F80421B1FBF2F002FB1011C3F81C1196 -:107670007047D36823F08003D3607047580E002012 -:107680000C480D4B4FF400525A60D0F828214FF6A9 -:10769000FE7311680B401360D0F81821D0F81C312C -:1076A0009A4202D0F430FFF7D7B9012380F838317D -:1076B000704700BF580E002000000240FFF700BFD7 -:1076C000FFF7FEBEFDF792BCFDF790BC0F4B1A68AA -:1076D00042F001021A6059680D4A0A405A601A685D -:1076E00022F0847222F480321A601A6822F4802216 -:1076F0001A605A6822F4FE025A604FF41F029A6020 -:10770000044B4FF000629A60704700BF00100240C7 -:107710000000FFF800ED00E0024B1A6801321A6029 -:10772000704700BFA00F002008B5084BB3F8D80081 -:1077300093F894260023D9B2914204D2044921F847 -:1077400013000133F7E7FEF789FEFEE7A00F0020E4 -:107750003616002081F0004102E000BF83F00043B4 -:1077600030B54FEA41044FEA430594EA050F08BFDC -:1077700090EA020F1FBF54EA000C55EA020C7FEAA0 -:10778000645C7FEA655C00F0E2804FEA5454D4EB1D -:107790005555B8BF6D420CDD2C4480EA020281EAE7 -:1077A000030382EA000083EA010180EA020281EA1F -:1077B0000303362D88BF30BD11F0004F4FEA013171 -:1077C0004FF4801C4CEA113102D0404261EB410180 -:1077D00013F0004F4FEA03334CEA133302D0524206 -:1077E00063EB430394EA050F00F0A780A4F10104C2 -:1077F000D5F1200E0DDB02FA0EFC22FA05F28018FC -:1078000041F1000103FA0EF2801843FA05F35941E1 -:107810000EE0A5F120050EF1200E012A03FA0EFC60 -:1078200028BF4CF0020C43FA05F3C01851EBE3718A -:1078300001F0004507D54FF0000EDCF1000C7EEBA7 -:1078400000006EEB0101B1F5801F1BD3B1F5001FE5 -:107850000CD349085FEA30004FEA3C0C04F1010404 -:107860004FEA445212F5800F80F09A80BCF1004F2D -:1078700008BF5FEA500C50F1000041EB045141EAAF -:10788000050130BD5FEA4C0C404141EB010111F4B0 -:10789000801FA4F10104E9D191F0000F04BF01465B -:1078A0000020B1FA81F308BF2033A3F10B03B3F139 -:1078B00020020CDA0C3208DD02F1140CC2F10C02C9 -:1078C00001FA0CF021FA02F10CE002F11402D8BF27 -:1078D000C2F1200C01FA02F120FA0CFCDCBF41EAF3 -:1078E0000C019040E41AA2BF01EB0451294330BDC2 -:1078F0006FEA04041F3C1CDA0C340EDC04F114049F -:10790000C4F1200220FA04F001FA02F340EA030075 -:1079100021FA04F345EA030130BDC4F10C04C4F1BB -:10792000200220FA02F001FA04F340EA030029469B -:1079300030BD21FA04F0294630BD94F0000F83F4E5 -:10794000801306BF81F480110134013D4EE77FEAC8 -:10795000645C18BF7FEA655C29D094EA050F08BF14 -:1079600090EA020F05D054EA000C04BF19461046F5 -:1079700030BD91EA030F1EBF0021002030BD5FEA39 -:10798000545C05D14000494128BF41F0004130BD61 -:1079900014F580043CBF01F5801130BD01F00045B5 -:1079A00045F0FE4141F470014FF0000030BD7FEA28 -:1079B000645C1ABF194610467FEA655C1CBF0B4623 -:1079C000024650EA013406BF52EA033591EA030F3A -:1079D00041F4002130BD00BF90F0000F04BF002132 -:1079E000704730B54FF4806404F132044FF0000565 -:1079F0004FF0000150E700BF90F0000F04BF0021DE -:107A0000704730B54FF4806404F1320410F0004543 -:107A100048BF40424FF000013EE700BF42004FEA3E -:107A2000E2014FEA31014FEA02701FBF12F07F43BB -:107A300093F07F4F81F06051704792F0000F14BFB8 -:107A400093F07F4F704730B54FF4607401F00045FC -:107A500021F0004120E700BF50EA010208BF704753 -:107A600030B54FF000050AE050EA010208BF704748 -:107A700030B511F0004502D5404261EB41014FF4B1 -:107A8000806404F132045FEA915C3FF4DCAE4FF0B5 -:107A900003025FEADC0C18BF03325FEADC0C18BF9C -:107AA000033202EBDC02C2F1200300FA03FC20FAED -:107AB00002F001FA03FE40EA0E0021FA02F114443A -:107AC000C1E600BF70B54FF0FF0C4CF4E06C1CEA4F -:107AD00011541DBF1CEA135594EA0C0F95EA0C0FC4 -:107AE00000F0DEF82C4481EA030621EA4C5123EA37 -:107AF0004C5350EA013518BF52EA033541F4801166 -:107B000043F4801338D0A0FB02CE4FF00005E1FB18 -:107B100002E506F00042E0FB03E54FF00006E1FB62 -:107B200003569CF0000F18BF4EF0010EA4F1FF04A5 -:107B3000B6F5007F64F5407404D25FEA4E0E6D41E5 -:107B400046EB060642EAC62141EA55514FEAC520F6 -:107B500040EA5E504FEACE2EB4F1FD0C88BFBCF572 -:107B6000E06F1ED8BEF1004F08BF5FEA500E50F123 -:107B7000000041EB045170BD06F0004646EA0101E9 -:107B800040EA020081EA0301B4EB5C04C2BFD4EB1B -:107B90000C0541EA045170BD41F480114FF0000E14 -:107BA000013C00F3AB8014F1360FDEBF002001F082 -:107BB000004170BDC4F10004203C35DA0C341BDCFC -:107BC00004F11404C4F1200500FA05F320FA04F0CE -:107BD00001FA05F240EA020001F0004221F0004102 -:107BE00010EBD37021FA04F642EB06015EEA430E75 -:107BF00008BF20EAD37070BDC4F10C04C4F12005A5 -:107C000000FA04F320FA05F001FA04F240EA020057 -:107C100001F0004110EBD37041F100015EEA430E28 -:107C200008BF20EAD37070BDC4F1200500FA05F248 -:107C30004EEA020E20FA04F301FA05F243EA0203C7 -:107C400021FA04F001F0004121FA04F220EA0200D6 -:107C500000EBD3705EEA430E08BF20EAD37070BD1C -:107C600094F0000F0FD101F00046400041EB0101FC -:107C700011F4801F08BF013CF7D041EA060195F0DE -:107C8000000F18BF704703F00046520043EB030398 -:107C900013F4801F08BF013DF7D043EA0603704785 -:107CA00094EA0C0F0CEA135518BF95EA0C0F0CD090 -:107CB00050EA410618BF52EA4306D1D181EA0301D6 -:107CC00001F000414FF0000070BD50EA410606BFD0 -:107CD0001046194652EA430619D094EA0C0F02D115 -:107CE00050EA013613D195EA0C0F05D152EA03365A -:107CF0001CBF104619460AD181EA030101F0004178 -:107D000041F0FE4141F470014FF0000070BD41F0C0 -:107D1000FE4141F4780170BD70B54FF0FF0C4CF49A -:107D2000E06C1CEA11541DBF1CEA135594EA0C0FB9 -:107D300095EA0C0F00F0A7F8A4EB050481EA030E06 -:107D400052EA03354FEA013100F088804FEA0333ED -:107D50004FF0805545EA131343EA12634FEA0222BB -:107D600045EA111545EA10654FEA00260EF000417C -:107D70009D4208BF964244F1FD0404F5407402D2CE -:107D80005B084FEA3202B61A65EB03055B084FEA5F -:107D900032024FF480104FF4002CB6EB020E75EB5C -:107DA000030E22BFB61A754640EA0C005B084FEA84 -:107DB0003202B6EB020E75EB030E22BFB61A754601 -:107DC00040EA5C005B084FEA3202B6EB020E75EB4C -:107DD000030E22BFB61A754640EA9C005B084FEAC4 -:107DE0003202B6EB020E75EB030E22BFB61A7546D1 -:107DF00040EADC0055EA060E18D04FEA051545EAC0 -:107E000016754FEA06164FEAC30343EA52734FEA68 -:107E1000C2025FEA1C1CC0D111F4801F0BD141EAE1 -:107E200000014FF000004FF0004CB6E711F4801F46 -:107E300004BF01430020B4F1FD0C88BFBCF5E06F26 -:107E40003FF6AFAEB5EB030C04BFB6EB020C5FEA36 -:107E5000500C50F1000041EB045170BD0EF0004E8B -:107E60004EEA113114EB5C04C2BFD4EB0C0541EABD -:107E7000045170BD41F480114FF0000E013C90E6BA -:107E800045EA060E8DE60CEA135594EA0C0F08BF7E -:107E900095EA0C0F3FF43BAF94EA0C0F0AD150EA7D -:107EA00001347FF434AF95EA0C0F7FF425AF104610 -:107EB00019462CE795EA0C0F06D152EA03353FF438 -:107EC000FDAE1046194622E750EA410618BF52EAB5 -:107ED00043067FF4C5AE50EA41047FF40DAF52EA89 -:107EE00043057FF4EBAE12E74A0011D212F50012FF -:107EF00011D20DD56FF47873B3EB62520ED44FEA02 -:107F0000C12343F0004343EA505323FA02F0704781 -:107F10004FF00000704750EA013002D14FF0FF30BF -:107F200070474FF00000704780F0004002E000BF53 -:107F300081F0004142001FBF5FEA410392EA030F54 -:107F40007FEA226C7FEA236C6AD04FEA1262D2EB9E -:107F50001363C1BFD218414048404140B8BF5B42A3 -:107F6000192B88BF704710F0004F40F4000020F03C -:107F70007F4018BF404211F0004F41F4000121F052 -:107F80007F4118BF494292EA030F3FD0A2F101029C -:107F900041FA03FC10EB0C00C3F1200301FA03F1DA -:107FA00000F0004302D5494260EB4000B0F5000FFD -:107FB00013D3B0F1807F06D340084FEA310102F1BC -:107FC0000102FE2A51D2B1F1004F40EBC25008BF6E -:107FD00020F0010040EA03007047490040EB000038 -:107FE00010F4000FA2F10102EDD1B0FA80FCACF167 -:107FF000080CB2EB0C0200FA0CF0AABF00EBC25066 -:1080000052421843BCBFD0401843704792F0000F53 -:1080100081F4000106BF80F400000132013BB5E7A6 -:108020004FEA41037FEA226C18BF7FEA236C21D01C -:1080300092EA030F04D092F0000F08BF0846704781 -:1080400090EA010F1CBF0020704712F07F4F04D14F -:10805000400028BF40F00040704712F100723CBF62 -:1080600000F50000704700F0004343F0FE4040F48C -:10807000000070477FEA226216BF08467FEA23634A -:108080000146420206BF5FEA412390EA010F40F435 -:10809000800070474FF0000304E000BF10F0004381 -:1080A00048BF40425FEA000C08BF704743F0964368 -:1080B00001464FF000001CE050EA010208BF704783 -:1080C0004FF000030AE000BF50EA010208BF70470A -:1080D00011F0004302D5404261EB41015FEA010C1F -:1080E00002BF84460146002043F0B64308BFA3F117 -:1080F0008053A3F50003BCFA8CF2083AA3EBC253F9 -:1081000010DB01FA02FC634400FA02FCC2F1200217 -:10811000BCF1004F20FA02F243EB020008BF20F04E -:108120000100704702F1200201FA02FCC2F12002B4 -:1081300050EA4C0021FA02F243EB020008BF20EAA9 -:10814000DC7070474FF0FF0C1CEAD0521EBF1CEAD7 -:10815000D15392EA0C0F93EA0C0F6FD01A4480EAC5 -:10816000010C400218BF5FEA41211ED04FF00063AE -:1081700043EA501043EA5111A0FB01310CF00040DA -:10818000B1F5000F3EBF490041EAD3715B0040EA00 -:10819000010062F17F02FD2A1DD8B3F1004F40EBD0 -:1081A000C25008BF20F00100704790F0000F0CF0A3 -:1081B000004C08BF49024CEA502040EA51207F3A67 -:1081C000C2BFD2F1FF0340EAC250704740F4000042 -:1081D0004FF00003013A5DDC12F1190FDCBF00F033 -:1081E00000407047C2F10002410021FA02F1C2F1E1 -:1081F000200200FA02FC5FEA310040F1000053EA7D -:108200004C0308BF20EADC70704792F0000F00F0CA -:10821000004C02BF400010F4000F013AF9D040EAD0 -:108220000C0093F0000F01F0004C02BF490011F464 -:10823000000F013BF9D041EA0C018FE70CEAD15362 -:1082400092EA0C0F18BF93EA0C0F0AD030F0004CE2 -:1082500018BF31F0004CD8D180EA010000F0004096 -:10826000704790F0000F17BF90F0004F084691F054 -:10827000000F91F0004F14D092EA0C0F01D142028E -:108280000FD193EA0C0F03D14B0218BF084608D157 -:1082900080EA010000F0004040F0FE4040F40000A1 -:1082A000704740F0FE4040F4400070474FF0FF0C34 -:1082B0001CEAD0521EBF1CEAD15392EA0C0F93EA7B -:1082C0000C0F69D0A2EB030280EA010C49024FEACD -:1082D000402037D04FF0805343EA111143EA101386 -:1082E0000CF000408B4238BF5B0042F17D024FF43E -:1082F000000C8B4224BF5B1A40EA0C00B3EB510F19 -:1083000024BFA3EB510340EA5C00B3EB910F24BF01 -:10831000A3EB910340EA9C00B3EBD10F24BFA3EB86 -:10832000D10340EADC001B0118BF5FEA1C1CE0D14E -:10833000FD2A3FF650AF8B4240EBC25008BF20F001 -:10834000010070470CF0004C4CEA50207F32C2BF55 -:10835000D2F1FF0340EAC250704740F400004FF0F2 -:108360000003013A37E792F0000F00F0004C02BF23 -:10837000400010F4000F013AF9D040EA0C0093F0ED -:10838000000F01F0004C02BF490011F4000F013B47 -:10839000F9D041EA0C0195E70CEAD15392EA0C0FAF -:1083A00008D142027FF47DAF93EA0C0F7FF470AFE7 -:1083B000084676E793EA0C0F04D14B023FF44CAF2A -:1083C00008466EE730F0004C18BF31F0004CCAD1BF -:1083D00030F000427FF45CAF31F000437FF43CAFFB -:1083E0005FE700BF4FF0FF3C06E000BF4FF0010C1D -:1083F00002E000BF4FF0010C4DF804CD4FEA4002FF -:108400004FEA41037FEA226C18BF7FEA236C11D048 -:1084100001B052EA530C18BF90EA010F58BFB2EBFB -:10842000030088BFC81738BF6FEAE17018BF40F07B -:10843000010070477FEA226C02D15FEA402C05D12F -:108440007FEA236CE4D15FEA412CE1D05DF8040BB4 -:10845000704700BF844608466146FFE70FB5FFF747 -:10846000C9FF002848BF10F1000F0FBD4DF808EDFF -:10847000FFF7F4FF0CBF012000205DF808FB00BFF0 -:108480004DF808EDFFF7EAFF34BF012000205DF84A -:1084900008FB00BF4DF808EDFFF7E0FF94BF012097 -:1084A00000205DF808FB00BF4DF808EDFFF7D2FF94 -:1084B00094BF012000205DF808FB00BF4DF808EDD7 -:1084C000FFF7C8FF34BF012000205DF808FB00BFA4 -:1084D0004FEA4002B2F1FE4F0FD34FF09E03B3EBD1 -:1084E00012620DD94FEA002343F0004310F0004F11 -:1084F00023FA02F018BF404270474FF00000704767 -:1085000012F1610F01D1420205D110F0004008BF05 -:108510006FF0004070474FF00000704742000ED2ED -:10852000B2F1FE4F0BD34FF09E03B3EB126209D4AE -:108530004FEA002343F0004323FA02F070474FF064 -:108540000000704712F1610F01D1420202D14FF0D9 -:10855000FF3070474FF00000704700BF73B96AB931 -:10856000002908BF0028BCBF00204FF00041C4BF55 -:108570006FF000414FF0FF3000F03CB882B0EC46A5 -:108580002DE9005000F006F8DDF804E002B00CBC64 -:10859000704700BF2DE9704F089E14461D46804667 -:1085A000894600F029F804FB01F3A4FB00AB00FBB3 -:1085B00005329344B8EB0A0869EB0B09C6E9008958 -:1085C000BDE8708F2DE9704F089E14461D46804609 -:1085D000894600F061F900FB05F5A0FB04AB04FB44 -:1085E0000154A344B8EB0A0869EB0B09C6E90089FA -:1085F000BDE8708F704700BF00292DE9F00FC0F271 -:10860000A1800024002BC0F29880154606460F4634 -:10861000002B3FD18A4258D9B2FA82F34BB1C3F151 -:10862000200201FA03F720FA02F29D4000FA03F655 -:108630001743290CB7FBF1F201FB1277A8B200FB3C -:1086400002F34FEA164C4CEA0747BB4209D97F199F -:1086500002F1FF3C80F00581BB4240F20281023A08 -:108660002F44FF1AB7FBF1F301FB137100FB03F07A -:10867000B6B246EA0141884208D9491903F1FF37E9 -:1086800080F0F180884240F2EE80023B43EA0242F1 -:10869000002303E08B420AD900231A4610461946EC -:1086A00014B1404261EB4101BDE8F00F7047B3FAED -:1086B00083F8B8F1000F40F088808B4202D38242E9 -:1086C00000F2E28000230122E8E712B90123B3FBA4 -:1086D000F2F5B5FA85F2002A3AD17F1B280C1FFA71 -:1086E00085FC0123B7FBF0F100FB11770CFB01F2D5 -:1086F0004FEA164848EA0747BA4207D97F1901F1FD -:10870000FF3802D2BA4200F2C4804146BF1AB7FB1A -:10871000F0F200FB12700CFB02FCB6B246EA00401D -:10872000844507D9401902F1FF3702D2844500F28F -:10873000AE803A4642EA0142B0E7E443524263EB7C -:10874000430362E7404261EB41014FF0FF3459E7D8 -:108750009540C2F1200927FA09F126FA09F9974054 -:10876000280CB1FBF0F800FB18111FFA85FC0CFB7C -:1087700008F349EA07094FEA194747EA01418B42E2 -:1087800006FA02F608D9491908F1FF327AD28B426B -:1087900078D9A8F102082944C91AB1FBF0F300FB0B -:1087A00013170CFB03F21FFA89F949EA0747BA428B -:1087B00007D97F1903F1FF3160D2BA425ED9023B7B -:1087C0002F44BF1A43EA08438CE7C8F1200225FA78 -:1087D00002F103FA08FC27FA02F320FA02F207FA80 -:1087E00008F741EA0C0C4FEA1C49B3FBF9F109FB0D -:1087F00011331FFA8CFA0AFB01FB17433A0C42EAC9 -:1088000003439B4505FA08F008D913EB0C0301F16B -:10881000FF3235D29B4533D902396344CBEB030396 -:10882000B3FBF9F209FB12330AFB02FABFB247EAC3 -:108830000347BA4508D917EB0C0702F1FF331BD2E7 -:10884000BA4519D9023A674442EA0145A5FB00013D -:10885000CAEB07078F424FF000030AD305D02A4620 -:108860001CE76246FDE63B4610E706FA08F686423C -:10887000F5D26A1E002311E71A46E5E70B46A0E78A -:108880001146CBE7904687E74346424606E7023A61 -:1088900050E702392F4439E72DE9F00F1446054619 -:1088A0000E46002B43D18A4253D9B2FA82F757B110 -:1088B000C7F1200620FA06F601FA07F302FA07F4D8 -:1088C00000FA07F51E43210CB6FBF1F201FB12661C -:1088D000A0B200FB02F32F0C47EA0646B34209D9C7 -:1088E000361902F1FF3780F0FD80B34240F2FA8082 -:1088F000023A2644F61AB6FBF1F301FB136100FBC2 -:1089000003F0ADB245EA0141884208D9091903F1E3 -:10891000FF3680F0E980884240F2E680023B43EA7D -:108920000242002310461946BDE8F00F70478B4203 -:108930004CD8B3FA83F6002E4FD18B4202D3824239 -:1089400000F2DD80BDE8F00F002301221046194639 -:10895000704712B90124B4FBF2F4B4FA84F2002A8D -:1089600040F08280091B260CA7B20123B1FBF6F070 -:1089700006FB101107FB00F24FEA154C4CEA0141CF -:108980008A4207D9091900F1FF3C02D28A4200F25B -:10899000C8806046891AB1FBF6F206FB121107FB8C -:1089A00002F7ADB245EA0145AF4208D92C1902F1F0 -:1089B000FF3180F09B80A74240F29880023A42EA61 -:1089C000004210461946BDE8F00F704700231A46D2 -:1089D00010461946BDE8F00F7047C6F1200522FA8F -:1089E00005F703FA06F421FA05F301FA06FB20FA6B -:1089F00005F53C434FEA1448B3FBF8FC08FB1C3375 -:108A00001FFA84F909FB0CFA45EA0B0B4FEA1B45E8 -:108A100045EA03439A4502FA06F204D91B190CF100 -:108A2000FF356FD3AC46CAEB0303B3FBF8F508FB85 -:108A3000153309FB05F91FFA8BFB4BEA0347B945D0 -:108A400004D93F1905F1FF3362D31D4645EA0C4CAA -:108A5000ACFB0223C9EB07079F424FF000054AD346 -:108A600046D062462B465DE79440C2F1200921FAC8 -:108A700009FC914020FA09F9260CBCFBF6F806FB2C -:108A800018CCA7B207FB08F349EA01094FEA1941DC -:108A900041EA0C4C634500FA02F509D91CEB040CC1 -:108AA00008F1FF323BD2634539D9A8F10208A4444A -:108AB000C3EB0C0CBCFBF6F306FB13C107FB03F284 -:108AC0001FFA89F949EA01418A4207D9091903F1D4 -:108AD000FF3022D28A4220D9023B2144891A43EA3C -:108AE000084343E73A4605E7334618E70A4666E790 -:108AF000B0409042B5D20CF1FF32002312E733466A -:108B000032460FE79A458DD9ACF1020C23448AE72F -:108B1000B9459AD9023D274498E70346DEE79046D7 -:108B2000C6E70238214435E74FEA4102B2F1E0439B -:108B300024BFB3F5001CDCF1FE5C0DD901F0004C44 -:108B40004FEAC0024CEA5070B2F1004F40EB830094 -:108B500008BF20F00100704711F0804F21D113F1C0 -:108B60003872BCBF01F00040704741F480114FEAF9 -:108B70005252C2F11802C2F1200C10FA0CF320FA82 -:108B800002F018BF40F001004FEAC1234FEAD3239F -:108B900003FA0CFC40EA0C0023FA02F34FEA430309 -:108BA000CCE77FEA625307D150EA01331EBF4FF092 -:108BB000FE4040F44000704701F0004040F0FE40AD -:108BC00040F40000704700BF1C481D490268006067 -:108BD0008A4200F01D80002100F004B8194B5B5858 -:108BE000435004311848194B42189A42FFF4F6AF2B -:108BF000174A00F003B8002342F8043B154B9A4291 -:108C0000FFF4F9AFFEF762FD00F036F8FFF7FEBFA4 -:108C1000114E124830601248016821F07061016005 -:108C2000410201600F4C182020600F490F48086076 -:108C30000F48D0F800D0406800470000F04F0020F7 -:108C4000EFBEADDE30F4000800000020F40000208C -:108C5000F8000020701600201810024009000000E3 -:108C600004000140140C0140000C01404434434412 -:108C700000F0FF1FFFF7FEBF2DE9804893B0F7F724 -:108C800047FA914E914CD6F80880002318F0080F4F -:108C90002370374600F0E78063681B7A042B00F2EC -:108CA000E080DFE803F00303058AB100237AD9E00E -:108CB000627A864B002A00F0D48000225A7293F820 -:108CC0002020100700F1CD80D97A9A7A01F00700B0 -:108CD00042EA00225A621A7B02F03F00400140EA59 -:108CE000D1019962597B890041EA92119A7B02F085 -:108CF000010041EA8021D962D97B01F00F00C00157 -:108D000040EA52021A631A7C02F07F00000140EA36 -:108D100011115963597C490041EAD212997C01F042 -:108D2000030042EA40229A63DA7C02F01F008001CD -:108D300040EA9101D963197DC90041EA5212997D37 -:108D40001A645A7D01F0070042EA00225A64DA7D73 -:108D500002F03F00400140EAD1019964197E890088 -:108D600041EA92115A7E02F0010041EA8021D96461 -:108D7000997E01F00F00C00140EA52021A65DA7EC6 -:108D800002F07F00000140EA11115965197F490086 -:108D900041EAD212597F01F0030042EA40229A656B -:108DA0009A7F02F01F00800140EA9101D965D97FC6 -:108DB000C90041EA52121A6651E094F86420434B0C -:108DC000002A4ED0002283F8642093F86620012AFE -:108DD00047D193F88A20102A84BF102283F88A2072 -:108DE00094F88A103A4A0023D8B2884202F102026B -:108DF00035D212F8010C12F8025C40EA052535481C -:108E000040F823500133EFE794F8CC202F4B42B3C6 -:108E1000002283F8CC2093F8CD20A82A21D193F802 -:108E2000E050F5B9294901EB450393F8D00093F8D8 -:108E3000D13003EB0020FEF7CFFD1FA3D3E90023C1 -:108E4000FEF76AFF1EA3D3E90023FEF787FCFFF7B6 -:108E50004BF8214B43F825000135082DE2D10123C1 -:108E600000E00023237018F4804F08D094F80431F8 -:108E700023B1164B002283F80421012323702378A9 -:108E800043B118F4807F05D0104BD3F808311B682C -:108E90001B689847DFF844802278D8F8003032B950 -:108EA0000A4AD2F80C219A1AD243D20F00E00122CA -:108EB000B2B1F9F7DDFDB2E09A9999999999194003 -:108EC0000000000000707740A40F0020F800002090 -:108ED0006001002084010020DC01002050160020E9 -:108EE000D4F810A1A84D0AF10101C4F81011BAF18B -:108EF000000F40F09080D5F81421110740F18F80C9 -:108F0000D5F818219A1A002AC0F2898003F5C339CE -:108F100005F58E7009F1A009C5F81891FEF720F942 -:108F20009A4B05F58E7001461A78F8F77BFE95F896 -:108F3000220105F58E7110F0040F17D0C5F82491A9 -:108F40005346FA180025A2F8FE508F4ACD5A02F572 -:108F5000947E23F80E5002F5977E23F80E500233CC -:108F6000062BEED120F0040082F8220194F834217F -:108F7000854BA2B1B3F81C01B6F8FE20821AA3F803 -:108F80001C21B3F81E01B6F80021821AA3F81E2195 -:108F9000B3F82001B6F80221821AA3F82021D4F8F0 -:108FA0002431794A002B3AD07948C3EB090981452D -:108FB00002F5947502F5977019D8764BDA6882F449 -:108FC0000052DA600023CA5A35F903E017B2BE45F1 -:108FD000C4BFDFF8D4E123F80E2030F903E0BE452A -:108FE000BCBF6D4FDA530233062BECD117E00023E0 -:108FF000C2F8243135F903E0C15EFA1871444FF02C -:10900000020E734491FBFEF1062BA2F8FE10F1D183 -:10901000F9F722FD03E00229C8BFC5F81021F8F7CF -:10902000AFFFB389C8F800002BB1D4F83821821AF9 -:10903000002AFFF626AE574F4FF480427A61524F16 -:10904000184496F80580D4F84431C4F8380107F57F -:10905000A870D4F83C51CDF81080984707F5A87057 -:10906000014694F85621F8F7DDFD4C4B1B88002B88 -:1090700000F0B980D7F858314FF000081B7807F599 -:10908000AE7903934746454A1288B2F57A7F029239 -:10909000434A04D1002142F80810C9F81010414990 -:1090A000C85F52F80810014442F80810FEF7F6FFB6 -:1090B000D9F8102083460132012AC9F8102007D1BF -:1090C0000022C9F80400C9F80000C9F808202CE003 -:1090D000D9F800C061468DE80410FEF729FF009A18 -:1090E00082461046FEF7DAFF01465046FFF7DEF8EB -:1090F000DDF804C001466046FEF71CFF024611463B -:10910000C9F8040058460092FEF712FF0146504687 -:10911000FFF718F8D9F80810FEF70CFF009AC9F805 -:109120000C00C9F80020C9F808001E49029B002263 -:1091300001F1540B012B7A5227F80B20DFF85CA0C9 -:1091400044D1D9F81000012808DD0138FEF7A6FF48 -:109150000146D9F80C00FFF7A9F800E0002002F062 -:109160000BFA039B02460BB318460092FEF796FFDC -:10917000009A01461046FFF7A1F9B8B14FF47A738F -:10918000AAF800302FE000BFF80000205A16002097 -:109190007FC3C9010010014026020020581600209C -:1091A000900200204802002020020020B54A4FF41F -:1091B0007A7158F802200A2002F5FA7292FBF1F255 -:1091C0002BF807200F210122F8F7C3FF0237062FE3 -:1091D00008F1040809F114097FF455AF029F07F163 -:1091E000FF39AAF800900023A74F07F5A87207F5EA -:1091F000D271985A595A411A99520233062BF3D117 -:10920000D7F8143113F0020300F00A83D7F8B03115 -:1092100007F5DC70984707F5DC70014697F8BE212A -:10922000F8F700FDB7F8C03107F5DC78002B45D022 -:109230000022D7F8C4011346934F38F902C0B7F89B -:10924000C01107F5E47EB1F5C87F04BF00214EF8D8 -:1092500003105EF803108C4F61444EF80310043382 -:1092600000210C2B28F80210815202F10202E3D1F6 -:10927000B7F8C031012B1CD1D7F8C8314FF4C872F0 -:10928000C83393FBF2F30380D7F8CC31C83393FB98 -:10929000F2F34380D7F8D031C83393FBF2F27B4B23 -:1092A0001B88D21A8280A5F85410A5F85610F9F739 -:1092B000D3FBB4F8C031013BA4F8C031B3685A07FE -:1092C00079D5B4F8D421704B322A13D1D3F8C42104 -:1092D0001188A3F8D61151889288A3F8D811A3F861 -:1092E000DA21B5F85420A3F8DC21B5F85620A3F80C -:1092F000DE2101E0002A3CD00021D4F8C4610A46F6 -:10930000614838F901E0B0F8D43100F5F077322B3C -:1093100004BF0023BB50B8585B4B7044B8500432B4 -:1093200000200C2A28F80100705201F10201E7D157 -:10933000B3F8D421012A17D183F8ED21052283F84F -:10934000EE21B3F8D62183F8EC013280B3F8D821AE -:109350007280B3F8DA21B280B3F8DC21B3F8DE31E1 -:10936000A5F85420A5F85630B4F8D431013BA4F840 -:10937000D43194F8EF21444BEAB1D3F8E001D3F8AB -:10938000C4113226002290FBF6F083F8EF2108800A -:10939000D3F8E40190FBF6F04880D3F8E83193FB72 -:1093A000F6F63A4B1B88F61A8E80A5F85420A5F8DD -:1093B0005620F9F751FBD4F8C431B4F8B8111A8823 -:1093C00000268A1AA4F8B821B4F8BA115A88B1460E -:1093D0008A1AA4F8BA219B88B4F8BC21D31AA4F83D -:1093E000BC31F8F7CDFDD4F8F0310546C31A184664 -:1093F0000293FEF74FFED4F8F4110390FEF7A2FE9D -:10940000D4F8F881C4F8F05198F800A005903546DA -:109410001F4F785FFEF742FE0599FEF793FE09A9FC -:109420008851BAF1000F35D05046FEF737FE01469D -:109430004FF07E50FEF73AFF0246114607F1AC0BA3 -:109440004FF07E500092FEF773FD56F80B10FEF7BA -:1094500079FE07F168018446485FCDF804C0FEF745 -:109460001DFE009AB8371146FEF76CFEDDF804C009 -:1094700001466046FEF75EFD4BF80600FFF728F850 -:1094800078530CE090020020F8000020000000203B -:109490004802002007F1B8026837E95BA952AD4FD6 -:1094A0000436EA5F0235062D02FB0299B0D1AA4DBF -:1094B0004FF0640A2A880AFB09F3524393FBF2FA3D -:1094C000AAF1490A07F1080009A91FFA8AFAF8F770 -:1094D00075FFBAF13B0FD8F8046010D9B4F91C023B -:1094E000FEF7DCFDD4F8186201463046FEF7E6FFD1 -:1094F0009A4F94F8223168B343F008032CE04FF000 -:109500007E513046FEF716FD01464FF07E50FEF7C5 -:10951000CDFE4FF0000B8246914B304653F81B10A6 -:109520000193FEF70FFE024637F90B000092FEF79B -:10953000B5FD009A01461046FEF7FCFC5146FEF7C9 -:1095400001FE019B43F81B000BF1020BBBF1060F60 -:10955000E2D1C3E723F008033146D4F8140287F8B8 -:10956000223102F007F80746C4F82002D4F81002AE -:10957000D4F818B200F10046D4F814020146FEF700 -:10958000E1FD594682465846FEF7DCFD014650464D -:10959000FEF7D0FC01F0F0FF0146304601F0EAFF93 -:1095A00070490646C4F824023846FEF7CBFD01F0A8 -:1095B00015FF6C49A4F828023046FEF7C3FD01F000 -:1095C0000DFFD4F81431A4F82A021B0739D56648D8 -:1095D00009A9F8F7F3FED8F808904FF07E514846F5 -:1095E000FEF7A8FC01464FF07E50FEF75FFE4FF0FD -:1095F000000B8246594D484605F50B7353F81B1076 -:109600000193FEF79FFD05F58E71024631F90B00BF -:109610000092FEF743FD009A01461046FEF78AFCD1 -:109620005146FEF78FFD019B43F81B000BF1020B27 -:10963000BBF1060FDED11846F8F778FFA5F838021F -:1096400040E0DFF814A109A90AF10400F8F7B6FE1A -:109650006868D5F808900146FEF774FD49468346D0 -:109660004846FEF76FFD01465846FEF763FCED687D -:10967000814629462846FEF765FD01464846FEF725 -:1096800059FC01F079FF00210546FEF7EFFEA0B975 -:10969000DAF804002946FEF709FE2946CAF8040054 -:1096A000DAF80800FEF702FE2946CAF80800DAF8E0 -:1096B0000C00FEF7FBFDCAF80C002C48F8F736FF4B -:1096C000A4F838022A490398FEF73CFD06F100464B -:1096D000054607F10047B4F938020D960C97FEF7DE -:1096E000DDFC244900F10040FEF72CFD0E90B4F99A -:1096F0000802FEF7D3FC0F90B4F90A02FEF7CEFC85 -:109700001090B4F90C02FEF7C9FC0CA911900FA837 -:10971000F8F754FE98F80130104E012B2ED1164B5D -:109720001B785F070ED4D6F83C32402093FBF0F054 -:10973000181AFEF7B3FC1199FEF7FCFBFEF7C8FE02 -:10974000C6F83C02054BD3F83C02402390FBF3F0F3 -:1097500016E000BF0003002000000020F8000020F9 -:10976000080300204C3D0F44240300200400002087 -:10977000BD37863535FA8E3C5C160020A94B18881B -:10978000FEF78CFC01461198FEF7D2FBD4F8441288 -:1097900011902846FEF7CEFB01462846FEF786FDCF -:1097A000D4F84062054631461198FEF7C1FB0146E8 -:1097B0002846FEF7C7FC01463046FEF7BBFB0646CF -:1097C000C4F840020F98D4F8487201F007FED4F8AC -:1097D00054522978F9F774F83844C4F848021098BC -:1097E000D4F84C7201F0FAFD2978F9F769F8384499 -:1097F000C4F84C023046D4F8507201F0EFFD69789D -:10980000F9F75EF8884B38441A68029FC4F8500292 -:109810003A441A60D4F858320133C4F8583205E09B -:10982000A7F8B831A7F8BA31A7F8BC317F4CB4F823 -:109830005031A4F85C32B4F85231A4F85E32049B83 -:10984000012B0ED1B4F96222B4F9543103EB420377 -:10985000032293FBF2F39BB2A4F86032A4F86232C5 -:1098600003E0B4F85431A4F86032F8F789FB704B88 -:10987000D4F890521860D4F86432C4F86402C31A61 -:109880009BB20293A4F86832B4F970022B89984213 -:109890000EDBB0F5FA6FAF7907DAC21A5743A3F5BA -:1098A000FA6397FBF3F7643703E0C7F1640700E05E -:1098B0006427604BD4F83C61B3F81A8193F9EC301B -:1098C00000215B429BB2CDF80C80049334460A46DB -:1098D000594BDDF80CE031F903B0CEEB0B0303F28A -:1098E000F31C40F2E63EF44503D8002BB8BF5B42C0 -:1098F00001E04FF4FA73022ADFF830E133D096F832 -:109900005DC1BCF1000F04D06345CCBFCCEB0303B9 -:1099100000234FF0640C93FBFCF80EEB48096FF04A -:10992000630A0AFB083AB9F894920EEB480EBEF9A6 -:1099300096820FFA89FECEEB080E0EFB0AFEDFF8C8 -:1099400004819EFBFCFEF14421F8089095F804E0A8 -:1099500003FB0EFE394B9EFBF3F363449BB27B4348 -:1099600093FBFCFC1CE096F85EC1BCF1000F04D038 -:109970006345CCBFCCEB03030023DDF8108003FB71 -:1099800008FCAEF8A6C295F805E083EAE37CACEBF0 -:10999000E37C0CFB0EFC294B9CFBF3FC0CF1640CF0 -:1099A00006EB020E9EF80480254B0CFB08F84FF0E6 -:1099B000640E98FBFEF802F8038094F80E9003F111 -:1099C00003080CFB09F999FBFEF902F8089094F8DA -:1099D000189003F106080CFB09FC9CFBFEFCDDF86B -:1099E0000CE002F808C0F345A3F2AA2807DA08F24F -:1099F000A22331F803E0CEF1000E21F803E001329A -:109A0000032A01F1020104F101047FF461AF094C62 -:109A1000B4F81C31984217DBB0F5FA6FA8BF4FF4C9 -:109A2000FA6012E00000002054160020F800002028 -:109A300050160020A40F0020620300200CFEFFFF40 -:109A4000A20300209A0300201846C01A4FF47A722D -:109A50005043C3F5FA63B0FBF3F3642693FBF6F2CD -:109A600008EB42016FF0630000FB0233B1F8B4125F -:109A700008EB4202B2F9B6020AB2821A534393FBD0 -:109A8000F6F6B8F8CC3231445806B04DA8F8A81212 -:109A90003DD5B5F8CE32B5F83802C01A00B2FEF79F -:109AA000FDFAAB49FEF74EFB064601F061FC0746A6 -:109AB000304601F0D1FC0646B5F9A402FEF7EEFAF5 -:109AC0008146B5F9A202FEF7E9FA39468246FEF769 -:109AD00039FB314683464846FEF734FB014658467B -:109AE000FEF726FAFEF7F4FC3946A5F8A20248462E -:109AF000FEF728FB314607465046FEF723FB01469A -:109B00003846FEF717FAFEF7E3FCA5F8A402A268B0 -:109B100040F602031340002B66D0D8F8D062029BB7 -:109B200006211E4498F8D432884D0133DBB2B3FBD2 -:109B3000F1F088F8D43201FB103313F0FF07C8F8B6 -:109B4000D06251D1910712D5F8F722F995F8D522B4 -:109B5000B5F8D632934207D3D5F8D8329B789342E2 -:109B60008CBF0023012300E03B4688F8DC32A36869 -:109B70001A0536D598F8F132D8F8E01208EB43030D -:109B8000B3F8F402082391FBF3F280B28A1A02447C -:109B900092FBF3F39BB240F6E4415943D8F8D83234 -:109BA00040F6FF70B1FBF0F1D888C8F8E022091A3E -:109BB0004FF47A7251439B8891FBF3F14E43654B0E -:109BC00096FBF2F2C8F8FC12D3E90001801841EBD1 -:109BD000E271C3E90001604A0023FEF7BFFCC8F848 -:109BE00008030023C8F8D032D8F80C33574A13F4CE -:109BF000805318BF012382F81033A36898F8DC6201 -:109C000013F4807F554C2CD0D8F8143320781B687F -:109C1000C0F380005B684D4D984758B1012385F82B -:109C20001833D5F814331B68DB68984710B102234A -:109C300085F81833D8F814331B689B68984730B1FF -:109C400023785B0703D4414B022283F81823D8F80A -:109C500014331B689B69984718B13C4B002283F86A -:109C6000182398F81823394B022A02D14C204E2190 -:109C700014E0012A06D153204D214C220B46FAF75D -:109C800075FE1FE093F81023012A04D153200146EA -:109C900002464D23F3E726B153204D210A464423C3 -:109CA000EDE7B3F8CC22170603D553204D21024629 -:109CB000E4E793F8EE211AB11920FAF72DFE01E03E -:109CC00083F819632278550704D5254F4FF40053C4 -:109CD0007B616DE0D8F80C33D80703D41F4942F0FC -:109CE00001020A70B8F8C02122B1184AD2F8142132 -:109CF000910705D41B4A1288003218BF012200E0E8 -:109D0000012242B11648C26882F40052C260227831 -:109D100022F00102227098F82221120703D422783F -:109D200022F001022270DB0203D5237823F0010325 -:109D3000237023780C4A13F0010F17D00023084931 -:109D4000C8F81C334FF400530B611EE0F8000020EC -:109D500035FA8E3CF8030020407E05005C1600209A -:109D6000001001405816002050160020D8F81C138F -:109D7000136851B903F5F4237D4903F590737D4FC2 -:109D8000C1F81C334FF400537B61D8F81C331268C0 -:109D900073B1D21A002A0BDB764803F5F423C268AC -:109DA00003F5907382F40052C260714AC2F81C330A -:109DB000714B1B781BB1F9F7D3FE00F063BD6F4CFC -:109DC00094F84A30012B40F05785694D2368C5F857 -:109DD000B843C5F8BC33664ED6F8BC0335460368B5 -:109DE0005B689847002800F04185D6F8BC030368FB -:109DF0009B689847D6F8B83393F84820E2B9B0F199 -:109E000024077A427A4183F84820002AE3D15C4B48 -:109E10001B785D07DFD4232802D1F9F7A1FEDAE72A -:109E2000D6F8C0331B7D8342D5D1564A564B1A60B3 -:109E3000564A574BDA60CEE7012A05D14D2814BFA8 -:109E40000022022200F00EBD022A05D13C2814BFD8 -:109E50000022032200F006BD032A0BD140284FF058 -:109E6000000200F2FF841A71DA71587198710422AD -:109E700000F0F8BC042A07D19A7983F849005040D1 -:109E80009871052200F0EEBC052AA4D159791A79FF -:109E90009142997906D941409971511C1971134425 -:109EA000187298E7814240F0D98493F84970682F7E -:109EB00000F0648200F218812C2F00F0828448D8D0 -:109EC000242F00F063842BD8202F00F04782222F0C -:109ED00000F08D83012F40F09D842C20F8F7CAF903 -:109EE0000020F8F798F93846F8F795F90020F8F7C8 -:109EF00092F94320F8F78FF94C20F8F78CF94620B7 -:109F0000F8F789F94C20F8F786F93846F8F783F91D -:109F10000020F8F780F90020F8F77DF9002662E1CB -:109F2000282F00F03B842A2F00F04584262F40F094 -:109F30007184184E0320F8F79DF9B6F9E600F8F79A -:109F40009CF9B6F9E800F8F798F9B6F9EA0000F0DC -:109F50002FBC642F00F06E811ED8342F00F0678371 -:109F6000402F00F04984322F40F0548400F03DBC73 -:109F7000F8000020001001405B16002018040020AB -:109F80005C160020EFBEADDEF04F00200400FA05A5 -:109F900000ED00E0A40F0020662F00F0768100F2B3 -:109FA000AB810B20F8F766F9B6F96802F8F765F9A6 -:109FB000B6F8C40300B2F8F760F9D6F81431C3F369 -:109FC000C000C3F38002800040EA4200C3F34002B5 -:109FD0001043C3F3401240EAC20003F010031843D9 -:109FE000F8F74BF9B6F8CC2212F0010F0CBF0021A4 -:109FF000022112F0020F0CBF0023042312F0040F01 -:10A000000CBF0027102712F0400F0CBF4FF00008C4 -:10A010004FF0200812F0100F0CBF4FF0000E4FF45D -:10A02000007E039312F0200FD6F80C330CBF0020F3 -:10A030004FF4806003F48026029102F0080B03F4D1 -:10A0400080110497CDF8148003F4003703F400580E -:10A0500003F4807ACDF818E0079003F4803E03F40F -:10A06000002003F4805903F4004C03F0C00343EADA -:10A070000B0343EA0A0343EA090343EA080343EAFA -:10A080000C0343EA0E033B43334303430B43D249E0 -:10A09000039F91F800E00299CEF3800E43EA0E038D -:10A0A0000B43DDF810803B43DDF814E0069843EAEB -:10A0B000080343EA0E03079912F4807F43EA000382 -:10A0C0000CBF00254FF400650B4312F4007F43EAF8 -:10A0D00005030CBF00224FF400121A43BF4B0020AF -:10A0E00093F8C6630346B9E0732F00F0188351D884 -:10A0F0006E2F00F0918110D86C2F00F0578100F284 -:10A100006381692F40F0868396F8DD0300264000C6 -:10A1100000F0FE00F8F7AEF83CE1702F00F0C981C6 -:10A12000C0F0A281722F40F07583AD4F1620F8F772 -:10A13000A1F80020F8F7A1F8B7F9D000F8F79DF8DA -:10A14000B7F9D200F8F799F8B7F9D400F8F795F80D -:10A15000D6F83C31B3F9A801F8F78FF80020F8F7EA -:10A160008CF80020F8F7AEF8D6F83C31B3F952007D -:10A170000A2390FBF3F0F8F780F897F80401F8F75A -:10A180004AF897F80601F8F746F897F80501F8F746 -:10A1900042F8C2E2782F00F0BB800DD8752F00F096 -:10A1A0001A82C0F06D82772F40F0348396F8C60390 -:10A1B000F8F760F80026A3E2F02F00F0D982FE2F16 -:10A1C00000F0B882A02F40F025830C20F8F752F859 -:10A1D000844B1868F8F776F8834B1868F8F772F82C -:10A1E000824B1868D7E2824B1B68985D0136F8F7FE -:10A1F00012F8042EF7D10020F8F73FF800267D4B27 -:10A20000985D0136F8F707F80B2EF8D100267A4B47 -:10A21000985D0136F7F7FFFF082EF8D10720F7F712 -:10A22000FAFF0026754B985D0136F7F7F4FF072E0D -:10A23000F8D172E207206A4EF8F71CF8E620F7F72B -:10A24000EAFF7079F7F7E7FF0020F7F7E4FF96F8E9 -:10A250002631002B0CBF04200C209CE2B3420CD210 -:10A2600067495F5C012101FA07F7174218BF99405F -:10A2700003F1010318BF0843F0E7F8F723F8584B40 -:10A2800093F86C06F7F7C7FFE2E21220F7F7F2FF48 -:10A290005C4B1B88B3F5806F21D900275A4BF85EC1 -:10A2A000082390FBF3F00237F7F7E7FF062FF5D10D -:10A2B000B6F95C02F7F7E1FFB6F95E02F7F7DDFFEA -:10A2C000B6F96002F7F7D9FFB6F91C01F7F7D5FF29 -:10A2D000B6F91E01F7F7D1FFB6F9200168E2B6F929 -:10A2E0000802F7F7CAFFB6F90A02F7F7C6FFB6F990 -:10A2F0000C02F7F7C2FFDBE71020F7F7BBFF0026E1 -:10A30000424B985D0136F7F786FF102EF8D19FE299 -:10A310003820F7F7AFFF0027D5F83C3107F12C06BE -:10A32000F6003344B3F90600F7F7A7FFD5F83C3140 -:10A3300001373344B3F90800F7F79FFFD5F83C31F4 -:10A340003344B3F90A00F7F798FFD5F83C311E44BF -:10A35000307BF7F760FF082FDED179E20820F7F7AE -:10A3600089FF0026D5F83C3103EBC60393F86D0155 -:10A370000136F7F750FF082EF4D169E21020F7F705 -:10A3800079FF0026224B985D0136F7F744FF102E27 -:10A39000F8D15DE295F8DD339E4280F059821D4B85 -:10A3A00033F91600F7F769FF0136F3E70620F7F7F0 -:10A3B00061FFB6F92802F7F760FFB6F92A02F7F74E -:10A3C0005CFFB6F93802F3E10620F7F753FF0020EF -:10A3D000F7F778FFBAE100BF5C160020F800002014 -:10A3E000A40F0020E8F7FF1FECF7FF1FF0F7FF1F97 -:10A3F000780000207CDD000888DD000891DD000881 -:10A40000BF040020000000200003002062000020A4 -:10A4100036160020620300200720F7F72BFF96F87E -:10A42000D502F7F7F8FED6F808034FF6FF77B842E3 -:10A43000A8BF384620EAE07000B2F7F71EFFB6F971 -:10A44000E003F7F71AFFC24DC24BD5F8FC0293F8B0 -:10A450000C310028B8BF40420BB10A235843B84220 -:10A46000A8BF384600B2A3E10720F7F703FFD6F8EC -:10A4700090321878F7F7CFFED6F890325878F7F781 -:10A48000CAFED6F890321879F7F7C5FED6F89032A2 -:10A490005879F7F7C0FED6F890329879F7F7BBFEF7 -:10A4A000D6F890329878F7F7B6FED6F89032D8788A -:10A4B000E8E61E20F7F7DEFED6F83C3100261B78D2 -:10A4C000022B72D1A24AA449D2F83C31A04F03EB2F -:10A4D0008603586AFDF736FE00F080FFFA28A8BF11 -:10A4E000FA2020EAE070C0B2F7F795FED7F83C31C9 -:10A4F0009A4903EB8603186BFDF724FE00F06EFF0C -:10A50000FA28A8BFFA2020EAE070C0B2F7F783FE6D -:10A51000D7F83C31924903EB8603D86BFDF712FE66 -:10A5200000F05CFF6428A8BF642020EAE070C0B29D -:10A530000136F7F770FE032EC4D1072ED5F83C3153 -:10A540001FD1986C8449FDF7FDFD00F047FFFA2804 -:10A55000A8BFFA2020EAE070C0B2F7F75CFED5F899 -:10A560003C317D49D86CFDF7EDFD00F037FFFA284E -:10A57000A8BFFA2020EAE070C0B2F7F74CFE002036 -:10A580000DE033441879F7F746FED5F83C313344F3 -:10A59000987BF7F740FED5F83C313344187E0136FE -:10A5A000F7F739FE0A2EC8D152E1D5F83C313344D1 -:10A5B0001879F7F730FED5F83C313344987BF7F73C -:10A5C0002AFED5F83C313344187E0136F7F723FED6 -:10A5D0000A2EEAD13CE12F20F7F74CFE614E16F827 -:10A5E000010F002800F03481F7F715FEF7E7A020EF -:10A5F000F7F740FE0026D5F83C3106F11C0203EBCC -:10A6000082035F1D584A5B790C2101FB0323187AF2 -:10A61000F7F701FE7878F7F7FEFDB878F7F7FBFD5E -:10A620000136F878F7F7F7FD282EE4D110E148203D -:10A63000F7F720FE00274FF0060909FB07F9D5F8C8 -:10A640003C3109F58879994499F80A00F7F7E3FD58 -:10A6500099F80500F7F7DFFD99F80600F7F7DBFD3D -:10A6600099F80700F7F7D7FD99F80800F7F7D3FD39 -:10A67000013799F80900F7F7CEFD0C2FDBD1E7E0A1 -:10A680004FF000090126002795F8C6339F4224DACF -:10A69000364BF95C0023344A03EB020B9A5C8A4286 -:10A6A00004D00C33B3F58A7FF5D114E0DBF8040055 -:10A6B00000F070FC80460EB9B24601E081440AE029 -:10A6C000C24508DADBF8042012F80A00F7F7A3FD08 -:10A6D0000AF1010AF4E70137D6E7002E00F0B8804E -:10A6E0005FFA89F0F7F7C6FD0026CCE71E4A9918F5 -:10A6F0009A5C82420DD00C33B3F58A7FF6D10136D5 -:10A7000095F8C6339E4280F0A380184BF05C00237E -:10A71000ECE7087AF7F77FFDF1E70020B2E50820C3 -:10A72000F7F7A8FD0126F0B20136F7F774FD092E00 -:10A73000F9D18DE00820F7F79DFD0020F7F79DFD8A -:10A740000020F7F79AFD0020F7F797FD00202FE093 -:10A75000F8000020A40F0020000020410000C842A3 -:10A7600000007A4447CA000878CA0008BF040020E5 -:10A770000420F7F77FFDD6F83C31B3F95600F7F720 -:10A780007CFDD6F83C31B3F9540011E00420F7F712 -:10A7900071FDB04B9868F7F795FD59E0AD4E042078 -:10A7A000F7F768FDB6F90801F7F767FDB6F90A0192 -:10A7B000F7F763FD4CE00120F7F75CFDA54B5879F6 -:10A7C00060E5A44E0720F7F755FD96F81801F7F756 -:10A7D00022FDB6F91E01F7F750FDB6F91A01F7F799 -:10A7E0004CFDB6F91C01F7F748FD0120F7F742FDD3 -:10A7F000984B93F8200145E50820F7F73BFD00262C -:10A80000944B334493F810010136F7F704FD082EFA -:10A81000F6D11DE0C82F00F04A8340F24881D02FC6 -:10A8200000F0328240F29081D42F00F01D8300F2BC -:10A83000FB82D22F40F0F182874B1B7803F0040398 -:10A8400003F0FF06002B00F0DD820020F7F712FD79 -:10A85000824BD3F8B8339879F7F7DDFC7F4B0022B1 -:10A86000D3F8B83383F84820FFF7B5BA96F8FC332D -:10A8700013B17B4A7B4BDA60DFF8FC814C344445F2 -:10A880007FF49EAA754CD4F8483113B104F2FE301F -:10A890009847D4F81431714A13F0080F6D4E38D030 -:10A8A000B2F8A61201F145039BB28A2B2DD8B2F85B -:10A8B000CC325F0729D5B2F83802B2F8E23394F807 -:10A8C0002251C21A92B293B218B2B330BCBF02F591 -:10A8D000B4739BB21AB2B32AC4BFA3F5B4739BB2CC -:10A8E0002D0796F8EC005D4A13D540B24042434331 -:10A8F000D2F83C011BB2007B43436FF01D0093FB79 -:10A90000F0F31944A2F8A61203E0B4F83832A4F820 -:10A91000E233D4F83C71514D97F86491B9F1000FCE -:10A9200051D0B5F8CC329A074DD0D5F81002D5F8F1 -:10A9300014320146D5F81882B5F8A8A20193FDF7A4 -:10A9400001FC019B834619461846FDF7FBFB0146B7 -:10A950005846FDF7EFFA414683464046FDF7F2FBC5 -:10A9600001465846FDF7E6FA00F006FE014640466D -:10A97000FDF79CFC3C498046FDF78CFDF8B940464C -:10A9800000F0A8FDD5F80014FDF7DCFB00F026FD73 -:10A99000B0F5617FA8BF4FF46170FDF77FFB3349CD -:10A9A000FDF784FC00F058FD05464846FDF776FBB0 -:10A9B0002946FDF7C7FB00F011FD80B200E0002042 -:10A9C0005044A4F8A8022A4B381D1D68D4F89012F0 -:10A9D00007F15403B6F8F620A847F9F777FBD4F847 -:10A9E0000434002B5FD01D4B93F80834013B142B2B -:10A9F00054D8DFE803F00B5353275653531F5353D8 -:10AA0000535353435353535353274300D4F80C34F5 -:10AA10005B782BB1174B00205989F7F7C9FF42E04B -:10AA20000D4B1B7803F0040303F0FF00002BF1D162 -:10AA30000146F2E70F4C0020E188F7F7B9FF01204B -:10AA40002189EAE70B4C00202189F7F7B1FF0120AB -:10AA50006189E2E7A40F00205C160020F8000020C6 -:10AA60000400FA0500ED00E08FC2753CEFB6B0447B -:10AA70007400002062000020B0040020C04C0020C0 -:10AA8000E188F7F795FF01202189F7F791FF022070 -:10AA90006189F7F78DFF0320A189BEE7B3689B06A4 -:10AAA00001D5F7F791FFFBF7D9FCFEF7EAB82B2F9A -:10AAB00007D10020F7F7DEFBF7F7AEF9B14B58717D -:10AAC000C3E636D8252F10D1AE4E0020F7F7D2FBC3 -:10AAD0000023B360F7F7AAF90746F7F7A7F9B368B9 -:10AAE00007EB00400343B360AFE650D8212F00F0DE -:10AAF000EC81232F40F0F681F7F78EF927281ED836 -:10AB0000D6F83C3100F11C0703EB8707F7F784F90F -:10AB10009D4B7E1D03F58A72197A814203D00C3356 -:10AB20009342F9D10BE01B787B71F7F775F97070E0 -:10AB300026E0352F6AD1F7F76FF90B284AD90120A3 -:10AB40000021F7F779FB80E6CD2F00F0A98000F215 -:10AB50000981CA2F00F0AE80CC2F40F0C381D6F817 -:10AB60009062F7F759F93070F7F756F97070F7F708 -:10AB700053F93071F7F750F97071F7F74DF9B0717B -:10AB8000F7F74AF9B070F7F747F9F0705DE6272F4D -:10AB900010D10020F7F76EFBF7F748F9794EA6F8C9 -:10ABA000E600F7F743F9A6F8E800F7F73FF9A6F84B -:10ABB000EA004AE6292F40F095810020F7F75AFB7A -:10ABC000F7F734F96F4EA6F80801F7F72FF9A6F852 -:10ABD0000A013AE606277843D6F83C7100F58870FA -:10ABE0000744F7F719F90328A9D8B872F7F714F949 -:10ABF0007871F7F711F9B871F7F70EF9F871F7F7FF -:10AC00000BF93872F7F708F978721EE622D82D2F63 -:10AC100014D10020F7F72EFBF7F7FEF8594E86F80F -:10AC20001801F7F703F9A6F81E01F7F7FFF8A6F8E1 -:10AC30001A01F7F7FBF8A6F81C0106E6332F40F0DF -:10AC400051810020F7F716FBF7F7E6F84D4B83F834 -:10AC50002001FAE5412F0DD10020F7F70BFB00266C -:10AC6000F7F7DAF8474B33440136082E83F8100122 -:10AC7000F6D1EAE5442F40F035810020F7F7FAFAE3 -:10AC8000012386F8FC33E0E5404B1B7858073FF57D -:10AC9000DCADF9F777F8FBF739FAF8F769FCD4E59A -:10ACA0003A4B1B7859073FF5D0AD4FF4C873A6F85F -:10ACB000C031CAE5D6F83C713B78022B42D1002660 -:10ACC000F7F7AAF8FDF7E6F93149FDF7EFFA7862F0 -:10ACD000F7F7A2F8FDF7DEF92E49FDF7E7FA38633A -:10ACE000F7F79AF8FDF7D6F92B49FDF7DFFA0136A9 -:10ACF000032EF86307F10407E2D1072ED5F83C7163 -:10AD000012D1F7F789F8FDF7C5F92149FDF7CEFA19 -:10AD1000B864F7F781F8FDF7BDF91D49FDF7C6FAEC -:10AD2000F864F7F779F809E0F7F776F837443871FF -:10AD3000F7F772F8B873F7F76FF8387601360A2E1E -:10AD4000DBD182E5013F0026F7F766F8013738715D -:10AD5000F7F762F8B873F7F75FF801360A2E38761E -:10AD6000F2D172E5CE2F19D1084B1B785A073FF567 -:10AD70006CAD96F8223143F0040386F8223164E585 -:10AD800062000020A40F002078CA00085C16002092 -:10AD9000000020410000C84200007A44CF2F40F05C -:10ADA000A180F7F743F8F7F741F8514FA7F8D00023 -:10ADB000F7F73CF8A7F8D200F7F738F8D6F83C6177 -:10ADC000A7F8D400F7F732F8A6F8A801F7F72EF89D -:10ADD000F7F72CF8F7F72AF8F7F728F800EB8000D8 -:10ADE0004000A6F85200F7F717F887F80401F7F7C4 -:10ADF00013F887F80601F7F70FF887F80501F7F75A -:10AE00000BF822E5F7F708F8394B022883F86C06AF -:10AE10007FF641AF83F86C663DE7D32F62D1F7F739 -:10AE200005F8A6F8E20310E5EF2F0AD1D6F83C6149 -:10AE3000F6F7FCFFA6F85600F6F7F8FFA6F8540060 -:10AE400003E5FA2F05D12B4B1B785B077FF523AF6A -:10AE500048E0D62F46D10026F6F7E8FF264B985358 -:10AE60000236102EF8D1F0E40027D5F83C61F6F751 -:10AE7000DDFF06EBC706A6F86601F6F7D7FFA6F8D2 -:10AE80006801F6F7D3FFA0F57A7307289BB298BF45 -:10AE900086F86D01B3F57A7F98BFA6F86A01F6F7D8 -:10AEA000BBFF0137082F86F86C01DED1CDE4002608 -:10AEB000F6F7BCFF114B03F26A2290530236102EB4 -:10AEC000F6D1012283F80421BFE40026D5F83C71B5 -:10AED000F6F7A2FF07EBC6070136082E87F86D01CB -:10AEE000F4D1B2E401200021F7F7A6F9B0E400BFE5 -:10AEF000A40F00205C160020DC040020F8000020D5 -:10AF000010B50023934203D0CC5CC4540133F9E75D -:10AF100010BD02440346934202D003F8011BFAE736 -:10AF2000704700000D4B70B51D680022845C2B1922 -:10AF30005B7803F00303012B8B5C08BF2034EE1811 -:10AF4000767806F00306012E08BF2033E41A02D1FA -:10AF50000132002BEAD1204670BD00BF88000020DE -:10AF600010B50446224613780134002BFAD1CC5C8C -:10AF7000D4540133002CFAD110BDC9B2024610F8E6 -:10AF8000013B1BB18B42F9D1104670470029FBD021 -:10AF900018467047034613F8012B002AFBD1181AF4 -:10AFA000013870470F4BF0B51E680023934215D04F -:10AFB000C55C7419647804F00304012CCC5C08BFF0 -:10AFC000203537197F7807F00307012F08BF203499 -:10AFD0002D1B04D10133002CE8D100E000252846C8 -:10AFE000F0BD00BF8800002010B5034632B111F853 -:10AFF000014B013A03F8014B002CF7D11A4493425C -:10B0000003D0002103F8011BF9E710BD30B5037828 -:10B010000BB1044604E00B78002B18BF002030BDB4 -:10B0200022461078013438B10023C85C28B1D55CC1 -:10B030008542F5D10133F8E730BD104630BD00211F -:10B040000A2200F001B92DE9F04E82468B461F46D8 -:10B05000144612B90020BDE8F08E002BFAD000266D -:10B06000A642F7D2A5196D0807FB05B95046494617 -:10B07000089B9847002802DB03D06E1C25462C460F -:10B08000EEE74846BDE8F08E174B2DE9F0411D680C -:10B090000646AC6D0F46FCB9502000F0E3F8A865F9 -:10B0A0008460AB6D046044601C61DC60AB6D9C61CE -:10B0B0005C61AB6DDC629C62AB6D5C631C63AB6D11 -:10B0C000DC639C63AB6D5C641C64AB6DDC649C6492 -:10B0D000AB6D1C77AB6D5C6230463946AA6D0123BF -:10B0E000BDE8F04100F002B8EC000020F0B508B96E -:10B0F000106828B3044614F8015B0F4617F8016B7B -:10B100003EB1B542FAD10BB12046F3E714600370AB -:10B11000F0BD4DB915602846F0BD17F8016BAE4281 -:10B1200007D0002EF9D11C46234613F8015B0F46C9 -:10B13000F3E715B10021217000E02B461360F0BD4C -:10B14000F0BD000084463F482DE9F04FD0F8008064 -:10B150000E46344614F8015B08EB0500407800F019 -:10B16000080000F0FF0708B12646F2E72D2D03D1B5 -:10B17000B41C7578012703E02B2D04BF7578B41C2F -:10B1800033F010000DD1302D08D1207800F0DF0011 -:10B19000582851D165781023023402E0002B08BFF3 -:10B1A0000A23002F0CBF6FF0004A4FF0004ABAFB91 -:10B1B000F3F903FB19AA0026304608EB050B9BF8B0 -:10B1C00001B01BF0040F01D0303D0BE01BF0030B6E -:10B1D0001BD0BBF1010F14BF4FF0570B4FF0370BD3 -:10B1E000CBEB05059D4210DAB6F1FF3F0AD048458A -:10B1F00006D801D1554503DC03FB0050012601E0D0 -:10B200004FF0FF3614F8015BD7E7731C0CD1002F09 -:10B210004FF022030CBF6FF000404FF00040CCF81D -:10B2200000302AB9BDE8F08F07B1404242B106B103 -:10B23000611E1160BDE8F08F002B08BF0823B0E746 -:10B24000BDE8F08F8800002030B51346044A05465B -:10B250000C46106829462246BDE83040FFF772BF11 -:10B26000EC000020024B0146186800F003B800BF54 -:10B27000EC00002070B5CD1C25F0030508350C2D21 -:10B2800038BF0C25002D06463FDB8D423DD3214BB8 -:10B290001C6818462146A1B10B685B1B0ED40B2B12 -:10B2A00003D90B60CC18CD501FE08C4202D16268EC -:10B2B00002601AE04B6863600C4616E00C46496871 -:10B2C000E9E7154C23681BB9304600F027F82060E9 -:10B2D0002946304600F022F8431C014615D0C41C14 -:10B2E00024F0030484420AD1256004F10B00231DDD -:10B2F00020F00700C31A0BD05A42E25070BD30460E -:10B30000611A00F00BF80130EED10C2333600020FD -:10B3100070BD00BF641600206016002038B5064CD2 -:10B32000002305460846236000F008F8431C02D1BC -:10B33000236803B12B6038BD6C160020094A1368DE -:10B3400063B118446946884202D8106018467047B5 -:10B35000054B0C221A604FF0FF307047034B13600F -:10B36000EFE700BF681600206C1600207016002062 -:10B3700000B5194A20F00043934283B0014617DD1F -:10B38000B3F1FF4F04DBFCF7D3FD03B05DF804FB22 -:10B39000694600F037FB00F00302012A009801998A -:10B3A00011D0022A0AD09AB1012201F0EFF8ECE79D -:10B3B000002100F0EFFC03B05DF804FB00F0EAFCB4 -:10B3C00000F10040E1E701F0E1F800F10040DCE7C6 -:10B3D00000F0E0FCD9E700BFD80F493F30B5C0F31B -:10B3E000C754A4F17F031E2B83B0014620DC581CF8 -:10B3F0001BDB162B4FEAD17509DDC1F3160040F4B3 -:10B400000000963CA04005B1404203B030BD114B56 -:10B4100053F825402046FCF78DFD01900198214608 -:10B42000FCF786FD20F0004333B9002003B030BDA7 -:10B43000FDF74EF803B030BDC0F31604C0F3C7509B -:10B4400044F40004C0F1960024FA00F0002DDCD092 -:10B45000DAE700BF1CF0000800B51D4A20F00043E9 -:10B46000934283B0014618DDB3F1FF4F04DBFCF7D4 -:10B470005FFD03B05DF804FB694600F0C3FA00F01D -:10B480000300012818D002280ED0D0B100980199ED -:10B4900000F080FC00F10040EBE70021002201F009 -:10B4A00075F803B05DF804FB00980199012201F0E2 -:10B4B0006DF800F10040DCE70098019900F06AFCAB -:10B4C000D7E700980199012201F060F8D1E700BFA9 -:10B4D000D80F493F70B58AB0054600F09BF8224C62 -:10B4E000064694F90030013303D0284601F02CFAC7 -:10B4F00010B930460AB070BD284601F0DBF94FF0B4 -:10B500007E51FCF7DBFF0028F3D01849012200230D -:10B510002846009208930191FCF780FA02460B46F8 -:10B520001348CDE90423CDE9022301F0A7F894F9EB -:10B530000030CDE90601022B0BD0684601F09CF8E3 -:10B5400038B1089B53B9DDE90601FDF7EDFA0AB001 -:10B5500070BD01F073FA21230360F2E701F06EFA87 -:10B56000089B0360EFE700BFF000002024F0000814 -:10B570002CF0000800F0B6B970B58AB0054600F0AE -:10B58000B5FB224C064694F90030013308D028461A -:10B5900001F0DAF920B128460021FCF771FF10B95B -:10B5A00030460AB070BD1A49012200232846019195 -:10B5B00000920893FCF732FA2478CDE90401CDE932 -:10B5C00002017CB900220023CDE90623684601F080 -:10B5D00053F888B1089BA3B9DDE90601FDF7A4FA89 -:10B5E0000AB070BD0020002102460B46FCF794FB18 -:10B5F000022CCDE90601E9D101F020FA21230360F4 -:10B60000E8E701F01BFA089B0360E5E7F000002083 -:10B6100030F00008F8B520F00043B3F17E5F044637 -:10B6200010D008DCB3F17C5F11DAB3F10C5F00F3EA -:10B6300084809D48F8BD0146FCF77AFC0146FCF782 -:10B6400035FEF8BD002840F3CD800020F8BD00286D -:10B65000C0F2CA8001464FF07E50FCF769FC4FF003 -:10B660007C51FCF76FFD044600F040FB8F49064615 -:10B670002046FCF767FD8E49FCF75CFC2146FCF791 -:10B6800061FD8C49FCF754FC2146FCF75BFD8A49BF -:10B69000FCF750FC2146FCF755FD8849FCF748FCB7 -:10B6A0002146FCF74FFD8649FCF744FC2146FCF798 -:10B6B00049FD844905462046FCF744FD8249FCF7D4 -:10B6C00037FC2146FCF73EFD8049FCF733FC214660 -:10B6D000FCF738FD7E49FCF72BFC2146FCF732FDD8 -:10B6E0004FF07E51FCF726FC01462846FCF7DEFDB4 -:10B6F0003146FCF727FD26F47F6525F00F05074648 -:10B7000029462846FCF71EFD01462046FCF710FCA2 -:10B71000294604463046FCF70DFC01462046FCF75E -:10B72000C5FD01463846FCF705FC01462846FCF7F6 -:10B7300001FC0146FCF7FEFBF8BD0146FCF702FDEB -:10B740005A490546FCF7FEFC5949FCF7F3FB29462C -:10B75000FCF7F8FC5749FCF7EBFB2946FCF7F2FC39 -:10B760005549FCF7E7FB2946FCF7ECFC5349FCF78D -:10B77000DFFB2946FCF7E6FC5149FCF7DBFB2946D9 -:10B78000FCF7E0FC4F4906462846FCF7DBFC4E4937 -:10B79000FCF7CEFB2946FCF7D5FC4C49FCF7CAFB6D -:10B7A0002946FCF7CFFC4A49FCF7C2FB2946FCF7C7 -:10B7B000C9FC4FF07E51FCF7BDFB01463046FCF75B -:10B7C00075FD01462046FCF7BDFC01464148FCF7EB -:10B7D000AFFB01462046FCF7ABFB01463E48FCF7B9 -:10B7E000A7FBF8BD3D48F8BD4FF07E51FCF7A2FB2A -:10B7F0004FF07C51FCF7A6FC2C490446FCF7A2FC58 -:10B800002B49FCF797FB2146FCF79CFC2949FCF7E8 -:10B810008FFB2146FCF796FC2749FCF78BFB214662 -:10B82000FCF790FC2549FCF783FB2146FCF78AFCDA -:10B830002349FCF77FFB2146FCF784FC06462046A3 -:10B8400000F054FA1F4905462046FCF77BFC1E49D0 -:10B85000FCF76EFB2146FCF775FC1C49FCF76AFB04 -:10B860002146FCF76FFC1A49FCF762FB2146FCF706 -:10B8700069FC4FF07E51FCF75DFB01463046FCF75A -:10B8800015FD2946FCF75EFC1249FCF751FB014609 -:10B890002846FCF74FFB0146FCF74CFB01461048DD -:10B8A000FCF746FBF8BD00BFDB0FC93F08EF1138BE -:10B8B000047F4F3A4611243DA80A4E3E90B0A63E62 -:10B8C000ABAA2A3E2EC69D3D6133303F2D57014025 -:10B8D00039D119406821A233DA0FC93FDB0F494043 -:10B8E000DA0F494021F00042B2F1FF4FF8B50446AB -:10B8F00014DC20F00045B5F1FF4F06460EDCB1F137 -:10B900007E5F3AD08F1707F0020747EAD07755B924 -:10B91000022F2FD0032F2FD13148F8BD08462146E2 -:10B92000FCF708FBF8BDFAB1B2F1FF4F29D0B5F131 -:10B93000FF4F19D0AA1AD2153C2A19DC002938DB8E -:10B940002046FCF7B3FC00F0B5FF00F09DFE012F90 -:10B950002CD0022F22D0002F2FD02249FCF7EAFA58 -:10B960002149FCF7E5FAF8BD002E15DB1F48F8BDAC -:10B970001E48ECE71C48F8BDF8BDBDE8F84000F0F3 -:10B9800083BEB5F1FF4F19D0022FF3D0032FC3D0E0 -:10B99000012F1BD00020F8BD1548F8BD1149FCF758 -:10B9A000C9FA01461048FCF7C3FAF8BD00F100409F -:10B9B000F8BD3C32C4DA0020C9E7F8BD022F0CD034 -:10B9C000032F08D0012F04D00A48F8BD4FF00040E3 -:10B9D000F8BD0948F8BD0948F8BD0948F8BD00BFE1 -:10B9E000DB0F49C02EBDBB33DB0F4940DB0FC93F26 -:10B9F000DB0FC9BFDB0F493FDB0F49BFE4CB16C0EC -:10BA0000E4CB16402DE9F04FAB4A20F000449442BD -:10BA100089B006460D4664DDA84A94421CDC002825 -:10BA2000A74940F3EC80FCF783FAA64B24F00F04FF -:10BA30009C42064664D0A449FCF77AFA0146286085 -:10BA40003046FCF775FAA049FCF772FA01236860EA -:10BA5000184609B0BDE8F08F9C4A944262DDB4F10B -:10BA6000FF4F46DAE715863FA4EBC7542046FCF7A4 -:10BA70002FFDFCF713FB0346014620460593FCF718 -:10BA800057FA4FF08741FCF75DFB8046FCF720FD3D -:10BA9000FCF704FB0146044640460694FCF748FACE -:10BAA0004FF08741FCF74EFB00210790FCF7DEFCCE -:10BAB000002800F0C58020460021FCF7D7FC0028B4 -:10BAC00014BF0123022382480221019000913A46CB -:10BAD00005A8294600F022FA002EC0F2A7800346EE -:10BAE00003E00022286000234A60184609B0BDE840 -:10BAF000F08F0146FCF71CFA002368602860F4E729 -:10BB00007449FCF715FA74490446FCF711FA01462A -:10BB100028602046FCF70CFA6F49FCF709FA01236C -:10BB20006860E2E700F0C6FE6C490746FCF70AFBD6 -:10BB30004FF07C51FCF7FEF9FCF7CAFC8246FCF79B -:10BB4000ADFA5F498346FCF7FDFA01463846FCF73B -:10BB5000EFF95D4980465846FCF7F4FABAF11F0F39 -:10BB600081464946404618DC5D4B0AF1FF3253F8E6 -:10BB7000223024F0FF029A420FD0FCF7D9F9074691 -:10BB80002F6039464046FCF7D3F94946FCF7D0F917 -:10BB9000002E686056DB5346A7E7FCF7C9F9E315AA -:10BBA000C0F3C7529A1A082A0746E9DD49495846A0 -:10BBB0000393FCF7C7FA074639464046FCF7B8F945 -:10BBC000044621464046FCF7B3F93946FCF7B0F984 -:10BBD000414907465846FCF7B5FA3946FCF7A8F93B -:10BBE000814649462046FCF7A3F9039BC0F3C752A0 -:10BBF0009B1A192B074641DC2860A046C1E7FCF7D9 -:10BC000099F9304B24F00F049C42064623D02E496C -:10BC1000FCF790F9014628603046FCF789F92A497B -:10BC2000FCF788F94FF0FF3368605EE795E80C0099 -:10BC300003F1004102F1004243422A60696054E787 -:10BC4000032340E707F1004700F100402F606860E0 -:10BC5000CAF1000349E71F49FCF76CF91E49044685 -:10BC6000FCF768F9014628602046FCF761F91A499B -:10BC7000FCF760F94FF0FF33686036E71949584622 -:10BC8000FCF760FA074639462046FCF751F9804632 -:10BC900041462046FCF74CF93946FCF749F9124970 -:10BCA00004465846FCF74EFA2146FCF741F9814616 -:10BCB0004946404661E700BFD80F493FE3CB1640F5 -:10BCC000800FC93FD00FC93F43443537800F4943E8 -:10BCD000B8F000080044353708A3852E84F9223FC8 -:10BCE00038F0000800A3852E32318D2420F0004268 -:10BCF000B2F1FF4FF8B5044603462DD25AB30028DF -:10BD00003DDBB2F5000F4FEAE0502CD37F38C3F390 -:10BD10001603C20743F4000348BF5B00002740102E -:10BD20005B003E4619244FF08072B5189D4202DC3C -:10BD30005B1BAE181744013C4FEA43034FEA520223 -:10BD4000F3D113B107F001031F447F1007F17C57B3 -:10BD500007EBC050F8BDF8BD0146FCF7F3F92146EA -:10BD6000FCF7E8F8F8BD14F400020FD15B001902EB -:10BD700002F10102FAD5C2F101021044C6E7014600 -:10BD8000FCF7D6F80146FCF791FAF8BD0122104401 -:10BD9000BCE700BF2DE9F84320F00046B6F1485F4C -:10BDA00005460F4649DAFCF793FB002800F09D801A -:10BDB00029462846FCF7C6F94E490446FCF7C2F965 -:10BDC0004D49FCF7B7F82146FCF7BCF94B49FCF7A5 -:10BDD000AFF82146FCF7B6F94949FCF7ABF8214624 -:10BDE000FCF7B0F94749FCF7A3F82146FCF7AAF99C -:10BDF0004549FCF79FF82146FCF7A4F98046204608 -:10BE00004FF07C51FCF79EF9414606462046FCF770 -:10BE100099F9394604462846FCF794F9014620462C -:10BE2000FCF786F801463046FCF782F801464FF0F1 -:10BE30007E50FCF77DF8BDE8F8830146FCF782F9F7 -:10BE40002C490446FCF77EF92B49FCF773F8214690 -:10BE5000FCF778F92949FCF76BF82146FCF772F9F1 -:10BE60002749FCF767F82146FCF76CF92549FCF7F0 -:10BE70005FF82146FCF766F92349FCF75BF8214699 -:10BE8000FCF760F9214B80469E42B8DD204B9E4274 -:10BE900027DC06F17F4631464FF07E50FCF748F82C -:10BEA000814620464FF07C51FCF74CF93146FCF7B7 -:10BEB0003FF8414606462046FCF744F93946044619 -:10BEC0002846FCF73FF901462046FCF731F80146C9 -:10BED0003046FCF72DF801464846FCF729F8BDE846 -:10BEE000F883DFF834900B4EDBE74FF07E50BDE86F -:10BEF000F88300BF4ED747ADF6740F317CF2933410 -:10BF0000010DD037610BB63AABAA2A3D9999993EFB -:10BF10000000483F0000903E0000383F2DE9F04F00 -:10BF2000DFB00B93013B0293D31E48BF131DB84CE7 -:10BF300006466898DB1054F8204023EAE3730C931C -:10BF4000DB4302EBC30308940693089C029B0C9A04 -:10BF50001D190991C3EB02071DD4699C3D4404EBF4 -:10BF6000870901354FF0000822AC0AE059F80800B3 -:10BF7000FCF794F80137AF4244F8080008F10408D0 -:10BF800009D0002FF2DA01370020AF4244F8080050 -:10BF900008F10408F5D1089A002AC0F2DF82089A55 -:10BFA0000B9B02F101089C0022AF4FEA880827444E -:10BFB0000025029A002AC0F2F28105EB070B4FF030 -:10BFC00000094FF0000A56F809005BF8041DFCF761 -:10BFD000B9F801465046FBF7ADFF09F10409A14548 -:10BFE0008246F0D14AA840F805A004354545E0D185 -:10BFF000089A0EAB03EB82030D9391464FEA890337 -:10C000000793079A5EAB1344B9F1000F53F850AC95 -:10C0100023DD0DF134084AAF174490440DAD4FF0C5 -:10C020006E515046FCF78EF8FCF752FAFCF736F8E2 -:10C030004FF087418346FCF785F801465046FBF7F1 -:10C0400077FFFCF745FA594645F8040F57F8040DF9 -:10C05000FBF770FF45458246E1D15046069900F056 -:10C060008DFC4FF078510546FCF76CF800F026FC8B -:10C070004FF08241FCF766F801462846FBF758FF6F -:10C080000546FCF725FA8246FCF708F801462846E3 -:10C09000FBF74EFF069A8046002A40F3678109F1BC -:10C0A000FF310EA850F82130C2F1080043FA00F227 -:10C0B00002FA00F01B1A06989244C0F1070743FAEF -:10C0C00007F70EA840F82130002F32DDB9F1000F3C -:10C0D0000AF1010A40F375810EAB079A1946114423 -:10C0E000002507E0C2F5807012B143F8040C012569 -:10C0F0008B420BD053F8042B002DF3D0C2F1FF027A -:10C100008B4243F8042C4FF00105F3D1069B002B22 -:10C110000DDD012B00F03281022B08D109F1FF3334 -:10C120000EA951F8232002F03F0241F82320022FEC -:10C1300070D040460021FCF799F9002800F0838078 -:10C14000089A09F1FF35AA420DDC079A0EAB0D984B -:10C150001344002253F8041D834242EA0102F9D13C -:10C16000002A40F0E481089B0EA85A1E50F82230A5 -:10C17000002B40F0F18100EB8202012352F8041DF4 -:10C1800001330029FAD04B4499450A933DDADDF892 -:10C190002CA022AACA44DDF8308002EB8A02C844EF -:10C1A000C9EB0309131D03920593699A079B4FEA94 -:10C1B00089094AAF02EB8808CDF810901F4400258A -:10C1C00058F8040FFBF76AFF029B039A002B5051AB -:10C1D0004FF0000B13DBDDF814A04FF00009AA4468 -:10C1E00056F809005AF8041DFBF7ACFF0146584603 -:10C1F000FBF7A0FE09F10409A1458346F0D1049A9A -:10C200000435954247F804BFDAD1DDF82890F5E609 -:10C21000D0F3000841464FF07E50FBF789FE804680 -:10C22000002D86D006994FF07E5000F0A7FB014606 -:10C230004046FBF77DFE804640460021FCF716F99C -:10C2400000287FF47DAF069B40465942CDF808A0F8 -:10C2500000F094FB4FF087410446FCF725F90028D5 -:10C2600000F07F814FF06E512046FBF76BFFFCF72B -:10C270002FF9FBF713FF4FF087410546FBF762FFED -:10C2800001462046FBF754FEFCF722F90EAB43F8BB -:10C2900029002846FCF71CF9069C09F10105083421 -:10C2A0000EA9069441F8250006994FF07E5000F043 -:10C2B00065FB002D04464FDB6E1C4FEA8508C6EB7C -:10C2C000867A0DF138094AABC1444FEA8A0A98448C -:10C2D0004FF0000B59F80B00FBF7E0FE2146FBF78F -:10C2E00031FF4FF06E5148F80B002046FBF72AFF54 -:10C2F000ABF1040BD3450446ECD1DFF88C92DDF8AA -:10C3000020A00024B34603950497BAF1000FB8BFEC -:10C31000002515DB00263746002501E0A7420FDC8B -:10C3200058F8061059F80600FBF70CFF014628469E -:10C33000FBF700FE0137BA45054606F10406EDDAC3 -:10C340005EA800EB84030134A345A8F1040843F878 -:10C35000A05CDAD1039D049F689C032C00F29880B6 -:10C36000DFE814F0CB009C009C00310010D109F1F3 -:10C37000FF330EA951F823703F12A5E609F1FF33F0 -:10C380000EA850F8232002F07F0240F82320CEE6CA -:10C390004FF07C51FCF788F858B90746C9E64FF0D2 -:10C3A000000A4AA840F805A0043545457FF401AECF -:10C3B0001EE6B9F1000F4FF002070AF1010A3FF73C -:10C3C0008BAE0025A2E6002D40F3DC804FEA850B02 -:10C3D0005EAB36AE05F1FF3A5B4406EB8A0A53F8D2 -:10C3E000A08C54465B4635AABB462F4600E0C846A3 -:10C3F00054F804594146284601920093FBF79AFDF0 -:10C40000814649462846FBF793FD4146FBF792FDDE -:10C41000019AC4F804909442A060009BE7D13D4685 -:10C42000012D5F469B4640F3AD805EAB9B445BF8BD -:10C43000A04C00E044465AF8049921464846FBF7D0 -:10C4400079FD804641464846FBF772FD2146FBF7E1 -:10C4500071FD5645CAF80480CAF80800EAD16C1C80 -:10C4600006EB84040020083654F8041DFBF762FD37 -:10C47000B442F9D1002F7ED0369A379B099C00F147 -:10C48000004002F1004203F10043A06022606360BB -:10C49000029A02F007005FB0BDE8F08F002DB8BF30 -:10C4A00000200ADB36AE6C1C002006EB840454F836 -:10C4B000041DFBF73FFDB442F9D1002F35D000F148 -:10C4C0000043099C014623603698FBF731FD002D9F -:10C4D00008DD36AC04EB850554F8041FFBF72AFD94 -:10C4E000AC42F9D10FB100F10040099A5060029AB4 -:10C4F00002F007005FB0BDE8F08F002D39DB6C1C47 -:10C5000036AE002006EB840454F8041DFBF712FD40 -:10C51000B442F9D10FB100F10040099A1060029ABB -:10C5200002F007005FB0BDE8F08F0346C9E7069A46 -:10C530000EAC54F82530083ACDF808A00692002B2E -:10C540007FF4B2AE04EB850353F8041D013D083AB5 -:10C550000029F9D00692A7E6012314E60B9B9C0064 -:10C5600046E52046FBF7B4FF0EAA4D4642F82900E7 -:10C570009AE60020CEE7099C369A379BA06022609D -:10C58000636085E7002075E7DCF300082DE9F843D8 -:10C5900020F00043B3F1485F04460F46904603DAAB -:10C5A000FBF796FF002857D021462046FBF7CAFD2F -:10C5B00021460546FBF7C6FD294906462846FBF7F6 -:10C5C000C1FD2849FBF7B4FC2946FBF7BBFD264912 -:10C5D000FBF7B0FC2946FBF7B5FD2449FBF7A8FCA7 -:10C5E0002946FBF7AFFD2249FBF7A4FC8146B8F1D1 -:10C5F000000F22D038464FF07C51FBF7A3FD49468F -:10C6000080463046FBF79EFD01464046FBF790FC16 -:10C610002946FBF797FD3946FBF78AFC1549054685 -:10C620003046FBF78FFD01462846FBF783FC0146A9 -:10C630002046FBF77DFCBDE8F88349462846FBF71A -:10C6400081FD0C49FBF774FC3146FBF77BFD21466D -:10C65000FBF770FCBDE8F8832046BDE8F88300BF17 -:10C66000D3C92E2F342FD7321BEF3836010D503956 -:10C670008988083CABAA2A3E002070470020014967 -:10C68000704700BF0000F87F2DE9F04120F0004521 -:10C69000B5F1A14F0446064608DBB5F1FF4F6FDC4C -:10C6A000002840F3A0806F48BDE8F0816E4B9D42AA -:10C6B00077DCB5F1445F68DB4FF0FF372146204659 -:10C6C000FBF740FD01468046FBF73CFD6749054608 -:10C6D000FBF738FD6649FBF72DFC2946FBF732FDD9 -:10C6E0006449FBF727FC2946FBF72CFD6249FBF761 -:10C6F00021FC2946FBF726FD6049FBF71BFC294678 -:10C70000FBF720FD5E49FBF715FC4146FBF71AFDE0 -:10C710005C4980462846FBF715FD5B49FBF708FCA2 -:10C720002946FBF70FFD5949FBF702FC2946FBF7A9 -:10C7300009FD5749FBF7FCFB2946FBF703FD55496B -:10C74000FBF7F6FB2946FBF7FDFC7B1C0146404648 -:10C750004CD0FBF7EFFB2146FBF7F4FC4E4B4F4D63 -:10C7600053F82710FBF7E4FB2146FBF7E1FB0146FA -:10C7700055F82700FBF7DCFB002E30DBBDE8F0812D -:10C780000146FBF7D7FBBDE8F0814549FBF7D2FB3B -:10C790004FF07E51FBF792FE00288DD02046BDE879 -:10C7A000F08100F087F83F4B04469D4229DCA3F559 -:10C7B000D0039D4244DC0146FBF7BCFB4FF07E51A9 -:10C7C000FBF7B6FB4FF0804105462046FBF7B2FB76 -:10C7D00001462846FBF76AFD002704466EE700F194 -:10C7E0000040BDE8F0813048BDE8F081FBF7A2FBD6 -:10C7F0002146FBF7A7FC01462046FBF799FBBDE865 -:10C80000F0812A4B9D4214DC4FF07F51FBF790FBE7 -:10C810004FF07F5105462046FBF794FC4FF07E51C8 -:10C82000FBF788FB01462846FBF740FD022704463C -:10C8300044E701461E48FBF739FD032704463DE760 -:10C840004FF07E51FBF774FB4FF07E5105462046BA -:10C85000FBF770FB01462846FBF728FD012704463D -:10C860002CE700BFDB0FC93FFFFFDF3ED769853CE8 -:10C8700059DA4B3D356B883D6E2EBA3D2549123E47 -:10C88000ABAAAA3E21A215BD6BF16E3D95879D3DD9 -:10C89000388EE33DCDCC4C3E08F4000818F4000877 -:10C8A000CAF24971FFFF973FDB0FC9BFFFFF1B4073 -:10C8B000000080BF20F00040704700BF2DE9F0412C -:10C8C00020F00047FD0D7F3D162D064613DC002DA0 -:10C8D00080461BDB194F2F41074214D01849FBF744 -:10C8E00029FB0021FBF7EAFD68B1002E1BDB28EADB -:10C8F0000700BDE8F081B7F1FF4F04D30146FBF715 -:10C9000019FBBDE8F0813046BDE8F0810C49FBF72A -:10C9100011FB0021FBF7D2FD0028F4D0002E08DB2C -:10C920000020BDE8F0814FF4000343FA05F5A84468 -:10C93000DDE7002FE7D00348BDE8F081FFFF7F006F -:10C94000CAF24971000080BF30F0004001D10220DE -:10C950007047A0F50003B3F1FE4F01D204207047E9 -:10C96000054B421E9A4201D803207047B0F1FF43A5 -:10C9700058425841704700BFFEFF7F0038B530F085 -:10C980000044024603460D4614D0B4F1FF4F0DD2C9 -:10C99000B4F5000F0FD3E40D2C44FE2C2EDC002C3C -:10C9A0001DDD23F0FF4343EAC45038BD0146FBF7C9 -:10C9B000C1FA38BD38BD4FF09841FBF7C3FB194BA6 -:10C9C00002469D4207DBC0F3C7540346193CE3E728 -:10C9D000154800F02DF81449FBF7B4FB38BD14F1ED -:10C9E000160F13DA4CF250339D421146F0DD0F481A -:10C9F00000F01EF80D49FBF7A5FB38BD11460B48AA -:10CA000000F016F80949FBF79DFB38BD04F1190049 -:10CA100023F0FF4343EAC0504FF04C51FBF792FB29 -:10CA200038BD00BFB03CFFFF6042A20DCAF24971A1 -:10CA300001F0004120F0004008437047014B1868A6 -:10CA4000704700BFEC000020524F4C4C3B50495403 -:10CA500043483B5941573B414C543B506F733B500B -:10CA60006F73523B4E6176523B4C4556454C3B4DA5 -:10CA700041473B56454C3B00000000009EDD00084E -:10CA80000000000001000000A3DD0008010000001C -:10CA900002000000AADD0008020000000300000000 -:10CAA000B3DD00080300000004000000B9DD000849 -:10CAB0000500000005000000BEDD000806000000C3 -:10CAC00006000000C8DD00080700000007000000A5 -:10CAD000D1DD00080800000008000000DADD0008D1 -:10CAE0000900000009000000E3DD00080A00000062 -:10CAF0000A000000EDDD00080B0000000B00000044 -:10CB0000F7DD00080C0000000C00000001DE00084A -:10CB10000D0000000D00000009DE00080E000000FE -:10CB20000E00000011DE00080F0000000F000000E2 -:10CB300019DE0008100000001000000022DE0008CE -:10CB4000110000001100000029DE000812000000A2 -:10CB50001200000033DE0008130000001300000084 -:10CB60003BDE0008140000001400000046DE000850 -:10CB7000150000001500000050DE0008160000003F -:10CB80001600000000000000FF00000091DD00081A -:10CB900088DD00087CDD0008001001400020100244 -:10CBA00000100140004010020000000000000000E2 -:10CBB0000301000000D1000804000000C0D00008FC -:10CBC0000400000080D000080201000060D00008CE -:10CBD00000010000000000000600000000D0000876 -:10CBE00006000000A0CF00080101000000000000C6 -:10CBF0000400000060CF00080600000000CF00081D -:10CC00000800000080CE00080800000000CE0008E8 -:10CC10000800000080CD00080101000000000000B5 -:10CC20000001000000000000000100000000000002 -:10CC30000400000040CD000806000000E0CC000821 -:10CC4000000100000000000002010000C0CC00084C -:10CC500001010000000000000000000000000000D2 -:10CC6000A8CC00089CCC00089ACC000898CC0008FE -:10CC70002D170008E9160008C51600089D160008C3 -:10CC80008D1600081526000819170008351600082B -:10CC90000D170008FF160008FFFFFFFF0001060345 -:10CCA0000D0307030C03FFFF00020102020203024F -:10CCB0000802090206030D0307030C03FFFF00002F -:10CCC0000000803F0000000000000000000080BF66 -:10CCD0000000803F00000000000000000000803FD6 -:10CCE0000000803F000080BF0000803F000080BF48 -:10CCF0000000803F000080BF000080BF0000803F38 -:10CD00000000803F0000803F0000803F0000803F27 -:10CD10000000803F0000803F000080BF000080BF17 -:10CD20000000803F00000000000000000000000044 -:10CD30000000803F00000000000000000000000034 -:10CD40000000803F000000000000803F0000803FA6 -:10CD50000000803F000080BF000080BF0000000096 -:10CD60000000803F000000000000803F000080BF06 -:10CD70000000803F0000803F000080BF0000008076 -:10CD80000000803F0000803F000000BF0000803FA7 -:10CD90000000803F000000BF000080BF0000803F17 -:10CDA0000000803F000080BF0000003F0000803F87 -:10CDB0000000803F0000003F0000803F0000803FF7 -:10CDC0000000803F0000003F000080BF000080BFE7 -:10CDD0000000803F000080BF000000BF000080BF57 -:10CDE0000000803F000000BF0000803F000080BFC7 -:10CDF0000000803F0000803F0000003F000080BF37 -:10CE00000000803FF704353FF70435BF0000803F46 -:10CE10000000803FF70435BFF70435BF0000803FB6 -:10CE20000000803FF70435BFF704353F0000803F26 -:10CE30000000803FF704353FF704353F0000803F96 -:10CE40000000803F00000000000080BF000080BFA5 -:10CE50000000803F000080BF00000000000080BF95 -:10CE60000000803F000000000000803F000080BF05 -:10CE70000000803F0000803F00000000000080BFF5 -:10CE80000000803F000080BF0000803F000080BFA6 -:10CE90000000803F000080BF000080BF0000803F96 -:10CEA0000000803F0000803F0000803F0000803F86 -:10CEB0000000803F0000803F000080BF000080BF76 -:10CEC0000000803F000080BF0000803F0000803FE6 -:10CED0000000803F000080BF000080BF000080BFD6 -:10CEE0000000803F0000803F0000803F000080BFC6 -:10CEF0000000803F0000803F000080BF0000803FB6 -:10CF00000000803F000000BFD0B35D3F0000803FC5 -:10CF10000000803F000000BFD0B35DBF0000803F35 -:10CF20000000803F0000003FD0B35D3F000080BFA5 -:10CF30000000803F0000003FD0B35DBF000080BF15 -:10CF40000000803F000080BF00000000000080BFA4 -:10CF50000000803F0000803F000000000000803F94 -:10CF60000000803F000000000000803F000080BF04 -:10CF70000000803F000080BF000080BF0000000074 -:10CF80000000803F000000000000803F0000803F64 -:10CF90000000803F0000803F000080BF00000000D4 -:10CFA0000000803FD0B35DBF0000003F0000803F25 -:10CFB0000000803FD0B35DBF000000BF000080BF15 -:10CFC0000000803FD0B35D3F0000003F0000803F85 -:10CFD0000000803FD0B35D3F000000BF000080BF75 -:10CFE0000000803F00000000000080BF0000803F84 -:10CFF0000000803F000000000000803F000080BF74 -:10D000000000803F00000000A8AAAA3F0000803F67 -:10D010000000803F000080BFB0AA2ABF000080BF90 -:10D020000000803F0000803FB0AA2ABF000080BF00 -:10D030000000803F00000000A8AAAA3F000080BFB7 -:10D040000000803F000080BFB0AA2ABF0000803FE0 -:10D050000000803F0000803FB0AA2ABF0000803F50 -:10D060000000803F0000803F000000000000000042 -:10D070000000803F000080BF0000000000000000B2 -:10D080000000803F000080BF0000803F000080BFA4 -:10D090000000803F000080BF000080BF0000803F94 -:10D0A0000000803F0000803F0000803F0000803F84 -:10D0B0000000803F0000803F000080BF000080BF74 -:10D0C0000000803F000000000000803F000080BFA3 -:10D0D0000000803F000080BF000000000000803F93 -:10D0E0000000803F0000803F000000000000803F03 -:10D0F0000000803F00000000000080BF000080BFF3 -:10D100000000803F00000000A8AAAA3F0000000025 -:10D110000000803F000080BFB0AA2ABF00000000CE -:10D120000000803F0000803FB0AA2ABF000000003E -:10D13000000000008025000000C201000600000081 -:10D14000010000008025000000C20100070000006F -:10D1500001000102000103000104000105000106B5 -:10D1600000010700010800010900010A00010B008D -:10D17000010C01031DE2000822E2000826E200087B -:10D1800039E200082BE2000831E2000835E200082D -:10D1900000000000B9E10008D9E10008E1E1000861 -:10D1A000E9E10008F1E10008F8E1000803E2000805 -:10D1B0000BE2000813E2000818E20008000000007B -:10D1C00043E200084CE20008FD5C000870E2000841 -:10D1D00074E20008155C00088AE200088FE200088B -:10D1E000D1570008D0E10008A3E20008B1400008D0 -:10D1F000C0E20008C5E20008E5380008F4E20008D3 -:10D20000B9E100082D640008F9E2000801E3000814 -:10D21000615A000815E3000819E300083D550008AD -:10D220002CE30008B9E100084535000831E30008A7 -:10D2300035E300082D5700089DE2000851E300087F -:10D24000D153000864E300086AE300086D5B00083E -:10D25000C9EC000885E300089938000894E3000849 -:10D2600085E3000815340008A0E30008A5E30008E2 -:10D27000BD62000886E60008B5E30008995500087D -:10D28000E3E30008D7E300086D3400088FEA0008E4 -:10D29000B9E10008E533000893E4000897E40008CA -:10D2A0009DE40008A3E40008A6E40008ADE400083B -:10D2B000B0E40008B5E40008C1E40008C4E40008D4 -:10D2C000CAE40008D1E40008DBE40008E5E4000853 -:10D2D000EEE40008FCE4000808E500080FE500089B -:10D2E00015E5000822E500082DE500083AE50008EC -:10D2F00000000000EAE30008F1E30008F6E300089C -:10D3000007E4000811E400081CE4000827E4000812 -:10D3100031E2000832E400082BE200083BE4000898 -:10D3200045E4000853E4000856E4000866E40008F9 -:10D330006DE4000876E4000880E4000888E4000852 -:10D34000000000001E1E6464646464649001C800F0 -:10D35000C800C800C800C800C800C800C8006400F1 -:10D360000000C800C800C800C80032000200000069 -:10D370008025000000C20100000000002000000025 -:10D380008025000000C201000100000040000000F4 -:10D390008025000000C20100000000000100000024 -:10D3A0008025000000C20100000000001000000005 -:10D3B0008025000000C201000003000004000000FE -:10D3C00080250000004B0000000000000800000065 -:10D3D00000E1000000E10000000400006D5E0008B4 -:10D3E0006B1700083917000815490008871700084F -:10D3F0001149000800540040000C0140400080002A -:10D400001F2000000000200000580040000C0140D8 -:10D41000000400082122000000004000C2E80008CB -:10D4200044000000B00F002000000000282300008E -:10D43000CBE8000841000000B20F0020000000000F -:10D4400001000000D9E8000844000000BE100020E0 -:10D45000B0040000A4060000E0E80008440000005A -:10D46000C010002000000000D0070000EAE800081B -:10D4700044000000C210002000000000D00700009F -:10D48000F4E8000842000000C41000200000000082 -:10D490001200000001E9000842000000C510002051 -:10D4A00001000000FF0000000CE90008420000003D -:10D4B000C6100020000000000100000021E9000863 -:10D4C000440000007410002000000000D00700009D -:10D4D0002EE9000844000000761000200000000043 -:10D4E000D00700003BE9000844000000781000204D -:10D4F00000000000D007000047E9000844000000D9 -:10D500007A10002000000000D007000057E9000852 -:10D51000440000007C10002000000000D007000044 -:10D5200068E90008440000007E10002000000000B0 -:10D53000D007000073E900084400000080100020BC -:10D5400000000000D007000088E900084400000047 -:10D550008210002032000000007D000097E90008E2 -:10D56000440000008410002032000000F20100009E -:10D57000A6E9000841000000C710002000000000DC -:10D5800001000000B3E9000841000000C8100020BD -:10D590000000000001000000C6E900084100000092 -:10D5A000C910002000000000B4000000D2E900080B -:10D5B00041000000CA1000200000000064000000CC -:10D5C000DEE9000842000000CB100020FFFFFFFF53 -:10D5D00001000000F4E9000841000000CC10002028 -:10D5E00000000000090000000BEA000841000000F4 -:10D5F000CD100020000000000900000022EA000811 -:10D6000041000000E0100020300000007E0000001B -:10D6100033EA000850000000D0100020B0040000E1 -:10D6200000C2010040EA000850000000D4100020B1 -:10D63000B004000000C201004DEA000841000000F3 -:10D64000BC10002000000000030000005FEA00089A -:10D6500041000000E4100020000000000300000072 -:10D6600072EA000841000000E51000200000000000 -:10D670000100000083EA000841000000E6100020DD -:10D68000000000000100000097EA000860000000B0 -:10D69000E8100020A6FFFFFF5A000000AFEA0008D4 -:10D6A00060000000EC1000204CFFFFFFB400000001 -:10D6B000C7EA000841000000F01000200000000050 -:10D6C00001000000E0EA000841000000F110002025 -:10D6D0000000000001000000EBEA00084400000028 -:10D6E000B210002000000000204E0000FCEA0008FC -:10D6F00041000000A810002000000000FF00000012 -:10D7000007EB000841000000A91000200A000000FB -:10D71000320000001DEB000841000000AA100020AC -:10D720000A0000003200000033EB00084400000053 -:10D73000AC100020010000001027000047EB00089B -:10D7400044000000AE10002000000000720600003F -:10D750005CEB000841000000B01000200000000059 -:10D76000010000007AEB0008410000008610002054 -:10D77000000000000800000085EB000841000000E8 -:10D780008710002000000000080000008FEB000858 -:10D790004100000088100020000000000800000088 -:10D7A00099EB0008480000008A1000204CFFFFFFA2 -:10D7B00068010000AAEB0008480000008C1000205F -:10D7C0004CFFFFFF68010000BCEB000848000000B0 -:10D7D0008E1000204CFFFFFF68010000CCEB00081A -:10D7E000440000009A100020640000008403000040 -:10D7F000E2EB00084400000092100020000000004E -:10D8000000010000EBEB0008410000009810002030 -:10D810000000000080000000FBEB00084400000056 -:10D820009410002064000000E80300000CEC0008E5 -:10D83000440000009610002064000000E80300008F -:10D840001EEC0008810000005312002001000000BF -:10D85000FA00000030EC00088100000054120020A3 -:10D86000000000000100000027EC0008810000001B -:10D8700051120020000000002000000045EC0008CC -:10D88000810000005212002000000000640000002F -:10D8900052EC000881000000581200200000000037 -:10D8A000960000006CEC0008840000005612002076 -:10D8B000010000008403000086EC00084200000024 -:10D8C00090100020FFFFFFFF010000009CEC00080B -:10D8D00082000000A2120020FFFFFFFF01000000F5 -:10D8E000AAEC000882000000A31200200000000043 -:10D8F00001000000BCEC0008810000004411002081 -:10D900000000000002000000D1EC0008010100004E -:10D910001216002000000000FA000000D9EC0008F8 -:10D920000101000013160020000000006400000048 -:10D93000E1EC0008010100001416002000000000C6 -:10D9400064000000E9EC0008010100001516002049 -:10D950000000000064000000F2EC0008010100007B -:10D9600016160020000000006400000002ED000810 -:10D9700001010000171600200000000064000000F4 -:10D980000BED000801010000181600200000000047 -:10D990006400000014ED0008040100001A160020C5 -:10D9A000E8030000D007000023ED0008810000001C -:10D9B0009A12002000000000C800000032ED0008AC -:10D9C000810000009B12002000000000C800000041 -:10D9D00045ED0008840000009C120020E8030000D0 -:10D9E000D007000057ED0008840000009E120020C0 -:10D9F00064000000D007000069ED0008840000000A -:10DA0000A012002064000000B80B00007BED0008AD -:10DA100081000000A412002000000000FF000000B0 -:10DA200088ED000841000000911000200000000077 -:10DA30000900000095ED0008810000004C11002055 -:10DA400000000000FA000000A4ED000881000000C2 -:10DA5000541100200000000064000000B3ED000835 -:10DA6000810000005511002000000000640000004B -:10DA7000C1ED0008A00000005011002001000000CE -:10DA800014000000D1ED00088100000068110020A2 -:10DA90000000000001000000E0ED00088800000028 -:10DAA0004A110020D4FEFFFF2C010000EFED00081A -:10DAB0008800000048110020D4FEFFFF2C01000068 -:10DAC000FDED00088100000058110020000000005A -:10DAD000300000000BEE0008A00000005C110020E8 -:10DAE00000000000010000001AEE0008A000000085 -:10DAF00060110020000000000100000026EE000878 -:10DB0000A0000000641100200000000001000000DF -:10DB100032EE00088800000046110020B0B9FFFF77 -:10DB20005046000042EE000881000000F410002082 -:10DB3000000000000200000051EE0008810000001B -:10DB4000F910002000000000C800000059EE000895 -:10DB5000810000000311002000000000C800000048 -:10DB6000B4EB0008810000000D110020000000004F -:10DB7000C800000061EE000881000000F8100020DD -:10DB800000000000C800000068EE000881000000EE -:10DB90000211002000000000C8000000A3EB0008F4 -:10DBA000810000000C11002000000000C8000000EF -:10DBB0006FEE000881000000FA1000200000000055 -:10DBC000C800000075EE000881000000041100206C -:10DBD00000000000C8000000C6EB00088100000043 -:10DBE0000E11002000000000C80000007BEE0008BD -:10DBF000A00000001C1100200000000064000000D4 -:10DC000084EE0008A00000002811002000000000A1 -:10DC1000640000008DEE0008A00000003411002018 -:10DC2000000000006400000096EE0008A000000064 -:10DC30001811002000000000640000009EEE0008A3 -:10DC4000A00000002411002000000000640000007B -:10DC5000A6EE0008A0000000301100200000000027 -:10DC600064000000AEEE0008A000000020110020BB -:10DC70000000000064000000B5EE0008A0000000F5 -:10DC80002C1100200000000064000000BCEE000821 -:10DC9000A000000038110020000000006400000017 -:10DCA000C3EE0008A00000004011002000000000AA -:10DCB0000A000000D1EE0008A00000003C11002086 -:10DCC000000000000A000000DDEE000881000000F6 -:10DCD000FB10002000000000C8000000E3EE000878 -:10DCE000810000000511002000000000C8000000B5 -:10DCF000E9EE0008810000000F1100200000000084 -:10DD0000C8000000EFEE000881000000FF100020B6 -:10DD100000000000C8000000F7EE000881000000CD -:10DD20000911002000000000C8000000FFEE0008FC -:10DD3000810000001311002000000000C800000056 -:10DD400007EF000881000000011100200000000022 -:10DD5000C80000000DEF0008810000000B1100203A -:10DD600000000000C800000013EF00088100000060 -:10DD70001511002000000000C80000004465632069 -:10DD8000203720323031340032323A31343A3039AF -:10DD9000003232376238396500434A4D3100415212 -:10DDA0004D3B00414E474C453B00484F52495A4F6E -:10DDB0004E3B004241524F3B004D41473B004845DE -:10DDC0004144465245453B004845414441444A3B55 -:10DDD0000043414D535441423B0043414D5452494D -:10DDE000473B0047505320484F4D453B0047505359 -:10DDF00020484F4C443B0050415353544852553BEC -:10DE0000004245455045523B004C45444D41583B2E -:10DE1000004C45444C4F573B004C4C4947485453E9 -:10DE20003B0043414C49423B00474F5645524E4F01 -:10DE3000523B004F53442053573B0054454C454DF3 -:10DE4000455452593B004155544F54554E453B00A3 -:10DE5000534F4E41523B000000000040000801407B -:10DE600001000000001C00280000004000080140E4 -:10DE700002000000041C00280000004000080140CF -:10DE800004000000081C00280000004000080140B9 -:10DE9000080000000C1C002800040040000801409D -:10DEA00040000000001D0028000400400008014060 -:10DEB00080000000041D002800040040000C014008 -:10DEC00001000000081D002800040040000C014073 -:10DED000020000000C1D0028002C01400008014039 -:10DEE00000010000001B0128002C01400008014037 -:10DEF000000800000C1B012800080040000C014035 -:10DF000040000000001E002800080040000C0140F6 -:10DF100080000000041E002800080040000C0140A2 -:10DF200000010000081E002800080040000C01400D -:10DF3000000200000C1E00283031323334353637F1 -:10DF400038394142434445464748494A4B4C4D4E77 -:10DF50004F505152535455565758595A00004F205C -:10DF600010044302400108436C65616E666C69678A -:10DF700068742F2573202573202F202573202825D2 -:10DF80007329007261746570726F66696C65202513 -:10DF9000640D0A0053797374656D20557074696D52 -:10DFA000653A202564207365636F6E64732C205678 -:10DFB0006F6C746167653A202564202A20302E3109 -:10DFC0005620282564532062617474657279290D86 -:10DFD0000A004350552025644D487A2C206465740E -:10DFE00065637465642073656E736F72733A2000A5 -:10DFF0002573200041434348573A202573002E25BE -:10E0000063004379636C652054696D653A2025642B -:10E010002C20493243204572726F72733A20256476 -:10E020002C20636F6E6669672073697A653A2025D4 -:10E03000640D0A00417661696C61626C6520636FF2 -:10E040006D6D616E64733A0D0A0025730925730DB9 -:10E050000A006D6173746572007261746573000DFE -:10E060000A232076657273696F6E0D0A000D0A230C -:10E070002064756D70206D61737465720D0A000DFA -:10E080000A23206D697865720D0A006D69786572E2 -:10E090002025730D0A00636D697820256400636D87 -:10E0A000697820256420302030203020300D0A008F -:10E0B0000D0A0D0A2320666561747572650D0A00EC -:10E0C00066656174757265202D25730D0A0066659D -:10E0D00061747572652025730D0A000D0A0D0A23FF -:10E0E000206D61700D0A006D61702025730D0A00AE -:10E0F0000D0A232064756D702070726F66696C65FF -:10E100000D0A000D0A232070726F66696C650D0A96 -:10E11000000D0A23206175780D0A000D0A23206185 -:10E12000646A72616E67650D0A000D0A23206475CA -:10E130006D702072617465730D0A000D0A232072E0 -:10E1400061746570726F66696C650D0A000D0A4531 -:10E150006E746572696E6720434C49204D6F64652B -:10E160002C20747970652027657869742720746F76 -:10E170002072657475726E2C206F72202768656C32 -:10E1800070270D0A000D0A2320000D1B5B4B001B9E -:10E190005B324A1B5B313B314800556E6B6E6F77CB -:10E1A0006E20636F6D6D616E642C20747279202710 -:10E1B00068656C70270008200800414554523132D0 -:10E1C000333400526573657474696E6720746F2010 -:10E1D00064656661756C7473004144584C33343522 -:10E1E000004D505536303530004D4D41383435787E -:10E1F00000424D41323830004C534D333033444CA3 -:10E200004843004D505536303030004D505536356E -:10E2100030300046414B45004E6F6E650047595205 -:10E220004F00414343004241524F00534F4E415231 -:10E2300000475053004750532B4D414700434A4D30 -:10E2400043550061646A72616E67650073686F7739 -:10E250002F7365742061646A7573746D656E7420C4 -:10E2600072616E6765732073657474696E6773009D -:10E270006175780073686F772F73657420617578A6 -:10E280002073657474696E677300636D69780064E8 -:10E29000657369676E20637573746F6D206D69783F -:10E2A000657200726573657420746F2064656661C1 -:10E2B000756C747320616E64207265626F6F740098 -:10E2C00064756D70007072696E7420636F6E66693C -:10E2D00067757261626C652073657474696E6773CB -:10E2E00020696E2061207061737461626C652066C4 -:10E2F0006F726D006578697400666561747572652A -:10E30000006C697374206F72202D76616C206F72BF -:10E310002076616C006765740067657420766172B1 -:10E320006961626C652076616C75650068656C700A -:10E33000006D6170006D617070696E67206F66209E -:10E340007263206368616E6E656C206F72646572C3 -:10E35000006D69786572206E616D65206F72206C4A -:10E36000697374006D6F746F72006765742F7365E5 -:10E3700074206D6F746F72206F7574707574207671 -:10E38000616C756500696E64657820283020746F53 -:10E39000203229007261746570726F66696C650065 -:10E3A00073617665007361766520616E64207265C5 -:10E3B000626F6F74006E616D653D76616C7565208E -:10E3C0006F7220626C616E6B206F72202A20666F04 -:10E3D00072206C6973740073686F7720737973743B -:10E3E000656D207374617475730052585F50504DA1 -:10E3F000005642415400494E464C494748545F41FB -:10E4000043435F43414C0052585F53455249414C8E -:10E41000004D4F544F525F53544F50005345525686 -:10E420004F5F54494C5400534F4654534552494151 -:10E430004C004641494C534146450054454C454DDE -:10E44000455452590043555252454E545F4D455420 -:10E4500045520033440052585F504152414C4C45A4 -:10E460004C5F50574D0052585F4D5350005253531C -:10E47000495F414443004C45445F53545249500066 -:10E48000444953504C4159004F4E4553484F543125 -:10E4900032350054524900515541445000515541C4 -:10E4A00044580042490047494D42414C005936000A -:10E4B0004845583600464C59494E475F57494E47E4 -:10E4C000005934004845583658004F43544F583887 -:10E4D000004F43544F464C415450004F43544F4615 -:10E4E0004C41545800414952504C414E450048451A -:10E4F0004C495F3132305F4343504D0048454C49F1 -:10E500005F39305F44454700565441494C34004818 -:10E51000455836480050504D5F544F5F5345525652 -:10E520004F004455414C434F505445520053494EBF -:10E53000474C45434F5054455200435553544F4D5B -:10E5400000414552543132333435363738616263D5 -:10E5500064656667680043757272656E74206D69E4 -:10E560007865723A2025730D0A00417661696C6105 -:10E57000626C65206D69786572733A2000496E7629 -:10E58000616C6964206D6978657220747970650DBD -:10E590000A004D697865722073657420746F2025B8 -:10E5A000730D0A0020256420256400556E6B6E6F84 -:10E5B000776E207661726961626C65206E616D654F -:10E5C0000D0A0043757272656E7420736574746908 -:10E5D0006E67733A200D0A002573207365742074EA -:10E5E0006F200056616C75652061737369676E6D8D -:10E5F000656E74206F7574206F662072616E67653A -:10E600000D0A004D75737420626520616E79206F6C -:10E6100072646572206F6620414554523132333442 -:10E620000D0A0043757272656E74206173736967B9 -:10E630006E6D656E743A20004E4709004F4B09001D -:10E64000437573746F6D206D697865723A200D0A99 -:10E650004D6F746F720954687209526F6C6C095077 -:10E6600069746368095961770D0A002325643A09C2 -:10E67000002573090053616E6974792063686563CE -:10E680006B3A09007265736574006C6F6164004CCD -:10E690006F61646564202573206D69780D0A0057E9 -:10E6A000726F6E67206E756D626572206F66206195 -:10E6B0007267756D656E74732C206E65656473206A -:10E6C0006964782074687220726F6C6C2070697451 -:10E6D0006368207961770D0A004D6F746F72206E48 -:10E6E000756D626572206D75737420626520626558 -:10E6F000747765656E203120616E642025640D0A93 -:10E7000000456E61626C6564206665617475726552 -:10E71000733A2000417661696C61626C65206665C0 -:10E720006174757265733A2000496E76616C696434 -:10E730002066656174757265206E616D650D0A00F5 -:10E7400047505320756E617661696C61626C650D2E -:10E750000A00534F4E415220756E617661696C61BB -:10E76000626C650D0A0044697361626C6564200027 -:10E77000456E61626C6564200055736167653A0D92 -:10E780000A6D6F746F7220696E646578205B7661C4 -:10E790006C75655D202D2073686F77205B6F72202C -:10E7A0007365745D206D6F746F722076616C756532 -:10E7B0000D0A004E6F2073756368206D6F746F7261 -:10E7C0002C207573652061206E756D626572205B0B -:10E7D000302C2025645D0D0A004D6F746F7220256A -:10E7E00064206973207365742061742025640D0AA8 -:10E7F00000496E76616C6964206D6F746F7220766B -:10E80000616C75652C20313030302E2E3230303036 -:10E810000D0A0053657474696E67206D6F746F72B2 -:10E8200020256420746F2025640D0A00617578200E -:10E8300025752025752025752025752025750D0A3F -:10E8400000696E6465783A206D7573742062652086 -:10E850003C2025750D0A0061646A72616E6765204F -:10E8600025752025752025752025752025752025E1 -:10E87000752025750D0A00736574202573203D20D1 -:10E88000000D0A5265626F6F74696E67005361769E -:10E89000696E67000D0A4C656176696E6720434CAE -:10E8A00049206D6F64652C20756E736176656420F8 -:10E8B0006368616E676573206C6F73742E0D0A0058 -:10E8C0002E006C6F6F7074696D6500656D665F61B9 -:10E8D000766F6964616E6365006D69645F72630081 -:10E8E0006D696E5F636865636B006D61785F636817 -:10E8F00065636B00727373695F6368616E6E656CEC -:10E9000000727373695F7363616C6500696E707523 -:10E91000745F66696C746572696E675F6D6F64655C -:10E92000006D696E5F7468726F74746C65006D6100 -:10E93000785F7468726F74746C65006D696E5F6384 -:10E940006F6D6D616E640033645F64656164626104 -:10E950006E645F6C6F770033645F646561646261ED -:10E960006E645F686967680033645F6E65757472B2 -:10E97000616C0033645F6465616462616E645F74DE -:10E9800068726F74746C65006D6F746F725F70770E -:10E990006D5F7261746500736572766F5F70776D1D -:10E9A0005F726174650072657461726465645F6151 -:10E9B000726D0064697361726D5F6B696C6C5F731B -:10E9C000776974636800736D616C6C5F616E676C0E -:10E9D0006500666C6170735F73706565640066697D -:10E9E00078656477696E675F616C74686F6C645F8B -:10E9F0006469720073657269616C5F706F72745FD5 -:10EA0000315F7363656E6172696F0073657269610E -:10EA10006C5F706F72745F325F7363656E61726991 -:10EA20006F007265626F6F745F63686172616374B7 -:10EA30006572006D73705F62617564726174650008 -:10EA4000636C695F6261756472617465007365729D -:10EA500069616C72785F70726F7669646572007458 -:10EA6000656C656D657472795F70726F76696465E7 -:10EA7000720074656C656D657472795F7377697423 -:10EA800063680074656C656D657472795F696E7634 -:10EA9000657273696F6E006672736B795F64656629 -:10EAA00061756C745F6C617474697475646500661B -:10EAB00072736B795F64656661756C745F6C6F6EA1 -:10EAC000676974756465006672736B795F636F6FF5 -:10EAD0007264696E617465735F666F726D617400F4 -:10EAE0006672736B795F756E6974006261747465C8 -:10EAF00072795F63617061636974790076626174D1 -:10EB00005F7363616C6500766261745F6D61785FED -:10EB100063656C6C5F766F6C7461676500766261CB -:10EB2000745F6D696E5F63656C6C5F766F6C74614A -:10EB300067650063757272656E745F6D657465728A -:10EB40005F7363616C650063757272656E745F6D8F -:10EB5000657465725F6F6666736574006D756C745D -:10EB6000697769695F63757272656E745F6D6574EC -:10EB700065725F6F757470757400616C69676E5F44 -:10EB80006779726F00616C69676E5F6163630061D2 -:10EB90006C69676E5F6D616700616C69676E5F626B -:10EBA0006F6172645F726F6C6C00616C69676E5F3D -:10EBB000626F6172645F706974636800616C696739 -:10EBC0006E5F626F6172645F796177006D61785F1B -:10EBD000616E676C655F696E636C696E6174696FA5 -:10EBE0006E006779726F5F6C7066006D6F726F6E2A -:10EBF0005F7468726573686F6C64006779726F5FC9 -:10EC0000636D70665F666163746F72006779726FBF -:10EC10005F636D70666D5F666163746F7200616CD7 -:10EC2000745F686F6C645F6465616462616E6400E8 -:10EC3000616C745F686F6C645F666173745F636856 -:10EC4000616E6765007961775F6465616462616EBA -:10EC500064007468726F74746C655F636F72726560 -:10EC60006374696F6E5F76616C7565007468726F4E -:10EC700074746C655F636F7272656374696F6E5FE5 -:10EC8000616E676C65007961775F636F6E74726F38 -:10EC90006C5F646972656374696F6E007961775F38 -:10ECA000646972656374696F6E007472695F756E12 -:10ECB00061726D65645F736572766F00646566612D -:10ECC000756C745F726174655F70726F66696C6594 -:10ECD0000072635F726174650072635F6578706F64 -:10ECE000007468725F6D6964007468725F65787043 -:10ECF0006F00726F6C6C5F70697463685F726174CF -:10ED000065007961775F72617465007470615F722C -:10ED1000617465007470615F627265616B706F69C8 -:10ED20006E74006661696C736166655F64656C61D1 -:10ED300079006661696C736166655F6F66665F64C2 -:10ED4000656C6179006661696C736166655F7468A2 -:10ED5000726F74746C65006661696C736166655F7F -:10ED60006D696E5F75736563006661696C7361667A -:10ED7000655F6D61785F757365630067696D62617A -:10ED80006C5F666C616773006163635F6861726486 -:10ED900077617265006163635F6C70665F66616373 -:10EDA000746F720061636378795F64656164626146 -:10EDB0006E64006163637A5F6465616462616E645E -:10EDC000006163637A5F6C70665F6375746F66661B -:10EDD000006163635F756E61726D656463616C0091 -:10EDE0006163635F7472696D5F7069746368006109 -:10EDF00063635F7472696D5F726F6C6C00626172E5 -:10EE00006F5F7461625F73697A65006261726F5FE0 -:10EE10006E6F6973655F6C7066006261726F5F63CD -:10EE2000665F76656C006261726F5F63665F616CDE -:10EE300074006D61675F6465636C696E6174696FAE -:10EE40006E007069645F636F6E74726F6C6C657274 -:10EE500000705F706974636800695F7069746368EB -:10EE600000705F726F6C6C00695F726F6C6C007029 -:10EE70005F79617700695F79617700705F706974AD -:10EE800063686600695F70697463686600645F70D8 -:10EE9000697463686600705F726F6C6C6600695FAE -:10EEA000726F6C6C6600645F726F6C6C6600705F92 -:10EEB0007961776600695F7961776600645F79617F -:10EEC0007766006C6576656C5F686F72697A6F6EE5 -:10EED000006C6576656C5F616E676C6500705F6184 -:10EEE0006C7400695F616C7400645F616C740070C5 -:10EEF0005F6C6576656C00695F6C6576656C006457 -:10EF00005F6C6576656C00705F76656C00695F7636 -:10EF1000656C00645F76656C000020202020202056 -:10EF200020202028282828282020202020202020B9 -:10EF300020202020202020202020881010101010B9 -:10EF40001010101010101010101004040404040409 -:10EF500004040404101010101010104141414141EC -:10EF60004101010101010101010101010101010151 -:10EF700001010101011010101010104242424242E2 -:10EF80004202020202020202020202020202020221 -:10EF90000202020202101010102000000000000007 -:10EFA0000000000000000000000000000000000061 -:10EFB0000000000000000000000000000000000051 -:10EFC0000000000000000000000000000000000041 -:10EFD0000000000000000000000000000000000031 -:10EFE0000000000000000000000000000000000021 -:10EFF0000000000000000000000000000000000011 -:10F000000000000000000000000000000000000000 -:10F010000000000000000000000000000000004BA5 -:10F02000000000CB61636F73660000000000000009 -:10F030007371727466000000000FC93F000F4940F1 -:10F0400000CB9640000FC9400053FB4000CB164157 -:10F0500000ED2F41000F49410031624100537B41D7 -:10F06000003A8A4100CB9641005CA34100EDAF41DC -:10F07000007EBC41000FC94100A0D5410031E241F2 -:10F0800000C2EE410053FB4100F20342003A0A4243 -:10F090000083104200CB164200141D42005C234244 -:10F0A00000A5294200ED2F4200363642007E3C4248 -:10F0B00000C74242000F4942A2000000F9000000D0 -:10F0C000830000006E0000004E00000044000000BD -:10F0D0001500000029000000FC00000027000000CF -:10F0E00057000000D1000000F500000034000000CF -:10F0F000DD000000C0000000DB0000006200000036 -:10F1000095000000990000003C0000004300000052 -:10F110009000000041000000FE00000051000000CF -:10F1200063000000AB000000DE000000BB00000038 -:10F13000C500000061000000B700000024000000CE -:10F140006E0000003A000000420000004D00000088 -:10F15000D2000000E00000000600000049000000AE -:10F160002E000000EA00000009000000D1000000AD -:10F17000920000001C000000FE0000001D000000C6 -:10F18000EB0000001C000000B1000000290000009E -:10F19000A70000003E000000E80000008200000020 -:10F1A00035000000F50000002E000000BB0000004C -:10F1B0004400000084000000E90000009C00000002 -:10F1C0007000000026000000B40000005F00000096 -:10F1D0007E000000410000003900000091000000A6 -:10F1E000D60000003900000083000000530000003A -:10F1F00039000000F40000009C00000084000000C2 -:10F200005F0000008B000000BD000000F90000005E -:10F21000280000003B0000001F000000F800000074 -:10F2200097000000FF000000DE0000000500000065 -:10F23000980000000F000000EF0000002F00000009 -:10F24000110000008B0000005A0000000A000000BE -:10F250006D0000001F0000006D000000360000007F -:10F260007E000000CF00000027000000CB0000005F -:10F2700009000000B70000004F0000004600000039 -:10F280003F000000660000009E0000005F000000DC -:10F29000EA0000002D0000007500000027000000BB -:10F2A000BA000000C7000000EB000000E50000000D -:10F2B000F10000007B0000003D000000070000009E -:10F2C00039000000F70000008A0000005200000032 -:10F2D00092000000EA0000006B000000FB0000004C -:10F2E0005F000000B10000001F0000008D00000062 -:10F2F0005D00000008000000560000000300000050 -:10F300003000000046000000FC0000007B00000010 -:10F310006B000000AB000000F0000000CF00000018 -:10F32000BC000000200000009A000000F400000073 -:10F33000360000001D000000A9000000E3000000EE -:10F3400091000000610000005E000000E600000087 -:10F350001B0000000800000065000000990000008C -:10F36000850000005F00000014000000A000000005 -:10F3700068000000400000008D000000FF00000059 -:10F38000D8000000800000004D0000007300000065 -:10F390002700000031000000060000000600000009 -:10F3A0001500000056000000CA00000073000000B5 -:10F3B000A8000000C900000060000000E20000009A -:10F3C0007B000000C00000008C0000006B0000000B -:10F3D0000400000007000000090000000000C93F11 -:10F3E0000000F0390000DA370000A2330000842E5C -:10F3F0000000502B0000C2270000D0220000C41FD4 -:10F400000000C61B000044176937AC316821223365 -:10F41000B40F14336821A2333863ED3EDA0F493F4D -:08F420005E987B3FDA0FC93F43 -:08F42800D091FF7F01000000FC -:10F43000000100000000803F00000000000000000C -:10F4400000000000000000000000000001000000BB -:10F45000000000000000000000127A000000000020 -:10F460000000000001020304060708090103000070 -:10F470000000803F0000803F0000803F010000004E -:10F48000000102030401020304060708090204063E -:10F490000800DC05DC05DC05DC05DC05DC05DC053D -:10F4A000DC050000F949000899DD000803000000B0 -:10F4B00000A24A043DE2000819EF00080000000025 -:10F4C000000000000000000000000000000000003C -:10F4D00000000000000000000000000024E200081E -:10F4E000000000000000000000000000000000001C -:10F4F000000000000000000000000000000000000C -:10F5000000000000000000000000000000000000FB -:10F510000000000000000000000000008C0000203F -:04F5200001000000E6 -:0400000508000000EF -:00000001FF diff --git a/obj/cleanflight_NAZE.hex b/obj/cleanflight_NAZE.hex index 1adb6bc542..d86d63f7e5 100644 --- a/obj/cleanflight_NAZE.hex +++ b/obj/cleanflight_NAZE.hex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diff --git a/src/main/blackbox/blackbox.c b/src/main/blackbox/blackbox.c new file mode 100644 index 0000000000..836205e4a7 --- /dev/null +++ b/src/main/blackbox/blackbox.c @@ -0,0 +1,756 @@ +/* + * This file is part of Cleanflight. + * + * Cleanflight is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * Cleanflight is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with Cleanflight. If not, see . + */ + +#include +#include +#include + +#include "platform.h" +#include "version.h" + +#include "common/maths.h" +#include "common/axis.h" +#include "common/color.h" + +#include "drivers/accgyro.h" +#include "drivers/light_led.h" + +#include "drivers/gpio.h" +#include "drivers/system.h" +#include "drivers/serial.h" +#include "drivers/timer.h" +#include "drivers/pwm_rx.h" + +#include "common/printf.h" + +#include "flight/flight.h" +#include "sensors/sensors.h" +#include "sensors/boardalignment.h" +#include "sensors/sonar.h" +#include "sensors/compass.h" +#include "sensors/acceleration.h" +#include "sensors/barometer.h" +#include "sensors/gyro.h" +#include "sensors/battery.h" +#include "io/beeper.h" +#include "io/display.h" +#include "io/escservo.h" +#include "rx/rx.h" +#include "io/rc_controls.h" +#include "flight/mixer.h" +#include "flight/altitudehold.h" +#include "flight/failsafe.h" +#include "flight/imu.h" +#include "flight/autotune.h" +#include "flight/navigation.h" +#include "io/gimbal.h" +#include "io/gps.h" +#include "io/ledstrip.h" +#include "io/serial.h" +#include "io/serial_cli.h" +#include "io/serial_msp.h" +#include "io/statusindicator.h" +#include "rx/msp.h" +#include "telemetry/telemetry.h" + +#include "config/runtime_config.h" +#include "config/config.h" +#include "config/config_profile.h" +#include "config/config_master.h" + +#include "blackbox_fielddefs.h" +#include "blackbox.h" + +#define BLACKBOX_BAUDRATE 115200 +#define BLACKBOX_INITIAL_PORT_MODE MODE_TX + +static const char blackboxHeader[] = + "H Product:Blackbox flight data recorder by Nicholas Sherlock\n" + "H Blackbox version:1\n" + "H Data version:1\n"; + +// Some macros to make writing FLIGHT_LOG_FIELD_PREDICTOR_* constants shorter: +#define STR_HELPER(x) #x +#define STR(x) STR_HELPER(x) + +#define CONCAT_HELPER(x,y) x ## y +#define CONCAT(x,y) CONCAT_HELPER(x, y) + +#define PREDICT(x) STR(CONCAT(FLIGHT_LOG_FIELD_PREDICTOR_, x)) +#define ENCODING(x) STR(CONCAT(FLIGHT_LOG_FIELD_ENCODING_, x)) + +/* These headers have info for all 8 motors on them, we'll trim the final fields off to match the number of motors in the mixer: */ +static const char * const blackboxHeaderFields[] = { + "H Field I name:" + "loopIteration,time," + "axisP[0],axisP[1],axisP[2]," + "axisI[0],axisI[1],axisI[2]," + "axisD[0],axisD[1],axisD[2]," + "rcCommand[0],rcCommand[1],rcCommand[2],rcCommand[3]," + "gyroData[0],gyroData[1],gyroData[2]," + "accSmooth[0],accSmooth[1],accSmooth[2]," + "motor[0],motor[1],motor[2],motor[3]," + "motor[4],motor[5],motor[6],motor[7]", + + "H Field I signed:" + /* loopIteration, time: */ + "0,0," + /* PIDs: */ + "1,1,1,1,1,1,1,1,1," + /* rcCommand[0..2] */ + "1,1,1," + /* rcCommand[3] (Throttle): */ + "0," + /* gyroData[0..2]: */ + "1,1,1," + /* accSmooth[0..2]: */ + "1,1,1," + /* Motor[0..7]: */ + "0,0,0,0,0,0,0,0", + + "H Field I predictor:" + /* loopIteration, time: */ + PREDICT(0) "," PREDICT(0) "," + /* PIDs: */ + PREDICT(0) "," PREDICT(0) "," PREDICT(0) "," + PREDICT(0) "," PREDICT(0) "," PREDICT(0) "," + PREDICT(0) "," PREDICT(0) "," PREDICT(0) "," + /* rcCommand[0..2] */ + PREDICT(0) "," PREDICT(0) "," PREDICT(0) "," + /* rcCommand[3] (Throttle): */ + PREDICT(MINTHROTTLE) "," + /* gyroData[0..2]: */ + PREDICT(0) "," PREDICT(0) "," PREDICT(0) "," + /* accSmooth[0..2]: */ + PREDICT(0) "," PREDICT(0) "," PREDICT(0) "," + /* Motor[0]: */ + PREDICT(MINTHROTTLE) "," + /* Motor[1..7]: */ + PREDICT(MOTOR_0) "," PREDICT(MOTOR_0) "," PREDICT(MOTOR_0) "," + PREDICT(MOTOR_0) "," PREDICT(MOTOR_0) "," PREDICT(MOTOR_0) "," + PREDICT(MOTOR_0), + + "H Field I encoding:" + /* loopIteration, time: */ + ENCODING(UNSIGNED_VB) "," ENCODING(UNSIGNED_VB) "," + /* PIDs: */ + ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," + ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," + ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," + /* rcCommand[0..2] */ + ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," + /* rcCommand[3] (Throttle): */ + ENCODING(UNSIGNED_VB) "," + /* gyroData[0..2]: */ + ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," + /* accSmooth[0..2]: */ + ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," + /* Motor[0]: */ + ENCODING(UNSIGNED_VB) "," + /* Motor[1..7]: */ + ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," + ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," + ENCODING(SIGNED_VB), + + //Motors and gyros predict an average of the last two measurements (to reduce the impact of noise): + "H Field P predictor:" + /* loopIteration, time: */ + PREDICT(INC) "," PREDICT(STRAIGHT_LINE) "," + /* PIDs: */ + PREDICT(PREVIOUS) "," PREDICT(PREVIOUS) "," PREDICT(PREVIOUS) "," + PREDICT(PREVIOUS) "," PREDICT(PREVIOUS) "," PREDICT(PREVIOUS) "," + PREDICT(PREVIOUS) "," PREDICT(PREVIOUS) "," PREDICT(PREVIOUS) "," + /* rcCommand[0..2] */ + PREDICT(PREVIOUS) "," PREDICT(PREVIOUS) "," PREDICT(PREVIOUS) "," + /* rcCommand[3] (Throttle): */ + PREDICT(PREVIOUS) "," + /* gyroData[0..2]: */ + PREDICT(AVERAGE_2) "," PREDICT(AVERAGE_2) "," PREDICT(AVERAGE_2) "," + /* accSmooth[0..2]: */ + PREDICT(AVERAGE_2) "," PREDICT(AVERAGE_2) "," PREDICT(AVERAGE_2) "," + /* Motor[0]: */ + PREDICT(AVERAGE_2) "," + /* Motor[1..7]: */ + PREDICT(AVERAGE_2) "," PREDICT(AVERAGE_2) "," PREDICT(AVERAGE_2) "," + PREDICT(AVERAGE_2) "," PREDICT(AVERAGE_2) "," PREDICT(AVERAGE_2) "," + PREDICT(AVERAGE_2), + + /* RC fields are encoded together as a group, everything else is signed since they're diffs: */ + "H Field P encoding:" + /* loopIteration, time: */ + ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," + /* PIDs: */ + ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," + ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," + ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," + /* rcCommand[0..3] */ + ENCODING(TAG8_4S16) "," ENCODING(TAG8_4S16) "," ENCODING(TAG8_4S16) "," + ENCODING(TAG8_4S16) "," + /* gyroData[0..2]: */ + ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," + /* accSmooth[0..2]: */ + ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," + /* Motor[0]: */ + ENCODING(SIGNED_VB) "," + /* Motor[1..7]: */ + ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," + ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," + ENCODING(SIGNED_VB) +}; + +static const char blackboxGpsHeader[] = + "H Field G name:" + "GPS_numSat,GPS_coord[0],GPS_coord[1],GPS_altitude,GPS_speed\n" + "H Field G signed:" + "0,1,1,0,0\n" + "H Field G predictor:" + PREDICT(0) "," PREDICT(HOME_COORD) "," PREDICT(HOME_COORD) "," PREDICT(0) "," PREDICT(0) "\n" + "H Field G encoding:" + ENCODING(UNSIGNED_VB) "," ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," + ENCODING(UNSIGNED_VB) "," ENCODING(UNSIGNED_VB) "\n" + + "H Field H name:" + "GPS_home[0],GPS_home[1]\n" + "H Field H signed:" + "1,1\n" + "H Field H predictor:" + PREDICT(0) "," PREDICT(0) "\n" + "H Field H encoding:" + ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "\n"; + +typedef enum BlackboxState { + BLACKBOX_STATE_DISABLED = 0, + BLACKBOX_STATE_STOPPED, + BLACKBOX_STATE_SEND_HEADER, + BLACKBOX_STATE_SEND_FIELDINFO, + BLACKBOX_STATE_SEND_GPS_HEADERS, + BLACKBOX_STATE_SEND_SYSINFO, + BLACKBOX_STATE_RUNNING +} BlackboxState; + +typedef struct gpsState_t { + int32_t GPS_home[2], GPS_coord[2]; + uint8_t GPS_numSat; +} gpsState_t; + +//From mixer.c: +extern uint8_t motorCount; + +//From mw.c: +extern uint32_t currentTime; + +static BlackboxState blackboxState = BLACKBOX_STATE_DISABLED; +static uint32_t startTime; +static unsigned int headerXmitIndex; +static uint32_t blackboxIteration; + +static serialPort_t *blackboxPort; +static portMode_t previousPortMode; +static uint32_t previousBaudRate; + +static gpsState_t gpsHistory; + +// Keep a history of length 2, plus a buffer for MW to store the new values into +static blackbox_values_t blackboxHistoryRing[3]; + +// These point into blackboxHistoryRing, use them to know where to store history of a given age (0, 1 or 2 generations old) +static blackbox_values_t* blackboxHistory[3]; + + +static void blackboxWrite(uint8_t value) +{ + serialWrite(blackboxPort, value); +} + +static void _putc(void *p, char c) +{ + (void)p; + serialWrite(blackboxPort, c); +} + +//printf() to the blackbox serial port with no blocking shenanigans (so it's caller's responsibility to not write too fast!) +static void blackboxPrintf(char *fmt, ...) +{ + va_list va; + va_start(va, fmt); + tfp_format(NULL, _putc, fmt, va); + va_end(va); +} + +/** + * Write an unsigned integer to the blackbox serial port using variable byte encoding. + */ +static void writeUnsignedVB(uint32_t value) +{ + //While this isn't the final byte (we can only write 7 bits at a time) + while (value > 127) { + blackboxWrite((uint8_t) (value | 0x80)); // Set the high bit to mean "more bytes follow" + value >>= 7; + } + blackboxWrite(value); +} + +/** + * Write a signed integer to the blackbox serial port using ZigZig and variable byte encoding. + */ +static void writeSignedVB(int32_t value) +{ + //ZigZag encode to make the value always positive + writeUnsignedVB((uint32_t)((value << 1) ^ (value >> 31))); +} + +#define FIELD_ZERO 0 +#define FIELD_4BIT 1 +#define FIELD_8BIT 2 +#define FIELD_16BIT 3 + +/** + * Write an 8-bit selector followed by four signed fields of size 0, 4, 8 or 16 bits. + */ +static void writeTag8_4S16(int32_t *values) { + uint8_t selector; + int x; + + /* + * 4-bit fields can only be combined with their paired neighbor (there are two pairs), so choose a + * larger encoding if that's not possible. + */ + const uint8_t rcSelectorCleanup[16] = { + // Output selectors <- Input selectors + FIELD_ZERO << 2 | FIELD_ZERO, // zero, zero + FIELD_ZERO << 2 | FIELD_8BIT, // zero, 4-bit + FIELD_ZERO << 2 | FIELD_8BIT, // zero, 8-bit + FIELD_ZERO << 2 | FIELD_16BIT, // zero, 16-bit + FIELD_8BIT << 2 | FIELD_ZERO, // 4-bit, zero + FIELD_4BIT << 2 | FIELD_4BIT, // 4-bit, 4-bit + FIELD_8BIT << 2 | FIELD_8BIT, // 4-bit, 8-bit + FIELD_8BIT << 2 | FIELD_16BIT, // 4-bit, 16-bit + FIELD_8BIT << 2 | FIELD_ZERO, // 8-bit, zero + FIELD_8BIT << 2 | FIELD_8BIT, // 8-bit, 4-bit + FIELD_8BIT << 2 | FIELD_8BIT, // 8-bit, 8-bit + FIELD_8BIT << 2 | FIELD_16BIT, // 8-bit, 16-bit + FIELD_16BIT << 2 | FIELD_ZERO, // 16-bit, zero + FIELD_16BIT << 2 | FIELD_8BIT, // 16-bit, 4-bit + FIELD_16BIT << 2 | FIELD_8BIT, // 16-bit, 8-bit + FIELD_16BIT << 2 | FIELD_16BIT, // 16-bit, 16-bit + }; + + selector = 0; + //Encode in reverse order so the first field is in the low bits: + for (x = 3; x >= 0; x--) { + selector <<= 2; + + if (values[x] == 0) + selector |= FIELD_ZERO; + else if (values[x] <= 7 && values[x] >= -8) + selector |= FIELD_4BIT; + else if (values[x] <= 127 && values[x] >= -128) + selector |= FIELD_8BIT; + else + selector |= FIELD_16BIT; + } + + selector = rcSelectorCleanup[selector & 0x0F] | (rcSelectorCleanup[selector >> 4] << 4); + + blackboxWrite(selector); + + for (x = 0; x < 4; x++, selector >>= 2) { + switch (selector & 0x03) { + case FIELD_4BIT: + blackboxWrite((values[x] & 0x0F) | (values[x + 1] << 4)); + + //We write two selector fields: + x++; + selector >>= 2; + break; + case FIELD_8BIT: + blackboxWrite(values[x]); + break; + case FIELD_16BIT: + blackboxWrite(values[x]); + blackboxWrite(values[x] >> 8); + break; + } + } +} + +static void writeIntraframe(void) +{ + blackbox_values_t *blackboxCurrent = blackboxHistory[0]; + int x; + + blackboxWrite('I'); + + writeUnsignedVB(blackboxIteration); + writeUnsignedVB(blackboxCurrent->time); + + for (x = 0; x < 3; x++) + writeSignedVB(blackboxCurrent->axisP[x]); + + for (x = 0; x < 3; x++) + writeSignedVB(blackboxCurrent->axisI[x]); + + for (x = 0; x < 3; x++) + writeSignedVB(blackboxCurrent->axisD[x]); + + for (x = 0; x < 3; x++) + writeSignedVB(blackboxCurrent->rcCommand[x]); + + writeUnsignedVB(blackboxCurrent->rcCommand[3] - masterConfig.escAndServoConfig.minthrottle); //Throttle lies in range [minthrottle..maxthrottle] + + for (x = 0; x < 3; x++) + writeSignedVB(blackboxCurrent->gyroData[x]); + + for (x = 0; x < 3; x++) + writeSignedVB(blackboxCurrent->accSmooth[x]); + + //Motors can be below minthrottle when disarmed, but that doesn't happen much + writeUnsignedVB(blackboxCurrent->motor[0] - masterConfig.escAndServoConfig.minthrottle); + + //Motors tend to be similar to each other + for (x = 1; x < motorCount; x++) + writeSignedVB(blackboxCurrent->motor[x] - blackboxCurrent->motor[0]); + + //Rotate our history buffers: + + //The current state becomes the new "before" state + blackboxHistory[1] = blackboxHistory[0]; + //And since we have no other history, we also use it for the "before, before" state + blackboxHistory[2] = blackboxHistory[0]; + //And advance the current state over to a blank space ready to be filled + blackboxHistory[0] = ((blackboxHistory[0] - blackboxHistoryRing + 1) % 3) + blackboxHistoryRing; +} + +static void writeInterframe(void) +{ + int x; + int32_t rcDeltas[4]; + + blackbox_values_t *blackboxCurrent = blackboxHistory[0]; + blackbox_values_t *blackboxLast = blackboxHistory[1]; + + blackboxWrite('P'); + + //No need to store iteration count since its delta is always 1 + + /* + * Since the difference between the difference between successive times will be nearly zero, use + * second-order differences. + */ + writeSignedVB((int32_t) (blackboxHistory[0]->time - 2 * blackboxHistory[1]->time + blackboxHistory[2]->time)); + + for (x = 0; x < 3; x++) + writeSignedVB(blackboxCurrent->axisP[x] - blackboxLast->axisP[x]); + + for (x = 0; x < 3; x++) + writeSignedVB(blackboxCurrent->axisI[x] - blackboxLast->axisI[x]); + + for (x = 0; x < 3; x++) + writeSignedVB(blackboxCurrent->axisD[x] - blackboxLast->axisD[x]); + + for (x = 0; x < 4; x++) + rcDeltas[x] = blackboxCurrent->rcCommand[x] - blackboxLast->rcCommand[x]; + + /* + * RC tends to stay the same or very small for many frames at a time, so use an encoding that + * can pack multiple values per byte: + */ + writeTag8_4S16(rcDeltas); + + //Since gyros, accs and motors are noisy, base the prediction on the average of the history: + for (x = 0; x < 3; x++) + writeSignedVB(blackboxHistory[0]->gyroData[x] - (blackboxHistory[1]->gyroData[x] + blackboxHistory[2]->gyroData[x]) / 2); + + for (x = 0; x < 3; x++) + writeSignedVB(blackboxHistory[0]->accSmooth[x] - (blackboxHistory[1]->accSmooth[x] + blackboxHistory[2]->accSmooth[x]) / 2); + + for (x = 0; x < motorCount; x++) + writeSignedVB(blackboxHistory[0]->motor[x] - (blackboxHistory[1]->motor[x] + blackboxHistory[2]->motor[x]) / 2); + + //Rotate our history buffers + blackboxHistory[2] = blackboxHistory[1]; + blackboxHistory[1] = blackboxHistory[0]; + blackboxHistory[0] = ((blackboxHistory[0] - blackboxHistoryRing + 1) % 3) + blackboxHistoryRing; +} + +static void configureBlackboxPort(void) +{ + blackboxPort = findOpenSerialPort(FUNCTION_BLACKBOX); + if (blackboxPort) { + previousPortMode = blackboxPort->mode; + previousBaudRate = blackboxPort->baudRate; + + serialSetBaudRate(blackboxPort, BLACKBOX_BAUDRATE); + serialSetMode(blackboxPort, BLACKBOX_INITIAL_PORT_MODE); + beginSerialPortFunction(blackboxPort, FUNCTION_BLACKBOX); + } else { + blackboxPort = openSerialPort(FUNCTION_BLACKBOX, NULL, BLACKBOX_BAUDRATE, BLACKBOX_INITIAL_PORT_MODE, SERIAL_NOT_INVERTED); + + if (blackboxPort) { + previousPortMode = blackboxPort->mode; + previousBaudRate = blackboxPort->baudRate; + } + } +} + +static void releaseBlackboxPort(void) +{ + serialSetMode(blackboxPort, previousPortMode); + serialSetBaudRate(blackboxPort, previousBaudRate); + + endSerialPortFunction(blackboxPort, FUNCTION_BLACKBOX); +} + +void startBlackbox(void) +{ + if (blackboxState == BLACKBOX_STATE_STOPPED) { + configureBlackboxPort(); + + if (!blackboxPort) { + blackboxState = BLACKBOX_STATE_DISABLED; + return; + } + + startTime = millis(); + headerXmitIndex = 0; + blackboxIteration = 0; + blackboxState = BLACKBOX_STATE_SEND_HEADER; + + memset(&gpsHistory, 0, sizeof(gpsHistory)); + + //No need to clear the content of blackboxHistoryRing since our first frame will be an intra which overwrites it + + blackboxHistory[0] = &blackboxHistoryRing[0]; + blackboxHistory[1] = &blackboxHistoryRing[1]; + blackboxHistory[2] = &blackboxHistoryRing[2]; + } +} + +void finishBlackbox(void) +{ + if (blackboxState != BLACKBOX_STATE_DISABLED && blackboxState != BLACKBOX_STATE_STOPPED) { + blackboxState = BLACKBOX_STATE_STOPPED; + + releaseBlackboxPort(); + } +} + +static void writeGPSHomeFrame() +{ + blackboxWrite('H'); + + writeSignedVB(GPS_home[0]); + writeSignedVB(GPS_home[1]); + //TODO it'd be great if we could grab the GPS current time and write that too + + gpsHistory.GPS_home[0] = GPS_home[0]; + gpsHistory.GPS_home[1] = GPS_home[1]; +} + +static void writeGPSFrame() +{ + blackboxWrite('G'); + + writeUnsignedVB(GPS_numSat); + writeSignedVB(GPS_coord[0] - gpsHistory.GPS_home[0]); + writeSignedVB(GPS_coord[1] - gpsHistory.GPS_home[1]); + writeUnsignedVB(GPS_altitude); + writeUnsignedVB(GPS_speed); + + gpsHistory.GPS_numSat = GPS_numSat; + gpsHistory.GPS_coord[0] = GPS_coord[0]; + gpsHistory.GPS_coord[1] = GPS_coord[1]; +} + +void handleBlackbox(void) +{ + int i; + blackbox_values_t *blackboxCurrent; + const int SERIAL_CHUNK_SIZE = 16; + static int charXmitIndex = 0; + int motorsToRemove, endIndex; + union floatConvert_t { + float f; + uint32_t u; + } floatConvert; + + switch (blackboxState) { + case BLACKBOX_STATE_SEND_HEADER: + /* + * Once the UART has had time to init, transmit the header in chunks so we don't overflow our transmit + * buffer. + */ + if (millis() > startTime + 100) { + for (i = 0; i < SERIAL_CHUNK_SIZE && blackboxHeader[headerXmitIndex] != '\0'; i++, headerXmitIndex++) + blackboxWrite(blackboxHeader[headerXmitIndex]); + + if (blackboxHeader[headerXmitIndex] == '\0') { + blackboxState = BLACKBOX_STATE_SEND_FIELDINFO; + headerXmitIndex = 0; + charXmitIndex = 0; + } + } + break; + case BLACKBOX_STATE_SEND_FIELDINFO: + /* + * Once again, chunking up the data so we don't exceed our datarate. This time we're removing the excess field defs + * for motors we don't have. + */ + motorsToRemove = 8 - motorCount; + + if (headerXmitIndex < sizeof(blackboxHeaderFields) / sizeof(blackboxHeaderFields[0])){ + endIndex = strlen(blackboxHeaderFields[headerXmitIndex]) - (headerXmitIndex == 0 ? strlen(",motor[x]") : strlen(",x")) * motorsToRemove; + + for (i = charXmitIndex; i < charXmitIndex + SERIAL_CHUNK_SIZE && i < endIndex; i++) + blackboxWrite(blackboxHeaderFields[headerXmitIndex][i]); + + if (i == endIndex) { + blackboxWrite('\n'); + headerXmitIndex++; + charXmitIndex = 0; + } else { + charXmitIndex = i; + } + } else { + if (feature(FEATURE_GPS)) { + blackboxState = BLACKBOX_STATE_SEND_GPS_HEADERS; + } else { + blackboxState = BLACKBOX_STATE_SEND_SYSINFO; + } + headerXmitIndex = 0; + } + break; + case BLACKBOX_STATE_SEND_GPS_HEADERS: + for (i = 0; i < SERIAL_CHUNK_SIZE && blackboxGpsHeader[headerXmitIndex] != '\0'; i++, headerXmitIndex++) + blackboxWrite(blackboxGpsHeader[headerXmitIndex]); + + if (blackboxGpsHeader[headerXmitIndex] == '\0') { + blackboxState = BLACKBOX_STATE_SEND_SYSINFO; + headerXmitIndex = 0; + } + break; + case BLACKBOX_STATE_SEND_SYSINFO: + + switch (headerXmitIndex) { + case 0: + blackboxPrintf("H Firmware type:Cleanflight\n"); + break; + case 1: + blackboxPrintf("H Firmware revision:%s\n", shortGitRevision); + break; + case 2: + blackboxPrintf("H Firmware date:%s %s\n", buildDate, buildTime); + break; + case 3: + blackboxPrintf("H rcRate:%d\n", masterConfig.controlRateProfiles[masterConfig.current_profile_index].rcRate8); + break; + case 4: + blackboxPrintf("H minthrottle:%d\n", masterConfig.escAndServoConfig.minthrottle); + break; + case 5: + blackboxPrintf("H maxthrottle:%d\n", masterConfig.escAndServoConfig.maxthrottle); + break; + case 6: + floatConvert.f = gyro.scale; + blackboxPrintf("H gyro.scale:0x%x\n", floatConvert.u); + break; + case 7: + blackboxPrintf("H acc_1G:%u\n", acc_1G); + break; + default: + blackboxState = BLACKBOX_STATE_RUNNING; + } + + headerXmitIndex++; + break; + case BLACKBOX_STATE_RUNNING: + // Copy current system values into the blackbox to be written out + blackboxCurrent = blackboxHistory[0]; + + blackboxCurrent->time = currentTime; + + for (i = 0; i < motorCount; i++) + blackboxCurrent->motor[i] = motor[i]; + + for (i = 0; i < 3; i++) + blackboxCurrent->axisP[i] = axisP[i]; + for (i = 0; i < 3; i++) + blackboxCurrent->axisI[i] = axisI[i]; + for (i = 0; i < 3; i++) + blackboxCurrent->axisD[i] = axisD[i]; + + for (i = 0; i < 4; i++) + blackboxCurrent->rcCommand[i] = rcCommand[i]; + + for (i = 0; i < 3; i++) + blackboxCurrent->gyroData[i] = gyroData[i]; + + for (i = 0; i < 3; i++) + blackboxCurrent->accSmooth[i] = accSmooth[i]; + + // Write a keyframe every 32 frames so we can resynchronise upon missing frames + int blackboxIntercycleIndex = blackboxIteration % 32; + int blackboxIntracycleIndex = blackboxIteration / 32; + + if (blackboxIntercycleIndex == 0) + writeIntraframe(); + else { + writeInterframe(); + + if (feature(FEATURE_GPS)) { + /* + * If the GPS home point has been updated, or every 128 intraframes (~10 seconds), write the + * GPS home position. + * + * We write it periodically so that if one Home Frame goes missing, the GPS coordinates can + * still be interpreted correctly. + */ + if (GPS_home[0] != gpsHistory.GPS_home[0] || GPS_home[1] != gpsHistory.GPS_home[1] + || (blackboxIntercycleIndex == 15 && blackboxIntracycleIndex % 128 == 0)) { + + writeGPSHomeFrame(); + writeGPSFrame(); + } else if (GPS_numSat != gpsHistory.GPS_numSat || GPS_coord[0] != gpsHistory.GPS_coord[0] + || GPS_coord[1] != gpsHistory.GPS_coord[1]) { + //We could check for velocity changes as well but I doubt it changes independent of position + writeGPSFrame(); + } + } + } + + blackboxIteration++; + break; + default: + break; + } +} + +bool canUseBlackboxWithCurrentConfiguration(void) +{ + if (!feature(FEATURE_BLACKBOX)) + return false; + + return true; +} + +void initBlackbox(void) +{ + if (canUseBlackboxWithCurrentConfiguration()) + blackboxState = BLACKBOX_STATE_STOPPED; + else + blackboxState = BLACKBOX_STATE_DISABLED; +} diff --git a/src/main/blackbox/blackbox.h b/src/main/blackbox/blackbox.h new file mode 100644 index 0000000000..19aeabbdc6 --- /dev/null +++ b/src/main/blackbox/blackbox.h @@ -0,0 +1,36 @@ +/* + * This file is part of Cleanflight. + * + * Cleanflight is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * Cleanflight is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with Cleanflight. If not, see . + */ + +#pragma once + +#include + +typedef struct blackbox_values_t { + uint32_t time; + + int32_t axisP[3], axisI[3], axisD[3]; + + int16_t rcCommand[4]; + int16_t gyroData[3]; + int16_t accSmooth[3]; + int16_t motor[8]; +} blackbox_values_t; + +void initBlackbox(void); +void handleBlackbox(void); +void startBlackbox(void); +void finishBlackbox(void); diff --git a/src/main/blackbox/blackbox_fielddefs.h b/src/main/blackbox/blackbox_fielddefs.h new file mode 100644 index 0000000000..e89b152d1e --- /dev/null +++ b/src/main/blackbox/blackbox_fielddefs.h @@ -0,0 +1,54 @@ +/* + * This file is part of Cleanflight. + * + * Cleanflight is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * Cleanflight is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with Cleanflight. If not, see . + */ + +#pragma once + +//No prediction: +#define FLIGHT_LOG_FIELD_PREDICTOR_0 0 + +//Predict that the field is the same as last frame: +#define FLIGHT_LOG_FIELD_PREDICTOR_PREVIOUS 1 + +//Predict that the slope between this field and the previous item is the same as that between the past two history items: +#define FLIGHT_LOG_FIELD_PREDICTOR_STRAIGHT_LINE 2 + +//Predict that this field is the same as the average of the last two history items: +#define FLIGHT_LOG_FIELD_PREDICTOR_AVERAGE_2 3 + +//Predict that this field is minthrottle +#define FLIGHT_LOG_FIELD_PREDICTOR_MINTHROTTLE 4 + +//Predict that this field is the same as motor 0 +#define FLIGHT_LOG_FIELD_PREDICTOR_MOTOR_0 5 + +//This field always increments +#define FLIGHT_LOG_FIELD_PREDICTOR_INC 6 + +//Predict this GPS co-ordinate is the GPS home co-ordinate (or no prediction if that coordinate is not set) +#define FLIGHT_LOG_FIELD_PREDICTOR_HOME_COORD 7 + + +#define FLIGHT_LOG_FIELD_ENCODING_SIGNED_VB 0 +#define FLIGHT_LOG_FIELD_ENCODING_UNSIGNED_VB 1 +#define FLIGHT_LOG_FIELD_ENCODING_U8 2 +#define FLIGHT_LOG_FIELD_ENCODING_U16 3 +#define FLIGHT_LOG_FIELD_ENCODING_U32 4 +#define FLIGHT_LOG_FIELD_ENCODING_S8 5 +#define FLIGHT_LOG_FIELD_ENCODING_S16 6 +#define FLIGHT_LOG_FIELD_ENCODING_S32 7 +#define FLIGHT_LOG_FIELD_ENCODING_TAG8_4S16 8 +#define FLIGHT_LOG_FIELD_ENCODING_NULL 9 diff --git a/src/main/config/config.h b/src/main/config/config.h index bbbc9e7949..351fc1e84b 100644 --- a/src/main/config/config.h +++ b/src/main/config/config.h @@ -40,7 +40,8 @@ typedef enum { FEATURE_RSSI_ADC = 1 << 15, FEATURE_LED_STRIP = 1 << 16, FEATURE_DISPLAY = 1 << 17, - FEATURE_ONESHOT125 = 1 << 18 + FEATURE_ONESHOT125 = 1 << 18, + FEATURE_BLACKBOX = 1 << 19 } features_e; bool feature(uint32_t mask); diff --git a/src/main/flight/flight.c b/src/main/flight/flight.c index 6d7891d7cc..ca1812ca9c 100644 --- a/src/main/flight/flight.c +++ b/src/main/flight/flight.c @@ -42,6 +42,11 @@ extern uint16_t cycleTime; int16_t heading, magHold; int16_t axisPID[3]; + +#ifdef BLACKBOX +int32_t axisP[3], axisI[3], axisD[3]; +#endif + uint8_t dynP8[3], dynI8[3], dynD8[3]; static int32_t errorGyroI[3] = { 0, 0, 0 }; @@ -243,6 +248,12 @@ static void pidMultiWii(pidProfile_t *pidProfile, controlRateConfig_t *controlRa delta1[axis] = delta; DTerm = (deltaSum * dynD8[axis]) / 32; axisPID[axis] = PTerm + ITerm - DTerm; + +#ifdef BLACKBOX + axisP[axis] = PTerm; + axisI[axis] = ITerm; + axisD[axis] = -DTerm; +#endif } } @@ -326,6 +337,12 @@ static void pidRewrite(pidProfile_t *pidProfile, controlRateConfig_t *controlRat // -----calculate total PID output axisPID[axis] = PTerm + ITerm + DTerm; + +#ifdef BLACKBOX + axisP[axis] = PTerm; + axisI[axis] = ITerm; + axisD[axis] = DTerm; +#endif } } diff --git a/src/main/flight/flight.h b/src/main/flight/flight.h index a6fadf55f6..ebccf21906 100644 --- a/src/main/flight/flight.h +++ b/src/main/flight/flight.h @@ -127,6 +127,8 @@ extern int16_t gyroADC[XYZ_AXIS_COUNT], accADC[XYZ_AXIS_COUNT], accSmooth[XYZ_AX extern int32_t accSum[XYZ_AXIS_COUNT]; extern int16_t axisPID[XYZ_AXIS_COUNT]; +extern int32_t axisP[3], axisI[3], axisD[3]; + extern int16_t heading, magHold; extern int32_t AltHold; diff --git a/src/main/flight/mixer.c b/src/main/flight/mixer.c index 46e50600ec..819c91e264 100644 --- a/src/main/flight/mixer.c +++ b/src/main/flight/mixer.c @@ -42,7 +42,7 @@ #define AUX_FORWARD_CHANNEL_TO_SERVO_COUNT 4 -static uint8_t motorCount = 0; +uint8_t motorCount = 0; int16_t motor[MAX_SUPPORTED_MOTORS]; int16_t motor_disarmed[MAX_SUPPORTED_MOTORS]; int16_t servo[MAX_SUPPORTED_SERVOS] = { 1500, 1500, 1500, 1500, 1500, 1500, 1500, 1500 }; diff --git a/src/main/io/serial.c b/src/main/io/serial.c index c37cd432be..24eb67cb6b 100644 --- a/src/main/io/serial.c +++ b/src/main/io/serial.c @@ -62,7 +62,10 @@ const serialPortFunctionScenario_e serialPortScenarios[SERIAL_PORT_SCENARIO_COUN SCENARIO_CLI_ONLY, SCENARIO_GPS_PASSTHROUGH_ONLY, SCENARIO_MSP_ONLY, - SCENARIO_SMARTPORT_TELEMETRY_ONLY + SCENARIO_SMARTPORT_TELEMETRY_ONLY, + + SCENARIO_BLACKBOX_ONLY, + SCENARIO_MSP_CLI_BLACKBOX_GPS_PASTHROUGH }; static serialConfig_t *serialConfig; @@ -132,7 +135,8 @@ const functionConstraint_t functionConstraints[] = { { FUNCTION_MSP, 9600, 115200, NO_AUTOBAUD, SPF_NONE }, { FUNCTION_SERIAL_RX, 9600, 115200, NO_AUTOBAUD, SPF_SUPPORTS_SBUS_MODE | SPF_SUPPORTS_CALLBACK }, { FUNCTION_TELEMETRY, 9600, 19200, NO_AUTOBAUD, SPF_NONE }, - { FUNCTION_SMARTPORT_TELEMETRY, 57600, 57600, NO_AUTOBAUD, SPF_SUPPORTS_BIDIR_MODE } + { FUNCTION_SMARTPORT_TELEMETRY, 57600, 57600, NO_AUTOBAUD, SPF_SUPPORTS_BIDIR_MODE }, + { FUNCTION_BLACKBOX, 115200,115200, NO_AUTOBAUD, SPF_NONE } }; #define FUNCTION_CONSTRAINT_COUNT (sizeof(functionConstraints) / sizeof(functionConstraint_t)) diff --git a/src/main/io/serial.h b/src/main/io/serial.h index 043d2c486e..4051e9fa56 100644 --- a/src/main/io/serial.h +++ b/src/main/io/serial.h @@ -25,7 +25,8 @@ typedef enum { FUNCTION_SMARTPORT_TELEMETRY = (1 << 3), FUNCTION_SERIAL_RX = (1 << 4), FUNCTION_GPS = (1 << 5), - FUNCTION_GPS_PASSTHROUGH = (1 << 6) + FUNCTION_GPS_PASSTHROUGH = (1 << 6), + FUNCTION_BLACKBOX = (1 << 7) } serialPortFunction_e; typedef enum { @@ -52,10 +53,12 @@ typedef enum { SCENARIO_MSP_CLI_TELEMETRY_GPS_PASTHROUGH = FUNCTION_MSP | FUNCTION_CLI | FUNCTION_TELEMETRY | FUNCTION_SMARTPORT_TELEMETRY | FUNCTION_GPS_PASSTHROUGH, SCENARIO_SERIAL_RX_ONLY = FUNCTION_SERIAL_RX, SCENARIO_TELEMETRY_ONLY = FUNCTION_TELEMETRY, - SCENARIO_SMARTPORT_TELEMETRY_ONLY = FUNCTION_SMARTPORT_TELEMETRY + SCENARIO_SMARTPORT_TELEMETRY_ONLY = FUNCTION_SMARTPORT_TELEMETRY, + SCENARIO_BLACKBOX_ONLY = FUNCTION_BLACKBOX, + SCENARIO_MSP_CLI_BLACKBOX_GPS_PASTHROUGH = FUNCTION_CLI | FUNCTION_MSP | FUNCTION_BLACKBOX | FUNCTION_GPS_PASSTHROUGH } serialPortFunctionScenario_e; -#define SERIAL_PORT_SCENARIO_COUNT 10 +#define SERIAL_PORT_SCENARIO_COUNT 12 #define SERIAL_PORT_SCENARIO_MAX (SERIAL_PORT_SCENARIO_COUNT - 1) extern const serialPortFunctionScenario_e serialPortScenarios[SERIAL_PORT_SCENARIO_COUNT]; diff --git a/src/main/io/serial_cli.c b/src/main/io/serial_cli.c index 97a85e9a20..e18370e0c0 100644 --- a/src/main/io/serial_cli.c +++ b/src/main/io/serial_cli.c @@ -123,7 +123,8 @@ static const char * const featureNames[] = { "RX_PPM", "VBAT", "INFLIGHT_ACC_CAL", "RX_SERIAL", "MOTOR_STOP", "SERVO_TILT", "SOFTSERIAL", "GPS", "FAILSAFE", "SONAR", "TELEMETRY", "CURRENT_METER", "3D", "RX_PARALLEL_PWM", - "RX_MSP", "RSSI_ADC", "LED_STRIP", "DISPLAY", "ONESHOT125", NULL + "RX_MSP", "RSSI_ADC", "LED_STRIP", "DISPLAY", "ONESHOT125", + "BLACKBOX", NULL }; // sync this with sensors_e diff --git a/src/main/main.c b/src/main/main.c index c772305ff0..09d35a609b 100644 --- a/src/main/main.c +++ b/src/main/main.c @@ -64,6 +64,7 @@ #include "sensors/acceleration.h" #include "sensors/gyro.h" #include "telemetry/telemetry.h" +#include "blackbox/blackbox.h" #include "sensors/battery.h" #include "sensors/boardalignment.h" #include "config/runtime_config.h" @@ -323,6 +324,10 @@ void init(void) initTelemetry(); #endif +#ifdef BLACKBOX + initBlackbox(); +#endif + previousTime = micros(); if (masterConfig.mixerConfiguration == MULTITYPE_GIMBAL) { diff --git a/src/main/mw.c b/src/main/mw.c index c582a3c40b..f181dc314f 100644 --- a/src/main/mw.c +++ b/src/main/mw.c @@ -65,6 +65,7 @@ #include "io/statusindicator.h" #include "rx/msp.h" #include "telemetry/telemetry.h" +#include "blackbox/blackbox.h" #include "config/runtime_config.h" #include "config/config.h" @@ -303,6 +304,15 @@ void mwDisarm(void) } } #endif + +#ifdef BLACKBOX + if (feature(FEATURE_BLACKBOX)) { + finishBlackbox(); + if (isSerialPortFunctionShared(FUNCTION_BLACKBOX, FUNCTION_MSP)) { + mspAllocateSerialPorts(&masterConfig.serialConfig); + } + } +#endif } } @@ -324,6 +334,16 @@ void mwArm(void) } } #endif + +#ifdef BLACKBOX + if (feature(FEATURE_BLACKBOX)) { + serialPort_t *sharedBlackboxAndMspPort = findSharedSerialPort(FUNCTION_BLACKBOX, FUNCTION_MSP); + if (sharedBlackboxAndMspPort) { + mspReleasePortIfAllocated(sharedBlackboxAndMspPort); + } + startBlackbox(); + } +#endif return; } } @@ -681,6 +701,12 @@ void loop(void) mixTable(); writeServos(); writeMotors(); + +#ifdef BLACKBOX + if (!cliMode && feature(FEATURE_BLACKBOX)) { + handleBlackbox(); + } +#endif } #ifdef TELEMETRY diff --git a/src/main/target/NAZE/target.h b/src/main/target/NAZE/target.h index 8fc63bb802..4c3ab677c2 100644 --- a/src/main/target/NAZE/target.h +++ b/src/main/target/NAZE/target.h @@ -109,6 +109,7 @@ #define LED_STRIP #define LED_STRIP_TIMER TIM3 +#define BLACKBOX #define TELEMETRY #define SERIAL_RX #define AUTOTUNE diff --git a/src/main/target/NAZE32PRO/target.h b/src/main/target/NAZE32PRO/target.h index 12ae41b82f..7ff38be458 100644 --- a/src/main/target/NAZE32PRO/target.h +++ b/src/main/target/NAZE32PRO/target.h @@ -43,6 +43,7 @@ #define SENSORS_SET (SENSOR_ACC) #define GPS +#define BLACKBOX #define TELEMETRY #define SERIAL_RX #define AUTOTUNE From e492aa6a3961dded50ffa44a96718ab66e3c660d Mon Sep 17 00:00:00 2001 From: Nicholas Sherlock Date: Tue, 9 Dec 2014 17:27:56 +1300 Subject: [PATCH 02/24] Add (untested) support for recording Tricopter tail servo position --- obj/cleanflight_NAZE.hex | 11766 ++++++++++++----------- src/main/blackbox/blackbox.c | 110 +- src/main/blackbox/blackbox.h | 3 +- src/main/blackbox/blackbox_fielddefs.h | 3 + 4 files changed, 5977 insertions(+), 5905 deletions(-) diff --git a/obj/cleanflight_NAZE.hex b/obj/cleanflight_NAZE.hex index d86d63f7e5..ac1771b1cb 100644 --- a/obj/cleanflight_NAZE.hex +++ b/obj/cleanflight_NAZE.hex @@ -1,24 +1,24 @@ :020000040800F2 -:10000000005000201DF90008C9F9000819E3000894 -:10001000C9F90008C9F90008C9F900080000000082 -:10002000000000000000000000000000C9F9000806 -:10003000C9F9000800000000C9F9000809E3000838 -:10004000C9F90008C9F90008C9F90008C9F9000888 -:10005000C9F90008C9F90008C9F900085DE10008FC -:10006000C9F90008C9F90008C9F90008C9F9000868 -:10007000C9F90008C9F900081DE10008C9F900081C -:1000800061E10008C9F90008C9F90008C9F90008C8 -:10009000C9F90008C9F90008C9F9000859E10008C0 -:1000A000C9F9000831E00008C9F9000841E000087A -:1000B00021E0000811E0000801E000089DE10008CF -:1000C00095E1000899E1000891E10008C9F90008EC -:1000D000C9F90008D9E0000851E00008C9F9000892 -:1000E000A1E10008C9F90008C9F9000800000000F2 +:100000000050002025F70008D1F7000821E1000882 +:10001000D1F70008D1F70008D1F700080000000070 +:10002000000000000000000000000000D1F7000800 +:10003000D1F7000800000000D1F7000811E1000826 +:10004000D1F70008D1F70008D1F70008D1F7000870 +:10005000D1F70008D1F70008D1F7000865DF0008E4 +:10006000D1F70008D1F70008D1F70008D1F7000850 +:10007000D1F70008D1F7000825DF0008D1F7000804 +:1000800069DF0008D1F70008D1F70008D1F70008B0 +:10009000D1F70008D1F70008D1F7000861DF0008A8 +:1000A000D1F7000839DE0008D1F7000849DE000862 +:1000B00029DE000819DE000809DE0008A5DF0008B7 +:1000C0009DDF0008A1DF000899DF0008D1F70008D4 +:1000D000D1F70008E1DE000859DE0008D1F700087A +:1000E000A9DF0008D1F70008D1F7000800000000E0 :1000F0000000000000000000000000000000000000 :0C01000000000000000000005FF808F1A3 :100110002DE9F04F734B744D9FB02B6000236B6043 -:100120000CF044F818B908F05AFB0CF061F80DF027 -:10013000A5FD002308936D4C09930A934FF4E01337 +:100120000AF0C8FF18B908F05FFA0AF0E5FF0DF011 +:10013000A9FC002308936D4C09930A934FF4E01334 :100140000B9323686A4943F480338A7B2360A36955 :10015000894643F01003A361236803F40033099335 :10016000089B01330893099B1BB9089BB3F5A06F4B @@ -45,34 +45,34 @@ :1002B00005E0526812F4003F3A6818BF52085143F3 :1002C00019606268C2F303123A4492F804B01A68E3 :1002D00022FA0BFB0A4AC3F800B03B68934217D1DD -:1002E000012219E0472600083801002000100240D2 -:1002F000E41F002000200240000000200410014004 -:1003000000127A00001BB7009400002000093D0095 +:1002E000012219E0D54F00085807002000100240F5 +:1002F0002C20002000200240240000200410014097 +:1003000000127A00001BB700A400002000093D0085 :10031000B24A934202D10222B14B1A70DFF800A315 :10032000B04B1EAECAF80C30A3694FF0000843F082 :100330000103A361636AAC4843F080736362A369FD :1003400043F01C03A3614FF6FF7326F82C3D3146A2 -:100350008DF84E8002F0E2FEA448314602F0DEFE47 -:100360003146A34802F0DAFEA24B30465A6842F00A -:1003700000725A6005F05EFD139B9F4A6420B3FB38 +:100350008DF84E800AF036FBA44831460AF032FB95 +:100360003146A3480AF02EFBA24B30465A6842F0B1 +:1003700000725A600CF05CF8139B9F4A6420B3FB38 :10038000F2F34FF47A72AB60BBFBF2FB9B4B0BF1C9 :10039000FF325A60F0228AF823200722C3F808802F -:1003A0001A6002F0F2F896484146A02211F0D1FC02 +:1003A0001A6004F0F0FC96484146A02211F00DFDC1 :1003B000E36943F00703E361A36943F4006343F097 :1003C0000C03A3618F4B002103F10C0208F802100B :1003D00008F10108B8F10E0FF4D1FF229A76DA760F :1003E0001A775A77884B0FCB86E80F00A36908224B :1003F00043F00803A361A369139843F00803A361C2 -:100400007A4B14A91A6110221A6102F087FE15981E -:1004100016A902F083FE724B73481A789846012A97 +:100400007A4B14A91A6110221A610AF0DBFA1598C6 +:1004100016A90AF0D7FA724B73481A789846012A3F :100420008CBF102314238DF84E304FF002038DF84B :100430004F30A3694FF4805243F00403ADF84C20D1 -:100440008CBF4FF0010A4FF0000AA361314602F061 -:1004500065FE6E4BBAF1000F01D06D4A00E06D4AA7 -:1004600000201A6002F09BF86B4B93E80300A3692D -:1004700086E8030043F0080314A9A361139802F06F -:100480004DFE0BF035FA9F238DF8383032200023D3 -:100490008DF839308DF83A308DF83B3002F075F830 +:100440008CBF4FF0010A4FF0000AA36131460AF059 +:10045000B9FA6E4BBAF1000F01D06D4A00E06D4A57 +:1004600000201A6004F099FC6B4B93E80300A36929 +:1004700086E8030043F0080314A9A36113980AF067 +:10048000A1FA0CF0D1FB9F238DF8383032200023E5 +:100490008DF839308DF83A308DF83B3004F073FC2C :1004A000524B4FF480525A61A3F554430EAA9B89D4 :1004B00005204FF47A7331469246013823D01AB1A1 :1004C00092F800E0013208E04FF0FF0E05E003F182 @@ -82,34 +82,34 @@ :1005000001339BB2EB83DFF8E4B04FF48053CBF8B8 :1005100010309DF84E109DF84D20090241EA02412D :100520009DF84F2011433D4A914214D0CBF814302E -:10053000F52002930CF0D2F8FF200CF0CFF8029BCC +:10053000F52002930BF0E1F9FF200BF0DEF9029BAE :100540007028CBF8103006D198F80030022B02D179 :10055000234B03221A7098F800B0BBF1030F02D0AE -:1005600001200CF0F3FBD9F80820DFF8988002F4A2 +:10056000012006F0EBFCD9F80820DFF8988002F4AF :1005700000434FF0100C02F4006204920021624626 -:1005800008F120000293CDF80CC011F0E2FB00222C +:1005800008F120000293CDF80CC011F01EFC0022EF :100590008DF83B200422DDF80CC0072085F82020D0 :1005A0000122022185F8230093458DF83A10ADF819 :1005B00038C085F82220029B36D94FF0300EADF8B6 :1005C00038E04FF0050E88F828E088F8292088F8F0 :1005D0002A2088F82B00884627E000BF001BB700C0 -:1005E000742700200005FA0500080140000C0140B6 +:1005E000D72700200005FA0500080140000C014053 :1005F000001001400000014040420F0010E000E008 -:10060000841E002038010020D843010878270020EC -:10061000E11E0008F51E0008E8430108152020002F +:10060000CC1E002058070020EC440108DC27002005 +:100610005146000865460008FC44010815202000EA :1006200000ED00E00038004090469BB1BDF8383046 :1006300085F8258043F00203ADF83830012308EB3C :10064000030285F8243085F82630072385F8273003 -:100650005FFA82F88548514605F03EFC049BABB139 -:10066000022383485146ADF8383005F035FC0923A4 +:100650005FFA82F8854851460BF03CFF049BABB132 +:10066000022383485146ADF838300BF033FF09239D :10067000012285F82C3085F82E2008F1010307228D :1006800085F82D8085F82F205FFA83F86369794813 :1006900043F001036361A369764D43F40073A361E2 -:1006A00005F0C8FC744B00241393744BB8F1010F90 +:1006A00004F02AF8744B00241393744BB8F1010F33 :1006B00014930CBF2346802318934FF4807319932F :1006C0004FF480631A93202331461B9328464FF43E -:1006D00000531C931594CDF8588017941D9405F081 -:1006E0008BFC2B68B8F1010F43F001032B60644BC6 +:1006D00000531C931594CDF8588017941D9403F083 +:1006E000EDFF2B68B8F1010F43F001032B60644B61 :1006F00098BF00215A6888BF012122F4702222F499 :10070000807242EA01225A6099685E4A20460A4095 :1007100042F4602242F002029A60D96A08F1FF3284 @@ -134,40 +134,40 @@ :1008400013F00403FAD19168B9F8E60041F4A0016D :1008500091600E4AE8B9B2F9E830CBB9B2F9EA30A2 :10086000D3F1010338BF002313E000BF00080140AB -:10087000000C0140080002404C24014068010020A7 -:1008800000240140FDF7F1FF58010020E41F002083 +:10087000000C0140080002404C2401408807002081 +:1008800000240140FDF7F1FF780700202C20002014 :10089000034613F0010340F081803B7500B20EF077 -:1008A0006FFAAB490EF0C0FAAA4C0646B4F9E8005C -:1008B0000EF066FAA6490EF0B7FA0546B4F9EA005A -:1008C0000EF05EFAA2490EF0AFFA0446304611F07F -:1008D0006FFC0746304611F0DFFC8046284611F0D9 -:1008E00067FC0646284611F0D7FC0546204611F065 -:1008F0005FFC8246204611F0CFFC394681465046C7 -:100900000EF092FA3946834648460EF08DFA51466B -:10091000049040460EF088FA4946059040460EF095 -:1009200083FA3146079050460EF07EFA8A4C4946CB -:10093000A06306F100400EF077FA2946E0632564D3 -:1009400005980EF071FA014604980EF065F92946F3 -:10095000606407980EF068FA014658460EF05AF99E -:100960003146A06408F100400EF05EFA2946E064CA -:1009700058460EF059FA014607980EF04BF92946F1 -:10098000206504980EF050FA014605980EF044F9DF -:100990003946606530460EF047FAA0656D4B6E4DE6 -:1009A0009A6812F4003F18D0C8206A4C01F0EDFD9F -:1009B00008F08BFDC82001F0E8FD04F588730021E4 -:1009C0000C2205F16000EB6511F0C3F908F0FCFDA5 -:1009D00001F0B6FD614B0344AB66614B00211A6820 +:1008A00073F9AB490EF0C4F9AA4C0646B4F9E80056 +:1008B0000EF06AF9A6490EF0BBF90546B4F9EA0054 +:1008C0000EF062F9A2490EF0B3F90446304611F079 +:1008D000ABFC0746304611F01BFD8046284611F060 +:1008E000A3FC0646284611F013FD0546204611F0EC +:1008F0009BFC8246204611F00BFD3946814650464E +:100900000EF096F93946834648460EF091F9514665 +:10091000049040460EF08CF94946059040460EF092 +:1009200087F93146079050460EF082F98A4C4946C5 +:10093000A06306F100400EF07BF92946E0632564D0 +:1009400005980EF075F9014604980EF069F82946ED +:10095000606407980EF06CF9014658460EF05EF898 +:100960003146A06408F100400EF062F92946E064C7 +:1009700058460EF05DF9014607980EF04FF82946EB +:10098000206504980EF054F9014605980EF048F8D9 +:100990003946606530460EF04BF9A0656D4B6E4DE3 +:1009A0009A6812F4003F18D0C8206A4C04F0EBF9A2 +:1009B00006F020FCC82004F0E6F904F58873002155 +:1009C0000C2205F16000EB6511F0FFF90CF0F0FC72 +:1009D00004F0CEF8614B0344AB66614B00211A680A :1009E000994642F00E021A605E4A5F4B12685948FF :1009F000B2F85220B0F8EE6005925C4A90F8ED70C3 :100A000011705B4903F10C0291F800A0594CBAF146 -:100A1000010F88BF1346EB6609F0B0F8DFF8848158 +:100A1000010F88BF1346EB6606F08CFEDFF8848179 :100A20008346DFF884C108B3534BBB2EC8F80030AF :100A3000524BC8F80CC0C8F8043001D901230EE0AD :100A4000612E01D902230AE0292E01D9032306E0F1 :100A5000132E01D9042302E0092E05D90523434AA8 :100A60006375012313702CE00623F8E71920CDF8F5 -:100A70000CC001F08AFD682015215A4608F068FC78 -:100A8000DDF80CC0002801F00D823D4A622EC8F846 +:100A70000CC004F088F9682015215A4606F058FB8E +:100A8000DDF80CC0002801F011823D4A622EC8F842 :100A900000203C4AC8F80CC0C8F804203A4AC8F8FC :100AA000082000F0ED8240F2E482BC2E00F0E682E5 :100AB000B6F5807F40F0E78284F816B02B4801231A @@ -176,41 +176,41 @@ :100AE000110011003200B900DA00F200F200F20049 :100AF000F2000A00D9F8003023F00203C9F80030F0 :100B0000E0E0BAF1010F20D84FF000081EAB03F867 -:100B10002C2D5320414601220CF018FA90B19DF87B +:100B10002C2D53204146012206F0EEFC90B19DF8A9 :100B20004C30E52B0ED11A4B1A4A85F870801A60AA :100B3000194A5A60042301223370184B97421A70E5 :100B400000F0C080BAF1010F30D9154B2FE000BF83 -:100B500035FA8E3CE41F002038010020404B4C0049 -:100B600084090020200B0020C04301083A0B00201C -:100B7000742700200000002009C100080791000828 -:100B80003D9A00087791000845910008A20B0020CB -:100B9000900B0020B19A00085192000875270020A0 -:100BA000CC430108240B002090C1793D8B4BDFF82A -:100BB0005882EB6608F0E2FF00284AD0062113AB0A -:100BC00068200A460CF0C2F99DF84F309DF851B0EC +:100B500035FA8E3C2C20002058070020404B4C00DA +:100B60004C020020E8030020D444010802040020C5 +:100B7000D72700202400002035730008F7760008EE +:100B80009D730008917700085F7700086A040020D1 +:100B900058040020A17400086B780008D8270020B2 +:100BA000E0440108EC03002090C1793D8B4BDFF855 +:100BB0005882EB6606F0BEFD00284AD0062113AB32 +:100BC00068200A4606F098FC9DF84F309DF851B019 :100BD00003F001035B000BF0010B43EA8B0B9DF864 :100BE0004D3003F001035BEA030B08D0BBF1010FAA :100BF00001D1002317E0BBF1020F0BD112E00EABC5 -:100C000068200C2101220CF0A1F99DF8383013F076 -:100C10000F0302D1052001F046B9042B02D188F858 +:100C000068200C21012206F077FC9DF8383013F0A3 +:100C10000F0302D1052001F04AB9042B02D188F854 :100C200071B002E0012388F871306D4B6D4A1A6093 :100C30006D4A5A6095F87120002A14BF6E226F2207 :100C40001A726A4B02221A7097424FF001033370F6 :100C500038D0BAF1010F1DD800221EAB03F82C2D9D -:100C60001C200D2101220CF071F998B19DF84C3037 +:100C60001C200D21012206F047FC98B19DF84C3064 :100C70002A2B01D01A2B0DD1594A5D4985F87230C3 :100C800011605C490223516033700322574B974235 :100C90001A7017D000211EAB03F82C1D182001225A -:100CA0000CF054F970B19DF84C30FB2B0AD14C4B31 +:100CA00006F02AFC70B19DF84C30FB2B0AD14C4B5E :100CB000514A1A60514A5A604C4B04221A70504BE8 :100CC00001221A70494B1B7843B90FB11F46FEE64B :100CD000D9F8003023F00203C9F80030BAF1010F4F -:100CE00005D10BF01FFD474B4FF400525A610A200B -:100CF00001F04BFC7720A02101220EAB0CF026F96D +:100CE00005D10AF095FE474B4FF400525A610A2095 +:100CF00004F049F87720A02101220EAB06F0FCFB9E :100D000038B995F884A0404EBAF1000F00F08A80FF -:100D100055E11E210122772008F01AFB4FF42F60C5 -:100D200001F028FC0026A6F160010027C9B20222CA -:100D300013AB77208DF84C708DF84D700CF006F9E0 +:100D100055E11E210122772006F00AFA4FF42F60D8 +:100D200004F026F80026A6F160010027C9B20222CD +:100D300013AB77208DF84C708DF84D7006F0DCFB0E :100D40009DF84D309DF84C1043EA01212E4B03F1E4 :100D50007402B1520236102EE5D1B3F882E00121BF :100D60000EF00F060EF47F4EA3F882E03A463B46A3 @@ -220,23 +220,23 @@ :100DA000F7D10132102AE3D146EA0E0EA5F882E00F :100DB0000029A6D1C3F303339E42A2D1134B42F2C2 :100DC00010721A805A80124A5A60124A9A60124A65 -:100DD000DA60124A1A61124A5BE100BFC04301089F -:100DE000900B002075C10008C990000875270020ED -:100DF00079C00008B59100088D9A00080D9200088E -:100E0000A20B00200010014038010020D80900206A -:100E1000FD99000821900008F5990008319000081C -:100E2000352200089C4F0BF07DFC4FF480450EA945 +:100DD000DA60124A1A61124A5BE100BFD44401088A +:100DE00058040020B95C0008B9760008D827002014 +:100DF000ED730008CF7700087D740008277800089D +:100E00006A0400200010014058070020A0020020C2 +:100E1000F772000811760008EF72000821760008CA +:100E2000E1A000089C4F0AF0F3FD4FF480450EA9A5 :100E300004233846ADF838508DF83A304FF4005856 -:100E400002F06CF9954BC7F810805A6913A822F488 +:100E400009F0C0FD954BC7F810805A6913A822F429 :100E500070625A615A694FF0030942F400725A6194 :100E60000823139501258DF851308DF850A08DF889 -:100E7000525006F01BF828230DA88DF834308DF859 -:100E800035908DF836A08DF8375005F0EFFF14201F -:100E900001F07BFB0EAB7720D0212A460CF056F8F0 +:100E7000525004F03DFF28230DA88DF834308DF832 +:100E800035908DF836A08DF8375004F0D7FE142039 +:100E900003F079FF0EAB7720D0212A4606F02CFB19 :100EA0009DF83830A6F8A890552B86F89F307FD152 -:100EB000D1212A460EAB77200CF048F89DF8383047 +:100EB000D1212A460EAB772006F01EFB9DF8383074 :100EC000772003F00F021B0986F8A02086F8A130D6 -:100ED000162213ABAA210CF039F89DF84C209DF88E +:100ED000162213ABAA2106F00FFB9DF84C209DF8BB :100EE0004D3043EA0223A6F888309DF84E209DF845 :100EF0004F3043EA0223A6F88A309DF850209DF82F :100F0000513043EA0223A6F88C309DF852209DF818 @@ -252,35 +252,35 @@ :100FA000414A9A60414ADA60414A1A61414A70E016 :100FB000414BC7F814801A6822F004021A601EAA76 :100FC000002302F82C3D04921E200A210122049BDA -:100FD0000BF0BCFF384F38B19DF84C30482B03D193 +:100FD00006F092FA384F38B19DF84C30482B03D1C7 :100FE000364B03221A7003E03B6823F008033B6092 :100FF000334D95F8E2300BB1324A137095F8E33077 :101000000BB1314A137095F8E4300BB12B4A1370D1 :101010003B68990702D52D4B1B689847DFF8BC80C9 :101020002B4ED8F8003098473B6813F0080F1CD0BF :10103000059B4FF0640A0FFA83F898FBFAF94846CB -:101040000DF09EFE83460AFB198000B20DF098FE5B -:1010500020490DF0E9FE014658460DF0DDFD1E4920 -:101060000DF0E2FEC6F8AC003AE00023C6F8AC3062 +:101040000DF0A2FD83460AFB198000B20DF09CFD55 +:1010500020490DF0EDFD014658460DF0E1FC1E491A +:101060000DF0E6FDC6F8AC003AE00023C6F8AC305F :1010700036E00A2E0BD0142E07D004E0012300E046 :101080000223A3751AE50323FBE70423F9E70523ED :10109000F7E75A6193E700BF0010014000000140EC -:1010A000D8090020299A000891900008059A0008A4 -:1010B000419000088D230008840900208B27002020 -:1010C000E41F00203A0B0020A20B0020900B002010 -:1010D000380100208988883C00002041240B002032 +:1010A000A00200202173000881760008FF7200086A +:1010B0003176000839A200084C020020CB2700201E +:1010C0002C200020020400206A0400205804002084 +:1010D000580700208988883C00002041EC0300204C :1010E000844B10225A6108221A614FF00A0ADFF875 :1010F00004921920D9F80C300AF1FF3A83F010035A :10110000C9F80C30D9F80C3083F00803C9F80C305A -:1011100001F03BFA012001F042FA192001F035FA02 -:10112000002001F03CFA1AF0FF0AE0D10823C9F8C8 +:1011100003F039FE012003F040FE192003F033FEF6 +:10112000002003F03AFE1AF0FF0AE0D10823C9F8C4 :1011300010301023C9F810306F4BDFF8FC911B689A -:1011400093F90C000DF01CFE6C490DF06DFE11F0D2 -:101150002FF88246B9F800000DF012FE51460DF04E -:1011600063FE11F05BF8664B1880B9F800000DF0D3 -:1011700007FE014663480DF00BFF63490DF008FFC1 -:10118000624B63491860C8685C490DF04DFE6149C7 -:101190000DF04AFE604B6A791860604B60491A7026 +:1011400093F90C000DF020FD6C490DF071FD11F0CC +:101150006BF88246B9F800000DF016FD51460DF00F +:1011600067FD11F097F8664B1880B9F800000DF094 +:101170000BFD014663480DF00FFE63490DF00CFEB8 +:10118000624B63491860C8685C490DF051FD6149C4 +:101190000DF04EFD604B6A791860604B60491A7023 :1011A000604B01EBC20292F83120C6F8B0305E4BC2 :1011B0001A60AA68920644BF01221A603B681B07A6 :1011C00040F1FF804B4B10225A61584A4FF0000803 @@ -288,34 +288,34 @@ :1011E0004FF0080E90698CBF4FF480414FF480514E :1011F0004EEA000090614F484FF0020298BF184637 :10120000ADF838108DF83B200EA904228DF83A2055 -:1012100001F084FF322001F0B8F9002111221E20D4 -:1012200008F096F8012160221E2008F091F8642051 -:1012300001F0ABF9049808F067FCC146C3460221EF -:1012400001221E2008F084F8322001F09EF9049853 -:1012500008F05AFCBDF94C20BDF94E10BDF95030D4 +:1012100009F0D8FB322003F0B6FD002111221E2078 +:1012200005F086FF012160221E2005F081FF642069 +:1012300003F0A9FD049806F09DF9C146C3460221BA +:1012400001221E2005F074FF322003F09CFD04985B +:1012500006F090F9BDF94C20BDF94E10BDF95030A3 :1012600093449142B8BF0A4698449A42B8BF134685 :1012700013F5805F89440ADD1E4BBAF1010ADA6872 :1012800082F01002DA60DAD14FF0010A01E04FF08B -:10129000000A1E200021122208F05AF80A23022117 -:1012A00001221E20029308F053F8322001F06DF95C -:1012B000049808F029FCBDF94C10BDF94E00BDF9A9 +:10129000000A1E200021122205F04AFF0A23022123 +:1012A00001221E20029305F043FF322003F06BFD64 +:1012B000049806F05FF9BDF94C10BDF94E00BDF978 :1012C0005020C1EB0B0B8842B8BF0146C2EB0808A7 :1012D0009142B8BF0A4612F5805FC0EB0909029B34 :1012E0002CDD044A013BD16881F01001D160D6D1D8 -:1012F00026E000BF000C0140DC0B002035FA8E3CDC -:10130000000C00200AE81C4100401C46F80A00209E -:10131000240B0020BD378635D80B0020D80C0020C8 -:10132000C0430108F41F0020D40C002074270020C3 -:101330000010024000100140240000204FF0000A7D -:10134000AF4B584602930DF01BFD0146AD480DF022 -:101350001FFE20F00040A06148460DF011FD01463F -:10136000A8480DF015FE20F00040E06140460DF069 -:1013700007FD0146A4480DF00BFE20F0004020625E -:10138000002170221E2007F0E3FF012120221E20F1 -:1013900007F0DEFF022100221E2007F0D9FF6420A3 -:1013A00001F0F3F8029BBAF1000F04D14FF07E5226 +:1012F00026E000BF000C0140A404002035FA8E3C1B +:10130000C80400200AE81C4100401C46C00300201D +:10131000EC030020BD378635A0040020A005002086 +:10132000D44401083C2000209C050020D727002041 +:101330000010024000100140000000204FF0000AA1 +:10134000AF4B584602930DF01FFC0146AD480DF01F +:1013500023FD20F00040A06148460DF015FC014639 +:10136000A8480DF019FD20F00040E06140460DF066 +:101370000BFC0146A4480DF00FFD20F00040206258 +:10138000002170221E2005F0D3FE012120221E2004 +:1013900005F0CEFE022100221E2005F0C9FE6420C9 +:1013A00003F0F1FC029BBAF1000F04D14FF07E5222 :1013B0009A61DA611A62954B10221A61944B0122EC -:1013C0001A700AF089FB0EA80021142210F0C1FC4B +:1013C0001A700BF025FD0EA80021142210F0FDFC70 :1013D0006B790E2B01D0082B02D101238DF84330FD :1013E0008C4A8C4C9368B4F8E000C3F380418DF8CC :1013F0003E108949C3F3400209688DF83D20C3F3CC @@ -347,104 +347,104 @@ :10159000606886F80091C6F80C41ADF84C308DF8C3 :1015A0004E10022304998DF84F3086F8B890C6F893 :1015B000BC90C6F8C090C6F8C490C6F8F89086F8FB -:1015C000FE9086F8FF90039201F0A8FD039A217B1C -:1015D00052F80B004A4604F0E1FB204649464246D9 -:1015E0000BF0B8F9134B1449C6F81031134BC6F879 -:1015F0001891C6F8143120460A1D05F07BFABFE0A9 -:101600000000002000406F4601C05E46000C014013 -:10161000CC090020E41F0020D40C0020200B002067 -:1016200038010020C0430108D80C0020D05F010819 -:10163000000400401521000848020020F1210008A4 +:1015C000FE9086F8FF90039209F0FCF9039A217BC4 +:1015D00052F80B004A460AF0E1FE204649464246D0 +:1015E0000AF070F9134B1449C6F81031134BC6F8C2 +:1015F0001891C6F8143120460A1D07F0ABFBBFE076 +:101600002400002000406F4601C05E46000C0140EF +:10161000940200202C2000209C050020E8030020DC +:1016200058070020D4440108A0050020606001088C +:1016300000040040C19F0008680800209DA0000829 :10164000B8F1020F43D10599B448CBB21C215943DC :101650004FF0000300EB010989F8023089F80A30E5 :10166000059B94F80FE089F8013001234354A168E9 :101670006068C9F80C40ADF84C1004998DF84EE044 -:10168000029303928DF84F8001F048FD039A217B6D -:1016900052F80B00002204F081FB029B20461A4600 -:1016A00000210BF057F99E4B0020C9F810309D4BDC +:10168000029303928DF84F8009F09CF9039A217B15 +:1016900052F80B0000220AF081FE029B20461A46F7 +:1016A00000210AF00FF99E4B0020C9F810309D4B25 :1016B000C9F81800C9F81430204609F1100109F1E1 -:1016C000140205F017FA059C0134059458E0B8F1AE +:1016C000140207F047FB059C0134059458E0B8F17B :1016D000030F39D19DF83E30DFF85C8233B198F8C2 :1016E000B690204608214FF6FF721CE0BDF844304A :1016F00098F8B690B3F5FA7F0FD98B4A2046B2FB23 -:10170000F3F20821BDF8483092B20AF09BFE08EBD4 +:10170000F3F20821BDF8483092B207F0FBFB08EB7A :101710008903C3F8E001854B0EE0854A2046B2FB01 -:10172000F3F2012192B2BDF848300AF08BFE08EBCB +:10172000F3F2012192B2BDF8483007F0EBFB08EB71 :101730008903C3F8E0017F4BC3607F4B93F8B62069 :10174000013283F8B6201BE0B8F1040F18D1BDF8C0 :101750004630774ADFF8E08192FBF3F22046BDF88D -:101760004A30012192B298F8B5900AF06BFE08EB6E +:101760004A30012192B298F8B59007F0CBFB08EB14 :101770008903C3F8100298F8B530013388F8B53002 :101780000AF1020ABAF11C0F7FF494AE9BE66B4B90 :1017900006EB030E98E80F008EE80F00684B10363A :1017A0001A78C02E02F101021A7009D0D4F8B030B4 -:1017B0000021985903EB06080DF0CAFC0028E6D07A +:1017B0000021985903EB06080DF0CEFB0028E6D077 :1017C000AB68DB0420D419E05E4B5D4A03EBC90330 :1017D00093F830C0D3F8348082F800C0B8F1000F1D :1017E000EED000266645EBDA544A330103EB020ED5 :1017F00043440FCB01368EE80F00F3E7B9F1080F31 :10180000DFF86C8128D12AE04D4B93F800A0BAF1A3 :10181000010FF3D94C4E4FF00008D04506F11006E9 -:10182000ECDA56F8100C4FF07C510DF0FDFA4FF049 -:101830007C5146F8100C56F8140C0DF0F5FA4FF0E8 -:101840007C5146F8140C56F80C0C0DF0EDFA08F12A +:10182000ECDA56F8100C4FF07C510DF001FA4FF045 +:101830007C5146F8100C56F8140C0DF0F9F94FF0E5 +:101840007C5146F8140C56F80C0C0DF0F1F908F127 :10185000010846F80C0CE0E7B9F10E0F04D198F836 :10186000003043F0100303E098F8003023F0100339 -:1018700088F800300BF002FD3449354B3548364AC4 +:1018700088F800300CF09AF83449354B3548364A30 :10188000C4F8F43201600023B5F81A01C4F8F0126C :10189000A4F8FA3284F8FC32C4F80023C4F8042314 :1018A0002E4958520233242BFAD12D4B1A60AB68C3 :1018B0001E0740F1AE802B4B002293F81831042B09 :1018C00000F2A180DFE803F00303567C8B00012BBC -:1018D0004FF0030208D184F82C23072284F82E331A -:1018E00084F82D230C2308E0022384F82C330023F2 -:1018F00084F82E3384F82D23072384F82F33002314 -:1019000000931020012318494FF4E13209F086FFBB -:10191000164BC4F83403C4F8383370E038020020A2 -:10192000D95D0008E920000800127A0011220008A1 -:1019300040420F0001220008380100206803002007 -:1019400098270020C043010870030020F4200020E5 -:10195000B8440108740800202C0400204004002032 -:1019600078090020E41F00202559000829580008A4 -:10197000BA0900200123574A574900931020052334 -:1019800009F04CFFC4F83C030646B5F81A010DF007 -:10199000F7F952490DF048FA51490DF03BF90DF0B5 -:1019A0002FFC00234F4A98500433402BFAD14E4B62 -:1019B000301CC4F838334FF0100384F82F331FE085 -:1019C00000920123102049494FF4E13209F026FF2B -:1019D000474BC4F84003C4F8383310230DE000929D -:1019E0000123102043494FF4E13209F017FF424B25 -:1019F000C4F84403C4F83833082384F82F33003084 -:101A000018BF012028B9082001F04FF90023C4F8BD -:101A10003833AB68580405D5082284F82F23374A99 -:101A2000C4F8382342F201021A4003F0010103F422 -:101A300000505AB1324AC4F8382318B1314A08204C -:101A400082F82F0311B10C2284F82F2394F82F234E -:101A50001906A2F1040284F8302369D5294B2A4AD9 -:101A6000D5F83811C3F848230023284A02EB0310A5 +:1018D0004FF0030208D184F80823072284F80A3362 +:1018E00084F809230C2308E0022384F8083300233A +:1018F00084F80A3384F80923072384F80B33002380 +:1019000000931020012318494FF4E1320BF022F923 +:10191000164BC4F81003C4F8143370E058080020C4 +:10192000D9C30008959F000800127A00BDA00008E6 +:1019300040420F00ADA00008580700208809002091 +:10194000E1270020D4440108900900203C21002018 +:10195000CC4501083C0100204C0A00201A07002059 +:10196000400200202C200020054C000859450008AA +:10197000820200200123574A574900931020052373 +:101980000BF0E8F8C4F818030646B5F81A010DF094 +:10199000FBF852490DF04CF951490DF03FF80DF0AC +:1019A00033FB00234F4A98500433402BFAD14E4B5F +:1019B000301CC4F814334FF0100384F80B331FE0CD +:1019C00000920123102049494FF4E1320BF0C2F894 +:1019D000474BC4F81C03C4F8143310230DE00092E5 +:1019E0000123102043494FF4E1320BF0B3F8424B8E +:1019F000C4F82003C4F81433082384F80B330030F0 +:101A000018BF012028B9082008F0B1FD0023C4F850 +:101A10001433AB68580405D5082284F80B23374AE1 +:101A2000C4F8142342F201021A4003F0010103F446 +:101A300000505AB1324AC4F8142318B1314A082070 +:101A400082F80B0311B10C2284F80B2394F80B23BA +:101A50001906A2F1040284F80C2369D5294B2A4AFD +:101A6000D5F83811C3F824230023284A02EB0310C9 :101A7000D0F824011646884204D00133DBB2042B8F -:101A8000F3D9002384F84D33214B0020C4F8683388 -:101A900004F0D4FF1F4B94F84D231B680021C4F8B9 -:101AA000543395F8283106EB02128B42C4F85013D8 +:101A8000F3D9002384F82933214B0020C4F84433D0 +:101A90000AF0A4F81F4B94F829231B680021C4F80E +:101AA000303395F8283106EB02128B42C4F82C1320 :101AB0004FF020000091D2F824210CBF0123032312 -:101AC00009F0ACFEC4F86C0330BB802001F0EDF8E7 -:101AD00025E000BFA0860100315A0008CDCCCC3FE4 -:101AE0000000B04494080020DD580008BD590008EB -:101AF000CD58000871590008B95800080959000864 -:101B0000155900083801002010210020C0430108A9 -:101B10000C210020E01F0020012004F08FFF8C4BDF -:101B200018688C4B00F5D97204301A6001F0F6F990 -:101B3000AB689A050CD59E044CBF874887480AF0CD -:101B40001BFC3B68002243F010033B60844B1A608F -:101B5000844BD4F80023C4F870338033C4F8743352 -:101B6000AB68814E0027D803C4F87823377040F162 -:101B7000B380DFF820B2DFF820A201F00BF901F00A -:101B800045F901F01FF940F22A334FF001091A46D6 -:101B90005846394686F80090029310F0DAF8DAF8E1 -:101BA0001820724842F00402CAF818204022ADF80A +:101AC0000BF048F8C4F8480330BB802008F04FFD05 +:101AD00025E000BFA0860100114D0008CDCCCC3F11 +:101AE0000000B0445C0100200D4600089D4C000839 +:101AF000FD450008514C0008E9450008394600083A +:101B0000454600085807002058210020D444010809 +:101B1000542100202820002001200AF05FF88C4B7F +:101B200018688C4B00F5D97204301A6008F058FE22 +:101B3000AB689A050CD59E044CBF8748874809F0CE +:101B400001FF3B68002243F010033B60844B1A60A6 +:101B5000844B8549D4F800230B608033C4F84C33A0 +:101B6000824B834E1A60AB680027D803377040F170 +:101B7000B380DFF828B2DFF828A208F06DFD08F086 +:101B8000A7FD08F081FD40F22A334FF001091A4603 +:101B90005846394686F80090029310F016F9DAF8A4 +:101BA0001820744842F00402CAF818204022ADF808 :101BB000302018228DF833200CA903228DF8322012 -:101BC00004F08AF9DAF81C20694E42F00202CAF8E1 -:101BD0001C20684AAAF6947A1168674AB1FBF2F1B0 +:101BC0000AF088FCDAF81C206B4E42F00202CAF8D8 +:101BD0001C206A4AAAF6947A1168694AB1FBF2F1AC :101BE0003288013922F45C721204120C328089B2FC :101BF0001D22B2853185A6F81490328C22F00102A4 :101C00001204120C3284328CB088318B22F0020222 @@ -452,5687 +452,5697 @@ :101C200080B242EA0902B0803183B7863284328BB7 :101C300022F008021204120C42F008023283B6F8B5 :101C400044206FEA42426FEA524292B2A6F8442020 -:101C5000DAF8A82F42EA0902CAF8A82F504604F081 -:101C6000E9F9464A029B1392802218924FF480723F +:101C5000DAF8A82F42EA0902CAF8A82F504602F083 +:101C60004BFD484A029B1392802218924FF48072D7 :101C7000CDF850B019924FF0100B4FF4005250466F :101C800004991C92CDF854B0169317971A971B9786 -:101C90001D9704F0B1F9B2890DA892B242F4007216 +:101C90001D9702F013FDB2890DA892B242F40072B2 :101CA000B281DAF8002042F00202CAF800208DF872 -:101CB00034B08DF835908DF836708DF8379005F08A -:101CC000D5F82F4B1A682F4BFA500437802FF8D1D4 -:101CD00004F0F5FF04F0F3FFAB68590540F18E8086 -:101CE00001F03EF808B1082000E00420012107F0CF -:101CF00056F9AB6884F8260713F4806F224E01D1A1 +:101CB00034B08DF835908DF836708DF8379003F08C +:101CC000BDFF314B1A68314BFA500437802FF8D1E1 +:101CD00003F0DEFE03F0DCFEAB68590540F19280B4 +:101CE00008F0A0FC08B1082000E00420012109F060 +:101CF000B4F9AB6884F87A0613F4806F244E01D1EE :101D000000201DE033681B78032B05D133681B7856 -:101D1000032B0BD0012013E0042007F0B0F801469C -:101D2000042006F07BFF0028F0D1E9E7082007F047 -:101D3000A6F80146082006F071FF003018BF012008 -:101D4000124B36681870337843BB114B1E6049E064 -:101D5000200B0020C40C0020304501083C45010840 -:101D6000A400002038210020BE0D00200008014002 -:101D7000000400409400002000366E01340400404E -:101D800048450108DE070020E40C0020E00C00209C -:101D90000C0D0020B404002000100240012B21D1C2 -:101DA000434F002138462C22C4F828670FF0D1FF9A -:101DB0008E237B704FF07C0AE0234FF07D09FB708F -:101DC00087F800A087F82B903A4F002138462C2244 -:101DD0000FF0BFFF8A237B70A02387F800A0FB7061 -:101DE00087F82B903378022B08BFC4F82C6700F0DB -:101DF000B7FF08B1C4F8306709F020FFAB6813F4EF -:101E0000002300D0012384F8363700F099FB2A4BD9 -:101E100018606B79052B03D1284B4FF4C8721A80D8 -:101E2000274B4FF47A721A80264BC8221A8098F8F2 -:101E3000003043F0080388F80030234B1A7822F072 -:101E400002021A70AB689A071ED5204B204A1D4625 -:101E50001A6004F035FA282000F097FB0699013942 -:101E60000691F6D129681B4B48781E78024601235B -:101E7000964203D30133082B0244F9D1164A13705A -:101E80008A785343A4F83437144B9B689B030CD5D2 -:101E900094F8633043F0010384F86330032384F83B -:101EA000643002E0032000F081FB1FB0BDE8F08F3A -:101EB000200D00204C0D0020380C0020A40B002029 -:101EC000882700208027002096270020F40C00207F -:101ED000E8200020F80C002098000020E41F0020DB -:101EE000034B4FF4805208B11A6170475A61704732 -:101EF00000080140034B4FF4805208B15A6170470B -:101F00001A61704700080140032810B50F4B0DD827 -:101F10000F4A126894888C4208D2D2888A4205D926 -:101F2000012202FA00F01A78104318701B780F2B68 -:101F30000BD1064B00221A70064B998808B2142860 -:101F400002DD1439998010BD9A8010BDC00D0020AB -:101F5000DC1F00202C040020024B9A8801329A805A -:101F6000704700BF2C040020074B1A68074B1178FC -:101F7000B3F9040053780B4403EB83039842D4BFB6 -:101F800000200120704700BFDC1F00202C0400202F -:101F9000064BB3F90400064B1B681B7803EB830365 -:101FA0009842D4BF00200120704700BF2C040020BD -:101FB000DC1F002010B50446FFF7EAFF002814BF1D -:101FC0002046002000F0010010BD024B01221A72D1 -:101FD000704700BF2C040020014B187A704700BFE7 -:101FE0002C040020034BB3F90400D0F1010038BFEA -:101FF000002070472C040020014B00229A8070477B -:102000002C04002003685A1C026019707047016B91 -:102010000346C26810B5406941B1196C541A005D9D -:10202000013918BF0A46C0B21A6410BD196A405C73 -:102030000131B1FBF2F402FB1412C0B21A6210BDFE -:10204000026B03691AB15168013B026C02E0C1697D -:10205000026A013B881A1840C0B27047436B13B143 -:1020600090F844007047826A436AD31A5842584134 -:10207000704743799B070AD5436A8269D154426A03 -:1020800003690132B2FBF3F103FB11234362704792 -:10209000437913F0010307D0C368C169026A013BA9 -:1020A000881A1840C0B2704718467047437910B577 -:1020B00013F0010304460DD0FFF7EAFF58B1226A7E -:1020C0006369985CE3680132B2FBF3F103FB11230F -:1020D000236210BD184610BD426A806A131A584226 -:1020E000584170474171704710F80A3C0133DBB228 -:1020F0000A2B00F80A3C0AD910F8123C23B910F850 -:10210000131C034A22F81130002300F80A3C7047E0 -:10211000E6110020334A10B5136C90681944081A70 -:1021200040F68C2398429160D060516013463CD9B0 -:10213000127893F945108A420BD1111F082908D84B -:1021400093F84610182901D8013103E083F84420A0 -:1021500002E0002183F8461093F944108A421CD112 -:10216000204991F84710C1B1002191421E4806DA7A -:1021700003EB8104246920F811400131F5E7511E79 -:1021800000EB41011630814203D0002421F8024FB8 -:10219000F9E7164908780130087083F845200022D5 -:1021A00001211A7083F8471010BD92F84710B9B199 -:1021B000A0F2EF2440F2DA518C4208D811780B29B2 -:1021C00005D80B1D0131117042F8230010BD00220B -:1021D00083F84720991804320020302A0861F9D189 -:1021E00010BD00BFF0010020E6110020111D0020ED -:1021F000024B1A6C0132114419647047F00100203F -:10220000024B53F820301B681980704718030020D8 -:10221000074BA1F57A7153F820304FF47A701A68A1 -:102220001B894B4393FBF0F39BB21380704700BFB5 -:10223000180300202DE9F04F504A514E176873895A -:1022400084463089A7EB032785B0039187FB000103 -:10225000B288CB111404C209F08842EA416287FBBC -:10226000000114EB020872884FF000054FEAC234F7 -:102270004FEA1022B08945EB030942EA01620B12D2 -:1022800087FB000114EB020A4FEAD05242EA4122D6 -:102290004FF0000545EB030B12F5FA604FEAE153EE -:1022A00043F10001CDE90001B0F5FA6F71F10001D1 -:1022B00047DAA2FB024502FB03F1052605EB4105C7 -:1022C000A4FB060106FB05114D104FEA3004B8EBE4 -:1022D000040869EB050984082A4844EA81748D10D2 -:1022E0004FF0FF31BAEB040A6BEB050BDDE900455B -:1022F00084428D4125DA40F6AC5012184FF00001AF -:1023000043EB010302FB03F1A2FB02236FF0060083 -:1023100003EB4103544200FB0344A2FB000118EB12 -:10232000000821444FF00B0449EB0109A2FB040112 -:1023300004FB031149104FEA3000BAEB000A6BEBC3 -:10234000010B114B1A68A2FB0A0102FB0B11420D93 -:1023500042EAC1224B15B2EB080263EB0903D00B32 -:1023600040EA4340BCF1000F01D0CCF800000398D4 -:1023700008B10099016005B0BDE8F08F5417002046 -:10238000AC01002024FAFFFF58170020324B2DE942 -:10239000F0411C88314B0A265A89B3F91250A41A0D -:1023A0001A89ED025443B3F91420E413224495FB37 -:1023B000F2F22244DA615643A2F57A6202FB02F499 -:1023C000B3F90480B3F902C0B3F90E7002FB0CFC40 -:1023D00002FB08F2B3F90C802413674304FB08F4F2 -:1023E000241404EB62320232DC88921002F50042BF -:1023F000B3F920506243B3F900304FEAEC2404EB08 -:10240000E72404EB8304AC40154B02341B68D20B69 -:10241000A3EBA4044CF250332B41634355BF5B0044 -:10242000B3FBF2F3B3FBF2F35B001A12524340F634 -:10243000DE3462430B4C08365C43241404EB224226 -:1024400002F6CF62361103EB221300B1036001B133 -:102450000E60BDE8F08100BF64170020C0010020BD -:102460006017002043E3FFFF2DE9F0478278C6782C -:102470001E4BC2F1640802EB820C54425FFA88F8EA -:102480004FEA4C0CC6F16409A4B203F11807A5B2D7 -:1024900028B2002804DC002D14BF1546012500E0F9 -:1024A000454600FB00FA6D430AFB06FA9AFBF5F578 -:1024B0004D4468434FF00A0A90FBFAF0604480B242 -:1024C00058800D88B1F802A000B2C5EB0A0A00FBE3 -:1024D0000AF04FF47A7A90FBFAF0054423F8025F91 -:1024E0000A34BB42A4B2D2D1BDE8F087E60E002088 -:1024F00010B544780078002303FB03F119396143D8 -:1025000001F6C4115943414340F6C41291FBF2F164 -:10251000034A22F813100133072BEDD110BD00BF81 -:10252000D00E002010B5044C2068FFF7E1FF2068B2 -:102530000249BDE8104097E7D00C0020B4200020ED -:1025400010B5094A094913688C6812689342F8D19A -:10255000074A106811684FF47A725043001BB0FBB1 -:10256000F1F002FB030010BDE01F002010E000E0CE -:102570004001002038B50446FFF7E2FF0546FFF7AB -:10258000DFFF401BA042FAD338BD10B504462CB182 -:102590004FF47A70FFF7EEFF013CF8E710BD08B585 -:1025A000014B1B68984708BD7827002040F2DB14D8 -:1025B000604308B50D4B10225A6108221A61841E2F -:1025C0000A4B2046DA6882F01002DA60DA6882F09C -:1025D0000802DA60FFF7D9FF0120FFF7E0FF1920BA -:1025E000FFF7D3FF0020FFF7DAFFE9E7000C014017 -:1025F00008B503685B69984708BD08B503681B699F -:10260000984708BD08B50368DB68984708BD08B55A -:1026100003689B68984708BD08B503685B689847DE -:1026200008BD10B5044C2068FFF7F6FF18B120680C -:10263000FFF7EDFFF6E710BD800D002008B5036839 -:102640001B68984708BD014B1868F7E7581E002023 -:10265000014B01461868F1E7D01F002010B5044671 -:102660007F2C06D964F07F00C0B2FFF7F1FFE409C8 -:10267000F6E7E0B2BDE81040EAE7430083EAE07025 -:10268000ECE770B5104E114C114D4720FFF7E0FFFD -:102690003078FFF7E3FF23682868C01AFFF7EDFFE3 -:1026A00063686868C01AFFF7E8FF0A4B1888FFF7ED -:1026B000D5FF094B1888FFF7D1FF337823742B68B7 -:1026C000A3606B68E36070BD080D0020441B002010 -:1026D000140D0020060D0020040D0020014B186889 -:1026E000ACE700BFD01F0020A0F17D03012B70B527 -:1026F00004460D460A4E05D830687D21FFF79EFF3F -:1027000084F0200430682146FFF798FF35B12B880C -:102710001C4404EB142404F0FF042C8070BD00BFA3 -:10272000A80D002038B5054C05465E212068FFF74E -:1027300085FF20682946BDE838407FE7E80C002087 -:10274000014B5E21186879E7E80C002010B50A4CAF -:102750005E280146206805D15D21FFF76FFF2068E4 -:102760003E2105E05D2903D1FFF768FF20683D2188 -:10277000BDE8104062E700BFE80C002010B5044639 -:10278000C0B2FFF7E3FFC4F30720BDE81040FFF736 -:10279000DDBF064B1B6803EBC00090F90630194201 -:1027A0000CBF01204FF0FF30704700BF5C1E0020BF -:1027B0000A4B1A6802EBC002D379FF2B07D00849F5 -:1027C0000978994203D9074A32F8130004E0072830 -:1027D000D4BF908840F2DC5000B270475C1E0020ED -:1027E00067040020400400202DE9F04F0C68836846 -:1027F00089B0D0F800A0D0F80480064620460393A4 -:102800008B460FF0D5FC074620460FF045FDDBF860 -:102810000440814620460FF0CBFC054620460FF0D1 -:102820003BFDDBF808200446104601920FF0C0FC87 -:10283000019A834610460FF02FFD39460290584604 -:102840000CF0F2FA3946049002980CF0EDFA594671 -:10285000059048460CF0E8FA0299069048460CF0BC -:10286000E3FA2946079058460CF0DEFA0146504636 -:102870000CF0DAFA2146834606980CF0D5FA0146A8 -:1028800005980CF0C9F9014640460CF0CDFA014616 -:1028900058460CF0C1F92146834604980CF0C4FA5E -:1028A000014607980CF0B6F9014603980CF0BCFA03 -:1028B000014658460CF0B0F93060029905F100402D -:1028C0000CF0B2FA014650460CF0AEFA21468346AF -:1028D00007980CF0A9FA014604980CF09BF9014600 -:1028E00040460CF0A1FA014658460CF095F92146F5 -:1028F000834605980CF098FA014606980CF08CF97E -:10290000014603980CF090FA014658460CF084F901 -:102910002146706050460CF087FA2946044609F1BA -:1029200000400CF081FA014640460CF07DFA014669 -:1029300020460CF071F93946044628460CF074FA2A -:10294000014603980CF070FA014620460CF064F939 -:10295000B06009B0BDE8F08F2DE9F84F2E4E044667 -:10296000376838460FF024FC054638460FF094FCD3 -:102970007668804630460FF01BFC834630460FF0E9 -:102980008BFCD4F804900646294648460CF04CFAD5 -:10299000A7688246414638460CF046FA0146504642 -:1029A0000CF038F92168824658460CF03DFA414651 -:1029B000044648460CF038FA31460CF035FA014628 -:1029C00020460CF029F93146044638460CF02CFA22 -:1029D00029460CF029FA014620460CF01DF9014663 -:1029E00050460FF0E7FC0D490CF01EFA0C490CF0B4 -:1029F000CFFA0C4B19680CF00FF90B490CF0C8FA20 -:102A00000FF00CFC83B21A0444BF00F5B4739BB200 -:102A100018B2BDE8F88F00BF040C00200000E144AC -:102A2000DB0F4940E401002000002041064B1B78E9 -:102A300003F0040303F0FF001BB1044B1888C0F33C -:102A4000C01000F001007047962700208C0900207C -:102A50002DE9F04102780346202A00F10100F9D067 -:102A6000092AF7D02D2A02D10346414D04E02B2A32 -:102A700008BF03464FF07E551E460024334616F825 -:102A8000012BA2F13007F9B209290DD839492046A6 -:102A90000CF0CAF9044638460CF072F9014620469B -:102AA0000CF0BAF80446E9E72E2A17D1314F334625 -:102AB00016F8010B3038C2B2092A0FD80CF060F9B1 -:102AC00039460CF065FA014620460CF0A5F8294974 -:102AD000044638460CF0A8F90746E8E71A7802F0F1 -:102AE000DF02452A38D15A782D2A02D10233012635 -:102AF00004E02B2A14BF013302330026013B0027D8 -:102B000013F8012F303AD1B2092903D80A2101FB69 -:102B10000727F5E7B7F59A7F28BF4FF49A77B846AD -:102B20004FF07E51B8F1070F07D9084612490CF053 -:102B30007BF9A8F108080146F4E707F0070737B169 -:102B400008460C490CF070F9013F0146F7E72EB139 -:102B500020460CF01DFA04E04FF07E5120460CF0A8 -:102B600063F9014628460CF05FF9BDE8F08100BF2B -:102B7000000080BF0000204120BCBE4CF0B5012405 -:102B8000B0FBF4F58D4201D34C43F9E70026DCB1EC -:102B9000B0FBF4F504FB1500B4FBF1F41EB9002DF5 -:102BA00001DC002CF3D1092D03F101075FFA85FC4C -:102BB00004DD002A0CBF5725372500E03025654489 -:102BC0001D7001363B46E2E71C70F0BDF0B50124F4 -:102BD000B0FBF4F58D4201D34C43F9E70026DCB19C -:102BE000B0FBF4F504FB1500B4FBF1F41EB9002DA5 -:102BF00001DC002CF3D1092D03F101075FFA85FCFC -:102C000004DD002A0CBF5725372500E03025654438 -:102C10001D7001363B46E2E71C70F0BD70B50646FC -:102C2000B6FBF2F40846154614B12046FFF7F6FF4E -:102C300005FB1464024B1B5D00F8013B70BD00BF37 -:102C4000AA6101082DE9F041069C002B06460F46BB -:102C50000CBF4FF020084FF03008234613F8011B3B -:102C600009B9154603E0002AFBDD013AF6E7002D1D -:102C700004DD30464146B847013DF8E714F8011B32 -:102C800011B13046B847F9E7BDE8F08180EAE0735A -:102C9000A3EBE0738B4206DB002801DD401A70478E -:102CA00002D00844704700207047034B9A6822EA1C -:102CB00000009860704700BFE41F00200E4B1B7897 -:102CC000BBB10E4B1B681A78032A06D10C4B18783F -:102CD00002288CBF0020012070475B7823B1094B8C -:102CE0001868C0F3C0407047074B1878C0F38000E5 -:102CF00070470120704700BF5E080020E40C0020F0 -:102D0000A40D00208809002096270020114A30B524 -:102D10000028B8BF4042104C90FBF2F304FB0300C4 -:102D20003C2568430D4D90FBF2F22D682D7B25B9B3 -:102D300003EB830303EB830301E0C3EB031302EB19 -:102D4000830304FB02020B804FF47A7392FBF3F2CD -:102D50004A8030BD80969800806967FF0C0D002086 -:102D6000034B1B681878C31E58425841704700BF78 -:102D7000E40C002008B506480FF02CF8C0B2142867 -:102D800005D8034A431C20211154D8B2F7E708BDE7 -:102D900081170020094A0A48002310B51168037002 -:102DA0001A46CC1864880CB9CC5C24B104330132C7 -:102DB000802BD2B2F5D1027010BD00BFA804002054 -:102DC0007412002010B50B4B0B4819780B4B5A7836 -:102DD0004B085C1E047001F0010109480B440370AC -:102DE00008495308581E087002F0010206491344AE -:102DF0000B7010BD811200207C120020C00D00203D -:102E00007E1200207F1200207D120020F0B50F4AB4 -:102E10000F4816780F4A0023176843701A46194660 -:102E20000546D0B2B0420CD217F822000132040994 -:102E30009C4200F00F00A8BF631C8842A8BF411C41 -:102E4000EFE76B70044B1970F0BD00BF74120020E7 -:102E5000C00D0020A804002081120020F8B5101A2F -:102E60000C461F460BF08CFF0546381B0BF088FF05 -:102E7000174B079E19680BF0D7FF294604462846D2 -:102E80000BF0D2FF2146074620460BF0CDFF01464E -:102E900038460BF0C1FE0FF017FC0E490BF0C4FFD3 -:102EA0000CF0AEF9069B2146186005F100400FF0CA -:102EB00081FA09490BF0B8FF08490BF0ADFE0CF0A0 -:102EC00079F90028BCBF00F50C40A0303060F8BD97 -:102ED0004C0000202C7D8E3FA00CB34500A00C467A -:102EE00010B50BF04DFF002104460CF059F908B164 -:102EF000204601E004F1004005490CF049F805497D -:102F00000BF092FF0FF054F9034B186010BD00BF97 -:102F10008096184B35FA8E3C4C00002070B5044664 -:102F200000790BF029FF1E490CF032F81D4D1E4EA2 -:102F30002860A07B0BF020FF19490CF029F8EE6007 -:102F4000686060790BF018FF18490CF021F8184DF3 -:102F50002860E07B0BF010FF11490CF019F8686055 -:102F6000607E0BF009FF13490CF012F8EE60A860C8 -:102F7000A0790BF001FF0D490CF00AF80E4D286006 -:102F8000207C0BF0F9FE06490CF002F86860A07E88 -:102F90000BF0F2FE07490BF0FBFFEE60A86070BD7E -:102FA0000000C842601100200000FA4400002041E7 -:102FB0007011002000007A449411002044F2506304 -:102FC000984203DDA0F50C40A0387047034B9842AF -:102FD000BCBF00F50C40A030704700BFB0B9FFFF88 -:102FE0002DE9F041038A87890446BFB20D461F4090 -:102FF000002F36D0B7FA87F34FF00042DA40D243C1 -:1030000091B21B3B21821740042BF1D8DFE803F07B -:10301000221F1C1903006B6A33B103F1FF38002330 -:103020001FFA88F86B6203E0B4F82C801FFA88F866 -:103030002E6A002EDCD033683046414698477668C9 -:10304000F7E72868A18E08E06868218F05E0A86886 -:10305000A18F02E0E868B4F84010036889B298478D -:10306000C6E7BDE8F0810C4B800A98420CD003D82B -:10307000B0F5801F0ED00BE0084B984206D04933C4 -:10308000984205D100207047022070470320704706 -:10309000FE20704701207047010010000200100060 -:1030A00090F83B3210B57BB990F83A3290F839225B -:1030B000934209D201219940B0F8404201332143A3 -:1030C000A0F84012DBB2F3E710BD8379012B03D1E6 -:1030D000D1F1010138BF0021D0F834315A681B8981 -:1030E00009B11361704753617047044B53F82030A6 -:1030F0001BB107289CBF1B6819807047480300203C -:1031000010B5054C00202188FFF7EFFF61880120F2 -:10311000BDE81040E9E700BF360000202DE9F0418E -:103120000F88002347FA03F2D2072BD58A7803F0E1 -:10313000070512F0100F18BF91F803C002F00F0638 -:1031400018BF46EA0C06AD004FF00F0C0CFA05FC58 -:1031500006FA05F5DC0850F82480282A28EA0C0C29 -:1031600045EA0C0540F8245005D101229A40C46874 -:1031700024EA020205E0482A04D101229A40C468E8 -:103180002243C2600133102BCCD1BDE8F08100BFD7 -:10319000A14A2DE9F04F1368A04903F59C43A04DC7 -:1031A00020330B60AB6885B013F4807F174604D0E2 -:1031B0009C4B1B681B681B699847AB6842F2010473 -:1031C0001C405CB9984E337873B1964B1B681B68F2 -:1031D0001B68984709F064FF347005E0934B1A7838 -:1031E00001321A7009F05CFFAB68DA0405D5904B28 -:1031F0001B68DB0701D40AF0E7FF8E4B3C681868B8 -:10320000037CCBB18C4A013B32F91300A0F57A70F4 -:10321000B0F57A7FA8BF4FF47A7020EAE0700BF027 -:10322000AFFD86490BF0B4FE85490BF0FDFD0BF0B8 -:10323000E7FF7E4B588039E0AA68160436D57B4AF2 -:103240005168611A002931DB04F59C41203151603D -:103250007C494E797C4931F81660417CB6B296FBC8 -:10326000F1F0117A013101F00F0111720A4450722C -:1032700018466E4E06F109029A5C01331044102B79 -:1032800080B2F6D100B290FBF3F000B26428A8BF80 -:10329000642020EAE0700BF073FD6C490BF078FEBF -:1032A00067490BF0C1FD0BF0ABFF7080AB68D80530 -:1032B00010D5674B9C42674C08D923681B681B6A72 -:1032C000984718B923681B685B6A984723681B688E -:1032D0005B699847AA68DFF860A112F4805F504BE1 -:1032E000B5F8DC10BAF9062007D0B3F81A31581A2D -:1032F000824207DD19448A4202E0B3F81C319A4247 -:10330000C0F254840122002195F8238195F824010C -:10331000B5F81C61B5F81E710B463AF901409B08DF -:10332000B442C4BF63F07F03DBB20231BC42B8BF1A -:1033300043F040030829F0D13C4C617E994204D10E -:10334000A17EF92903D8013100E00021A17663763E -:10335000414B374F1978A1B93B68D90707D582B9D6 -:103360003E4B1B78DB070CD508F0F6FD09E03B4B24 -:103370001B785E0705D510B10AF026FF01E0002A90 -:10338000FAD0A37E294A142B354E40F09980334B56 -:1033900018F100081B7818BF4FF0010803F0040370 -:1033A00003F0FF0093B12C490B78002B00F08880CC -:1033B000537E5F2B01D10AF007FFB8F1000F7FD0D9 -:1033C000637E7D2B7CD10AF0FFFE79E0537E572B84 -:1033D0000BD1244B4FF47A721A80234B1B6813F0E5 -:1033E00008036DD1214A13806AE0A968490745D5D1 -:1033F0005A2B43D11E4B197819B1187001221D4B5D -:103400004DE0D17E1C4B81F00101D17609B104223F -:1034100045E0062243E000BF7C2700207C09002015 -:10342000E41F00207809002070080020C40D00204F -:1034300088090020740800204004002000007A441D -:1034400000C07F4458010020680100200000C842ED -:10345000404B4C00380400204800002096270020F4 -:10346000200B00208827002084090020180C002051 -:10347000D10B0020D30B0020D20B00205D2B00F0DD -:103480001D835B2B00F01C835E2B0AD1032218E303 -:10349000A72B40F05F83AA4B1A7842F004021A70FF -:1034A0000EE0562B01D108F079FAA64A1378002BCA -:1034B00000F01D83637E6F2B40F0138308F04CFDFA -:1034C000AB685B0731D5E37E9BB19F4B1B785807F8 -:1034D0000FD59E4BBAF90620B3F81C319A4208DD8D -:1034E0003B6813F0010304D1994A32211180994AB3 -:1034F000D3763B68D9030AD5974B1A782AB9974AED -:10350000127812B9924A3221118001220CE0934BB9 -:103510001A7852B18C4A127802F0040202F0FF01CC -:103520001AB919708E4B01221A70D6F80090002338 -:1035300009F1750B3B6009F1770698460BF1020320 -:1035400003EB080113F808204B7816F8010C9A4297 -:103550000AD2314603F0AAFA30B116F8023C012231 -:103560009A403B6813433B6008F10408B8F1A00F90 -:1035700006F10406E2D17B4B1B7843B13B68DFF8D0 -:10358000FC8113F0020F784E40F09A818FE109F22E -:103590001512019209F58B769846019A16F8010CDE -:1035A000531C03EB080113F808204B789A4228D2E9 -:1035B000314603F07BFA20B3B0786C4B013800EB56 -:1035C000400096F804B018444FF00C0CF3780CFB54 -:1035D0000BFC00935F4B03F11C0909EB0C014A68DB -:1035E00082420ED0009A09F80C2000228A60012243 -:1035F00002FA0BFB93F84C20486022EA0B0B83F88D -:103600004CB008F10608B8F1480F06F10606C4D11F -:10361000574BDFF86C811E68564B4FF00009D3F80A -:1036200000B0D8F80030002B00F03881197800295C -:1036300000F03481D8F80420C2EB0B02002A0CDB26 -:103640000BF5FA72C8F80420012202FA09F294F884 -:103650004C0020EA020284F84C2018F8040C5A7836 -:103660000430C0B2002A40F0E1803AF91020B5F8E9 -:103670001A0100F1C80C624501DD9B7813E0C838DF -:10368000824202DA9B785B420DE0012303FA09F3E0 -:1036900094F84C2022EA030384F84C300BF5FA73BB -:1036A000C8F80430FAE094F84C2042FA09F2D20744 -:1036B00000F1F480002B304ACCBF022001200139F8 -:1036C00010700A2900F2E280DFE801F0060F1B28E3 -:1036D000315C6E80929CA60032781344FA2BA8BF0E -:1036E000FA2323EAE373337007E072781344642B00 -:1036F000A8BF642323EAE37373703046FEF7F8FE35 -:10370000C4E0F27830461344642BA8BF642323EA54 -:10371000E373F370216DFEF7A7FEB7E0327913442F -:10372000642BA8BF642323EAE3733371AEE072799C -:103730001344642BA8BF642323EAE3737371A5E0E9 -:10374000BA0900204800002096270020E41F00202E -:10375000B80B0020C40D0020D00B0020D10B00209E -:10376000D30B0020902700208C090020B04A0108CC -:10377000D00C0020E01F0020D20B00208409002084 -:10378000E40D0020616D4A781A44C82AA8BFC822F7 -:1037900022EAE2724A700A781344C82BA8BFC823F1 -:1037A00023EAE3730B7071E0616DCA7A1A44C82A88 -:1037B000A8BFC82222EAE272CA728A7A1344C82BCE -:1037C000A8BFC82323EAE3738B725FE0616D4A7D73 -:1037D0001A44C82AA8BFC82222EAE2724A750A7DA2 -:1037E0001344C82BA8BFC82323EAE3730B754DE02D -:1037F000626D91780B44C82BA8BFC82323EAE373FA -:10380000937043E0626D117B0B44C82BA8BFC823A3 -:1038100023EAE373137339E0626D917D0B44C82B87 -:10382000A8BFC82323EAE37393752FE0012A2DD1A3 -:103830003AF910009B784FF49662B0F5617F92FBE5 -:10384000F3F305DB40F633029042B8BF024601E0D5 -:103850004FF46172A2F5617292FBF3F3DBB2A84AF6 -:10386000581C0C29107011D194F858209A420DD090 -:10387000A44A042B28BF02230A2184F8583001FBF4 -:103880000323A14A06331360FEF74CFE012303FA1B -:1038900009F394F84C20134384F84C3009F10109E2 -:1038A000B9F1040F08F10C087FF4BBAE66E6AB6813 -:1038B000D80514D5954B1B681B689B68984770B159 -:1038C000D8F800309B070AD5338813F001020CD1D9 -:1038D0008F4943F00103E26522660B8006E03388DE -:1038E000012223F00103338000E000223B685907E6 -:1038F00010D57AB1328822F0010102F0020289B2B9 -:1039000092B2318052B9E2652266814A41F00201E9 -:10391000118003E0328822F00202328032887D4931 -:1039200012F0030F4FF0100014BF48610861D8F87F -:10393000001011F00A0F21D0D80609D550070AD47B -:1039400042F004023280744A1088744A108002E007 -:1039500022F0040232809806328806D5500607D439 -:103960006B4842F04002028002E022F040023280C6 -:10397000580603D5684A1288A4F86420890640F1E5 -:103980008880674A127892077CD5664A1278042AA2 -:1039900078D913F4007C328812D002F010039BB265 -:1039A000002B76D15A4922F0200242F010025E48E4 -:1039B0000A805E4A011D537005F0EAF8022366E0B2 -:1039C00022F0100189B2580531802ED5584B1B6862 -:1039D0005889584BB3F90080B8F1000FB8BFC8F14F -:1039E0000008804509DAB3F90230002BB8BF5B420A -:1039F0008342ACBF0023012300E06346DB0714D5FC -:103A000002F0200292B2002A43D1484B4A485A7031 -:103A10004A4B41F020011A685B683180011DA367A1 -:103A2000626705F0B5F8012331E022F03002328000 -:103A30003E4A53786BBB012151701A464049002021 -:103A400050524049404C5052404904EB030C5052F4 -:103A5000002119510232CCF80400CCF8081004F10E -:103A6000280C503443F80C1019519C441C44042A6F -:103A7000CCF80400CCF808106060A16003F11403D6 -:103A8000DCD106E0338823F030033380002384F850 -:103A900070303B6813F4006F338814BF43F48073B5 -:103AA00023F4807333806B79082B02D00E2B40F007 -:103AB0009080338823F0400333808AE0012200E0C5 -:103AC00002225FFA82F808F1FF3385F8543708F0D4 -:103AD0008FFB0AF0D3F802202821424602F034FC82 -:103AE000EEE4B8F1000F02D07E2B3FF4E7AC637E2A -:103AF000972B7FF4CDAC164B4FF4C8721A80DFE4DD -:103B0000D20B002034270020D00C002038040020E5 -:103B10008C090020000C0140180C0020B20C002081 -:103B2000BA090020080D00202C0E002048000020BB -:103B3000C40C00209A090020380E0020140D00202B -:103B400092270020C80C0020400E0020CC0C002042 -:103B5000A40B00200022BB2B039201D1022303E01F -:103B6000B72B04D14FF6FE73ADF80E300AE0BE2B32 -:103B700001D1022304E0BD2B7FF4A2AC4FF6FE730B -:103B8000ADF80C303368BDF80C10B3F854200A447B -:103B9000A3F85420BDF80E10B3F856200A44A3F839 -:103BA000562007F0FBFE0023A37689E40A4B00228F -:103BB0000021DA651A66C3F8F420C3F8F820C3F8C8 -:103BC000FC20C3F80011C3F80411C3F80811FFF773 -:103BD0009ABB05B0BDE8F08FC40D0020664B2DE9FF -:103BE000F04FB3F90600654B87B01D682B899842EA -:103BF0000EDBB0F5FA6FAF7907DAC21A5743A3F5B7 -:103C0000FA6397FBF3F7643703E0C7F1640700E05A -:103C100064275B4B5B4AB3F81A1193F9EC301668D2 -:103C20005B4204919BB20021059334460A46524BF5 -:103C3000DDF810C0CB5E40F2E63E0393CCEB03030D -:103C400003F2F31CF44503D8002BB8BF5B4201E03C -:103C50004FF4FA73022ADFF8388131D096F85DE12B -:103C6000BEF1000F04D07345CCBFCEEB030300239D -:103C70004FF0640EDFF814A193FBFEFC6FF0630BB2 -:103C80003AF81C900BFB0C3B0CF1010C3AF91CA010 -:103C90000FFA89FCCCEB0A0C0CFB0BFC9CFBFEFC2A -:103CA000CC4428F801C095F804C003FB0CFC364B4B -:103CB0009CFBF3F373449BB27B4393FBFEFE1BE040 -:103CC00096F85EE1BEF1000F04D07345CCBFCEEB99 -:103CD00003030023DDF814C003FB0CFEA8F804E086 -:103CE00095F805E0002BB8BF5B4203FB0EFE264BA8 -:103CF0009EFBF3FE0EF1640EB31893F80480DFF818 -:103D000094C00EFB08F8642398FBF3F802F80C80CB -:103D100094F80E900CF103080EFB09F999FBF3F9E6 -:103D200002F8089094F818800CF1060C0EFB08FEBF -:103D30009EFBF3F302F80C30DDF80CE0049B9E458B -:103D4000DFF84CE004DA3EF801305B422EF8013037 -:103D50000132032A01F1020104F101047FF467AF8B -:103D6000074EB6F81C31984216DBB0F5FA6FA8BFC3 -:103D70004FF4FA6011E000BF40040020D00C002096 -:103D8000E41F0020200B00200CFEFFFFD00E0020BF -:103D90009A090020DE0E00201846C01A4FF47A72ED -:103DA0005043C3F5FA63B0FBF3F36427A34C93FBD2 -:103DB000F7F204EB42016FF0630000FB0233098B62 -:103DC00004EB4202B2F91A000AB2821A534393FB7F -:103DD000F7F739449A4F9B4D3B88AEF806105A06C8 -:103DE0003DD5994B1888994B1B88C01A00B20AF030 -:103DF000C7FF97490BF018F880460EF0D9F98146B5 -:103E000040460EF049FA8046B5F902000AF0B8FFC4 -:103E10008246B5F900000AF0B3FF494683460BF02D -:103E200003F841460346504602930AF0FDFF029B09 -:103E3000014618460AF0EEFE0BF0BCF94946288010 -:103E400050460AF0F1FF4146814658460AF0ECFF21 -:103E5000014648460AF0E0FE0BF0ACF96880B26813 -:103E600040F602031340002B53D07A4B06211D88E5 -:103E7000236B1D4494F8343025630133DBB2B3FB6C -:103E8000F1F084F8343001FB103313F0FF0F40D110 -:103E9000930706D502F014FA02F0FCF9674B83F899 -:103EA0003500B368180532D56B4BA16B5A7B6B4B51 -:103EB00033F81200082391FBF3F280B28A1A02440D -:103EC000A26392FBF3F292B240F6E4435A43644B8E -:103ED00040F6FF71B2FBF1F219684FF47A73C888AB -:103EE0008988121A5A4392FBF1F255435D4995FBBA -:103EF000F3F30A60D4E91001C01841EBE371C4E99F -:103F000010010023584A0BF09BF9584B186000230E -:103F100023635749494A0B6894F8358013F480535A -:103F200018BF012382F84830B3688A4613F4807FB3 -:103F3000504D2CD0DFF850912878D9F80030C0F3DC -:103F400080001B685B68984760B1012384F84930A2 -:103F5000D9F800301B68DB68984718B1374B02224C -:103F600083F84920D9F800301B689B68984728B12E -:103F70002B7859075CBF022384F84930D9F8003008 -:103F80001B689B69984710B1002384F849303A4B6D -:103F90001A6892060DD5DAF8003013F4C06F05D018 -:103FA000364B1B789B0701D4012300E0002384F8E3 -:103FB0004A3094F84920214B022A02D14C204E214C -:103FC0001EE0012A06D153204D214C220B4602F05F -:103FD000ABFC2BE093F84A20012A03D15320014681 -:103FE0004E2206E093F84820012A04D153200146CE -:103FF00002464D23EBE7B8F1000F04D053204D21CA -:104000000A464423E3E73A88170603D553204D2197 -:104010000246DBE71A4A12781AB1192002F058FC5E -:1040200004E0404683F84B80FEF7B9FA2B78580736 -:104030002CD5144B08225A6183E000BFD00E00201B -:104040008C0900209A090020180C0020280E00205E -:1040500035FA8E3C340C0020580100206801002005 -:10406000F40C0020FC0C0020407E0500000D002018 -:10407000880900209627002084090020BA09002022 -:10408000D20B0020000C01403C040020DAF8002094 -:10409000D10703D4B74943F001030B70B6490B684D -:1040A00013F0020302D0B5490988A1B9B4490988BF -:1040B00001B12BB9B34B1B88003318BF012300E0BB -:1040C000012343B1B04BD96881F00801D9602B7846 -:1040D00023F001032B70AD4B1B781F0703D42B7803 -:1040E00023F001032B70D00203D52B7823F00103BA -:1040F0002B702B78A64A13F0010F05D00023E36440 -:10410000A14B082119610BE0E16C136841B9A14989 -:1041100003F5F42303F59073CB649B4B082159619D -:10412000E36C12686BB1D21A002A0ADB964A03F5D7 -:10413000F423D16803F5907381F00801D160954AAA -:10414000D36407F07BFD944B1B7813B109F096FC08 -:10415000F9E3012004F034FF002800F0F483DFF8D5 -:10416000589299F84A30012B40F0E7838B4A8C4BE8 -:10417000D9F80010C2F8009019609246884A106879 -:10418000FEF74AFA002800F0D283854B1868FEF744 -:104190003EFADAF8003093F84820DAB9B0F1240199 -:1041A0004A424A4183F84820002AE7D12B785B072E -:1041B000E4D4232802D109F061FCDFE7D4F8E83029 -:1041C0001B7D8342DAD1774A774B1A60774A784B66 -:1041D000DA60D3E7012A04D14D2814BF002202225D -:1041E000A2E3022A04D13C2814BF002203229BE34D -:1041F000032A0AD140284FF0000200F295831A7179 -:10420000DA715871987104228EE3042A06D19A79E2 -:1042100083F8490050409871052285E3052AADD105 -:1042200059791A799142997906D941409971511C6D -:10423000197113441872A1E7814240F0728393F818 -:10424000490005F02BFD002840F06683DAF80030C5 -:1042500093F84930C82B00F0DD8043D82D2B00F0B7 -:10426000F08224D8252B00F0CD8206D8212B00F037 -:104270002382232B00F0688186E3292B00F0CD8276 -:104280002B2B00F0D682272B40F07E83002002F0FB -:10429000CDF802F089F8474FA7F8E60002F084F85D -:1042A000A7F8E80002F080F8A7F8EA0031E3332B22 -:1042B00000F0DB820CD82F2B00F0ED82312B40F088 -:1042C00063833C4FC02002F0B1F807F18008F8E2A8 -:1042D000412B00F0D282442B00F01583352B40F0A7 -:1042E000538353E1D02B00F0F58169D8CC2B00F03B -:1042F0007B8106D8C92B00F02782CA2B00F0A28050 -:1043000042E3CE2B00F0128240F2EF8102F04CF833 -:1043100002F04AF8274FDFF8A480A7F8D00002F097 -:1043200043F8A7F8D20002F03FF8D8F800B0A7F899 -:10433000D40002F039F8ABF8A80102F035F802F029 -:104340003DF8D8F8008002F02FF800EB8000400024 -:10435000A8F8520002F01EF887F8040102F01AF8DB -:1043600087F8060102F016F887F8050102F012F846 -:10437000CFE200BF9627002084090020802700207C -:10438000A40B002088270020000C0140BA0900205F -:104390007C270020D00E002090270020980D0020C0 -:1043A0009C0D0020EFBEADDEF04F00200400FA05AA -:1043B00000ED00E0E41F0020200F0020200B002073 -:1043C000D42B00F0438108D8D22B10D040F2E181E9 -:1043D00001F0EAFFC94B18809BE2EF2B25D0FA2BA6 -:1043E00000F0AE81D62B40F0CF82002726E12B785B -:1043F00003F0040303F0FF07002B40F08A8201F072 -:10440000C9FFBF4B022883F8540740F2698183F843 -:10441000547765E1002701F0C7FFBA4BD853023744 -:10442000102FF8D10122B84B88E1B84FD7F800809F -:1044300001F0BAFFA8F856003F6801F0B5FFA7F8F1 -:10444000540066E2B14B00271A6898461278022A97 -:1044500061D1D8F800B001F09DFF07F108020BEB25 -:10446000820B0AF089FCAA490AF092FDCBF80400FD -:10447000D8F800B001F08EFF07F10A020BEB820BB7 -:104480000AF07AFCA3490AF083FDCBF80800D8F8BB -:1044900000B001F07FFF07F10E020BEB820B0AF078 -:1044A0006BFC9D490AF074FD0137032FCBF8040023 -:1044B000CFD1072FD8F800B016D101F06BFF0AF06A -:1044C0005BFC93490AF064FDCBF84800D8F800B0D3 -:1044D00001F060FF0AF050FC8D490AF059FDCBF85D -:1044E0004C0001F057FF12E001F054FF0BEB070303 -:1044F0001871D8F800B001F04DFF0BEB070398736B -:10450000D8F800B001F046FF0BEB0703187601372F -:104510000A2FCED1FDE1D8F800B001F03BFF0BEB44 -:1045200007031871D8F800B001F034FF0BEB070354 -:104530009873D8F800B001F02DFF0BEB070301379B -:104540000A2F1876E7D1E4E101F024FF272821D8CB -:104550006E4B00F11C081B6803EB880801F01AFF82 -:104560006E4B08F1050703F58A72197A814203D070 -:104570000C339342F9D10DE01B7888F8053001F037 -:1045800009FF787001F006FFB87053E001F002FFF8 -:104590000B2804D90120002101F02AFFB9E14FF0D6 -:1045A000060808FB00F0594B00F588701B6803EB08 -:1045B000000801F0EFFE0328ECD888F80A0001F0AB -:1045C000E9FE88F8050001F0E5FE88F8060001F034 -:1045D000E1FE88F8070001F0DDFE88F8080001F030 -:1045E000D9FE88F8090094E14D4FD7F8008001F01A -:1045F000D1FE88F80000D7F8008001F0CBFE88F8E3 -:104600000100D7F8008001F0C5FE88F80400D7F853 -:10461000008001F0BFFE88F80500D7F8008001F0A7 -:10462000B9FE88F80600D7F8008001F0B3FE88F8DC -:1046300002003F6801F0AEFEF8706AE101F0B4FEDE -:10464000384BD8530237102FF8D162E14FF00008F1 -:104650002E4F08F12C0B3968029101F0A5FE02994A -:104660004FEACB021144C88039680192029101F0EF -:104670009BFE019A029911440881019201F094FE77 -:104680000728019A02D839680A445073A0F57A7253 -:1046900092B2B2F57A7F03D83A6802EBCB0250812E -:1046A0003F6801F077FE08F1010807EBCB03B8F192 -:1046B000080F1873CCD12CE10027144BD3F80080DD -:1046C00001F068FE08EBC7030137082F83F86D017E -:1046D000F3D11EE12B785F0700F11B8104F07FF816 -:1046E00007F086FD09F0CAFA13E12B78580700F1AC -:1046F00010810D4B4FF4C8721A800AE1B20C0020F1 -:10470000E41F00204004002074090020200B00203A -:10471000000020410000C84200007A44D44A010849 -:10472000D00C0020BC0F0020A40B00202B785907D0 -:1047300000F1EF80984B1A7842F004021A70E8E01A -:104740002B785A07CCD51FE101F024FE924B1A7842 -:1047500010B142F0020201E022F002021A7001F0F0 -:1047600019FE8E4B8E4F187001F028FE386001F054 -:1047700025FE786001F018FE8A4B188001F014FEC7 -:10478000894B188094F8043143F0020384F8043113 -:10479000BFE001F0FFFD019001F010FE029001F07A -:1047A0000DFE804601F00AFE074601F0FDFD01F016 -:1047B000FBFD01F0EFFD019A029B92B97B4A82E872 -:1047C00008017B4B1A8822F010021A80724B1A786B -:1047D00042F001021A70002F00F09B80754B1F60A1 -:1047E00097E0102A40F09580734A82E808010FB1E3 -:1047F000704B1F607048714B0222011D1A7004F04B -:10480000C7F986E0002001F011FE0023B36001F03B -:10481000D5FDB3681843B0607BE0002001F006FED0 -:1048200001F0C2FDA6F8080101F0BEFDA6F80A01DC -:104830006FE0002001F0FAFD01F0ACFD604B587113 -:1048400067E0002001F0F2FD01F0A4FD86F81801F8 -:1048500001F0AAFDA6F81E0101F0A6FDA6F81A01B6 -:1048600001F0A2FDA6F81C0153E0002001F0DEFDDE -:1048700001F090FD86F820014BE0002001F0D6FD0C -:10488000002701F087FD4E4B3B440137082F83F88A -:104890001001F6D13DE0002001F0C8FD484F07F1BE -:1048A000400801F081FDA7F8D40101F073FD87F8FD -:1048B000D60101F06FFD043787F8D3014745F0D1E9 -:1048C00027E001F071FD00F03F00A7F8560101F06C -:1048D0006BFDB7F85621800100F4F8631343A7F885 -:1048E000563101F057FD000187F8540101F052FDE7 -:1048F00097F8543100F00F00184387F8540104373B -:104900004745DED105E0002001F090FD012384F849 -:104910000531002001F08AFDDAF80030987901F0C5 -:1049200056FDDAF80030002283F8482026E494F897 -:10493000053113B1234A244BDA60244B09F14C09A9 -:1049400099457FF40EAC22490B689B0616D5214B86 -:10495000D4F808211B689A1A002A0FDB0F4A127834 -:10496000042A0BD91C4A03F5123303F5F873C2F875 -:1049700008311A4BDA6882F01002DA60184B9B6833 -:104980003BB11848984704E00120002101F030FDB8 -:10499000C2E707B0BDE8F08FBA090020080D00207B -:1049A000140D0020060D0020040D00202C0E002008 -:1049B0008C09002090090020380E0020340E0020C1 -:1049C000E41F00200400FA0500ED00E0B80F00200D -:1049D000840900207C270020D00E0020000C01401C -:1049E000240B0020DC0F00202DE9F04F974B91B0F5 -:1049F0001B68BBB9964C2378013B042B00F2F08670 -:104A0000DFE813F00B060B060B06DE06C406206873 -:104A1000FDF7FDFD8F4B04461B681B784BB1012B46 -:104A200000F0ED80894C2068FDF7F6FD0028EED1FE -:104A3000E0E72428884D0CD006D80A2800F08E80A4 -:104A40000D2800F08B80C6E02A2806D02C2804D040 -:104A5000C1E02B706B70AB70CEE06A782E782A4480 -:104A600000217D4BD170EEB9DA789E74472A19D1B6 -:104A70001A79502A16D15A79472A07D19A79472AA2 -:104A800004D1DA79412A01D101229A746A79724BF0 -:104A9000522A07D19A794D2A04D1DA79432A04BFE0 -:104AA00002229A74AB7C6C4F012B02D0022B36D0C1 -:104AB00049E0B31E072B46D8DFE803F004081014C2 -:104AC0001C27452C02F070FA68613CE0EA78624BE2 -:104AD000532A38D15A6952425A6134E002F064FADA -:104AE000A86130E0EA785C4B572A2CD19A6952428F -:104AF0009A6128E0EB78302B584B1A788CBF42F043 -:104B0000020222F002021A701DE0002002F0A6FA52 -:104B1000287718E0002002F0A1FAE88313E0072EBE -:104B200006D0082E0FD1012002F098FA78840AE00E -:104B3000012002F093FA41F2184358434FF47A727D -:104B4000B0FBF2F33B84013600232A2C424A2E703C -:104B50006B704CD1012182F824104DE095F824307F -:104B6000002B34D03C4BDB78402B04D9A3F1370227 -:104B70001201D2B202E01B0103F0F0022B79A978F6 -:104B8000402B8CBF373B303BDBB21344DBB2994246 -:104B9000314A1BD1937C012B08D0022B16D1118CEA -:104BA0002F4B528C19802F4B1A800FE02B4909781C -:104BB0008E070CD52C495069086090694860107FB9 -:104BC0002A490870D18B2A4A118000E00023002274 -:104BD00085F8242010E06B781F4A0E2B03D8591C4F -:104BE00013445170DC7095F824301B4A1BB991783E -:104BF0004C40947000E0002303F0010361E1164B88 -:104C0000002193F82520082A00F25A81DFE802F0FB -:104C10000B0514324353718D9A00622801D1022290 -:104C200007E083F82510B52C40F04A8193F8252041 -:104C3000013283F8252043E1032283F8252083F8FD -:104C4000260083F8270083F8280039E1A404002017 -:104C500084040020A0040020E00F0020BA090020F6 -:104C6000040D00209A170020140D0020080D0020CC -:104C7000060D0020042283F8252093F8272093F8BE -:104C800028100244D2B283F827200A4483F828204F -:104C900083F8290014E1052283F8252093F82720C2 -:104CA00093F828100244D2B283F827200A4483F8EC -:104CB0002820588504E1062183F8251093F8271051 -:104CC00093F828002144C9B283F82710014483F8DF -:104CD0002810598D6C4A01EB0424A4B2B4F5007F6E -:104CE00089BF00215485518582F8251000229A85BC -:104CF000E6E093F8272093F828100244D2B283F814 -:104D000027200A4483F828209A8DC72A03D85E49B1 -:104D1000114481F83000013292B29A855B8D934242 -:104D200040F0CE800722584B83E7082283F82520E5 -:104D300093F82730834200F0C380534A002382F85F -:104D40002530BEE083F8251093F828104E4A8142A2 -:104D500040F0B68092F82910062947D004D80229DD -:104D600012D003292CD0ABE012295CD0302940F0BE -:104D7000A78092F83410454A102988BF102111707D -:104D80001078434900225CE04249506B4860906BC8 -:104D90000860116C4FF47A7091FBF0F13E4801808D -:104DA00092F8F8103D4A19B1117841F0020102E081 -:104DB000117821F002011170012283F8F92055E0E9 -:104DC00092F8351011F0010105D092F83420D41E6C -:104DD0006242624100E00A4683F8F820002A45D189 -:104DE0002E4A117821F0020111703FE092F83B1039 -:104DF00011F0010105D092F83A20D01E4242424102 -:104E000000E00A4683F8F82022B9244A117821F0FC -:104E10000201117093F85F10214A1170B3F85C1011 -:104E2000204A118022E0516C1F480180916C42F2AF -:104E3000107091FBF0F11D480180012182F8FA10F9 -:104E400014E0824201F10C0110DA11F8045C184CF4 -:104E5000155511F8035C174C155511F8015C164CEB -:104E600015550D78154C15550132EAE793F8F930D0 -:104E7000054A2BB392F8FA3013B3002382F8F930C5 -:104E800082F8FA3001231CE0E00F00209C1700207C -:104E900010100020140D0020060D0020BA0900207B -:104EA000080D0020A0000020040D00209A1700200B -:104EB0009D170020AD170020BD170020CD17002042 -:104EC0000023002B3FF4AEADA54BA64E9A68DA60E6 -:104ED00032689A60A44B1A6842F020021A60A34B11 -:104EE0001A78012A0CBF002201221A70A04B1A78EE -:104EF00091077FF597AD9F49097804297FF692AD18 -:104F00009D49097801F0040101F0FF0011B922F078 -:104F100001021A701B78964F13F0010F974C984DB1 -:104F200011D180B19B070ED5964B28686A6818602E -:104F30005A60FDF7D5FF944B1B88A4F8FC303B78F2 -:104F400043F001033B7094F8FE304FF00509013344 -:104F500093FBF9F909EB8909C9EB03098B4B8C48E1 -:104F60001B7884F8FE900593831D03EB8909079055 -:104F70000023DFF80CE2874A53F80E00864F985062 -:104F800090FBF7FC02F1080743F807C0834F03EBDF -:104F90000E0107FB0C0742F2107097FBF0F0069130 -:104FA000079980B221F8020F02F1100A03EB830B7C -:104FB0000490079153F80A0059F80B1049F80B7048 -:104FC000C1EB000808EB0700734F4FF0050843F8EA -:104FD0000A0090FBF8F007FB0C0005991832012934 -:104FE0009850774608D1DDF810E0AEF10202B2F534 -:104FF000797F9CBF069908600433082BB9D1DFF88C -:105000007C813068D8F84C31C01A09F0B5FE64498B -:1050100009F0BEFF33684FF07E51C8F84C3181462D -:105020000AF0A0F810B94FF07E5000E048460CAAF4 -:10503000C4F85001534B00920DAA019297E8030067 -:105040000CCBFDF70BFF0C9B56496422B3FBF2F32C -:105050000D980B80544B90FBF2F21A80444A474E55 -:10506000127812F0010208BF1A8098F8543108BF74 -:105070000A80002B3AD0D6F850114FF07E5009F03C -:1050800087FFD6F8583181462868C01A09F078FEA3 -:10509000494609F0C9FE0AF08DF8D6F85C211FFADE -:1050A00080FA68680FFA8AFA801A09F069FE3F4BA5 -:1050B000196809F0B9FE494609F0B6FE0AF07AF817 -:1050C000B6F9623100B2C218B6F960310221534418 -:1050D00092FBF1F293FBF1F392B29BB2A6F8662138 -:1050E000A6F86431A6F86221A6F86031012388F899 -:1050F00054312F4B79681B88386803F030031F4EFA -:105100001F4DC8F85C11C8F85801002B3FF48AAC59 -:1051100006F5B873009306F5BA730193D6F86821C3 -:10512000D6F86C31FDF79AFE6B68D6F86C01C01AA0 -:1051300009F026FE1D4B196809F076FE0AF03AF8D0 -:10514000D6F868312A68C6F87C019B1AC6F878310F -:105150000E4B1B78012B2DD0022B00F0F58061E463 -:1051600084040020E01F002084090020D40F0020C8 -:10517000BA090020080D002096270020E00F00202B -:10518000140D00202C0E0020180C0020340E0020DE -:10519000DE1000200C11002080969800806967FFC7 -:1051A00000007A44780D00207A0D00204C00002089 -:1051B0008C090020D6F89C41D6F89031D6F8802191 -:1051C000D6F8947104F1004005930492079709F012 -:1051D000F1FF0746204609F0EDFF8C4BD6F8505101 -:1051E0001B68D6F898618A4C0890069609934FF090 -:1051F000000ADFF83C9259F81A60A9F1140230460F -:105200003AF8028009F0BCFD049909F00DFE09F09E -:10521000D1FFC8EB000080B209F128092AF8090083 -:105220000FFA80F9484609F0ABFD059909F0FCFD3D -:1052300009F0C0FF1FFA80FB09EB060009F0A0FD92 -:10524000079909F0F1FD294609F0EEFD216809F002 -:10525000E3FC09F0AFFFB84204DB089A9042A8BF14 -:10526000104600E0384609F08BFD206009F0A2FFEF -:1052700058441FFA80FB606808F13108301A09F0C1 -:105280007FFD294609F084FE099B2061024698783B -:10529000D4F80890039209F06FFD5E4909F0C4FD4F -:1052A00001464FF07E5009F073FE294609F0B4FC28 -:1052B0000146284609F06CFE039A8446494610468A -:1052C000CDF80CC009F0A6FCDDF80CC00146604624 -:1052D00009F0AAFD0146484609F09EFC1FFA88F82D -:1052E000B8F1620F014620616660A0600ED9069891 -:1052F00009F09AFD09F05EFF474AB0F5FA6FA8BFC2 -:105300004FF4FA609042B8BF104600E0002083449A -:1053100040F6B8320FFA8BFB9345A8BF93463F4A3D -:105320000A219345B8BF934601FB0AF13C4A54F861 -:10533000140B2AF802B03B4A0AF1020ABAF1040F30 -:1053400088503FF46FAB54E7304BD6F870911F682C -:10535000B6F8A451B7F808A04FEA59039A4528BFF8 -:105360009A462BB29A4502DC1FFA8AFA0BE02E49C4 -:10537000D6F8500109F058FD09F01CFF28441FFA27 -:1053800080FAA6F8A4A1D8F87451D8F8A861AE1B89 -:105390003046FDF713FE0028D8BF404241F2931378 -:1053A0009842CCBF00200120002843D0304609F0AD -:1053B000E7FC1E4909F038FD0CF06EFF0646484632 -:1053C00009F0DAFC0146304609F02EFD09F0F2FE44 -:1053D00080B240F6B83203B29342A8BF13460F4AD8 -:1053E000A8F8AC019342ACBFEB18AB1848F6A0424A -:1053F000934203DDA3F50C43A03B04E0002BBCBFAC -:1054000003F50C43A033C8F8B03115E0C40C0020FC -:10541000680E0020DB0FC94030F8FFFF48F4FFFFA3 -:10542000CC0C0020900E00200000C842D302373977 -:1054300058110020C8F8B051D4F8B021C2F50C5072 -:105440002830049209F09CFCAA4909F0EDFC0546BD -:105450000CF0AEFE0F9028460CF01EFFD4F8C051A1 -:10546000D4F8B431D4F8B8210E9005F10040079378 -:105470000A9209F09FFE0590284609F09BFED4F899 -:105480005081D4F8BC410B9009949B4C00255046A8 -:1054900009F076FC0EAB53F8151009F0C5FCDFF8E7 -:1054A00094B206463BF9050009F06AFC0146304615 -:1054B00009F0B0FB09F07EFE904B06B2B6F57A7F9C -:1054C000A8BF4FF47A769E42B8BF1E46B0B20BF129 -:1054D0003C0B25F80B0000B209F052FC07998346FB -:1054E00009F0A2FC09F066FE80B208900A995846BD -:1054F00009F09AFC414609F097FC216809F08CFB01 -:1055000009F058FE059B984204DB0B9A9042A8BF15 -:10551000104600E0059809F033FC8346206060687F -:105520001434301A09F02CFC414609F031FD54F8CE -:105530000C3C44F8040C0246B8780693039209F038 -:105540001BFC6F4909F070FC01464FF07E5009F0DA -:105550001FFD414609F060FB0146404609F018FD79 -:10556000039A844606991046CDF80CC009F052FB08 -:10557000DDF80CC00146604609F056FC014606986D -:1055800009F04AFB44F8106C014644F8040C44F856 -:105590000C0C099809F048FC09F00CFE089E064422 -:1055A000584609F007FE304440F6B83200B2904247 -:1055B000A8BF1046534A0A219042B8BF104669431B -:1055C000514AA852514A0235042D41F802B07FF4E5 -:1055D0005EAF3B792BB1049B642293FBF2F24C4B00 -:1055E0001A803B884B4C99450ED9D4F8A831D4F891 -:1055F0007401C01AFDF7E2FC42F210730028B8BF34 -:10560000404298427FF70EAA434B01221A70B4F829 -:10561000FC203F4B1A80FFF705BA404A11689046BC -:105620000F7817B1012F0DD0ADE0012B00F2AB8048 -:1056300062783B4B03EB02133A4A59681068FCF757 -:10564000E1FF9DE0374E3068FCF7D7FFB1460028F8 -:1056500000F099802378344D022B29D0032B31D0D0 -:10566000012B40F09080314B1F686B69FB1A632B54 -:1056700040F289802B69042B18D8DFF8A4803068A9 -:1056800008EB03135968FCF7BDFF6B78366808EB2D -:1056900003139D6815F8011B19B13046FCF7CEFFC6 -:1056A000F8E723696761013323616CE0022068E059 -:1056B0006A781B4B306803EB02135968FCF7A2FFB2 -:1056C00003205EE02B7E03B92F76227E164B012A43 -:1056D00036D11A697B2A2FD8D8F800309B782BB99D -:1056E000134BD9F80000995CFCF7A8FF236901333C -:1056F000236125E0D3023739900E002018FCFFFF0C -:10570000DB0FC94048F4FFFFCC0C0020680E0020DE -:10571000B20C0020E00F0020340E0020A004002076 -:10572000E0440108A404002084040020E01F0020BD -:10573000E84B01084411002000221A6102221A7667 -:10574000227E294B022A18D11A690F2A13D8D8F8B9 -:105750000030997859B95B78244903EB03130B4463 -:105760001A44D9F8000092F87D10FCF767FF23690E -:105770000133236101E003221A76237E022B02D932 -:10578000042001F05BF90023636029E063680522CF -:1057900001336360637801200133DBB2B3FBF2F2C3 -:1057A00002EB82029B1A6370114B00221B68A360FC -:1057B000104B1A70104B1A7822F002021A700DE08A -:1057C0000B4B1A68A368D21A40F6C4139A4207D941 -:1057D0000A4B05201A6822F020021A6001F02EF907 -:1057E00011B0BDE8F08F00BF84040020E84B010831 -:1057F000E01F0020080D0020BA09002084090020C5 -:10580000084BDA68D10709D4DA68520708D4DB6894 -:1058100013F0100F0CBF04200320704701207047C5 -:1058200002207047002002401E4B2DE9F0431A78F9 -:105830001D460AB31C4B07781E781C4B93F800C01A -:1058400002231B4A03F10108D45C344104F00F0425 -:10585000BC420CD20B2C0AD812F8039012F8088024 -:1058600002EB840209EA0C0408EB042414610233FD -:10587000102BE6D100232B7003788B420FD90C4BF1 -:1058800093F8400060B10B4A890012780B44186904 -:1058900002B1400800F5777080B2BDE8F0830020C7 -:1058A000BDE8F0837808002064040020650400202F -:1058B000A41100206604002007299ABF024B33F888 -:1058C00021000020704700BF54090020024B53F80C -:1058D0002100C0F3CF007047FC08002008B5074B3B -:1058E00053F8210009F048FA054909F09DFA0549E5 -:1058F00009F092F909F084FC80B208BD94080020F8 -:105900000000203F00005C44014B33F81100704759 -:1059100040040020024B03EB4101B1F84200704704 -:10592000A411002038B5104C0123054684F84030FE -:10593000FCF706FEE36D41F28832C31A93422366F8 -:1059400084BF002384F8643094F86430EDB20F2BE8 -:10595000E065E55403D1054B01221A7038BD024AB7 -:10596000013382F8643038BDA4110020780800208B -:1059700010B50446FCF7E4FD0D4B41F288319A6EF8 -:105980009866821A8A42DA6684BF002283F8702001 -:1059900093F87030074A142BD45403D1064B0122DC -:1059A0001A7010BD024A013382F8703010BD00BF7A -:1059B000A41100203D0900203C09002010B5044638 -:1059C000FCF7BEFD164A536F5067C31AB3F57A6FE2 -:1059D00084BF002382F8783092F8783023B9A82C5D -:1059E0001CD110490B7006E0022B02D10E490C703D -:1059F00001E0242B01D80D49CC540133DBB282F8ED -:105A00007830094A127852000532934206D1044B8D -:105A1000002283F87820034B01221A7010BD00BFCA -:105A2000A4110020D4080020FA080020D508002086 -:105A300038B50446FCF784FD114B40F6C411DA6F0B -:105A4000D867821A8A4284BF002283F8802093F8A4 -:105A500080200AB90F2C11D10A480021017052B1DF -:105A6000094D182A154405F8014C04D1012283F888 -:105A70008010027038BD013283F8802038BD00BF2D -:105A8000A4110020790800207A08002038B50C689D -:105A9000054620460CF09EF9214602462868BDE8DE -:105AA00038400CF09FB930B587B005460C4603A8C6 -:105AB00000210C220CF04DF92846002109F070FB62 -:105AC00020B12846294909F0A7F803E028462749CC -:105AD00009F0A0F8264909F0A7F909F06BFB054683 -:105AE00085EAE570A0EBE57069460A22FDF796F8B5 -:105AF00000239D420370ACBF20232D2368468DF800 -:105B00000C300CF067F9012807D130238DF80D30E7 -:105B10008DF80E308DF80F300CE0022805D13023BF -:105B20008DF80D308DF80E3004E0032804BF3023CB -:105B30008DF80D30694603A80CF032F903A80CF07B -:105B400049F90338C5B22A4603A920460CF06CF97E -:105B500000236355204607490CF022F903A920468B -:105B600029440CF01DF9204607B030BD6F12033AEE -:105B700000007A44886201080A88F0B54B888F8853 -:105B80000E89CD88002A3AD1048C834A24F001047E -:105B90002404240C0484018B048C89B221F0F301C9 -:105BA00041EA0616B6B29042A4B246EA070743F0AD -:105BB000010315D002F50062904211D0B0F1804F80 -:105BC0000ED0A2F5983290420AD002F5806290423F -:105BD00006D002F58062904218BF24F00A0401D179 -:105BE00024F00204234307830384038B23F00C0374 -:105BF0001B041B0C0383038B9BB21D4344E0042A4C -:105C000044D1048C644A24F010042404240C048439 -:105C1000018B048C21F440710905090D41EA06311C -:105C200089B241EA07279042A4B2BFB212D002F56E -:105C3000006290420ED0B0F1804F0BD0A2F59832A6 -:105C4000904207D002F58062904203D002F5806254 -:105C5000904207D124F0200444EA03139BB243F09E -:105C6000100304E024F0A00443F01003234307834F -:105C70000384038B23F440631B041B0C0383038BFB -:105C80009BB243EA0525ADB20583F0BD082A018C1D -:105C90003ED121F480710904090C0184818B3E4AB4 -:105CA00089B221F0F301048C41EA0616B6B29042A3 -:105CB000A4B246EA070712D002F5006290420ED065 -:105CC000B0F1804F0BD0A2F59832904207D002F588 -:105CD0008062904203D002F58062904207D124F4A2 -:105CE000007444EA03239BB243F4807304E024F479 -:105CF000206443F48073234387830384838B23F0DE -:105D00000C031B041B0C8383838B9BB21D4341E05C -:105D100021F480510904090C0184828B048C22F443 -:105D200040721205120D42EA072242EA06361A4A6A -:105D3000A4B29042B6B212D002F5006290420ED0E8 -:105D4000B0F1804F0BD0A2F59832904207D002F507 -:105D50008062904203D002F58062904207D124F421 -:105D6000005242EA033292B242F4805205E047F612 -:105D7000FF52224043F480531A4386830284838B6C -:105D800023F440631B041B0C8383838B9BB243EA85 -:105D90000525ADB28583F0BD002C01401FB5012360 -:105DA000ADF808300023ADF80C30ADF80A30094BDF -:105DB000ADF804101B7801A9012B08BF0323ADF82F -:105DC000062008BFADF80C30FFF7D6FE05B05DF831 -:105DD00004FB00BFEC01002038B510F80E2C04467F -:105DE00050F8043C52B9012200F80E2C20F80C1C8B -:105DF000197B18680222BDE83840CFE730F80C2C38 -:105E000020F80A1C891A89B220F8081C084A10F8E0 -:105E10000F0C002502EB4002A2F8421004F80E5CC1 -:105E20001868197B2A46FFF7B9FF04F8065C38BDED -:105E3000A41100201F4B10B55A6802F00C02042A6E -:105E400003D0082A04D01C4A14E01C4A126811E04E -:105E50005A685968C2F38342C90302F1020201D4AD -:105E6000174906E0596811F4003F1449096818BF42 -:105E700049084A4302605968124AC1F30311545C4D -:105E80000168E14041605C68C4F30224145D21FABA -:105E900004F484605C68C4F3C224145DE140C16012 -:105EA0005B68C3F381331A44137CB1FBF3F10161E6 -:105EB00010BD00BF0010024000127A000000002058 -:105EC00000093D0050000020024B1A6922EA000040 -:105ED0001861704700100240CB78F0B5DA0648BF71 -:105EE0008A78098803F00F0548BF154311F0FF0FAA -:105EF0001DD0046800220127974007EA0106BE4230 -:105F000011D197004FF00F0C0CFA07FC05FA07F7B8 -:105F100024EA0C04282B44EA070401D1466102E07C -:105F2000482B08BF06610132082AE4D10460FF292A -:105F30001FD94468002202F108060127B74007EA8A -:105F40000106BE4211D197004FF00F0C0CFA07FC6E -:105F500005FA07F724EA0C04282B44EA070401D1C8 -:105F6000466102E0482B08BF06610132082AE2D1EF -:105F70004460F0BD10B50446FFF742FC012806D18D -:105F80001CB1FFF73DFC013CF8E7052010BD002CDB -:105F900008BF052010BD38B5124B134C9968134B40 -:105FA0001A681D465288114204D0FCF7C9FAC4F899 -:105FB000840012E0FCF7C4FAD4F8843098420CD97B -:105FC000C01A0B4B3B22B0FBF2F01B68B0F5967F7A -:105FD000C8BF4FF0FF3003B118602B685A68054BFB -:105FE0005A6138BD000C0140A4110020180B00209C -:105FF000140B0020000401408A6810B50C6A036885 -:1060000014430A6923F4FF4314434A6923F07003DD -:1060100014438A691443CA6914434A6A14438A6A56 -:10602000224313430360CB6843600B6883604B6873 -:10603000C36010BD02684FF6FE7313400360002377 -:10604000036043608360C3602A4B984222D02A4B8E -:10605000984229D0294B984230D0294B984237D0CA -:10606000284B98423ED0284B984206D153F8682CD2 -:1060700042F4700243F8682C7047244B984206D1D2 -:1060800053F87C2C42F0706243F87C2C7047204B14 -:10609000984206D153F8042C42F00F0243F8042C26 -:1060A00070471C4B984206D153F8182C42F0F0026E -:1060B00043F8182C7047184B984206D153F82C2CF3 -:1060C00042F4706243F82C2C7047144B984206D16E -:1060D00053F8402C42F4704243F8402C7047104B68 -:1060E000984205D153F8542C42F4702243F8542CB2 -:1060F000704700BF080002401C0002403000024010 -:1061000044000240580002406C00024080000240FF -:10611000080402401C0402403004024044040240CF -:10612000580402402DE9F843574B0C460168013AE8 -:10613000C3F888108188A3F88C10072A42D8DFE8BA -:1061400002F0040A101822292F35B3F88820228083 -:10615000B3F88A2013E0B3F88A202280B3F88820AD -:1061600005E0B3F8882052422280B3F88A205242D8 -:1061700005E0B3F88A2052422280B3F8882062807A -:10618000B3F88C301DE0B3F8882052422280B3F877 -:106190008A2012E0B3F88A202280B3F888200CE02D -:1061A000B3F888202280B3F88A2005E0B3F88A206B -:1061B00052422280B3F8882052426280B3F88C3079 -:1061C0005B42A380314B1B78002B5AD1B4F90000FD -:1061D00008F0D6FD8046B4F9020008F0D1FD07466C -:1061E000B4F9040008F0CCFD294D06462968404664 -:1061F00008F01AFEE9688146384608F015FE0146A7 -:10620000484608F009FDA9698146304608F00CFEB1 -:106210000146484608F000FD0CF000F8696820804F -:10622000404608F001FE29698146384608F0FCFD29 -:106230000146484608F0F0FCE9698146304608F01E -:10624000F3FD0146484608F0E7FC0BF0E7FFA968BC -:106250006080404608F0E8FD69698046384608F0ED -:10626000E3FD0146404608F0D7FC296A0746304660 -:1062700008F0DAFD0146384608F0CEFC0BF0CEFF00 -:10628000A080BDE8F88300BFA41100201400002006 -:1062900070010020074B084A1B7812889A4207D3E6 -:1062A000064A1268907898428CBF002001207047FF -:1062B00000207047F80C00206C080020F40C00202F -:1062C00010B5194B93F88E20511C83F88E10174986 -:1062D00002F007024878164903EB420331F8101028 -:1062E000A3F8901000231846124A9A5A0233104419 -:1062F000102B80B2F8D1C00808F042FD0E4908F01A -:1063000093FD0E4908F044FE0D4B04461B681878B7 -:1063100008F036FD0146204608F086FD08F070FFC3 -:10632000084B187010BD00BFA411002058010020B8 -:1063300068010020341200203333534000F07F45C1 -:10634000F40C0020F80C00202DE9F04106460F4621 -:1063500090460025EBB2434518D20024E3B2B34285 -:106360000FD20B4B0120DA68013482F00802DA60A8 -:10637000FCF715F93846FCF708F90020FCF70FF98F -:10638000ECE73C20FCF701F90135E3E7BDE8F081DB -:10639000000C0140034B1B68DA79511CD97113447E -:1063A000187A7047980D002010B5FFF7F3FF0446E8 -:1063B000FFF7F0FF04EB002080B210BD10B5FFF72F -:1063C000F3FF0446FFF7F0FF04EB004010BD064B5F -:1063D00010B5044621461868FCF730F9034B1B68DA -:1063E0009A7954409C7110BD9C0D0020980D00209E -:1063F00038B5044624200D46FFF7E9FF4D20FFF78E -:10640000E6FF002C084C0CBF3E202120FFF7DFFFE9 -:106410002368002228469A71FFF7D9FF236893F872 -:106420004900BDE83840D2E7980D00200146002021 -:10643000DEE7F8B50E4E0F4C0F4DC1B2074630687F -:1064400084F8A010FCF7FAF82B6894F8A0109A7959 -:1064500030684A409A71C7F3072184F8A010FCF70E -:10646000EDF82B6894F8A0109A794A409A71F8BD1B -:106470009C0D0020A4110020980D0020F8B51B4DA4 -:106480001B4C1C4F0646C1B2286884F8A110FCF7CB -:10649000D5F83B6894F8A1109A7928684A409A7117 -:1064A000C6F3072184F8A110FCF7C8F83B6894F8FC -:1064B000A1109A7928684A409A71C6F3074184F876 -:1064C000A110FCF7BBF83B6894F8A1109A792868F2 -:1064D0004A409A71310E84F8A110FCF7AFF83B687E -:1064E00094F8A1109A794A409A71F8BD9C0D002049 -:1064F000A4110020980D002010B5441E14F8011FAF -:1065000021B1034B1868FCF799F8F7E710BD00BFFD -:10651000101B00200B4AA2F13003197A81420BD0E4 -:106520000C339342F9D1084B197A014004D10C3352 -:106530009342F9D1084603E018460BB158687047FA -:10654000704700BF9400002064000020002305492C -:10655000DAB2595C814203D001330C2BF7D11A46D1 -:1065600010467047BC68010870B50E4620211546DC -:106570000BF023FC0446B8B1441C20460BF07FFC12 -:10658000B0F5617F05DB40F634039842A8BF18469A -:1065900001E04FF461701923A0F5617090FBF3F0F6 -:1065A00030702B7801332B70204620210BF005FC36 -:1065B0000446B8B1441C20460BF061FCB0F5617F85 -:1065C00005DB40F634039842A8BF184601E04FF4BB -:1065D00061701923A0F5617090FBF3F070702B7857 -:1065E00001332B70204670BD70B586B005460BF0A8 -:1065F000F1FBC0B208BB044606236343444A03F5DB -:106600008873126819201344591D4D789A7A4543AE -:1066100005F561755B7900958D78684300F56170CB -:106620000190C878029009793A48039121460134D3 -:1066300004F0A2F90C2CDFD168E028460BF01FFC17 -:106640000B285FDC06267043314B00F588701E680E -:10665000202106440023681C8DF817300BF0ADFB99 -:10666000741D054658B1451C28460BF008FC03284C -:1066700005D89DF81730607101338DF81730284622 -:1066800020210BF09AFB054658B1451C28460BF01B -:10669000F6FB0D2805D870719DF8173001338DF881 -:1066A00017302846611C0DF11702FFF75DFF20210E -:1066B0000BF083FB054658B1451C28460BF0DFFB69 -:1066C0000C2805D89DF81730E07001338DF817308D -:1066D000284620210BF071FB50B101300BF0CFFBAD -:1066E0000D2805D89DF81730207101338DF817302B -:1066F0009DF81730062B09D02046002106220BF00A -:1067000028FB03E004480C2104F036F906B070BD04 -:10671000200B00208A620108FA680108F0B585B0F4 -:1067200007460BF057FBC0B2E0B90446324B04F108 -:106730001C021B68192003EB8203591D8D785A79BE -:10674000454305F561759B790095C978484300F587 -:106750006170019021462948013404F00DF9282C7C -:10676000E4D146E038460BF08AFB27283DDC224B7B -:1067700000F11C061B68781C03EB86062021002311 -:106780008DF80F300BF019FB751D044658B1441CF1 -:1067900020460BF074FB152805D870719DF80F305A -:1067A00001338DF80F30204620210BF006FB044604 -:1067B00058B1441C20460BF062FB0D2805D89DF80B -:1067C0000F30687001338DF80F302046A91C0DF191 -:1067D0000F02FFF7C9FE9DF80F30042B09D02846A1 -:1067E000002104220BF0B5FA03E00548282104F04B -:1067F000C3F805B0F0BD00BF200B0020AA6201085D -:10680000FA68010837B582880446836810060D4689 -:1068100006D529494FF4E07091F8541700FB013375 -:10682000D10504D525490A20097800FB013302F07F -:106830003F02042A12D006D8012A0DD0022A2FD1F5 -:1068400093F900102DE0102A0AD0202A0AD0082A35 -:1068500026D1B3F9001024E0197822E0198820E04D -:1068600019681EE069461868FFF71DF901461448CB -:1068700004F082F8F5B1E06808F082FA6946FFF7A3 -:1068800012F901460F4804F077F8206908F078FA09 -:106890006946FFF708F901460A4804F06DF809E077 -:1068A0000021094804F068F825B10848E168226928 -:1068B00004F062F803B030BDE41F00201C0E00207D -:1068C0002D6301082C630108E8670108BF62010815 -:1068D00038B5114B114D1A78114C29688AB12268CC -:1068E0000244914217D300201870FBF758FE2B6822 -:1068F00023600C4B1A780AB1013A1A7001232371F4 -:1069000038BD2268C832914205D301201870FBF7C8 -:1069100046FE2B68236038BD1B0F0020E01F0020BF -:1069200048120020D20B002037B5214D8DF80730DA -:106930006B798DF8062002AA8DF804008DF80510F9 -:106940001A4412F8042C443AD2B20F2A29D8194911 -:10695000022B31F8124003D814B12046FFF7B8FFDC -:106960006B79134A022B09D9134B19681368091B59 -:106970008B4203D200235371104A13702B79012BE1 -:1069800000D09CB96B79022B02D8094A01335371AC -:106990000B4B00202871187003B0BDE83040FBF7A6 -:1069A000FEBD022B4FF0C804D7D9D9E703B030BDE4 -:1069B00048120020BA4C0108E01F0020D20B002032 -:1069C0001B0F002030B585B004AC002524F8025D13 -:1069D0000091ADF8060021461020FBF785FE9DF8DA -:1069E00006002146FBF780FE9DF807002146FBF7D5 -:1069F0007BFE9DF800002146FBF776FE9DF8010026 -:106A00002146FBF771FE9DF802002146FBF76CFE64 -:106A10009DF803002146FBF767FE9DF80E0029460E -:106A2000C043C0B2FBF760FE024B1A68024B1A600B -:106A300005B030BDE01F0020B80D00200449054B13 -:106A40000968002218701A6159611A76704700BFF0 -:106A5000E01F002084040020114B70B51B685E8984 -:106A6000104B186880F31000301A07F0BFFD0022A9 -:106A70000D4B07F021FE044630460D4607F0B6FDEB -:106A800002460B462046294607F040FF08F026F84C -:106A90006428A8BF642020EAE070C0B270BD00BFC7 -:106AA000F40C0020000D002000005940104B043071 -:106AB00033F91030B3F5617F05DB40F633029342C2 -:106AC000A8BF134601E04FF46173087819225043C0 -:106AD00000F28330984208DA4878504300F283305D -:106AE0009842B4BF0020012070470020704700BFCB -:106AF00040040020F8B50468054620460E461746B7 -:106B0000FCF7B1FA032845D82B7B9B089AB246B90B -:106B10004FF0020C0CFA03F3A18989B221EA0303B6 -:106B2000A3810A2101FB00211B4B43F821600431A2 -:106B300043F8217046B12A7B0225920805FA02F239 -:106B4000A1890A4392B2A281282202FB003000F1FF -:106B50002002EFF31286502383F312880023C1181A -:106B60000D6915B115600A6904320433102BF6D192 -:106B700000231360F3B283F31188036A23B1A3895E -:106B80009BB243F0010304E0A38923F001031B043B -:106B90001B0CA381F8BD00BF841E002070B5046DDE -:106BA0004279A38902F0040123F400531B041B0C57 -:106BB0000546866886B0A38101F0FF0021B14FF43D -:106BC00080604FF4005100E0014612F0010F14BF45 -:106BD0000423002312F0020F1CBF43F008039BB2F2 -:106BE00012F0080F228A18BF0C2392B222F44052EE -:106BF00011432182A28992B222F4B05222F00C02F7 -:106C0000104303439BB2A381A38A01A823F44073DA -:106C10001B041B0CA382FFF70DF91949049A039B6F -:106C20008C4208BF1346A2891921594312B2002A87 -:106C3000B4BF7600B600B1FBF6F16423B1FBF3F20A -:106C40001201100903FB1011A08900B2002806DA16 -:106C5000C9003231B1FBF3F303F0070305E009018A -:106C60003231B1FBF3F303F00F031A4392B22B6DF1 -:106C700022819A8992B242F400529A8106B070BD84 -:106C800000380140417189E7816087E7826A816944 -:106C9000436B1144D960416A914203D98A1A5A6000 -:106CA000816204E001698A1A5A600022826200222D -:106CB00080F844201A6842F001021A6070472DE9FA -:106CC000F04F634CA3686349581C0A78894602F068 -:106CD000FF0C0AB10346F6E7277C667CA57C616958 -:106CE000A360E0461FFA88F213B21F2B00F39380D3 -:106CF000594901EB8300C278807831F82310C0F144 -:106D0000FF0080B2002861D0C0F1FF0050433C2357 -:106D1000B1FBF3FA0012BAF1050F5AD8DFE80AF016 -:106D2000030B1A283846161A4E43C5B2B6FBF3F6C3 -:106D30002E44F6B248E0B1FBF3F703FB1717BFB2DE -:106D4000C5B2C7F13C07101A4743B7FBF3F72F440E -:106D5000164629E0B1FBF3F503FB1515C7B2ADB23A -:106D6000101A4543B5FBF3F53D44EDB2164630E04D -:106D7000B1FBF3F603FB1616B6B2C7B2C6F13C067A -:106D8000101A4643B6FBF3F63E441546F6B220E031 -:106D9000B1FBF3F703FB1717C6B2BFB2101A474394 -:106DA000B7FBF3F737441546FFB212E0B1FBF3F53A -:106DB00003FB1515ADB2C6B2C5F13C05101A45432B -:106DC000B5FBF3F53544EDB2174602E0154616461D -:106DD00017464FEA072A4AEA064A4AEA050A1723EB -:106DE000012199400CF1170211EA0A0FC3EB0202CC -:106DF0001A490CBF0920112092B213F1FF338854B5 -:106E0000EED20CF1180C08F101081FFA8CFC1FFAE5 -:106E100088F8134966E7012389F80030114BE281B5 -:106E200040F22A3227746674A5746161A4F80CC01C -:106E30005A600D4A00219184118889B241F0010104 -:106E400011801A6842F001021A60BDE8F08F00BF9D -:106E5000481200208A270020DE070020B40400200A -:106E6000581200206C000240000400400D4B0278D4 -:106E7000D9684378C943C1F30221C1F1040103FA7F -:106E800001F1094B0901C9B21A4482F800130278D2 -:106E90000120510902F01F0200FA02F243F82120FA -:106EA000704700BF00ED00E000E100E0134B026816 -:106EB00010B51C68D1430C401C605C6821405960CF -:106EC00019680A431A6002689C68D1430C409C60B0 -:106ED000DC682140D9604179102906D199681143B5 -:106EE0009960D9680A43DA6010BD01F1804303F567 -:106EF000823319680A431A6010BD00BF00040140C4 -:106F0000254B10B55343254A254C12680139B2FB75 -:106F1000F3F20388013AA04289B292B29BB212D036 -:106F200004F50064A0420ED0B0F1804F0BD0A4F560 -:106F30009834A04207D004F58064A04203D004F541 -:106F40008064A04202D123F070039BB2154CA04292 -:106F500006D004F58064A0421CBF23F440739BB2AA -:106F600003800F4B8185984202850FD003F50063A3 -:106F700098420BD003F54063984207D003F5806335 -:106F8000984203D003F58063984201D10023038621 -:106F90000123838210BD00BF40420F0094000020F7 -:106FA000002C014000100040284BF0B51D68002265 -:106FB0002748165C1418AB19597801F0040101F048 -:106FC000FF0371B10132102AF2D10020F0BD1BB1D4 -:106FD00003EB83035B00DBB210F8012B303A134460 -:106FE000DBB2221A022AF2DC002184420AD919B14A -:106FF00001EB81014900C9B210F8012B303A11446C -:10700000C9B2F2E72E2E14D1601C002204240678A7 -:1070100002EB8202AF197F7852007F0792B203D54C -:10702000303A3244013092B2013C14F0FF04EED108 -:1070300000E00022074806244143642000FB0212BE -:107040000548B2FBF4F200FB0320F0BDC8000020AD -:10705000E30F002040420F008096980030B50022D8 -:1070600013460D495C5C9CB12E2C04D1013378B1E0 -:107070001C1800250D550A246243C95CA1F1300497 -:10708000092C9CBF303A52180E2B03D80133E8E785 -:10709000104630BD002030BDE30F00200FB407B50F -:1070A00004AB53F8042B00200449019303F088FB40 -:1070B00003B05DF804EB04B0704700BFDD260008A4 -:1070C000954B2DE9F74F1B78013B012B00F22081F6 -:1070D000924B1E78864240F01B81914B1B78022B0D -:1070E00000F016818F4B904D13F806808F4B83F87C -:1070F00000808F4B1A7801921AB18E4B33F916002B -:1071000007E08C4A2B6832F9160003F100432B602C -:10711000404207F035FE884907F03AFFDFF838A211 -:107120000446DAF800B00021584608F011F80027AC -:10713000DFF82C92002859D0D9F800B020465946E3 -:1071400008F02EF868B17D4B2A687B491A60C9F8AF -:107150000040204607F068FE08F02CF8784BD880F5 -:10716000BDE05846394608F01BF8002800F0B7800B -:10717000744B1A78002A31D12046296807F04AFD5D -:107180004FF07E5107F0EEFF6F4C28B160686F49F9 -:1071900007F04AFE60600FE06D49606807F044FE4A -:1071A000DFF8CCA18346514607F0DCFF10B9C4F8E4 -:1071B00004B001E0C4F804A0624A01231370654BD7 -:1071C00000221B68C9F8007043449A72019A82F049 -:1071D0000103574A1370604B1F6080E05F4BCAF891 -:1071E00000401A68554BFA325A6078E020465946FA -:1071F00007F0B8FF48B1584A4F491460204607F0DD -:1072000013FE07F0D7FF4E4BD880534BD9F80090B0 -:10721000D3F800A04846514607F0FCFC4F4B83468C -:107220001968464B5A688A1A002A0BDA4FF07E51C9 -:1072300007F0B6FF002852D02046514607F0B0FFB5 -:1072400000284CD03D4A4846116807F0A9FF3E4C43 -:1072500038B120683E4907F0E7FD3C492060A0684E -:1072600007E058464FF0804107F09AFF28B1A06828 -:10727000374907F0D9FDA06004E02068334907F0E2 -:10728000D3FD2060334B2C492068D3F8009007F0E1 -:10729000CBFD07F0B5FF09F80800A06807F0B0FFC4 -:1072A000019AC84482F00103214A88F8140013703F -:1072B000294B1F602A4B1F60224B1A780132D2B231 -:1072C000032A01D01A700AE000221A701E4B2549C9 -:1072D000586807F0A9FD07F093FF88F80A001EB967 -:1072E000174B1A8864321A80114A13780BB11E4B5F -:1072F00000E01E4B2B600F4B33F9160007F040FDEA -:107300000D4907F045FE0146286807F083FC00E0C0 -:10731000084603B0BDE8F08F3C0C0020900C002024 -:10732000A00C0020A44A0108400C0020A10C002061 -:10733000910C0020E00A0020000020416012002093 -:10734000DE170020920C0020A40C00200AD7833FF7 -:10735000EC51783F9C0C0020940C0020E01F002092 -:10736000980C002000007A440000A0410000A0C159 -:107370006F12833A2DE9F84FFBF7E2F89B4C064673 -:10738000E368A768C31A6FEA030A2369C71BC31A15 -:107390006FEA0309FF434FEAD979FF0F4FEADA7A20 -:1073A000B9F1000F05D1BAF1000F02D1002F00F0A2 -:1073B00013824FF0000B227D5FFA8BF59542DFF8C8 -:1073C000808241D2D8F80030894A03EB85081268E0 -:1073D000884B43F82520B8F80220D1050BD490053E -:1073E0002FD5854A1278510754BF844A844A1268BF -:1073F00043F8252025E0834A2846414605F0C5FA92 -:10740000814B1B885A0603D5284641467F4A16E021 -:10741000580703D5284641467D4A10E0190703D591 -:10742000284641467B4A0AE09A0703D5284641464A -:10743000794A04E0DB0704D5784A2846414605F03E -:10744000A4FA0BF1010BB6E7754BD8F80050B3F96D -:1074500006107823A1F57A7159434FF47A7391FBA2 -:10746000F3F101F22B1140F2671391FBF3F003FBF0 -:107470001011002389B2D8B2904209D205EB8300E3 -:107480004088400544BF5B4820F823100133F2E7F1 -:10749000B9F1000F23D006F5C333A0332361637D18 -:1074A000524DE3B9AB755F4B9B68990704D5FEF766 -:1074B000F1FE08B10123AB755B4B1B681B689B6831 -:1074C000984718B1A37D43F00203A3754A4B1B787C -:1074D00013F0050F03D1A37D43F00403A375A17D31 -:1074E00019B9424B5B7D002B4AD0627D12F0010F2F -:1074F000A2F10C001AD1032A06D83D4B3F4D11F0E2 -:10750000040F18BF2B4600E0394B043A072A04D871 -:10751000464A11F0010F18BF1346C0B2032810D815 -:10752000434A11F0020F18BF13460AE0C0B2032805 -:1075300006D82F4B324A11F0020F18BF134600E055 -:107540002B4B0025227DE8B282420DD9D8F80020CD -:1075500002EB80025288120604D5D3F800C0254AF7 -:1075600042F820C00135EDE7B9F1000F10D051B15C -:10757000627D1E4B0132D2B2142A08D1002206E0ED -:10758000B9F1000F04D0637D002BF1D100E05A75F2 -:10759000BAF1000F21D027483221B0F90230B0F9FA -:1075A0000020002BB8BF5B42002AB8BF524293FBB9 -:1075B000F1F392FBF1F1DBB2C9B28B4238BF0B465B -:1075C0001D4A0BB192FBF3F23244E260E27D074BBD -:1075D0000AB9012200E00022DA75E27D034B1AB9F4 -:1075E000164A9A61002035E0014AFAE7601200204D -:1075F000CC5F0108DE0700209627002068450108BF -:1076000058450108DA4C01088C090020E04C0108BB -:10761000E64C0108EC4C0108F24C0108F84C01085A -:1076200040040020E41F0020B00400207845010839 -:10763000704501089A090020400D030074450108B7 -:10764000A8040020D8F8001001EB83056D886D06B2 -:1076500006D40130217DC3B29942604AF2D89AE043 -:107660005F4DB5F900C0BCF1190F22DD11F8239070 -:1076700092F81CA009F00F0BD345D2F818C008DC13 -:10768000527FB2EB191F04DCDCF80090554A42F837 -:10769000239011F8232094F81E9002F00F0ACA4597 -:1076A00031DBDFF8389199F81D90B9EB121F2ADC15 -:1076B00024E01CF1190F26DA11F8239092F81CA08F -:1076C00009F00F0BD345D2F818C008DCD27FB2EB1B -:1076D000191F04DBDCF80090424A42F8239011F8AD -:1076E000232094F81E9002F00F0ACA450BDBDFF846 -:1076F000EC9099F81F90B9EB121F04DBDCF800C086 -:10770000384A42F823C0B5F90220192A1BDD11F8C6 -:1077100023C0257F0CF00F09A945A2690CDCDFF816 -:10772000BC9099F81D90B9EB1C1F05DCD2F80090B5 -:10773000DFF8B0C04CF8239011F8231001F00F0CC3 -:10774000AC451EDD85E7193283DA11F823C0A57F29 -:107750000CF00F09A945A2690CDBDFF8809099F8BD -:107760001D90B9EB1C1F05DCD2F80090DFF874C047 -:107770004CF8239011F8231001F00F0CAC45FFF6E4 -:1077800068AFE57FB5EB111FFFF663AF1168154ACF -:1077900042F823105DE7DFB192F8213092F8201013 -:1077A00006F54346C818013890FBF3F403FB1400B8 -:1077B00082F82310013182F8220091FBF3F003FBE1 -:1077C00010135036DBB2966082F8243082F82030F5 -:1077D000BDE8F84FFFF773BABDE8F88F60120020DC -:1077E0009A090020DE070020234B70B519684FF47A -:1077F0007A73B1FBF3F1214B21481A78214B224DCA -:107800001B7803F0B9F8214B21481968214B2E68E9 -:10781000B1FBF3F103F0B0F800241F4BE2B253F8D0 -:10782000221049B1012303FA02F2324202D01B486E -:1078300003F0A2F80134F0E72A6892070DD5184A40 -:107840001848127803EB8203196A03F095F8164B77 -:10785000197A11B1154803F08FF81548FEF74CFE60 -:10786000BDE87040134B14481A88144B92B2198823 -:107870004FF4EF6303F080B8E01F0020F80C002005 -:10788000C6620108980000208409002094000020AE -:107890000463010840420F00004D01082263010803 -:1078A0007527002026630108900B00203063010833 -:1078B000557001089817002034630108340C00202B -:1078C0002DE9F04FAE4E85B03778032F14D9AD4B6C -:1078D000AD48B3F90410B0F904200029B8BF4942FB -:1078E0006FF063035B1A9A4204DB01F16403934275 -:1078F000A8BF134683801FE0012F1DD8A34BA44CC3 -:107900001B78013B142B00F2E181DFE813F09100BA -:10791000DF01DF0168009F00DF01DF012F01DF01D0 -:10792000DF01DF01DF01DF01BD00DF01DF01DF017A -:10793000DF01DF01A101B801924B9649B3F806A01F -:10794000914B0968B3F80280B3F80090B3F904B022 -:10795000914C02910025BD4204F11004CED20FFAE1 -:107960008AF007F00DFA54F8101C07F05DFA034690 -:107970000FFA88F0019307F003FA54F8081C07F097 -:1079800053FA019B0146184607F046F903460FFAE1 -:1079900089F0019307F0F4F954F80C1C07F044FA4D -:1079A000019B0146184607F037F9029A034692F9FF -:1079B0000000019340420BFB00F007F0E1F954F89E -:1079C000041C07F031FA019B0146184607F024F920 -:1079D00007F0F0FB714B23F815000135BBE70221DE -:1079E0000420FAF7D6FE684D0121AF8878431FFACC -:1079F00080F80420FAF7CDFE6D8800FB05801FFAA1 -:107A000080F80420FAF7D4FE4044208102210520AA -:107A1000FAF7BFFE7843012187B20520FAF7B9FED5 -:107A200000FB057087B20520FAF7C2FE38440BE070 -:107A300005200121FAF7ADFE534B9D88684385B2BE -:107A40000520FAF7B5FE284460813FE1544B002041 -:107A50001D68FAF7ADFEDFF8648195F90630B8F9D4 -:107A600002203227534393FBF7F318442080012070 -:107A7000FAF79EFE95F90E30B8F90020534393FBB8 -:107A8000F7F73844608021E1464B1B7813F0040F70 -:107A9000454B02D11B689B880BE01968394A0B885B -:107AA000B2F9062049889A4203DB9142B4BF0B46E3 -:107AB0001346E381E289394B394F1A803B4B1B68EF -:107AC0001D7845B30220FAF773FE3A68B2F9103018 -:107AD000518A984203DB0BB29842B8BF034634493F -:107AE00009684889C3EB000E324B0FFA8EFE1988E5 -:107AF0000FFA81FCF44501DA0D4401E001DD4D1B74 -:107B00001D8092F91620B3F900305343642293FB91 -:107B1000F2F31844A080284B1B88DB050CD5194BC9 -:107B20001A88D7F80090E28022819A88184F6281E3 -:107B30005B880325A38101E0134BF1E709EBC50343 -:107B400093F90630B7F90680284608FB03F864234A -:107B500098FBF3F8A7F80680FAF72AFE01354044AF -:107B6000072DF88007F10207E8D1AFE00D4B1B7835 -:107B700013F0040F0C4B23D11B689B882CE000BF33 -:107B8000982700209A090020E81D0020D80C00202A -:107B900036000020DC0C0020680300205C27002059 -:107BA0005C1E002096270020641E0020681E002016 -:107BB0006C1E0020881200208C090020E00A0020A2 -:107BC0001968AD4A0B88B2F9062049889A4203DB4E -:107BD0009142B4BF0B461346E381E289A74BA84DFF -:107BE0001A80A84B03201B880121DF0503D5FAF773 -:107BF000D0FDA14F02E0FAF7CCFDA34FB7F8028009 -:107C0000022100FB08F01FFA80F90320FAF7C1FDFA -:107C10003F88012100FB0790E8800420FAF7B9FDB6 -:107C200000FB08F002211FFA80F80420FAF7B1FDEA -:107C300000FB078028810320FAF7BAFDE388184487 -:107C4000E0800420FAF7B4FD2389184420813DE048 -:107C500001210420FAF79DFD8B4D6F88784387B290 -:107C600004202781FAF7A4FD384420810121052052 -:107C7000FAF78FFD2D88684385B26581E0E6824B77 -:107C80000325B3F80490984628460221FAF781FDAF -:107C900000FB09F0012187B22846FAF77AFDC5F109 -:107CA00006035B0838F8133000FB037087B224F832 -:107CB00015702846FAF77CFD384424F81500013584 -:107CC000072DE1D16C4BDA886C4B1A806F4DDFF8D1 -:107CD000E491AB6813F0200F34D00020FAF768FD70 -:107CE000208080460120FAF763FD694B644F1B68D2 -:107CF00060801A0626D5674B1B681B7813F0020FAD -:107D0000654B23D0D9F800C0B3F900109CF90E20C0 -:107D10009CF906C0B3F902304A43CCF1000C03FBD6 -:107D20000CF3322192FBF1F26FF0310C92B293FB23 -:107D3000FCFC9444E04493FBF1F1A7F800800A4472 -:107D400010447880D9F80010002319E0D9F8001009 -:107D5000B3F902C091F90620B3F900300CFB02FC24 -:107D600032229CFBF2FCE044A7F8008091F90E104F -:107D70004B4393FBF2F2E3E7E2520233102B0CD0B9 -:107D8000E05E31F9232001EB830790427F88F3DB2B -:107D90003AB28242A8BF0246EEE73E4B1B681B7810 -:107DA0005B0704D435493478088801231BE03B4B3A -:107DB00000241F780423043FFFB25FFA87F84FFACC -:107DC00088F2D4420BD4364A03F10109381932F84B -:107DD00013105FFA89F9C0B2FBF787F94B460134FB -:107DE000042CECD1DEE7A34208D231F9132000B213 -:107DF0008242A8BF104680B20133F4E7294B4FEA14 -:107E000044081A68AB6803F480550395244D03F0C9 -:107E10001009254BB5F90660244D1B782F68244DB9 -:107E200003F00403DBB2D5F800C0029300234345FE -:107E300062D0B2F802A004B2544505DD0F4CC0EB8D -:107E40000A0A1D5B55441D53039D0C4C002D33D075 -:107E50007D8931F903A0AE42CBBFBCF802509588B2 -:107E6000B2F802B0BCF800B0AA4503DBDA45B4BFF3 -:107E700055465D46E55238E09A0900205C2700200F -:107E8000360000208C090020E81D0020E41F00209F -:107E900088090020701E0020E00A0020EF01002069 -:107EA00040040020641E0020962700206C1E002045 -:107EB000601E00205C1E002031F903A01588B2F876 -:107EC00002B0AA4503DBDA45B4BF55465D46E5522C -:107ED00004EB030ABC89A64207DAB9F1000F01D10D -:107EE000148800E09488AAF80040029C14B9044C5D -:107EF0001C5BCC5202339AE705B0BDE8F08F00BF9F -:107F0000BC0F00202DE9F04F704C89B02378023B64 -:107F1000042B00F21C83DFE813F007002F0005009C -:107F20008B00C60010266DE0694B1A68694B1B6810 -:107F300064339A4240F20B831026674D674B2A68E0 -:107F400098461A4492F84C002F4638B1FAF780FB55 -:107F50002A68013E02F101022A60EED13B684344E7 -:107F600093F84C30002B40F0F282032222705A4AE0 -:107F700013605B4A5360EAE2574D5A4B2E681F78F4 -:107F8000052E2ED8554CC7F1080704EB8603D3F80D -:107F9000B00009F01FFF002E14BF02230923504E2A -:107FA00007FB1307A046746873680F33A3420ADA0D -:107FB000BC4214D10A20FAF74BFB2B6801332B602B -:107FC00000237360C3E2BC42F2DA2B6808EB830340 -:107FD000D3F8B030185DFAF73BFB0134E4E7746086 -:107FE000B5E2414B9B681A064CBF0423052323705E -:107FF000002356E0FAF72CFB2A68013E02F1010249 -:108000002A6009D0344D354B2A6898461A4492F8B4 -:10801000C8002F460028EDD13B68434493F8C83090 -:10802000002B40F09482052222702B4A13608EE2CE -:10803000294D2B68072B30D8DFE803F004080B111B -:108040001D22272B2948FFF729F828E0284829492D -:108050000EE0294829492A4AFFF720F81FE0224B61 -:108060000A2193F85427274801FB023393F8561747 -:10807000FFF714F813E01C4B2348B3F8D010F7E7D0 -:10808000194B2248B3F8D210F2E7214B2148D968A6 -:10809000EEE7214B21481988EAE7062323702B6875 -:1080A00001332B6053E21E4D1E4B2C681B680D4A9A -:1080B00023601178002390468B4237DA1A4804EB8C -:1080C000430230F8130001339087F5E76E08002073 -:1080D000E01F0020381B00203C1B0020004D010841 -:1080E0008812002098270020E41F00206663010802 -:1080F000836301089B630108A3630108BA63010855 -:10810000C6630108CF630108DC630108EE63010860 -:10811000240B0020006401082400002013640108DF -:10812000581B00207C2700205C270020A84BA94E6C -:108130001A6862605A689B68A260E360A64B1A687E -:1081400022615A689B686261A361A44B1A68E2616C -:108150005A689B6822626362A14B1A8822855A88FA -:1081600062859A88DB88A285E3859E4B1A882286E1 -:108170005A889B886286A3869B4B1A88E28637685A -:108180005A889B8817F01F09228763877AD1492074 -:10819000FAF75EFA3068FAF761FA2068FAF75EFAE1 -:1081A0006068FAF76AFAA068FAF767FAE068FAF71F -:1081B00064FA2069FAF761FA6069FAF75EFAA06971 -:1081C000FAF75BFAE069FAF758FA206AFAF755FA13 -:1081D000606AFAF752FAB4F92800FAF74EFA834FB8 -:1081E000B4F92A00FAF749FAB4F92C00FAF745FA7B -:1081F000B7F8D030B4F92E00C01AFAF72FFAB4F954 -:108200003000FAF73AFAB4F93200FAF736FAB4F96C -:108210003400FAF732FAB4F93600FAF72EFAB4F964 -:108220003800FAF72AFAB4F93A00FAF726FAB7F85A -:10823000D030B4F93C000127C01AFAF70FFA98F8C9 -:1082400000309F420ADA04EB4703B3F93C00B4F96B -:108250003C300137C01AFAF710FAF0E72B68644A8D -:1082600064496B60AB609B1A9B104B430321013345 -:1082700093FBF1F101EB41015B1A4C2101FB03225D -:108280002A6061E15020D5F804A0FAF7E1F9AA6864 -:108290002B6810681B684FF0000B18446B681B6854 -:1082A000A0EB4300FAF7E9F904EB0B020AEB0B032E -:1082B00050685B680BF1040BC01AFAF7DEF9BBF1EA -:1082C0000C0FF1D14FF0000B04EB0B020AEB0B0388 -:1082D00010691B690BF1040BC01AFAF7CEF9BBF158 -:1082E0000C0FF1D14FF0000B04EB0B020AEB0B0368 -:1082F000D069DB690BF1040BC01AFAF7BEF9BBF1C8 -:108300000C0FF1D10023E218B2F928100AEB030296 -:10831000B2F928208A1A4DF813200233082BF2D123 -:10832000354B04AC03F1100E18685968224603C29D -:10833000083373451446F7D103AAADF104000023B6 -:1083400052F804199B00DBB269B101F108040F2C4B -:1083500002D843F0010306E08031FF2994BF43F0C7 -:10836000020343F003038242EAD108A901EB13128E -:1083700003F00F030B4412F810AC13F8103C002468 -:1083800043EA0A1A5FFA8AFA5046FAF761F90AF0E4 -:108390000303022B15D0032B30D0012B3BD108AAAD -:1083A00002EB840353F8200C53F81C2C00F00F0050 -:1083B00040EA0210C0B2FAF74BF901344FEA9A0AC8 -:1083C00029E008A901EB840313F8200C21E000BF89 -:1083D000F01D0020401B0020FC1D0020081E002076 -:1083E0009A0900202C0C0020EC0B0020E41F002038 -:1083F000641B00201BCA6B28D54E010808AA02EB9B -:10840000840353F820BC5FFA8BF0FAF721F9CBF321 -:108410000720FAF71DF90134032C4FEA9A0AB6DD5A -:1084200000242A6804F1180332F913006A68013441 -:1084300032F91310AA6832F9133002220B4493FB6D -:10844000F2F3C01AFAF719F9032CEAD100242A68CA -:1084500004F118035B001A44B2F906006A6801349B -:108460001A44B2F90610AA681344B3F9063002227E -:108470000B4493FBF2F3C01AFAF7FFF8032CE6D192 -:10848000002498F800309C4217DA2A6804F11C0393 -:108490005B001A44B2F904006A6801341A44B2F964 -:1084A0000410AA681344B3F9043002220B4493FB6E -:1084B000F2F3C01AFAF7E1F8E3E76B682A68AB60F9 -:1084C000244B25496A60D21A92104A430321013293 -:1084D00092FBF1F101EB4101521A4C2101FB0233F5 -:1084E0002B601E4B9B681B062ED51D4C1D4D226814 -:1084F0002B689A4209D162686B689A4205D1B9F13A -:108500000F0F10D117F47E6F0DD14820FAF7A0F8A5 -:108510002068FAF7B2F86068FAF7AFF823682B60C2 -:1085200063686B600EE0104A0E4B11782A7C914212 -:1085300008D10E4A99681068884203D15268DB68F6 -:108540009A4201D0FAF79DF833680133336009B0DD -:10855000BDE8F08F641B00201BCA6B28E41F0020BD -:108560002C0E0020441B0020080D0020140D0020BC -:1085700010B50446204609F02DFC10F0FF0F06D17F -:108580000C4B0D481978BDE8104002F0F5B92046B3 -:1085900009F075FC02280CD8064B0A221870074B0C -:1085A000074C02FB0030074B06301860F9F7BAFFA2 -:1085B000E0E710BD1C0E00203F67010834270020B3 -:1085C0004E710108D00C00201FB50123ADF8083012 -:1085D000ADF80410002301A9ADF80A30ADF80C3055 -:1085E000ADF80620FDF7C8FA05B05DF804FB10B53C -:1085F000A0F5127494F83C22C2B9A36A616A994248 -:1086000029D0591CA069A162C05C2369C0B29942FB -:108610004FEA400343F40073A4F83E324FF00A03DC -:1086200084F83D3228BFA262012312E094F93D3262 -:108630007BB1B4F83E1220464B08A4F83E3201F05C -:108640000101FAF742FD94F83D32013B84F83D32D6 -:1086500001E084F83C3294F83832002B4FD194F882 -:1086600039320133DBB2092B84F8393204D1204688 -:10867000BDE81040FAF714BD0A2B40D194F83B3204 -:108680002BB9B4F8403243F00103A4F840326379C7 -:10869000D9071CD5B4F84002820501D4C30705D41C -:1086A000B4F844320133A4F8443210E0E36AC0F372 -:1086B00047000BB198470AE0E3696269D054E26968 -:1086C000E3680132B2FBF3F103FB1123E361012202 -:1086D00084F8382294F83B220023012A84F83932A6 -:1086E0000DD1A27984F83B32236B012A1868197BDB -:1086F00014BF02220022BDE81040FFF765BF10BD85 -:1087000010B5A0F513746379DB074CD594F83832B3 -:1087100013B3236B1868828DC2F34E02828494F8DF -:108720003C2222B1B4F842220132A4F84222A279BA -:10873000197B012A0CBF02220022FFF745FF01230B -:1087400084F83B32002384F8393284F83A3284F8D2 -:108750003832A4F8403210BD94F83B322046012B49 -:1087600004BF94F8393284F83A32FAF799FC94F855 -:108770003B12236BA27949B9012184F83B128A424A -:108780001868197B0CBF0222002208E0002184F83F -:108790003B12012A1868197B14BF02220022BDE88F -:1087A0001040FFF711BF10BD426A10B58469A15493 -:1087B000416A02690131B1FBF2F402FB1412426218 -:1087C000426B32B11368DB0708D4BDE81040FEF7F6 -:1087D0005DBA036DDA6842F08002DA6010BD2DE9FF -:1087E000F04FD84AD84C85B01068516802AB03C32B -:1087F000DFF88C8300214FF4EF62204609F0A9FADC -:1088000004F50573C8F80030D04B0025DFF874A3D9 -:108810001D7004F25673CAF80030032363710223FB -:10882000A36040F24C404FF41673A4F8F030A4F863 -:108830001C01FA2340F26C70A4F8F230A4F81E0177 -:108840002A231920A4F8EE3084F825014FF4FA7396 -:1088500040F27E40A4F8F630A4F8D000202340F285 -:108860003A7084F8F430A4F8D2006E234FF47A7092 -:1088700084F80431A4F8D4002B2340F27E5084F80D -:108880000531A4F8D600212340F2EA5001265522F2 -:1088900040F2DC514FF01E0B4FF0320984F80631E4 -:1088A000A4F8D8004FF4C87340F2B4502270A4F872 -:1088B0000831A4F81A11A4F8DA00A4F8DE3084F81C -:1088C000EC6084F821B184F8246184F82761A4F86D -:1088D000DC90A4F8E0908DE8060002F035FC40F64C -:1088E000AC53A381D8F8003028271720A573187639 -:1088F0001F7183F80EB05F7183F80FB058761D704A -:108900000B20019A1872142058721875502098770D -:108910006420D8774FF0080E782083F813E058735E -:10892000DFF864C28A484FF00E0E9A7183F80AE0AD -:108930002D224FF05A0E4FF00A0B1A745A7783F813 -:108940000BE01F73DA7583F821609D7683F807903A -:108950005D74DD769D741D7783F815B0C3F824C06F -:10896000D86318644FF08240D8624FF07C5098630F -:108970007848C3F828C05864774A7848DFF80CC2B2 -:1089800000991A635A639864C3F84CC084F856E798 -:108990004FF0410EA4F85E1784F857E784F85A5751 -:1089A00084F85B5784F8589784F8595784F85C57D3 -:1089B0009A666B4A0421DA666A4A83F858101521D0 -:1089C000D86583F8607083F861701A6783F8746003 -:1089D000A3F85450A3F85650A3F8525083F86410EB -:1089E000614802F0D1FBD8F800304FF44872A3F888 -:1089F0006221C82283F8A7214FF49662A3F8A82128 -:108A000040F2D932A3F8AA2140F6430283F85F71FD -:108A100083F86061A3F8AC2183F85D5183F85E515F -:108A200083F8645183F8A6B11A46474656464FF478 -:108A30007F71A2F866114FF4FA61A2F8681102A8DA -:108A400040F2DC51A2F86A11415D013582F86C11E7 -:108A5000082D4FF0FF0182F86D1102F10802E6D1F6 -:108A6000012283F8AE2183F8AF2183F8B021C82119 -:108A700083F8B6216422A3F8B211A3F8B821142117 -:108A80004FF4967283F8B411A3F8BA211E2128225C -:108A900083F8B511A3F8BC210023E218103300219C -:108AA000C02B1161F9D131480021402209F051F960 -:108AB00000232F49E218595804330868382BC2F8AC -:108AC000D401F6D12B480021802209F042F92A4B2B -:108AD000284D03F1300E186859682A4603C208333E -:108AE00073451546F7D1254DFAF754F9FAF78EF983 -:108AF000FAF768F93F68284639464FF4E07209F002 -:108B00001FF9394605F5E0704FF4E07209F018F9E5 -:108B1000336805F563725968186803C219891180B2 -:108B20001A68C5F896235A68C5F89A231B89A5F8D0 -:108B30009E33012384F82434022384F8E43505B0FD -:108B4000BDE8F08FE84E0108E41F00201C0E002055 -:108B50008FC2753DCDCC4C3D9A99193F0000A04085 -:108B6000F6287C3F3D0A773F50670108B821002076 -:108B70007C45010838210020F04E0108B823002070 -:108B8000200B0020D00C00200000204000004040BE -:108B9000F7B50368174C184D23600B68174E6360D8 -:108BA0000068FAF79DF995E80300154B01960093CC -:108BB00094E80C00FAF752F93668124B60681E60B0 -:108BC0006B68114FC01A06F0DBF8104B196806F0FD -:108BD0002BF906F0EFFA22682B687860D31A3B6015 -:108BE0000B4B1E600B4B1B68DA880B4B1A8003B0D3 -:108BF000F0BD00BF48110020140D002054110020CA -:108C00005011002090110020581100204C0000202D -:108C100088110020C40C0020841100202DE9F043AD -:108C2000142285B0814688461B48002109F091F83E -:108C300003261A4B0027B74224DA13F8042C00212C -:108C4000C8B2013112B1501E0240F9E71C7AD1B20C -:108C5000013214B1611E0C40F9E7421A002A0EDD00 -:108C600001ACA3F10C0595E8070084E8070093E840 -:108C7000070085E8070094E8070083E8070001374C -:108C80000C33D8E7013ED4D1034A4846414605B0EB -:108C9000BDE8F04304F094BA901200207000002068 -:108CA0000022064B13445968814203D00C32302A0B -:108CB000F7D1002300225A725A60704764000020E6 -:108CC00038B50E4D04462B68834207D10121FFF7CA -:108CD000E7FF284600214C2209F03BF8EB6CA34249 -:108CE0000AD120460121FFF7DBFFBDE838400448E8 -:108CF00000214C2209F02DB838BD00BF200F002004 -:108D00006C0F002010B50023054A1A4454688442B1 -:108D100003D00C33302BF7D10022517210BD00BFAD -:108D2000640000202DE9F34706461F464FF41473F4 -:108D3000734347489246C41880460EB9454A02E03C -:108D4000012E04D1444A22631032C4F83421434A2C -:108D50000025C250032363714FF480734FF0010963 -:108D6000E3602361D4F8343184F83C5284F83892BB -:108D700084F8395284F84662586804F134029B68DA -:108D8000626104F59C72A261E1622562E561A562FF -:108D90006562A4F84252A4F84452ADF804300225AA -:108DA000102301A9C4F808A0A7718DF806308DF82A -:108DB0000750FAF7B3F9236B01A958689B688DF83F -:108DC0000750ADF8043048238DF80630FAF7A6F9BD -:108DD00049462046FAF779F93220F9F7D6FB204BBD -:108DE000D4F834911B681D46B5FBFAF1B1F5803F0C -:108DF00003D3012DF8D96D08F6E71A4A4846B3FBAC -:108E0000F2F289B2D2B203F0A5FD4FF414735E43BF -:108E1000154B06F5127608EB060548F8063048466D -:108E200029460022FDF766FE266B012F14BF0222A1 -:108E300000223068317BFFF7C7FB0C4B30466B607C -:108E4000291D0022FDF756FE204602B0BDE8F0873E -:108E5000A41200201060010830600108204F0108B2 -:108E60009400002040420F00EF85000801870008B1 -:108E700003460A4690F84602D96A9B7952E7F8B54C -:108E8000002207463749130101F15000185CB8422F -:108E900004D00132082AF5D10020F8BD324E0B442F -:108EA000503306F2B445082F0FCB344685E80F0047 -:108EB0001BD009D8022F0ED0042F16D0012F4FD16E -:108EC0002A4B1B685B6847E0202F42D0402F06D01A -:108ED000102F45D122E0254B1B689B6802E0234BF5 -:108EE0001B681B69C6F8B83436E0214B1B681B7839 -:108EF00053B1013B012B0AD9F9F732FF002814BF07 -:108F00004FF46143002304E04FF4165301E04FF4A3 -:108F10009643C4F8B834C4F8BC3421E0154B1B6840 -:108F20001B7A042B1CD8DFE803F00A0A030A0A00A4 -:108F3000114BC6F8B834C6F8BC34032306E04FF42E -:108F4000E133C6F8B834C6F8BC34012384F8C13420 -:108F500006E0064B1B68DB68C6F8BC342846F8BD43 -:108F60000648F8BDE84E010890120020B80F002016 -:108F7000E40C002074080020A086010044170020A3 -:108F800010B50446FFF77BFF01462046FFF746FE7B -:108F90004368187A10F0010018BF586810BD38B542 -:108FA00005460C46FFF76BFF01462846FFF736FEE5 -:108FB00028B143681B7A1C420CBF0020012038BD39 -:108FC00038B50B4B05469B685A050ED5F9F7C8FE18 -:108FD000044650B10820E9B2FFF7E1FF30B1054B7C -:108FE0001C78231F5C425C4100E00124204638BD10 -:108FF000E41F0020A40D002007B5002101AB0322CF -:10900000772003F0A3FF9DF805009DF804300002CF -:1090100040EA03409DF80630184303B05DF804FBB6 -:1090200008B5FFF7E9FF014B186008BD5417002091 -:1090300008B5FFF7E1FF014B586008BD5417002049 -:10904000104B13B51B78104C13B9238901332381BE -:1090500001ABF6210322772003F078FF9DF805305D -:109060009DF804201B0243EA02439DF806201343A7 -:10907000064AB2F92020C2F10802D340E36002B0F0 -:1090800010BD00BFCC1F002054170020C0010020DD -:109090000B4B13B51B780B4C13B923890133238178 -:1090A00001ABF6210222772003F050FF9DF8042047 -:1090B0009DF8053043EA0223238202B010BD00BFB1 -:1090C000CC1F00205417002013B5062204466B461F -:1090D0003B21682003F03AFF9DF800209DF8013005 -:1090E00043EA022323809DF802209DF8033043EADF -:1090F000022363809DF804209DF8053043EA022393 -:10910000A38002B010BD13B5062204466B4643216E -:10911000682003F01BFF9DF800209DF8013043EA12 -:10912000022323809DF802209DF8033043EA0223A6 -:1091300063809DF804209DF8053043EA0223A38054 -:1091400002B010BD13B50222044601AB1B216820FA -:1091500003F0FCFE9DF804209DF8053043EA02234D -:1091600003F54E534FF48C72103393FBF2F3233319 -:10917000238002B010BD13B5062204466B461D21A4 -:10918000682003F0E3FE9DF800209DF8013043EADB -:10919000022323809DF802209DF8033043EA022336 -:1091A00063809DF804209DF8053043EA0223A380E4 -:1091B00002B010BD13B5062204466B4601211C20E7 -:1091C00003F0C4FE9DF801309DF800209DF80210C8 -:1091D00043EA022242F38D02042392FBF3F222803F -:1091E0009DF8032042EA012242F38D0292FBF3F242 -:1091F00062809DF804109DF8052042EA012242F3A6 -:109200008D0292FBF3F3A38002B010BD13B50622CA -:1092100004466B460221182003F098FE9DF80030AA -:109220009DF801209B0803EB022323809DF8023068 -:109230009DF803209B0803EB022363809DF8043014 -:109240009DF805209B0803EB0223A38002B010BD0C -:109250002E4B2DE9F3411B780546002B38D0002416 -:1092600026462746A04608226B465320322103F0AB -:109270006DFE9DF801209DF80030013403EB0223C0 -:109280001BB29DF8032098449DF80230E4B203EB32 -:1092900002231BB21F449DF805209DF80430202CAA -:1092A00003EB02231BB21E449DF8073003F07F033B -:1092B00001D0002BD7D1164B98FBF4F897FBF4F7AD -:1092C00096FBF4F6A5F800806F80AE809C741AE0DF -:1092D00006226B465320322103F038FE9DF8012010 -:1092E0009DF8003003EB02232B809DF803209DF8AE -:1092F000023003EB02236B809DF805209DF80430BB -:1093000003EB0223AB8002B0BDE8F081A80100208E -:10931000541700200C4B07B51B68196819B10B4A8C -:109320009069014391619A889868ADF804200222FF -:109330008DF8072004220DEB02018DF80620F9F7C5 -:10934000EDFE03B05DF804FBA40100200010024014 -:1093500013B5214B4000C0B2D87402AC586A1975DD -:1093600004F8012D002101225A759C619975DC6178 -:1093700083F8202083F8212083F8221048B38288C4 -:10938000920515D40288D4050DD447F230520188D5 -:10939000890502D5013AFAD113E092B1028892B25E -:1093A00042F480720280828892B242F440728280DB -:1093B00047F2305293F8211011B1013AFAD100E08E -:1093C00012B903F0B3FD04E0034B93F8220080F0E0 -:1093D000010002B010BD00BF54170020024640211A -:1093E0003C20B5E770B50A4E00EB8000064400242F -:1093F000331913F8A00C074B01341D786840FFF7B0 -:10940000EDFF052CF4D12846BDE87040FFF7E6BF1C -:10941000B84F010897270020642928BF6421F8B5B8 -:1094200001FB00F7642497FBF4F40546E4B2002640 -:10943000F3B2A34204D29F20FFF7D4FF0136F7E72F -:10944000AC420BD2142097FBF0F0C4EB84136638C7 -:10945000C4EB83031844C0B2FFF7C4FF0134E4B285 -:10946000AC4238BF9A20F7D3F8BD0F4B10B5044675 -:10947000185CFFF7B7FF0D4B33F91430B3F57A7F63 -:1094800005DBB3F5FA6FA8BF4FF4FA6301E04FF4C0 -:109490007A73A3F57A730A2293FBF2F10920C9B219 -:1094A000BDE81040FFF7B8BFF66D0108400400208A -:1094B00010B5441E14F8010F10B1FFF793FFF9E740 -:1094C00010BD024680213C2042E710B5AE20FFF7D8 -:1094D000F8FFD420FFF7F5FF8020FFF7F2FFA82068 -:1094E000FFF7EFFF3F20FFF7ECFFD320FFF7E9FF87 -:1094F0000020FFF7E6FF4020FFF7E3FF8D20FFF796 -:10950000E0FF1420FFF7DDFFA120FFF7DAFFC820FE -:10951000FFF7D7FFDA20FFF7D4FF1220FFF7D1FFC4 -:109520008120FFF7CEFFCF20FFF7CBFFD920FFF739 -:10953000C8FFF120FFF7C5FFDB20FFF7C2FF402087 -:10954000FFF7BFFFA420FFF7BCFFA620FFF7B9FF7E -:10955000AF20FFF7B6FFA620FFF7B3FFAE20FFF75F -:10956000B0FF2020FFF7ADFF0020FFF7AAFFB020DB -:10957000FFF7A7FF4020FFF7A4FF0020FFF7A1FFA0 -:109580001020FFF79EFF4FF48064013C0020A4B23E -:10959000FFF724FF002CF8D18120FFF792FFC820AD -:1095A000FFF78FFFBDE81040AF20FFF78ABF08B577 -:1095B0005038C0B2FFF785FF0020FFF782FFBDE8FB -:1095C00008401020FFF77DBF2DE9F341F8F7B8FF01 -:1095D000AB4D0746AB6AC31A002BC0F2F38100F50E -:1095E000C333A033AB62A74B95F82C201E78C6F38B -:1095F0008006B21A18BF012285F82C604EB1002AED -:1096000000F0E081A04B5A789A7001225A701A70CB -:1096100020E09D4B2AB1DA7842F00202DA709A78A3 -:109620005A70D9788A0705D4974A9068381AC04387 -:10963000C00F00E00120944A187058B1CC0709D53A -:1096400013799249013303F0030313710B4493F828 -:10965000803253708C4C23784BB3FFF736FFB02029 -:10966000FFF72FFF4020FFF72CFF0020FFF729FF17 -:109670001020FFF726FF4FF4806808F1FF38002024 -:109680001FFA88F8FFF7AAFEB8F1000FF5D140469F -:10969000FFF78DFF7E4B627853F82200FFF708FF3B -:1096A000E37823F00203E3707A4B3B44A3606378D2 -:1096B000052B00F27281DFE813F0080070011B0037 -:1096C000770006001B010024D5E07349734A7448F3 -:1096D00001F03CF90120FFF76AFF7148FFF7E8FE4F -:1096E000704B6F4870491A6801F030F902204FE161 -:1096F0006E4B9A68984612F0020F2ED06C4C0A23DB -:1097000021786C4FB1FBF3F203FB12133978DBB213 -:1097100063480091684901F019F9F9F72BFB012022 -:10972000FFF745FF5E48FFF7C3FE644B3A781868C1 -:1097300024788378642102FB13444C43417802204F -:10974000CB1A5A43B4FBF2F4E4B2FFF730FF2146E0 -:109750001520FFF761FE032400E00124D8F808304B -:10976000180540F11A81564B56491F680968642351 -:1097700097FBF3F203FB127300914948524901F041 -:10978000E5F8F9F7F7FA2046FFF711FF4448FFF72D -:109790008FFEFDF761F90746601CFFF708FF1520F3 -:1097A0003946FFF739FEF8E00120484FFFF7FFFE8A -:1097B0004748FFF77DFE3B68990715D5454938486E -:1097C000B1F90020B1F90230B1F90410032400917D -:1097D000414901F0BBF8F9F7CDFA0220FFF7E7FEA7 -:1097E0002F48FFF765FE00E002243B68DA0718D532 -:1097F0003A492B48B1F90020B1F90230B1F904100F -:1098000004F101080091364901F0A0F8F9F7B2FA25 -:109810002046FFF7CCFE2248FFF74AFE5FFA88F8A1 -:1098200044463B681B0740F1B8802E491C48B1F9FB -:109830000020B1F90230B1F9041000912A4901F079 -:1098400085F8F9F797FA2046A2E00E2C00F0A580E3 -:1098500060080130FFF7ABFE2046FFF706FE3B78BD -:10986000A34206D92020FFF7BDFD601CC0B2FFF760 -:10987000FCFD0234E4B21D4F3B78A342E5D88CE0F6 -:10988000541700209627002098010020B84F0108A7 -:10989000A8000020404B4C00596701089B63010859 -:1098A00081170020C000002061670108E41F00202C -:1098B000F80C0020980000206C670108F40C0020D0 -:1098C000FC0C0020000D00208467010884090020A2 -:1098D00099670108EC0B0020AF670108340B0020EA -:1098E000BF670108B4090020CF67010867040020A2 -:1098F000364C374994F85427364801F027F80120B0 -:10990000FFF755FE3348FFF7D3FD334B33491F783C -:1099100030483A4601F01AF80220FFF748FE2D4879 -:10992000FFF7C6FD0A2303FB07472D4997F8572782 -:10993000284801F00BF8F9F71DFA0320FFF737FE6E -:109940002448FFF7B5FD274997F85627214800F02E -:10995000FDFFF9F70FFA0420FFF729FE1D48FFF776 -:10996000A7FD214997F85A271A4800F0EFFFF9F7A9 -:1099700001FA0520FFF71BFE1648FFF799FD154871 -:109980001A4997F85B2700F0E1FFF9F7F3F9062091 -:10999000FFF70DFE0F48FFF78BFD9EB9B020FFF7D4 -:1099A00090FD0820FFF78DFD1720FFF78AFD95F841 -:1099B00043400F4B185D013404F00304FFF712FD20 -:1099C00085F8434002B0BDE8F08100BFE41F0020ED -:1099D000DF670108811700201C0E0020EB670108DB -:1099E000FC6701080868010814680108216801087B -:1099F0002E680108772048210122A9E47720582108 -:109A00000122A5E4064B002193F82020054B92018A -:109A1000343219707720F42102F0FC0298E400BF80 -:109A2000C0010020CC1F0020034B00221A707720B9 -:109A3000F4212E228CE400BFCC1F002008B5192091 -:109A4000F8F7A3FD682015210022FFF781FC10B96B -:109A50000320F8F7ABFD0C4B16211A78682042F072 -:109A60001802FFF775FC172100226820FFF770FC31 -:109A70003D2101226820FFF76BFCBDE8084068200B -:109A80003E21012264E400BF1600002008B50F212A -:109A900008221820FFF75CFC0E2218201021FFF787 -:109AA00057FC024B4FF480521A8008BD240000205E -:109AB00008B5134B53201B782D2108227BB1FFF7EB -:109AC00047FC31210A225320FFF742FC2C210C22B3 -:109AD0005320FFF73DFC53203821902209E0FFF787 -:109AE00037FC31210A225320FFF732FC53202C216E -:109AF0000A22FFF72DFC034B40F209121A8008BD21 -:109B0000A80100202400002037B5062204460321C6 -:109B10006B461E2003F01AFA9DF801309DF80000F4 -:109B2000154D43EA002000B205F02AF9296805F036 -:109B30007BF905F03FFB9DF8033020809DF8020083 -:109B400043EA002000B205F01BF9A96805F06CF9A2 -:109B500005F030FB9DF80530A0809DF8040043EA35 -:109B6000002000B205F00CF9696805F05DF905F018 -:109B700021FB608003B030BD1800002007B5232012 -:109B8000F8F703FD6820752101220DF1070303F0AA -:109B9000DDF928B19DF80700B0F16803584258413B -:109BA00003B05DF804FB00BF2DE9F047054608F05F -:109BB00011F92E4B0446D3F808809A4690B92C48E8 -:109BC000FCF79AFC2B4B53F8241049B10123A34016 -:109BD00013EA080F02D0284800F0CEFE0134F1E766 -:109BE000264821E028462649224608F0FBF858B9C5 -:109BF0002448FCF781FC244C54F8041F0029EFD0C2 -:109C00001D4800F0B9FEF7E72B7800262D2B03BF87 -:109C1000013504F1FF344FF001094FF00009154BF5 -:109C200053F8267027B91948BDE8F047FCF764BC23 -:109C300028463946224608F0D5F8A8B90120B04098 -:109C4000B9F1000F03D0F9F730F8114804E040EA09 -:109C50000800CAF808000F48FCF74EFC39460E48C9 -:109C6000BDE8F04700F088BE0136D8E7E41F0020C9 -:109C7000656801080C53010822630108557001084A -:109C8000A06F010878680108085301088D68010871 -:109C9000A4680108AE680108456901082DE9F04F84 -:109CA000692887B0044600F0A78200F296802E282B -:109CB00000F03A8562D8242800F00A852BD82028A5 -:109CC00000F08282222800F0BE83012840F05D85EA -:109CD0002C20FCF7ABFB0020FCF779FB2046FCF7BF -:109CE00076FB0020FCF773FB4320FCF770FB4C2055 -:109CF000FCF76DFB4620FCF76AFB4C20FCF767FB8A -:109D00002046FCF764FB0020FCF761FB0020FCF719 -:109D10005EFB0024F0E0282800F0E28412D8262818 -:109D200040F03385924C0320FCF780FBB4F9E60049 -:109D3000FCF77FFBB4F9E800FCF77BFBB4F9EA0021 -:109D400000F034BC2A2800F0D6842C2840F01D8571 -:109D5000874C0720FCF76AFB94F81801FCF737FBE7 -:109D6000B4F91E01FCF765FBB4F91A01FCF761FBBD -:109D7000B4F91C01FCF75DFB00F0C3BC642800F0E3 -:109D8000E3801AD8322800F0BC840AD8302840F08A -:109D9000FC84774C8020FCF749FB04F1800500F03F -:109DA000D9BC342800F06F83402840F0EE840820AE -:109DB000FCF73CFB002400F0ADBC662800F09C8161 -:109DC000C0F0F080672800F0D081682840F0DD8482 -:109DD0001020FCF72BFB002406E2732800F0BA8366 -:109DE00055D86D2800F01B8212D86B2800F0008433 -:109DF00040F2BB835F4C0620FCF718FBB4F900006F -:109E0000FCF717FBB4F90200FCF713FB5A4B0EE208 -:109E10006F2800F06782C0F00D82702800F0818208 -:109E2000722840F0B284524C1620FCF7FFFA002052 -:109E3000FCF7FFFAB4F9D000FCF7FBFA4F4DB4F988 -:109E4000D200FCF7F6FAB4F9D400FCF7F2FA2B686A -:109E5000B3F9A801FCF7EDFA0020FCF7EAFA0020BC -:109E6000FCF70CFB2B68B3F952000A2390FBF3F0CC -:109E7000FCF7DFFA94F80401FCF7A9FA94F806015C -:109E8000FCF7A5FA94F80501FCF7A1FAE6E37828B7 -:109E900000F0778110D8752800F0C982C0F01483D3 -:109EA000762800F0B783772840F06F84344D002483 -:109EB0002878FCF7BBFA42E3A42800F0D18310D83D -:109EC000A02840F062840C20FCF7B0FA2D4B1868F3 -:109ED000FCF7D4FA2C4B1868FCF7D0FA2B4B186817 -:109EE000FBE3F02800F0E783FE2840F04E840820D2 -:109EF000FCF79CFA0024D6E3254B1B68185D01345F -:109F0000FCF765FA042CF7D1224B00241878FCF7F3 -:109F100090FA214B185D0134FCF759FA0B2CF8D15B -:109F200000241E4B185D0134FCF751FA082CF8D1BF -:109F30000720FCF74CFA0024194B185D0134FCF79C -:109F400046FA072CF8D189E30720094CFCF76EFA92 -:109F5000E620FCF73CFA6079FCF739FA0020FCF7C0 -:109F600036FA94F82631002B0CBF04200C20B4E301 -:109F7000E41F0020E00A0020180C0020200B002025 -:109F80000E1B0020E8F7FF1FECF7FF1FF0F7FF1F85 -:109F9000C400002074270020BA630108C6630108CA -:109FA0009B6301080B20FCF741FAB64BB3F90000A4 -:109FB000FCF73FFAB44B188800B2FCF73AFAB34BFF -:109FC0001B68C3F3C000C3F38002800040EA420074 -:109FD000C3F340021043C3F3401240EAC20003F04F -:109FE00010031843FCF725FAA94B1A8812F0010F49 -:109FF0000CBF0020022012F0020F0CBF0021042130 -:10A0000012F0040F0CBF0023102312F0400F0CBFFE -:10A0100000242024019312F0100F9E4B02940CBFD9 -:10A0200000244FF4007412F0200F1B6803940CBF3F -:10A0300000244FF4806412F4807F04940CBF002449 -:10A040004FF4006402F0080B03F4807A059403F4E3 -:10A05000805903F4005803F4004C03F4803E03F4E9 -:10A06000003703F4802603F4002503F4801403F082 -:10A07000C00343EA0B0343EA0A0343EA090343EA42 -:10A08000080343EA0C0343EA0E0E834B4EEA07072C -:10A090003E431B7835432C43C3F3800323430343E0 -:10A0A0000B430199029C0B4303992343049C0B43EC -:10A0B0000599234312F4007F43EA01030CBF0022F9 -:10A0C0004FF400121A43754B00201C780346A3423C -:10A0D0000CD273495D5C012101FA05F5154218BFE8 -:10A0E000994003F1010318BF0843F0E7FCF7C6F9F4 -:10A0F0006C4B93F854070AE31220FCF797F96A4B6C -:10A100006A4C1B88B3F5806F22D90025605F082355 -:10A1100090FBF3F00235FCF78CF9062DF6D1644C78 -:10A12000B4F90000FCF785F9B4F90200FCF781F9F5 -:10A13000B4F904005F4CFCF77CF9B4F90000FCF7BB -:10A1400078F9B4F90200FCF774F9B4F904002DE2CF -:10A15000B4F90000FCF76DF9B4F90200FCF769F9F5 -:10A16000B4F90400FCF765F9D9E71020FCF75EF9B3 -:10A170000024514B185D0134FCF729F9102CF8D15B -:10A1800016E23820FCF752F900254C4E05F12C045C -:10A190003368E4002344B3F90600FCF74AF9336856 -:10A1A00001352344B3F90800FCF743F9336823442D -:10A1B000B3F90A00FCF73DF933681C44207BFCF737 -:10A1C00006F9082DE1D1F3E10820FCF72FF900246E -:10A1D0003A4B1B6803EBC40393F86D010134FCF7A1 -:10A1E000F6F8082CF4D1E3E1354B185D0134FCF7A7 -:10A1F000EEF8102CF8D1DBE1324D00242878400035 -:10A2000000F0FE00FCF712F92B789C4280F0D08120 -:10A210002D4B33F91400FCF70CF90134F4E7062058 -:10A22000FCF704F9294B1868FCF728F9284BB3F917 -:10A230000000BBE10720FCF7F9F8264B4FF6FF744E -:10A240001878FCF7C4F8244B1868A042A8BF204631 -:10A2500020EAE07000B2FCF7ECF8204BB3F9000004 -:10A26000FCF7E7F80F4B93F80C211D4B18680028FA -:10A27000B8BF40420AB10A235843A042A8BF2046B3 -:10A2800000B293E1340C00209817002084090020CC -:10A290008C09002088090020962700200E1B002032 -:10A2A000F81A0020E41F002024000020EC0B0020FE -:10A2B0002C0C0020B409002036000020200B0020C8 -:10A2C0005C2700206704002040040020940900203F -:10A2D000000B0020F80C0020000D0020C60D00200F -:10A2E000FC0C0020B34C0720FCF7A0F8236818787A -:10A2F000FCF76DF823685878FCF769F8236818793B -:10A30000FCF765F823685879FCF761F823689879B9 -:10A31000FCF75DF823689878FCF759F82368D8783B -:10A32000F5E1A54D1E20FCF781F82B6800241B7871 -:10A33000022B69D12B68A14903EB8403586A04F00E -:10A3400073FD07F06BFFFA28A8BFFA2020EAE0703F -:10A35000C0B2FCF73CF82B68994903EB8403186BF7 -:10A3600004F062FD07F05AFFFA28A8BFFA2020EA9D -:10A37000E070C0B2FCF72BF82B68924903EB840322 -:10A38000D86B04F051FD07F049FF6428A8BF642092 -:10A3900020EAE070C0B20134FCF719F8032CC9D1EF -:10A3A000072C2B681ED1986C844904F03DFD07F002 -:10A3B00035FFFA28A8BFFA2020EAE070C0B2FCF707 -:10A3C00006F82B687D49D86C04F02EFD07F026FFB7 -:10A3D000FA28A8BFFA2020EAE070C0B2FBF7F7FF26 -:10A3E00000200BE023441879FBF7F1FF2B6823448E -:10A3F000987BFBF7ECFF2B682344187E0134FBF7B6 -:10A40000E6FF0A2CCCD1D3E02B6823441879FBF764 -:10A41000DEFF2B682344987BFBF7D9FF2B6823448E -:10A42000187E0134FBF7D3FF0A2CEDD1C0E02F20BA -:10A43000FBF7FCFF644C14F8010F002800F0B88013 -:10A44000FBF7C5FFF7E7A020FBF7F0FF00245A4B0E -:10A4500004F11C021B680C2103EB82035D1D5B4AA7 -:10A460005B79013401FB0323187AFBF7B0FF6878AE -:10A47000FBF7ADFFA878FBF7AAFFE878FBF7A7FF8B -:10A48000282CE4D194E04820FBF7D0FF00250626D5 -:10A490006E43494B06F588761B6801351E44B07A39 -:10A4A000FBF795FF7079FBF792FFB079FBF78FFF11 -:10A4B000F079FBF78CFF307AFBF789FF707AFBF7B6 -:10A4C00086FF0C2DE3D173E0002701240025404BCB -:10A4D0001B789D4222DA3F4BE95C00233B4A03EBA9 -:10A4E00002089A5C8A4204D00C33B3F58A7FF5D116 -:10A4F00012E0D8F8040007F06DFC81460CB926463E -:10A5000001E0074408E04E4506DAD8F80430985DCB -:10A51000FBF75DFF0136F6E70135D8E7002C47D0A1 -:10A52000F8B2FBF783FF0024D0E7284A99189A5C19 -:10A5300082420BD00C33B3F58A7FF6D101342B78ED -:10A540009C4235D2234BE05C0023EEE7087AFBF710 -:10A550003EFFF3E70820FBF769FF0124E0B2013476 -:10A56000FBF735FF092CF9D122E01020FBF75EFF45 -:10A57000194B1A4C187800F00200FBF728FF184B13 -:10A580001878FBF724FF2068FBF778FF6068FBF77B -:10A5900075FF144BB3F90000FBF74BFF124BB3F9F7 -:10A5A0000000FBF746FF114BB3F90200FBF741FF38 -:10A5B0000120EBE0D00C0020200B00200000204107 -:10A5C0000000C84200007A443B520108D44A010806 -:10A5D0000E1B0020F81A0020BA090020140D0020DC -:10A5E000080D0020060D0020040D00209817002003 -:10A5F0000520FBF71BFF674BB3F90000FBF719FFC2 -:10A60000654BB3F90000FBF714FF644B187800F0BA -:10A6100001007CE0FBF7BEFE06461220FBF706FFBA -:10A620000EB95F4B02E0102E03D15E4B1D685C68D3 -:10A6300001E0002425463046FBF7C9FE2846FBF71B -:10A640001DFF2046FBF71AFF574B1868FBF716FF54 -:10A650000020FBF7EEFE0020FBF7EBFE002056E0AB -:10A66000524D002428792E4680000130C0B2FBF7FD -:10A67000DDFE2879FBF7ABFE33799C4298D24C4D36 -:10A68000285DFBF7A4FE05F11003185DFBF79FFEA4 -:10A6900005F12003185D3035FBF799FE285DFBF7C7 -:10A6A00096FE0134E8E7434B185F0234FBF7C1FE26 -:10A6B000082CF8D17CE7404C0420FBF7B7FE236858 -:10A6C000B3F95600FBF7B5FE2368B3F954006DE704 -:10A6D0000420FBF7ABFE394B9868FBF7CFFE67E72A -:10A6E000364C0420FBF7A2FEB4F90801FBF7A1FEEB -:10A6F000B4F90A015AE70120FBF798FE2F4B58796D -:10A7000005E00120FBF792FE2C4B93F82001FBF7AC -:10A710005EFE4DE7294B234493F810010134FBF70B -:10A7200056FE082CF6D143E74020FBF77FFE234C72 -:10A7300004F14005B4F9D401FBF77BFE94F8D6018F -:10A74000FBF745FE043494F8D301FBF740FEAC421E -:10A75000F0D12DE7B4F85601043400F03F00FBF7C8 -:10A7600068FEB4F85201C0F38410FBF762FE94F85F -:10A7700050010009FBF72BFE94F8500100F00F0088 -:10A78000FBF725FEAC42E5D112E7002007B0BDE89B -:10A79000F08F00BF780D00207A0D0020D40F00202C -:10A7A0002C0E0020380E0020900900209817002061 -:10A7B0009D170020DE170020200B0020E41F002042 -:10A7C0002DE9F04F064689B00F4615469B4629787D -:10A7D000002900F0B880252902D001353046B0E0CC -:10A7E0006C78302C03D002354FF0000903E0AC78D0 -:10A7F0004FF001090335A4F13003092B4FF0000895 -:10A800001AD8A4F13003DAB2092A07D80A2B13DCCC -:10A810000A2202FB083815F8014BF2E7A4F16103A4 -:10A82000052B02D8A4F15703F0E7A4F14103052B4F -:10A8300002D8A4F13703E9E76C2C03BF2C7801227E -:10A8400001350022632C66D006D8252C77D0582CF1 -:10A850003FD0002C77D0BAE7732C63D002D8642C99 -:10A8600011D0B4E7752C02D0782C32D0AFE70BF1C1 -:10A87000040A05ACDBF800000A2112B100222346CD -:10A8800013E0234620E00BF1040A05ACDBF80000DE -:10A8900072B1002806DA2D238DF8143040420DF1F4 -:10A8A000150300E023460A210022F8F78FF90DE096 -:10A8B000002806DA2D238DF8143040420DF11503DF -:10A8C00000E023460A210022F8F758F9D346009405 -:10A8D0001AE00BF1040303930DF1140ADBF80000F6 -:10A8E000102132B1583C624262415346F8F76EF98A -:10A8F00006E0B4F158035A425A415346F8F73EF97C -:10A90000DDF80CB0CDF800A03046394642464B4643 -:10A91000F8F798F95BE730469BF800100BF1040458 -:10A92000B8470AE0DBF8003030460093394642462B -:10A9300000230BF10404F8F785F9A34647E73046F6 -:10A940002146B84743E709B0BDE8F08F0EB40FB514 -:10A9500005AB53F8042B0190064901A80393FFF7B8 -:10A960002FFF019B00221A7004B05DF804EB03B0C6 -:10A97000704700BF052000080FB407B50A4904ABB3 -:10A9800008680A4953F8042B09680193FFF718FF78 -:10A99000074B1868F7F731FE0028F9D003B05DF8CF -:10A9A00004EB04B0704700BF3C01002038010020D8 -:10A9B000581E00202DE9F0438DB0054607F00AFA35 -:10A9C000C0B2002858D104467F4B00211E681422D3 -:10A9D00007A807F0BEF9A500002303A905A8039363 -:10A9E000059377190B7183801A46DFF8F0E1B7F809 -:10A9F00002C03EF8138018EA0C0F0CD00EF10A0EBC -:10AA00000DF1300813F80EE002F1010C424402F897 -:10AA100024EC5FFA8CF20133052BE6D100231A46B1 -:10AA2000DFF8C0E1B7F802C013F80E8018EA0C0F87 -:10AA30000CD00EF1060E0DF1300813F80EE002F105 -:10AA4000010C424402F81CEC5FFA8CF20133062B35 -:10AA5000E6D1735D8DE803001A0907A85B4903F08E -:10AA60000F03FFF773FF2146594807AA0134FFF788 -:10AA700083FF202CA8D1A3E0284607F000FA1F2866 -:10AA8000044600F3918028462021E4B207F095F9AE -:10AA90001F2C01D94F4888E04B4B471C1B680021F5 -:10AAA00003EB84042046042207F053F900254A4BA7 -:10AAB00007AE304600210A2215F803905FFA85F8A8 -:10AAC00007F047F90023FA5CF91832B10A2B04D0D9 -:10AAD0004A4502D0F2540133F5E74A4501F1010736 -:10AAE00067D1B8F1020F0DD0B8F1030F0CD0B8F157 -:10AAF000010F0BD0304607F0C2F92378C0B243EA09 -:10AB000000100AE0002219E0002226E0304607F09B -:10AB1000B6F9237800F00F001843207038E00133B5 -:10AB2000062B0AD02D4800F115069E5D8E42F6D107 -:10AB30000344D97B63880B43638001320CA9D3B2F1 -:10AB40000B4413F8141C19B30023EBE7412B1DD061 -:10AB5000542B08BF04230ED00132D3B20DF13008BC -:10AB6000434413F8143C9BB1492B01D1002302E06C -:10AB7000572B07D10123194931F8131063880B4370 -:10AB80006380E9E7462BE1D10223F4E70323F2E7F0 -:10AB90000135042D8BD10124F8F7FCF8F8F736F9CC -:10ABA000F8F710F964B975E70D482021FFF7E4FEC6 -:10ABB00006E020460021042207F0CBF80024EBE752 -:10ABC0000DB0BDE8F08300BFA8040020C8680108EC -:10ABD000D4680108E068010893520108785201081E -:10ABE000EE6801088752010807B5064B0648009336 -:10ABF000064B074A1968074BFFF7BEFE03B05DF826 -:10AC000004FB00BF9B63010810690108C00000201D -:10AC1000BA630108C663010810B50748FBF76CFC6E -:10AC20000024064B0648E218E15852680C34FFF73E -:10AC3000A3FEFC2CF5D110BD2C690108605301085E -:10AC4000426901082DE9F04389B0044607F0C2F8D3 -:10AC5000C6B2002E6CD18B48FBF74EFC8A4C2069A3 -:10AC6000002104F075FA40BB013688483146FFF7F1 -:10AC700083FE206904A9FAF716FF01468448FFF70E -:10AC80007BFE606904A9FAF70EFF01468048FFF7D2 -:10AC900073FEA06904A9FAF706FF01467C48FFF796 -:10ACA0006BFEE06904A9FAF7FEFE01467948FFF75A -:10ACB00063FE0C2E04F11004D1D10025764C2F46F2 -:10ACC0002B464FF00008B04504F1100415DA184681 -:10ACD00054F8101C03F0A0FF54F80C1C81462846C1 -:10ACE00003F09AFF54F8081C0546384603F094FF19 -:10ACF00008F101084B460746E5E7684801930295CD -:10AD00000397FBF7F9FB002401ABE058644920F0FE -:10AD1000004004F045FA634B634A0434002814BF32 -:10AD200010461846FBF7E8FB0C2CEDD15F4891E08C -:10AD300020465F49052207F055F838B9524B0022EA -:10AD400003441030C0281A61F8D197E020465949D1 -:10AD5000042207F047F806462046002E40D1202165 -:10AD600007F02BF8002800F08980451C284607F0E2 -:10AD700031F834468046504B53F824600EB94F48A2 -:10AD800068E0284631465FFA88F207F02BF8671C26 -:10AD900020BB3D4B0021C2181030C02811619C46D9 -:10ADA000F7D1474B002403EBC702D2F804E09846E2 -:10ADB000BEF1000F04D143483146FFF7DDFD55E0F9 -:10ADC00018F837309C42F6DA23010CEB03051035F6 -:10ADD00073440FCB013485E80F00F1E73C46CAE726 -:10ADE00007F04DF8461E0B2E074643DC2046202177 -:10ADF00006F0E3FF054640B1451C2846F7F728FE5C -:10AE0000214B3F01D851012400E00446284620216F -:10AE100006F0D3FF054640B1451C2846F7F718FE5B -:10AE2000194B013403EB061358612846202106F024 -:10AE3000C4FF054640B1451C2846F7F709FE124BF2 -:10AE4000013403EB061398612846202106F0B5FF74 -:10AE500018B91D48FBF750FB10E00130F7F7F8FD7B -:10AE6000094B032C03EB0616F061F2D11748FFF7EC -:10AE7000E9FE03E016480C21FFF77EFD09B0BDE8AE -:10AE8000F08300BF52690108E41F00207D690108BA -:10AE90008369010845690108F81F002087690108D6 -:10AEA0000AD7233C4E6901084A6901085570010818 -:10AEB000966901089C690108B0520108A16901085E -:10AEC000F0430108B6690108C66901084E7101081E -:10AED000006A0108F8B5074606F07CFF044638B959 -:10AEE000194B1A485A791A4B013A53F8221028E0A4 -:10AEF00038461849224606F075FF60B91648FBF738 -:10AF0000FBFA164C54F8041F19B11548FFF734FD2D -:10AF1000F8E7144805E000250D4B53F8256026B9E5 -:10AF20001148BDE8F840FBF7E7BA384631462246FB -:10AF300006F058FF01350028EED1034B0B485D7138 -:10AF40003146BDE8F84017E5E41F0020286A0108F3 -:10AF5000B0520108A06F01083C6A0108AC52010818 -:10AF60002263010855700108A16901084F6A0108B0 -:10AF700070B5044606F02EFF08B91E482EE02046A4 -:10AF80001D4906F0A1FF00242646254678B12CB1C4 -:10AF9000012C06D106F073FF064602E006F06FFFB3 -:10AFA000054615490020013406F08EFFEEE70B2D13 -:10AFB00004D9BDE8704011480C21DDE4012C07DC08 -:10AFC0000F4B294633F915200E48BDE87040D3E4F5 -:10AFD000A6F57A73B3F57A7F03D90B48BDE87040C4 -:10AFE000CAE40A4829463246FFF7C6FC044B23F858 -:10AFF000156070BD616A01081D7101089B6A010836 -:10B00000BC0F0020C16A0108D96A0108FB6A010867 -:10B010002DE9F743044606F0DDFEC0B290B9304C8E -:10B02000054694F8D711B4F8D42194F8D6312D48B8 -:10B03000009129460135FFF79FFC102D04F104040F -:10B04000EFD14AE0204606F01AFF0F28054636DC0D -:10B050002046202106F0B1FE234FEDB2D7F8009034 -:10B06000441CAD000026204606F009FF5FFA86F872 -:10B07000B8F1010F83B208D0B8F1020F0BD0B3F5CD -:10B08000B47F1ED23A6853530AE0FF2B19D83B68AD -:10B090002B44987004E0FF2B13D83B682B44D870E6 -:10B0A00020462C2106F089FE044608B1441C02E02B -:10B0B000B8F1020F05D10136032ED4D10DE00B48B3 -:10B0C00006E009EB05000021042206F042FE0848D4 -:10B0D000102103B0BDE8F0434EE403B0BDE8F083B7 -:10B0E000E41F0020146B0108AC040020286B010849 -:10B0F000E0680108F0B500231946CEB200220C2505 -:10B1000005FB02F70D48D4B23F5CB74203D00132D1 -:10B11000042AF4D10BE0FF2C09D0094A05FB0400F6 -:10B120001A4492F82C21074C0133A25C02720131BF -:10B13000052901D0032BE0D9F0BD00BF6400002039 -:10B14000E41F0020BC68010810B54F20FBF7FEF992 -:10B150000C4C84F82C010020FBF7F8F94FF4E13394 -:10B16000C4F83031C4F83431C4F83831C4F83C3153 -:10B17000522384F82D0184F82E0184F82F0184F8DD -:10B18000403110BDE41F002070B50546441E14F880 -:10B19000011F61B1064E304606F00FFE0028F6D0C2 -:10B1A000861B0448631B304480F81031EFE770BD04 -:10B1B000F66D0108E41F00207FB5044606F00AFE84 -:10B1C000082824D100231F49E25C0968114449780A -:10B1D00001F00301022908BF203AE2540133082B91 -:10B1E000F1D10025665D1848314606F0E6FD28B12C -:10B1F00001356019314606F0E0FD18B11348FBF740 -:10B200007BF91CE0082DEDD12046FFF7BDFF10486B -:10B21000FBF772F900230F4A04A91A4492F810218F -:10B220000A440949595C0133082B02F80C1CF2D17D -:10B230000023094801A98DF80C30FFF79DFB04B0ED -:10B2400070BD00BFC8000020F66D01084C6B0108FE -:10B250006C6B0108E41F0020456901082DE9F041ED -:10B260008CB01D469DF848308846012B174608D102 -:10B27000A84B984240F04681042203F548431A61E6 -:10B2800065E0A54B98425ED1A448A54B876003605A -:10B29000A44BA907436103F1C00383614FF0C003CE -:10B2A000C36003619C4B036503F104038364C364BF -:10B2B00003F5484303F154030363A3F11403D3F8E4 -:10B2C000D42F436342F48042C3F8D42FD3F8D02F55 -:10B2D00042F00102C3F8D02F4FF002038DF8033083 -:10B2E0004FF40073ADF800304FF018038DF80230C2 -:10B2F00003D58D486946F7F711FF1C232A078DF8FF -:10B30000023003D588486946F7F708FF4FF4806399 -:10B31000ADF8003048238DF80230EB0703D58248A2 -:10B320006946F7F7FBFE0E238DF804300022012357 -:10B3300001A88DF805308DF806208DF80730774C80 -:10B34000FBF794FD55E0734B984240F0DF80774B5C -:10B35000734A9F601A60C022DA601A61744AAE07AD -:10B360005A6102F1C0029A616A4A1A6502F1040246 -:10B370009A64DA646F4BDA6942F40032DA615A692E -:10B3800042F001025A614FF002038DF803304FF092 -:10B390000403ADF800304FF018038DF8023003D5E8 -:10B3A00061486946F7F7BAFE1C232C078DF8023076 -:10B3B00003D55D486946F7F7B1FE0823ADF80030C4 -:10B3C000E8074FF048038DF8023003D55648694628 -:10B3D000F7F7A4FE26238DF804300022012301A8EC -:10B3E0008DF805308DF806208DF80730FBF73EFD0F -:10B3F0004E4C0026012384F844302662E661A662A2 -:10B400006662C4F82C806571A760A6712046FBF7C0 -:10B41000C5FB15F0090F31D0206B002826D0E36C56 -:10B42000039601934FF480530A9380230693E368B5 -:10B43000059604932023099363690796029308965F -:10B440000B96FAF7F7FD01A9206BFAF7D5FD236BF0 -:10B450001A6842F001021A60226D918A89B241F0A5 -:10B46000400191825B689BB2236407E0236D4FF635 -:10B47000DF721A80DA6842F02002DA6015F00A0FF3 -:10B480002CD0606B28B3A36C002601934FF480533B -:10B490000A9380230693236902960493102303934F -:10B4A00005960796089609960B96FAF7C3FD606B0A -:10B4B00001A9FAF7A1FD636B1A6842F002021A6053 -:10B4C0005E605E60236D9A8A92B242F080029A8238 -:10B4D00004E0236DDA6842F08002DA60236D290708 -:10B4E0009A8992B242F400529A819A8A03D592B212 -:10B4F00042F0080203E022F008021204120C9A82C1 -:10B50000204604E0044B98423FF4BEAE00200CB04D -:10B51000BDE8F0810044004000380140781F002061 -:10B5200098520108E817002000080140241F00205D -:10B53000681900200010024010B50446204606F0AD -:10B5400049FC10F0FF0F07D10B4B0C4893F8541730 -:10B55000BDE81040FFF710BA204606F090FC022824 -:10B5600008D8054B064C83F8540700F041FE02F062 -:10B5700085FBE3E710BD00BFE41F0020436701081F -:10B580004E7101082DE9F04F844985B0054606F05B -:10B59000E9FB8349002828460CBF0124072406F054 -:10B5A000E1FB80490028284608BF022406F0DAFBA8 -:10B5B000002808BF0424E10740F1BE807A48FFF765 -:10B5C000DBF90020FFF710FB784F7948FFF7D4F93B -:10B5D0007848FFF7D1F97A79774B784803EB820303 -:10B5E0005969FFF7C9F93869002103F0B1FD002856 -:10B5F0005CD13D460646D5F810800021404603F058 -:10B60000A7FD00284ED101366D483146D5F814B05B -:10B61000D5F818A0D5F81C90FFF7AEF940460021E8 -:10B6200003F0A0FD10B16748FFF7A6F96946404650 -:10B63000FAF739FA01466448FFF79EF958460021A7 -:10B6400003F090FD10B15F48FFF796F96946584640 -:10B65000FAF729FA01465C48FFF78EF950460021B7 -:10B6600003F080FD10B15748FFF786F96946504650 -:10B67000FAF719FA01465448FFF77EF948460021C7 -:10B6800003F070FD10B14F48FFF776F96946484660 -:10B69000FAF709FA01464D48FFF76EF90C2E05F14D -:10B6A0001005A8D14A48711CFFF766F94948FFF711 -:10B6B00063F9494DD7F8088055F8041F19B1474878 -:10B6C000FFF75AF9F8E70D46454B53F8256056B198 -:10B6D0000123AB4013EA080F03D042483146FFF77D -:10B6E0004BF90135F0E74048FFF746F931467B1842 -:10B6F00093F8103104AA13443C4A8A5C01310829AA -:10B7000003F8102CF3D10023694639488DF808302E -:10B71000FFF732F93748FFF72FF93748FFF74AF9B3 -:10B720003648FFF729F93448FFF772FC3448FFF731 -:10B7300023F9402001F0EAFAA2071AD53148FFF7B1 -:10B740001BF93148FFF718F92B48FFF7F5FE2F4892 -:10B75000FFF712F92848FAF7E1FF2D48FFF70CF937 -:10B760002548FAF741FF2648FFF706F9802001F047 -:10B77000CDFA63070FD52748FFF7FEF82648FFF7F5 -:10B78000FBF81D48FCF7F4FE1D48FFF7F5F84FF4F1 -:10B79000807001F0BBFA05B0BDE8F08F816B010845 -:10B7A0007F760108886B01088E6B0108E41F00207A -:10B7B0009C6B0108AE6B010898520108BA6B010836 -:10B7C000C56B01081D7101082D6301084569010859 -:10B7D000CD6B0108DF6B010808530108EF6B01080E -:10B7E0000C530108FD6B01080A6C0108F66D010895 -:10B7F000166C01081F6C01084E7101082B6C0108C2 -:10B8000055700108396C01084C6C01085A6C01082C -:10B81000646C0108736C0108846C01082DE9F04F19 -:10B8200087B0984682460F4616469DF84040FDF781 -:10B8300026FB0DF1080E0546034600F1100C1868B2 -:10B840005968724603C2083363459646F7D12B7B8D -:10B850000BB903960496504602A9FDF7DFF9054699 -:10B8600040B14368586830B1504602A92A4601F0F9 -:10B87000A7FCF4E733E0AB6895F800B093F80090CC -:10B88000B9F1040F2BD8DFE809F003062A0F1100E5 -:10B890000094144801E01448009439463246434667 -:10B8A000FFF7DCFC04460BE0002000E001203946F5 -:10B8B00023463246FDF736FA41460446F6F798FE2F -:10B8C00064B10A4B84F8049003EB8B03C3F8004384 -:10B8D0006B6820465C605146FDF714FA204607B0BD -:10B8E000BDE8F08F0038014000440040E817002018 -:10B8F000F7B5274C274DE369284643F48043E361BD -:10B90000236901A943F48043236118238DF806308D -:10B910004FF42043ADF8043003238DF80730F7F7D8 -:10B92000FDFB04234FF480460DEB030128468DF800 -:10B9300006304FF48057ADF80460F7F7EFFB1023A3 -:10B94000284601A98DF80630ADF80470F7F7E6FB3C -:10B950002F612369304633432361FAF7B5FA0E4B62 -:10B960001A8802F4415242F4457242F003021A80EE -:10B970009A8B22F400621204120C9A8307221A8214 -:10B980001A8892B242F040021A8003B0F0BD00BFA4 -:10B9900000100240000C01400038004008B500F0E3 -:10B9A00027FC02F06BF9BDE808400F2014210122AA -:10B9B000FAF7CABC2DE9F3412D4B1B78042B50D16B -:10B9C0004020FAF7A7FD044670B12046F6F715FEB1 -:10B9D00018B90A20F6F7D9FDF7E7264B20461B6871 -:10B9E0001969F6F70FFE0BE0224B21461B68009009 -:10B9F0001A6940200323FFF711FF0446002830D0C6 -:10BA00001D4D286841798B0703D441F00201F6F7F8 -:10BA1000EFFD1A4B08221A6110221A612868F6F706 -:10BA2000FBFD58B1144B154E082718687761F6F7DF -:10BA3000EEFD01462046F6F701FE37612046F6F797 -:10BA4000EBFD0028EAD00D4E102777612046D5F88F -:10BA50000080F6F7DCFD01464046F6F7EFFD376162 -:10BA6000DCE7074802B0BDE8F041FAF745BD00BF8A -:10BA70008404002080040020A4040020000C014065 -:10BA80000B6E01082DE9F743124C814604F198082A -:10BA900094F84A60C6B9D9F8042000250095012021 -:10BAA00029460323FFF7BAFE074620B97EB94FF4B3 -:10BAB00096420126F1E7204629464C2206F049F934 -:10BAC0000123276084F84A304C344445E0D103B068 -:10BAD000BDE8F083200F0020F7B5524B524C236095 -:10BAE000FFF708FB0120FDF76BFA002800F08480C7 -:10BAF0004E4BFF2118461622256806F02AF900222F -:10BB000002704B4A0121126803469707817504D5DC -:10BB100041700321817502218170560704D5997DFA -:10BB2000481C98750320585412F00A0F0CD09A7DC7 -:10BB300004219954511CC9B205205854D11C023219 -:10BB40009975D2B2062199543A4FBA68900604D535 -:10BB5000997D481C987507205854110608D5997D81 -:10BB600009205854881C01319875C9B20A205854CC -:10BB70007979082901D00E2904D1997D481C98753E -:10BB80000B205854997D4FF00C0E481CC0B212F097 -:10BB9000040F264E987503F801E003D00231B17509 -:10BBA00010213154997D97F84571481CC0B24FF06F -:10BBB000120E002F0CBF002702F001071B4E9875D4 -:10BBC00003F801E01FB10231B17513213154997DA1 -:10BBD0001427481CC0B298755F549305134E03D5C3 -:10BBE00002311523B175335413480021982206F011 -:10BBF000B0F82846FFF746FF0220FDF7E1F970B1E3 -:10BC00000220FAF787FC2568084C0146A06130B98C -:10BC10000090AA6802200323FFF700FEA06103B092 -:10BC2000F0BD00BF10210020B80F0020F81A00203E -:10BC300084090020E41F0020200F0020A94B2DE9DB -:10BC4000F7431B78002B00F08181F7F737F8A64EF9 -:10BC500005463378834200F07981A44C23681B7831 -:10BC6000002800F0F08063BB0420FAF753FCA04FDB -:10BC700001463860DFF8848290B143794FF4165161 -:10BC800088F81C308368C8F82030F6F7BBFC3868A9 -:10BC90000221F6F7ADFC38680421FDF733F810E017 -:10BCA000944B04201B684FF416529B780093022398 -:10BCB000FFF7B4FD4379386088F81C308368C8F812 -:10BCC000203023681F78012F34D10420FAF722FC9A -:10BCD000DFF844820146C8F80000DFF82092A0B1E6 -:10BCE00043794FF4964189F824308368C9F82830A5 -:10BCF000F6F788FCD8F800003946F6F779FCD8F852 -:10BD000000000421FCF7FEFF14E000903B460420F5 -:10BD10004FF49642FFF782FD4379C8F8000089F896 -:10BD200024308368C9F828300379033B012B9CBF7A -:10BD3000714B1F7023681F78022F41D10420FAF73E -:10BD4000E9FB6E4C0146E06288B143794FF49641BD -:10BD500084F8303083686363F6F754FCE06A394650 -:10BD6000F6F746FCE06A0421FCF7CCFF0CE00090FB -:10BD70003B4604204FF49642FFF750FD4379E062C2 -:10BD800084F8303083686363E76A5D4C94F84A3026 -:10BD9000022B09D094F89620022A00F0D5801BB11E -:10BDA0004C34002A18BF0024564B1C6044B1204676 -:10BDB00000214C2205F0CDFF0223276084F84A3091 -:10BDC000F6F7CEFF002800F0BD804F4F3B78002BE8 -:10BDD00040F0B8800820FAF79DFB4C4C01462060EB -:10BDE00090B1464B42794FF4614183F83820826824 -:10BDF000DA63F6F707FC20680821F6F7F9FB2068FC -:10BE00000821FCF77FFF9DE0414B08201B684FF4A1 -:10BE100061429B7800930346FFF700FD206040B12C -:10BE2000012342793B70354B83F838208268DA630E -:10BE300088E0384B1B78002B00F0848004233B7093 -:10BE4000FFF74AFE7EE083B9294FDFF8B0803868FB -:10BE500098F81C10F6F7CCFB3868D8F82010F6F7E5 -:10BE6000D1FB38680421FCF71BFF23681B78012BEA -:10BE700010D1294FDFF88480386898F82410F6F73D -:10BE8000B7FB3868D8F82810F6F7BCFB38680421EF -:10BE9000FCF706FF23681B78022B0DD1174CE06AD4 -:10BEA00094F83010F6F7A4FBE06A616BF6F7AAFB92 -:10BEB000E06A0421FCF7F4FEF6F752FF002841D0B7 -:10BEC000114F3B7813F0FB0F3CD0124B0F4C1B78FB -:10BED00023B320680821FCF7E3FE04233B70FFF73F -:10BEE000FBFD2DE0E00C0020E10C0020E40C002024 -:10BEF000E80C00200C0D0020BF0D0020F81A0020D7 -:10BF0000200F0020940D0020A40D0020A80D00207B -:10BF1000680800205E080020800D0020DFF83480D3 -:10BF2000206898F83810F6F763FB2068D8F83C10C2 -:10BF3000F6F768FB20680821FCF7B2FE04233B708B -:10BF400000232360357001E04C342DE703B0BDE8D9 -:10BF5000F08300BFF81A002037B53D490B7813F085 -:10BF6000010F03F0040268D0002A6FD1980764D44F -:10BF700043F004030B70374B1A88374B1A80374B4A -:10BF80009A681C4612F4806F05D00420FCF7F8FF75 -:10BF900008B1FCF795FEA3681B0357D58020FCF77A -:10BFA000EFFF08B1FCF78CFE2D4D2B78012B4DD106 -:10BFB0008020FAF7AFFA2B4C0146206090B142790D -:10BFC000294B4FF4E1311A708268284B1A60F6F75A -:10BFD00019FB20680221F6F70BFB20688021FCF793 -:10BFE00091FE0EE000904FF4E13280200223FFF733 -:10BFF00015FC206028B142791B4B1A7082681B4BDC -:10C000001A6023680BB92B7020E0194B194C1B6880 -:10C010000021236404F14C00022314222B7061647C -:10C02000A16405F096FE04F16C03236604F1B803E5 -:10C03000636604F58273A36608E03AB90220FF2123 -:10C04000012203B0BDE83040FAF77EB903B030BD3D -:10C0500096270020180C0020280E0020E41F002046 -:10C060006E080020D01F0020D41F0020D81F002001 -:10C07000E01F0020F81A002013B500222A211C20FE -:10C08000FDF766F90E2102221C20FDF761F90F2150 -:10C0900003221C20FDF75CF92B2112221C20FDF746 -:10C0A00057F9164B02249A69154842F004029A6126 -:10C0B0002023ADF8043004230DEB03018DF8063086 -:10C0C0008DF80740F7F72AF822462C211C20FDF7AF -:10C0D0003FF92D2101221C20FDF73AF92E210022E3 -:10C0E0001C20FDF735F92A2105221C20FDF730F927 -:10C0F000044B4FF480721A8002B010BD0010024051 -:10C10000000801402400002010B5184C23681BB122 -:10C11000FDF700F9002323606B2180226820FDF7E2 -:10C1200017F96420F6F731FA192100226820FDF78B -:10C130000FF96B2103226820FDF70AF9372102224B -:10C140006820FDF705F90A4B1A211A786820FDF7D7 -:10C15000FFF81B2118226820FDF7FAF8BDE810400F -:10C1600068201C211022FDF7F3B800BFA4010020B5 -:10C170001500002010B50A4C23681BB1FDF7CAF862 -:10C1800000232360074B1B7813B1012B03D010BD94 -:10C190004FF4006201E04FF48052034B1A8010BD4F -:10C1A000A4010020A9010020240000200E4B1A78D1 -:10C1B000552A16D15A88B2F5EF6F12D11A79BE2AD4 -:10C1C0000FD193F874270020EF2A0CD113F8012B1C -:10C1D0005040064A9342F9D1D0F1010038BF002007 -:10C1E000704700207047704700F8010878FF010889 -:10C1F0004A4B55222DE9F3411A704FF4EF625A80F1 -:10C20000BE221A71EF2283F87427002283F8752763 -:10C2100011461E46B35C0132B2F5EF6F81EA0301AD -:10C22000F8D13E4B3E4A83F875173E4B04275A60BF -:10C2300002F188325A600020013F17F0FF075DD0FD -:10C24000384B3422384CDA60C4F309037BB133191C -:10C2500003F17843A3F5FC33D3F800804FF400508A -:10C2600000230193F9F786FE0428E5D11BE04FF483 -:10C270003020F9F77FFE0428DED12A4D4FF430201C -:10C280002B6943F002032B616C612B6943F040037F -:10C290002B61F9F76FFE2A6941F6FD7313400428FC -:10C2A0002B61D4D0C8E71F4D4FF400502B6943F0E9 -:10C2B00001032B611FFA88F32380F9F75BFE042842 -:10C2C00012D1A31C0193019B4FEA1848A3F80080E8 -:10C2D0004FF40050F9F74EFE2B6941F6FE721A40FA -:10C2E00004282A6106D0A7E72B6941F6FE721A409E -:10C2F0002A61A1E70D4B04349C42A5D1094B0428C7 -:10C300001A6942F080021A6102D1FFF74FFF10B99B -:10C310000A20F6F74BF902B0BDE8F081E41F0020D7 -:10C32000230167450020024000F8010878FF01085A -:10C330008A2802D08E2809D07047094B1B689B06BB -:10C340000DD5084B1B7853B9074A03E0054B1B7802 -:10C350002BB9064A064B1A60064B2D221A707047FD -:10C36000840900207C0D00204C0D0020200D0020B1 -:10C37000880D0020910D00207FB52B4B2B4C9A6926 -:10C38000206042F001029A61294D03881026ADF821 -:10C3900004302846022301A98DF807308DF8066085 -:10C3A000F6F7BCFE236828465B88ADF8043004230A -:10C3B0000DEB03018DF80630F6F7B0FE22680F2072 -:10C3C000137A03F003018900884003F0FC0303F1B2 -:10C3D000804303F580339D6825EA0000012505FAB6 -:10C3E00001F198609868014399605368114A02A866 -:10C3F0005361029300238DF80C308DF80E508DF8A8 -:10C400000D60FAF753FD23680B4A5B7A59B203F0CB -:10C410001F039D404909094B42F821501A68084BF7 -:10C420003C3A1A6004B070BD00100240180B0020A6 -:10C43000000C01400004014000E100E0E01F00208A -:10C44000100B00202DE9F74FA24E0C463778054619 -:10C450001146006891469B4622467B1C06F8043B29 -:10C46000FAF74EFDAB686868ADF8043018238DF814 -:10C47000063001A902238DF80730F6F74FFE2B7B1B -:10C480003F0106EB070A2C680C2B00F2F280DFE874 -:10C4900013F00D00F000F000F0004D00F000F0008F -:10C4A000F0008200F000F000F000B600238C8A4813 -:10C4B00023F001031B041B0C2384218CA288238BF3 -:10C4C000844223F073034FEA03434FEA134389B2D4 -:10C4D00092B243F0700314D000F50060844210D093 -:10C4E00000F5406084420CD000F58060844208D0A2 -:10C4F00000F58060844204D021F0020141F0030184 -:10C5000007E021F00E0122F4407241F0030142F4F1 -:10C510008072A2802383A4F834B02184238B23F07B -:10C5200008031B041B0C43F0080332E0238C6A4809 -:10C5300023F010031B041B0C2384218CA288238B63 -:10C54000844223F4E6434FEA03434FEA134389B29C -:10C5500092B243F4E04308D000F50060844204D076 -:10C5600021F0200141F0300107E021F0E00122F448 -:10C57000406241F0300142F48062A2802383A4F83B -:10C5800038B02184238B23F400631B041B0C43F479 -:10C59000006323836DE0238C4F4823F480731B04D6 -:10C5A0001B0C2384218CA288A38B844223F0730369 -:10C5B0004FEA03434FEA134389B292B243F0700348 -:10C5C00008D000F50060844204D021F4007141F4E9 -:10C5D000407107E021F4606122F4405241F440715F -:10C5E00042F48052A280A383A4F83CB02184A38BA0 -:10C5F00023F008031B041B0C43F0080338E0B4F8D5 -:10C6000020C0354A2CF4805C4FEA0C4C4FEA1C4C9D -:10C61000A4F820C0B4F820C0A388B4F81C802CF47F -:10C62000005C28F4E6484FEA08484FEA0C4C4FEA11 -:10C6300018484FEA1C4C94429BB248F4E0484CF432 -:10C64000405C03D002F50062944203D123F480439E -:10C6500043F48043A380A4F81C80A4F840B0A4F85D -:10C6600020C0A38B23F400631B041B0C43F4006362 -:10C67000A383AB7B43B1B4F844306FEA43436FEA22 -:10C6800053439BB2A4F8443023889BB243F0010388 -:10C6900023802B7B0C2B14D8DFE803F00713131334 -:10C6A0000A1313130D131313100004F1340307E0DE -:10C6B00004F1380304E004F13C0301E004F1400319 -:10C6C000F3515046AAF80890CAF8044003B0BDE8F8 -:10C6D000F08F00BF481C0020002C014040F2E933DD -:10C6E0000E4A1189890709D5908140F2E9330B4A36 -:10C6F0001189C9070DD59089C0B27047013B9BB223 -:10C70000002BEDD1064BFF201A88013292B21A801D -:10C710007047013B9BB2002BE9D1F3E700380040A2 -:10C72000560100200B4B07B59A690B4842F01002E6 -:10C730009A614FF40053ADF8043002238DF80730AE -:10C7400001A910238DF80630F6F7E8FC03B05DF878 -:10C7500004FB00BF00100240001001402DE9F04131 -:10C76000002407462546114B3946E65804EB0308DA -:10C77000304605F06BFB58B10D483146FEF7FCF82A -:10C7800040460021FAF73EF80A48FEF7F5F8013571 -:10C79000143440F604339C42E5D125B90648BDE87F -:10C7A000F041F9F7A9BEBDE8F08100BFC854010807 -:10C7B00087700108557001082B7001082DE9F74FAB -:10C7C000044605F007FB054620B1012819D123785E -:10C7D0002A2B16D15648F9F78FFE0024554B5648A0 -:10C7E000E618E158FEF7C8F830462946FAF70AF885 -:10C7F0005248F9F781FE143440F604339C42EDD1DF -:10C8000092E020463D2105F0D8FA002800F087800C -:10C81000034613F8012C202A01D1013BF9E7451CFE -:10C820002846C4EB030A05F02AFB83462846F6F7A0 -:10C830000FF90026054614237343DFF8F89053F8E8 -:10C84000097003EB0908384605F0C4FA03461A4696 -:10C8500020463946019305F0C5FA019B002855D1C1 -:10C860005FFA8AF29A4251D1D8F80C0002F088FAA5 -:10C870000146284602F08AFC002845D0D8F810006E -:10C8800002F07EFA0146284602F076FC00283BD0F2 -:10C89000B8F804309B064FF0140303FB0696B288E9 -:10C8A00058BF5D4614062946B36806D524484FF4A0 -:10C8B000E07490F8540704FB0033D00504D52148F8 -:10C8C0000A24007804FB003302F03F02042A0BD054 -:10C8D00004D8013A012A0CD819700AE0102A05D0B0 -:10C8E000202A05D0082A04D1198002E0196000E04E -:10C8F0001D6039461448FEF73FF83046002103B06A -:10C90000BDE8F04FF9F77EBF104803E001368D2EE9 -:10C9100091D10F4803B0BDE8F04FF9F7EDBD2046C7 -:10C9200003B0BDE8F04F19E703B0BDE8F08F00BFDA -:10C9300043700108C8540108877001085570010848 -:10C94000E41F00201C0E00205870010863700108CD -:10C950002B70010813B504460068FAF7D1FA236872 -:10C9600001A81A8892B242F001021A80637B002269 -:10C970008DF8043001238DF805308DF806208DF8F0 -:10C980000730FAF773FA02B010BD4B8810B5DC0619 -:10C9900007D52D4B14791B6853F824402B4B43F8D3 -:10C9A00020404B889B0607D5274B54791B6853F8CA -:10C9B0002440264B43F820404B881C070DD5244BC0 -:10C9C0000C781B78B3EB141F07DB1F4BD4781B6864 -:10C9D00053F824401D4B43F820404B889B070DD54E -:10C9E0001C4B0C781B78B3EB141F07DC164B5478E8 -:10C9F0001B6853F82440154B43F820404B88DC0754 -:10CA00000ED5154B0C781B7804F00F049C4207DC04 -:10CA10000D4B14781B6853F824400C4B43F820400E -:10CA20004B885B070ED50D4B09781B7801F00F0181 -:10CA3000994207DB044B92781B6853F82220034B82 -:10CA400043F8202010BD00BFAC040020DE0700200A -:10CA50007F1200207D1200207C1200207E12002018 -:10CA6000F0B5884C884A23689D8AADB2E9B211F0CE -:10CA7000010F32D0198821F400610904090C1980D2 -:10CA8000198889B241F480611980002111707F49B1 -:10CA900008787F49A8B1507818B97E480078FF28F7 -:10CAA0000FD1012050707C480078022804D11888EA -:10CAB00080B240F400601880097841F001011982C9 -:10CAC00002E1097801F0FE011982724B1B78FF2BFD -:10CAD00000F0FA80FF231370F6E08F073CD5BFF318 -:10CAE0005F8F6D490878C0B2012814D1674D2D7849 -:10CAF0008DB155787DB1198821F480610904090C44 -:10CB00001980BFF35F8F198B1988907089B241F437 -:10CB1000007119801BE0188BBFF35F8F0878022823 -:10CB20000BD15A48007840B1507830B1198821F4BF -:10CB300080610904090C1980C0E00978032906D135 -:10CB40005249097819B15178002940F0B780998885 -:10CB500089B241F48061B6E04E075BD50121917046 -:10CB60004A49097800293AD05178002937D04A49F2 -:10CB700010780978494D022919881ED921F480615D -:10CB80000904090C19801F8A2E68C1B2FFB240B295 -:10CB90003754188880B240F4007018808B1C1370D2 -:10CBA000236828681D8A013149B2EDB2455499883D -:10CBB00089B241F48061998027E089B241F4007123 -:10CBC00019801E8A2D68C1B2F6B240B22E541B8A5B -:10CBD000481C40B2DBB203312B54117015E0517880 -:10CBE00011B92F49097841B1198889B241F400710E -:10CBF000198013780133137007E0198889B241F462 -:10CC000080711980204B0121597021680B88D8054B -:10CC1000FCD459E001F0400101F0FF061E48F1B1DB -:10CC20001E49B3F810C00F6811785FFA8CFCCDB2C2 -:10CC30006E1C49B2F6B207F801C01670077876B2DA -:10CC4000F11C8F4205D1998821F480610904090CF7 -:10CC500099800378B34237D10235157034E0290644 -:10CC600032D511784DB26F1C1ED00E4E0131366890 -:10CC7000C9B2755D1170EDB21D82007849B288426B -:10CC800022D11BE0781700200C1D00206A1700201D -:10CC90006717002068170020741700207017002005 -:10CCA000691700206C170020134916700978C9B263 -:10CCB00019821249097809B9017829B9998821F4AA -:10CCC00080610904090C99800D4B92F900101878C5 -:10CCD0000C4B421C91420DD100225A709B7833B10B -:10CCE0002268938823F440731B041B0C9380064B2B -:10CCF00000221A70F0BD00BF681700206A170020DC -:10CD0000741700200C1D00207517002070B5064612 -:10CD100000240B4BE518AA8816420AD0E1580948AE -:10CD2000FDF72AFE28460021F9F76CFD0648F9F7C1 -:10CD3000E3FB143440F604339C42EAD170BD00BFDB -:10CD4000C854010883700108557001082DE9F04F9F -:10CD50001421012834BF0746012701FB07F06B4A65 -:10CD6000DFF8C4B113181058694ECBF800006948B9 -:10CD7000F469077018691D89B3F80A9020435C684C -:10CD800089B049EA0508F0610223C4F81080204602 -:10CD90008DF80E1003A9ADF80C808DF80F300192BC -:10CDA000F6F7BCF94FF0080AA3681D4203D10A2028 -:10CDB000F5F7E0FBF8E70A206561F5F7DBFB256195 -:10CDC0000A20F5F7D7FBBAF1010AEDD10A20C4F821 -:10CDD0001490F5F7CFFB0A206561F5F7CBFB0A202D -:10CDE0002561F5F7C7FB0223C4F8109020468DF8A3 -:10CDF0000F3003A91C238DF80E30ADF80C80F6F728 -:10CE00008DF9DBF80030444A9342336905D143F48D -:10CE1000001333614FF4001004E043F480033361E6 -:10CE20004FF48000F9F750F8DBF8004003A8A3881E -:10CE300023F440731B041B0CA38023889BB243F094 -:10CE400001032380A588F8F7F5FF25F03F05059934 -:10CE5000324A2D04B1FBF2F22D0C1543ADB2A58080 -:10CE60002388012523F001031B041B0C23802C4B7A -:10CE700003A8B1FBF3F34FF496714A439BB24FF40E -:10CE80007A71002B92FBF1F208BF0123013243F4C7 -:10CE9000004392B22284A38323881C4A9BB243F0AE -:10CEA00001032380238823F4816323F002031B04FE -:10CEB0001B0C23804FF480432381142303FB07279B -:10CEC0007B7B00248DF80C308DF80D408DF80E40E2 -:10CED0008DF80F50F9F7CAFF3B7B9DF80F208DF8B6 -:10CEE0000C308DF80D408DF80E401AB103A8F9F7FB -:10CEF000BDFF07E0590903F01F039D40094A203197 -:10CF000042F8215009B0BDE8F08F00BF5C54010821 -:10CF100000100240101D00200054004040420F004D -:10CF2000804F120000E100E07817002008B5054BA3 -:10CF30001A88013292B21A80034B1878FFF706FF65 -:10CF4000002008BD98170020101D002010B54000DB -:10CF5000204CC0B220702048204C01702048002195 -:10CF60000170012020701F4C23601F4C23601F4B59 -:10CF70001A701F4B1F4A107019701F490868194614 -:10CF800030B383889C0515D40388DB050DD447F2A4 -:10CF900030530488A40502D5013BFAD112E08BB1CD -:10CFA00003889BB243F48073038083889BB243F46D -:10CFB0004073838047F23053107810B1013BFBD1AE -:10CFC00000E013B9BDE81040B0E7087880F0010038 -:10CFD00010BD00BF67170020681700206A170020E7 -:10CFE00069170020701700206C17002074170020AC -:10CFF000761700207517002078170020244A13B5F3 -:10D0000013681446998A89B20191019911F4706FDD -:10D0100002D0204A01211170019A12F4E06F2AD047 -:10D020001A8B9A8822F480621204120C9A80019A58 -:10D03000910520D41A8892051DD41A88D0050FD5E1 -:10D040001A88D105FCD41A8892B242F400721A8070 -:10D050001A889205FCD4104B1878FFF777FE0AE087 -:10D060001A8892B242F400721A809A8822F44072AE -:10D070001204120C9A802268938A23F470631B04B2 -:10D080001B0C9382054B00221A7002B010BD00BF2A -:10D090007817002076170020101D0020751700203B -:10D0A0003F4A2DE9F84F916840F201130B4040F2DE -:10D0B00001118B4293460AD13A4B5A7893F8029069 -:10D0C0009A70B9EB020918BF4FF0010901E04FF067 -:10D0D00001094FF00008344B5FFA88F41B78A34233 -:10D0E0005CD9324B324E1B68324F23B93B685B89A7 -:10D0F00026F814304FE03A68072C94BF12F804A0C9 -:10D10000A246294851469847DBF808300546DB051A -:10D1100009D5B9F1000F06D0274B50461B682946A8 -:10D120001B68DB699847A5F2EE2240F2DC5392B20D -:10D130009A4288BF3B68DBF8082088BF5D8942F2CD -:10D14000010313402BB31D4B1978164B01F003025A -:10D1500002EB840293F8640003EB420295801A46C6 -:10D1600020B9032915D9012183F8641002EBC40307 -:10D17000D9889D8802EB44020D4419895B890D44CE -:10D180001D44ADB2A2F8665004232DB295FBF3F511 -:10D19000ADB226F8145008F101089CE7BDE8F88FFD -:10D1A000E41F0020101D00206704002070040020F0 -:10D1B000400400207408002078090020C40D0020DD -:10D1C0002DE9F74F2A4B157C9B68019003F040092D -:10D1D00003F4007C03F40058032D45D80C246C4361 -:10D1E000244B0198E618377A013538423AD0E35C8F -:10D1F0004BB1012B07D0032B04D0042B14BF042305 -:10D20000032300E00223DFF870A01F010AEB0704EC -:10D21000B9F1000F06D11AF807B0ABF1030BBBF15F -:10D22000010F1FD9BCF1000F06D0B8F1000F03D1D8 -:10D230001AF80770042F15D04F7B94F80CA007EA5A -:10D240000A0ABA450ED14F68606887420AD38F68D0 -:10D25000A068874206D8137094605660D160157438 -:10D26000104602E0EDB2B7E7002003B0BDE8F08F52 -:10D27000E41F00206400002084540108094B30B5ED -:10D280009D68094B05F480551868084B1C680023FD -:10D290000DB1828800E0A28805495A520233182B4A -:10D2A000F6D130BDE41F0020601E0020641E002067 -:10D2B000BC0F0020F8B50024204BE0B21F78B84224 -:10D2C0000CD21F4B33F810101E4B53F820301BB1FB -:10D2D0000B2801D8DB6898470134EDE71A4B9B68AF -:10D2E0005B032AD50025194E2B46EAB2BA4224D256 -:10D2F000726854689C4218D02046F5F7B4FEEFF3EC -:10D300001283502282F3128811494FF0280CA28C0C -:10D310000CFB001092B201324262A28ADBB292B2DE -:10D3200042F00102A28283F3118856F8043F0022E2 -:10D330001B6801351A802346D7E7F8BD98270020DF -:10D340005C27002018030020E41F002014030020A5 -:10D35000841E002010B50848F9F7CEF8074B1C686A -:10D360002046F5F74AF918B90A20F5F70EF9F7E75C -:10D37000034A044BDA6010BD8D700108101B0020B9 -:10D380000400FA0500ED00E008B50548F9F7B4F827 -:10D39000FBF725FAFEF72CFFBDE80840FFF7DABFE0 -:10D3A0009970010808B50748F9F7A6F8064A00235E -:10D3B00013701363054A1370FFF760FFBDE8084060 -:10D3C000FFF7C8BFAF700108901D00209027002014 -:10D3D00008B50448F9F790F8FEF70AFFBDE80840E1 -:10D3E000FFF7B8BFDB7001082DE9F04F002487B0CC -:10D3F000074604919246059380462546022DDFF8A4 -:10D4000088914FEA450607D104984379B9F9040099 -:10D410001B3343435B1148E0524B39F9151033F984 -:10D42000153003EB4101CAF10003994203DB51457A -:10D43000B4BF0B4653464C49059A31F906B0915F8B -:10D44000CBEB030303EB010BF5F7F0FA98B1474B75 -:10D4500058465B5D039301F093FC454901F098FD4C -:10D46000039B01461846F9F72BFE414901F0DCFC0D -:10D4700001F0A0FE83463F4B1988C80711D40498D9 -:10D480008A07037939F9060003F11B0300FB03F354 -:10D490004FEA231309D57A7C02FB0BFB03EB2B230A -:10D4A00003E0FB7903FB0BF31B11334A98F80AB036 -:10D4B000905F042290FBF2F0181A7B5D2F4A4343E1 -:10D4C000DB1101932E4B01351988A35801FB00FC99 -:10D4D0004FEAEC2C0BFB0C33DFF8B0C0B3F5001FA8 -:10D4E000A8BF4FF400136345B8BF6346A3504FEA8B -:10D4F000633C244B0909E258E050821A4FF6FF7052 -:10D50000B0FBF1F14A4303F10C0003F1180B215871 -:10D5100054F80B90921189442250CDF80890914410 -:10D5200098F8142044F80B1002FB09F10198091235 -:10D53000084403F1240260449053019803F12C0243 -:10D54000A050032D03F1380203F1440344F802C054 -:10D55000E15008F1010804F104047FF44FAF07B073 -:10D56000BDE8F08F92270020E00A0020C454010893 -:10D57000000020418C0900202C0C0020B80E002057 -:10D58000340C0020C41D00209A0900200000E0FF98 -:10D590002DE9F04F89B00793994B0692B3F9022019 -:10D5A000B3F90030002AB8BF5242002BB8BF5B422B -:10D5B00000249A42B8BF1A46039005922646A04618 -:10D5C00027460494A3462546DFF86092B9F8003058 -:10D5D00099075AD0022D58D0894BDDF818C0F25E59 -:10D5E000884BF35E03EB4202CCF100039A4203DB6B -:10D5F00063469A42B8BF1346834ADDF81CC036F929 -:10D6000002A03CF90620CAEB030303EB020AF5F77C -:10D610000DFA90B17D4B504615F803B001F0B0FB08 -:10D620007B4901F0B5FC01465846F9F749FD7849B8 -:10D6300001F0FAFB01F0BEFD824603986423C27933 -:10D640006FF0040102FB0AF292FBF3F2C37E01FBCE -:10D6500003FB5A4505DB03EB83039A42B4BF9346B1 -:10D660009B466C4A42F21071A35853448B42A8BFA8 -:10D670000B4669498B42B8BF0B460399A35091F8FA -:10D6800011A00AFB03F31B130493B9F8003003F055 -:10D690000302012A01D1022D3DD1594A5F49B75EEB -:10D6A000895F039A81EAE170A0EBE17012F805C08E -:10D6B0005B4AB0F5206F54F802801DDC022D15D0B6 -:10D6C0005020784390FBFCFC042091FBF0F1C1EB6F -:10D6D0000C0CE0445348B8F57A5FA8BF4FF47A5871 -:10D6E0008045ACBF42F80480105107E087EAE7703C -:10D6F000A0EBE7706428E3DD00211151484AA158EE -:10D700007D2291FBF2F8039A2A44927A02FB08F8F0 -:10D71000402298FBF2F89A0716D5022D14D0059BEB -:10D72000DDF814C0C3F5FA720CFB08F07B43DDF89A -:10D7300010C002FB0B3302FB0C024FF4FA7193FB97 -:10D74000F1F392FBF1F208E0DB0701D5022D02D1E3 -:10D7500042463B4601E0049A5B463049DFF8D0A0E0 -:10D76000715A4FF0040C0FFA81F915F80AA099FBD1 -:10D77000FCF00AFB00F06FF04F0A90FBFAF018443F -:10D78000294B019036F903A0F152CAEB090999FB24 -:10D79000FCF903F1140A03F1080C54F80C0054F8D6 -:10D7A0000A1044F80C90DFF88CC0014415F80CC046 -:10D7B000494402910CFB01F14FF0200C91FBFCF16C -:10D7C00044F80A000198C1EB0209A3F12C0C814432 -:10D7D00026F80C900135A3F1240C44F80C004942C2 -:10D7E000A3F11800032DA3F10C032250E15006F120 -:10D7F000020604F104047FF4E7AE09B0BDE8F08F3F -:10D800009A09002092270020E00A0020C454010851 -:10D8100000002041200E0020F0D8FFFF2C0C00203B -:10D82000B80E002080C1FFFF141E00208C090020CC -:10D83000DE0E0020E40E00202DE9F04F89B00793A2 -:10D840007A4B814618880491059201F095FA78493F -:10D8500001F0EAFA002403904F4625462646022EA0 -:10D86000DFF80CA20BD10499BAF904004B790A3302 -:10D87000584301F085FA6F4901F08AFB44E06E4B92 -:10D880003AF90520EB5E05991A444B429A4203DBB4 -:10D890000B469A42B8BF1346684AAA5E9B1A079A7B -:10D8A000505F184401F06CFA654901F071FB804645 -:10D8B000F5F7BCF828B1634B4146985DF9F700FCD9 -:10D8C0008046614B1A88D10705D54046D9F84410E7 -:10D8D00001F0AAFA18E004993AF905000B790192CF -:10D8E0001433584301F04CFA524901F051FB019AAC -:10D8F0008346930709D5D9F84810404601F094FAB9 -:10D900000146584601F088F98346504A505F01F0BD -:10D9100037FA4F4AD16801F087FA82465146584695 -:10D9200001F078F9396A804601F07EFADFF844B1F7 -:10D9300006900399404601F077FAF96A01F074FA0B -:10D9400054F80B1001F068F94249804601F00AFCD6 -:10D9500038B94046404901F023FC20B1DFF8F88097 -:10D9600001E0DFF8F0804BF80480DFF80CB150469E -:10D9700054F80B1001F04EF944F80BA0034603993C -:10D980004FF07E50029301F003FB029B01461846C4 -:10D9900001F04AFA0BF10C03E2580BF1180B54F8A2 -:10D9A0000B10824610460192029301F035F9514660 -:10D9B00001F032F9019A029B44F80B2044F803A0CD -:10D9C000264901F0E5FAB96B01F02EFA24498246A6 -:10D9D00001F0C8FB38B95046224901F0E1FB20B103 -:10D9E000DFF880A001E0DFF878A00698414601F05A -:10D9F00013F9514601F00EF904F010FC1A4BB0F582 -:10DA00007A7FA8BF4FF47A709842B8BF18460136A3 -:10DA1000164B032EE85204F1040405F1020507F148 -:10DA200004077FF41CAF09B0BDE8F08F340C002070 -:10DA3000BD3786350000484292270020E00A0020CA -:10DA400000002041C45401088C0900202C0C002047 -:10DA5000240B002000007AC300007A4300004040FD -:10DA6000000096C30000964318FCFFFFE81D00204D -:10DA70009A090020C40E0020341E00202DE9F04732 -:10DA8000704A86B013789146DFF8CC81C3B9012281 -:10DA9000D8F8001089F800206B4A1A445068884270 -:10DAA00003D00C33302BF7D1002202235372674B83 -:10DAB0006748C3F8C810F8F71FFD6648F8F71CFD63 -:10DAC000D8F80000F4F7A8FD002800F0B780624BFA -:10DAD0005E4C1868F4F79BFD0928014601D03F28E9 -:10DAE0004CD14FF0000A256B5C4F56462DB157487C -:10DAF00039682A4604F076F910B9BA4606B93E46A6 -:10DB0000574B0C379F42F1D3B6B13768DAF800E0D3 -:10DB10002B46F85C1EF80310814201D023630BE012 -:10DB20005A1C31B92D2B04D82020E0542263A15473 -:10DB300002E0E0541346ECE7236B0BB1564512D0DC -:10DB40004848F8F7D9FC564509D856F80C0BF8F7B1 -:10DB5000D3FCD8F800000921F4F770FDF3E73D4845 -:10DB6000F8F7CAFC0025236B9D42A9D2374BD8F8A1 -:10DB70000000595DF4F762FD0135F4E7236B2BB922 -:10DB8000042839D12046FFF70DFC57E00C2801D1BD -:10DB9000354890E70A2901D00D2947D13348F8F7D5 -:10DBA000ABFC226B0023A3542278284E232A16D0E4 -:10DBB00004932F4B03A80093284915220C230396A6 -:10DBC00004F061F9054638B1006804F003F901304A -:10DBD000AB683044984702E02648F8F78DFC1B48B4 -:10DBE0000021302204F0B5F80023236399F80030B7 -:10DBF000002B7FF462AF21E00C28C9D07F2903D12C -:10DC00005EE72F2B3FF65CAFA1F12002D2B25E2A75 -:10DC10003FF656AF13B920293FF452AF5A1CD8F83B -:10DC200000002263E154F4F709FD49E77F29E8D1B8 -:10DC3000013B00222363E2540F483FE706B0BDE8F2 -:10DC4000F08700BF9027002064000020901D002076 -:10DC5000E27001081A710108101B002060530108CE -:10DC60005C5401081F7101082471010855700108F6 -:10DC70008D5A00082F7101084B7101082DE9F04100 -:10DC8000FEF794FA10B90A20F4F790FC824C4FF496 -:10DC9000EF622046814904F053F894F854374FF46A -:10DCA000E072022B84BF002384F8543794F8543771 -:10DCB0007B4E02FB034303F5057393F8502033605A -:10DCC000022A84BF002283F8502093F85030754A0E -:10DCD00013700A2202FB0343734A03F25673136064 -:10DCE000A36842F201021A403AB944F208021A400B -:10DCF0001AB9694A43F400539360A368D90703D55E -:10DD00004FF40050F4F7D1FFA3685A0409D5082056 -:10DD1000F4F7CBFF4FF40050F4F7C7FF0120F4F7FE -:10DD2000C4FFA3681B0706D54FF40050F4F7BDFFEE -:10DD30000120F4F7BAFFA3689F040ED54FF400400A -:10DD4000F4F7B3FF4FF40060F4F7AFFF4FF4803007 -:10DD5000F4F7ABFF4020F4F7A8FFA3685D0603D5F6 -:10DD60004FF48030F4F7A1FFA368980408D503F4BA -:10DD70002063B3F5206F03D14FF40060F4F795FFF3 -:10DD80004A4D4B4B2F461D60FDF7B4F9494B05F149 -:10DD90001C0201201A60FBF772F801460120FAF715 -:10DDA0003DFF002849D00220FBF769F80146022018 -:10DDB000FAF734FF002840D02020FBF760F8014636 -:10DDC0002020FAF72BFFA368190601D5002834D0CC -:10DDD0001020FBF754F801461020FAF71FFFA36844 -:10DDE0001A0700D548B30420FBF749F80146042080 -:10DDF000FAF714FF30B90820FBF741F80146082074 -:10DE0000FAF70CFFA3685B0503D400231A461946F2 -:10DE100009E00028F9D110E079B90121C00708D440 -:10DE20000C33302B0BD024481844007A8507F5D5E5 -:10DE3000F2E70132D2B2022AF2D9FDF785F9F4F7FE -:10DE400071FB1E4D1E4B32681D601E4B101D18606D -:10DE500002F175010023A846CD5C55B901EB030E14 -:10DE60009EF802C09EF803E0F44502D2164B1D70E6 -:10DE700002E00433A02BEFD1144B15490B60154978 -:10DE800050330B601178144B012903D0022929D09B -:10DE9000124928E0124926E0E41F002000F801089A -:10DEA000200B00201C0E0020D00C0020F4200020AD -:10DEB00074080020B80F002064000020B420002067 -:10DEC000140E0020180E002048000020D82000204A -:10DED0003C0B0020E40C00209C00002091D50008A1 -:10DEE000E9D3000833491960334B02F5D9721A603F -:10DEF000F5F714F83568314B05F5D3721A60304BDD -:10DF000000229A802F4B304A304E136005F5B372D1 -:10DF10003260A3F1220272602E332D4A05F5D771CB -:10DF2000F36005F5D87311607361C6F80880376136 -:10DF3000B4F8F00000F020FFF061B4F8F20000F057 -:10DF40001BFF95F858303062337695F874301836E8 -:10DF5000737094F825312A1D33731E4BB5F8620196 -:10DF60001E601D4B1A601D4B05F160021A601C4BB0 -:10DF700005F164021A601B4B05F25D121A601A4B20 -:10DF8000C3F8008000F0FCFE0146184801F000F8DC -:10DF9000174900F049FF174B17491860E86D00F06A -:10DFA00043FF01464FF07C5000F0F2FF134B186026 -:10DFB000BDE8F08139D80008C40C0020DC1F002027 -:10DFC0002C040020DC200020A80B00205C1E002078 -:10DFD000DC0C0020DC0B00200C0B0020280C0020A7 -:10DFE000000A0020B40C0020BC0C0020000061449A -:10DFF0004C3D0F44C00C0020DB0F4940240C002096 -:10E0000001480249F4F7ECBF00080040FC1E002064 -:10E0100001480249F4F7E4BF00040040D41E002088 -:10E020004FF080400149F4F7DBBF00BFAC1E002079 -:10E0300001480249F4F7D4BF002C0140841E00209F -:10E0400001480249F4F7CCBF002C0140841E002097 -:10E0500038B5204CD4F8F0301D88ADB2AA0618D5DA -:10E06000D4F8CC201AB1988880B2904711E09B88F0 -:10E07000D4F8BC20D4F8B410DBB28B54D4F8BC2054 -:10E08000D4F8AC300132B2FBF3F103FB1123C4F836 -:10E09000BC302B061DD5D4F8C820D4F8C4100D4BC5 -:10E0A0008A4210D0D3F8B800D3F8F010805C013267 -:10E0B000C0B28880D3F8B010B2FBF1F001FB10229F -:10E0C000C3F8C82038BDD3F8F030DA6822F08002F7 -:10E0D000DA6038BD841E00200F4BD3F8442111882C -:10E0E000090618D5D3F81C11D3F8180181420ED0B7 -:10E0F000D3F80C01405C0131C0B29080D3F8042108 -:10E10000B1FBF2F002FB1011C3F81C117047D36889 -:10E1100023F08003D3607047841E00200C480D4B11 -:10E120004FF400525A60D0F828214FF6FE73116860 -:10E130000B401360D0F81821D0F81C319A4202D05D -:10E14000F430F8F7A3BD012380F83831704700BFE1 -:10E15000841E002000000240F7F71DBFF7F71BBF29 -:10E16000084A13689B020BD5074B00211970074919 -:10E170004FF6FE73086803400B604FF400135360C2 -:10E18000704700BF000002408A2700206C00024058 -:10E19000FEF734BFFEF732BFFEF762BCFEF760BC8D -:10E1A000074B1A685969490408D5520406D54FF43B -:10E1B00080425A61034B012283F84821704700BF17 -:10E1C00000040140841E002010B51B4B1A78510733 -:10E1D00031D51A4C22F004021A70A3685A050AD5E8 -:10E1E000FDF72CFD04200121FAF7D9FE18B104F542 -:10E1F0009670FDF747FCA3681B031CD5104B1A78DB -:10E20000012A0ED90F4C0122206821791A70F4F7E7 -:10E21000EFF92068A168F4F7F5F920688021FAF792 -:10E220003FFD80200121FAF7BAFE20B10648BDE883 -:10E230001040FDF727BC10BD96270020E41F0020EA -:10E240006E080020D01F00201021002070B5F3F7C9 -:10E250009FFE38B3144C237A0BB9A38070BD134DC5 -:10E260002E78C6F38000F3F7A5FE90B1104B46F070 -:10E2700002061A680F4B51892E70198051895980F6 -:10E2800052899A800C4AD2685288DA80E388013336 -:10E29000E380F3F769FE10B92B785B0702D4BDE881 -:10E2A000704091E770BD00BF2C040020962700202D -:10E2B0002804002040040020D01F00200F4B1A68C3 -:10E2C00042F001021A6059680D4A0A405A601A6801 -:10E2D00022F0847222F480321A601A6822F48022BA -:10E2E0001A605A6822F4FE025A604FF41F029A60C4 -:10E2F000044B4FF000629A60704700BF001002406C -:10E300000000FFF800ED00E0024B1A6801321A60CD -:10E31000704700BFE01F002008B5084BB3F8D800D5 -:10E32000074B1A780023D9B2914204D2054921F84B -:10E3300013000133F7E7FEF7BDFFFEE7E01F002003 -:10E34000982700205C27002081F0004102E000BFF8 -:10E3500083F0004330B54FEA41044FEA430594EAA5 -:10E36000050F08BF90EA020F1FBF54EA000C55EAE0 -:10E37000020C7FEA645C7FEA655C00F0E2804FEAB1 -:10E380005454D4EB5555B8BF6D420CDD2C4480EA93 -:10E39000020281EA030382EA000083EA010180EAC3 -:10E3A000020281EA0303362D88BF30BD11F0004F11 -:10E3B0004FEA01314FF4801C4CEA113102D0404247 -:10E3C00061EB410113F0004F4FEA03334CEA133382 -:10E3D00002D0524263EB430394EA050F00F0A7809A -:10E3E000A4F10104D5F1200E0DDB02FA0EFC22FA95 -:10E3F00005F2801841F1000103FA0EF2801843FA89 -:10E4000005F359410EE0A5F120050EF1200E012A79 -:10E4100003FA0EFC28BF4CF0020C43FA05F3C018B7 -:10E4200051EBE37101F0004507D54FF0000EDCF130 -:10E43000000C7EEB00006EEB0101B1F5801F1BD3D9 -:10E44000B1F5001F0CD349085FEA30004FEA3C0CDD -:10E4500004F101044FEA445212F5800F80F09A80D3 -:10E46000BCF1004F08BF5FEA500C50F1000041EBD7 -:10E47000045141EA050130BD5FEA4C0C404141EBDB -:10E48000010111F4801FA4F10104E9D191F0000F02 -:10E4900004BF01460020B1FA81F308BF2033A3F185 -:10E4A0000B03B3F120020CDA0C3208DD02F1140C7C -:10E4B000C2F10C0201FA0CF021FA02F10CE002F1B7 -:10E4C0001402D8BFC2F1200C01FA02F120FA0CFCB0 -:10E4D000DCBF41EA0C019040E41AA2BF01EB0451F9 -:10E4E000294330BD6FEA04041F3C1CDA0C340EDCF7 -:10E4F00004F11404C4F1200220FA04F001FA02F33A -:10E5000040EA030021FA04F345EA030130BDC4F1F7 -:10E510000C04C4F1200220FA02F001FA04F340EAEC -:10E520000300294630BD21FA04F0294630BD94F09D -:10E53000000F83F4801306BF81F480110134013D84 -:10E540004EE77FEA645C18BF7FEA655C29D094EAF5 -:10E55000050F08BF90EA020F05D054EA000C04BF73 -:10E560001946104630BD91EA030F1EBF002100205E -:10E5700030BD5FEA545C05D14000494128BF41F0FD -:10E58000004130BD14F580043CBF01F5801130BD61 -:10E5900001F0004545F0FE4141F470014FF00000EC -:10E5A00030BD7FEA645C1ABF194610467FEA655C9D -:10E5B0001CBF0B46024650EA013406BF52EA03353F -:10E5C00091EA030F41F4002130BD00BF90F0000F2D -:10E5D00004BF0021704730B54FF4806404F1320469 -:10E5E0004FF000054FF0000150E700BF90F0000F22 -:10E5F00004BF0021704730B54FF4806404F1320449 -:10E6000010F0004548BF40424FF000013EE700BF18 -:10E6100042004FEAE2014FEA31014FEA02701FBFA8 -:10E6200012F07F4393F07F4F81F06051704792F07A -:10E63000000F14BF93F07F4F704730B54FF46074F4 -:10E6400001F0004521F0004120E700BF50EA01023F -:10E6500008BF704730B54FF000050AE050EA0102EC -:10E6600008BF704730B511F0004502D5404261EB5C -:10E6700041014FF4806404F132045FEA915C3FF49D -:10E68000DCAE4FF003025FEADC0C18BF03325FEA36 -:10E69000DC0C18BF033202EBDC02C2F1200300FAEB -:10E6A00003FC20FA02F001FA03FE40EA0E0021FA10 -:10E6B00002F11444C1E600BF70B54FF0FF0C4CF4FA -:10E6C000E06C1CEA11541DBF1CEA135594EA0C0FB0 -:10E6D00095EA0C0F00F0DEF82C4481EA030621EAEB -:10E6E0004C5123EA4C5350EA013518BF52EA033526 -:10E6F00041F4801143F4801338D0A0FB02CE4FF0D8 -:10E700000005E1FB02E506F00042E0FB03E54FF007 -:10E710000006E1FB03569CF0000F18BF4EF0010EFF -:10E72000A4F1FF04B6F5007F64F5407404D25FEAFB -:10E730004E0E6D4146EB060642EAC62141EA5551AE -:10E740004FEAC52040EA5E504FEACE2EB4F1FD0CF0 -:10E7500088BFBCF5E06F1ED8BEF1004F08BF5FEA6E -:10E76000500E50F1000041EB045170BD06F0004620 -:10E7700046EA010140EA020081EA0301B4EB5C04CD -:10E78000C2BFD4EB0C0541EA045170BD41F48011C5 -:10E790004FF0000E013C00F3AB8014F1360FDEBFEA -:10E7A000002001F0004170BDC4F10004203C35DAC6 -:10E7B0000C341BDC04F11404C4F1200500FA05F349 -:10E7C00020FA04F001FA05F240EA020001F00042EA -:10E7D00021F0004110EBD37021FA04F642EB060160 -:10E7E0005EEA430E08BF20EAD37070BDC4F10C048A -:10E7F000C4F1200500FA04F320FA05F001FA04F24E -:10E8000040EA020001F0004110EBD37041F1000139 -:10E810005EEA430E08BF20EAD37070BDC4F1200544 -:10E8200000FA05F24EEA020E20FA04F301FA05F2AC -:10E8300043EA020321FA04F001F0004121FA04F254 -:10E8400020EA020000EBD3705EEA430E08BF20EA24 -:10E85000D37070BD94F0000F0FD101F0004640005E -:10E8600041EB010111F4801F08BF013CF7D041EAE0 -:10E87000060195F0000F18BF704703F000465200E4 -:10E8800043EB030313F4801F08BF013DF7D043EAB5 -:10E890000603704794EA0C0F0CEA135518BF95EA6B -:10E8A0000C0F0CD050EA410618BF52EA4306D1D1F2 -:10E8B00081EA030101F000414FF0000070BD50EA11 -:10E8C000410606BF1046194652EA430619D094EA9B -:10E8D0000C0F02D150EA013613D195EA0C0F05D185 -:10E8E00052EA03361CBF104619460AD181EA0301D9 -:10E8F00001F0004141F0FE4141F470014FF0000091 -:10E9000070BD41F0FE4141F4780170BD70B54FF02B -:10E91000FF0C4CF4E06C1CEA11541DBF1CEA1355AB -:10E9200094EA0C0F95EA0C0F00F0A7F8A4EB05048D -:10E9300081EA030E52EA03354FEA013100F0888084 -:10E940004FEA03334FF0805545EA131343EA12634D -:10E950004FEA022245EA111545EA10654FEA002602 -:10E960000EF000419D4208BF964244F1FD0404F5BB -:10E97000407402D25B084FEA3202B61A65EB030517 -:10E980005B084FEA32024FF480104FF4002CB6EBD4 -:10E99000020E75EB030E22BFB61A754640EA0C0054 -:10E9A0005B084FEA3202B6EB020E75EB030E22BF94 -:10E9B000B61A754640EA5C005B084FEA3202B6EBD5 -:10E9C000020E75EB030E22BFB61A754640EA9C0094 -:10E9D0005B084FEA3202B6EB020E75EB030E22BF64 -:10E9E000B61A754640EADC0055EA060E18D04FEA22 -:10E9F000051545EA16754FEA06164FEAC30343EAC2 -:10EA000052734FEAC2025FEA1C1CC0D111F4801F8E -:10EA10000BD141EA00014FF000004FF0004CB6E787 -:10EA200011F4801F04BF01430020B4F1FD0C88BF26 -:10EA3000BCF5E06F3FF6AFAEB5EB030C04BFB6EB31 -:10EA4000020C5FEA500C50F1000041EB045170BD24 -:10EA50000EF0004E4EEA113114EB5C04C2BFD4EB51 -:10EA60000C0541EA045170BD41F480114FF0000ED5 -:10EA7000013C90E645EA060E8DE60CEA135594EA51 -:10EA80000C0F08BF95EA0C0F3FF43BAF94EA0C0F54 -:10EA90000AD150EA01347FF434AF95EA0C0F7FF4C9 -:10EAA00025AF104619462CE795EA0C0F06D152EA1D -:10EAB00003353FF4FDAE1046194622E750EA410601 -:10EAC00018BF52EA43067FF4C5AE50EA41047FF412 -:10EAD0000DAF52EA43057FF4EBAE12E74FEA410275 -:10EAE00012F5001215D211D56FF47873B3EB6252A0 -:10EAF00012D94FEAC12343F0004343EA505311F0C7 -:10EB0000004F23FA02F018BF404270474FF0000058 -:10EB1000704750EA013005D111F0004008BF6FF096 -:10EB2000004070474FF00000704700BF4A0011D20C -:10EB300012F5001211D20DD56FF47873B3EB625257 -:10EB40000ED44FEAC12343F0004343EA505323FA63 -:10EB500002F070474FF00000704750EA013002D1D8 -:10EB60004FF0FF3070474FF0000070474FEA41020E -:10EB7000B2F1E04324BFB3F5001CDCF1FE5C0DD91B -:10EB800001F0004C4FEAC0024CEA5070B2F1004F65 -:10EB900040EB830008BF20F00100704711F0804F68 -:10EBA00021D113F13872BCBF01F00040704741F42D -:10EBB00080114FEA5252C2F11802C2F1200C10FA31 -:10EBC0000CF320FA02F018BF40F001004FEAC12315 -:10EBD0004FEAD32303FA0CFC40EA0C0023FA02F3B9 -:10EBE0004FEA4303CCE77FEA625307D150EA01338F -:10EBF0001EBF4FF0FE4040F44000704701F000405F -:10EC000040F0FE4040F40000704700BF80F000403C -:10EC100002E000BF81F0004142001FBF5FEA4103F4 -:10EC200092EA030F7FEA226C7FEA236C6AD04FEAF4 -:10EC30001262D2EB1363C1BFD21841404840414039 -:10EC4000B8BF5B42192B88BF704710F0004F40F4EB -:10EC5000000020F07F4018BF404211F0004F41F407 -:10EC6000000121F07F4118BF494292EA030F3FD0D3 -:10EC7000A2F1010241FA03FC10EB0C00C3F12003E6 -:10EC800001FA03F100F0004302D5494260EB400075 -:10EC9000B0F5000F13D3B0F1807F06D340084FEAE0 -:10ECA000310102F10102FE2A51D2B1F1004F40EBD5 -:10ECB000C25008BF20F0010040EA0300704749003D -:10ECC00040EB000010F4000FA2F10102EDD1B0FA08 -:10ECD00080FCACF1080CB2EB0C0200FA0CF0AABFFD -:10ECE00000EBC25052421843BCBFD040184370479B -:10ECF00092F0000F81F4000106BF80F400000132A1 -:10ED0000013BB5E74FEA41037FEA226C18BF7FEA77 -:10ED1000236C21D092EA030F04D092F0000F08BFB9 -:10ED20000846704790EA010F1CBF0020704712F0A0 -:10ED30007F4F04D1400028BF40F00040704712F1DF -:10ED400000723CBF00F50000704700F0004343F044 -:10ED5000FE4040F4000070477FEA226216BF08467A -:10ED60007FEA23630146420206BF5FEA412390EA3D -:10ED7000010F40F4800070474FF0000304E000BF33 -:10ED800010F0004348BF40425FEA000C08BF7047E4 -:10ED900043F0964301464FF000001CE050EA0102A8 -:10EDA00008BF70474FF000030AE000BF50EA0102BD -:10EDB00008BF704711F0004302D5404261EB4101AA -:10EDC0005FEA010C02BF84460146002043F0B643CF -:10EDD00008BFA3F18053A3F50003BCFA8CF2083AF4 -:10EDE000A3EBC25310DB01FA02FC634400FA02FCFD -:10EDF000C2F12002BCF1004F20FA02F243EB020004 -:10EE000008BF20F00100704702F1200201FA02FC65 -:10EE1000C2F1200250EA4C0021FA02F243EB020058 -:10EE200008BF20EADC7070474FF0FF0C1CEAD0529C -:10EE30001EBF1CEAD15392EA0C0F93EA0C0F6FD05D -:10EE40001A4480EA010C400218BF5FEA41211ED03B -:10EE50004FF0006343EA501043EA5111A0FB013127 -:10EE60000CF00040B1F5000F3EBF490041EAD371FC -:10EE70005B0040EA010062F17F02FD2A1DD8B3F178 -:10EE8000004F40EBC25008BF20F00100704790F0E7 -:10EE9000000F0CF0004C08BF49024CEA502040EA39 -:10EEA00051207F3AC2BFD2F1FF0340EAC2507047FF -:10EEB00040F400004FF00003013A5DDC12F1190F3D -:10EEC000DCBF00F000407047C2F10002410021FAAF -:10EED00002F1C2F1200200FA02FC5FEA310040F1C7 -:10EEE000000053EA4C0308BF20EADC70704792F040 -:10EEF000000F00F0004C02BF400010F4000F013A78 -:10EF0000F9D040EA0C0093F0000F01F0004C02BF72 -:10EF1000490011F4000F013BF9D041EA0C018FE7E1 -:10EF20000CEAD15392EA0C0F18BF93EA0C0F0AD0E7 -:10EF300030F0004C18BF31F0004CD8D180EA01000D -:10EF400000F00040704790F0000F17BF90F0004FA6 -:10EF5000084691F0000F91F0004F14D092EA0C0F88 -:10EF600001D142020FD193EA0C0F03D14B0218BF1B -:10EF7000084608D180EA010000F0004040F0FE4061 -:10EF800040F40000704740F0FE4040F440007047FD -:10EF90004FF0FF0C1CEAD0521EBF1CEAD15392EA7C -:10EFA0000C0F93EA0C0F69D0A2EB030280EA010C6C -:10EFB00049024FEA402037D04FF0805343EA111105 -:10EFC00043EA10130CF000408B4238BF5B0042F163 -:10EFD0007D024FF4000C8B4224BF5B1A40EA0C0008 -:10EFE000B3EB510F24BFA3EB510340EA5C00B3EB3A -:10EFF000910F24BFA3EB910340EA9C00B3EBD10F28 -:10F0000024BFA3EBD10340EADC001B0118BF5FEA79 -:10F010001C1CE0D1FD2A3FF650AF8B4240EBC250A2 -:10F0200008BF20F0010070470CF0004C4CEA502063 -:10F030007F32C2BFD2F1FF0340EAC250704740F4B2 -:10F0400000004FF00003013A37E792F0000F00F0A4 -:10F05000004C02BF400010F4000F013AF9D040EA22 -:10F060000C0093F0000F01F0004C02BF490011F4B6 -:10F07000000F013BF9D041EA0C0195E70CEAD153AE -:10F0800092EA0C0F08D142027FF47DAF93EA0C0F95 -:10F090007FF470AF084676E793EA0C0F04D14B0279 -:10F0A0003FF44CAF08466EE730F0004C18BF31F02B -:10F0B000004CCAD130F000427FF45CAF31F0004325 -:10F0C0007FF43CAF5FE700BF4FF0FF3C06E000BFBE -:10F0D0004FF0010C02E000BF4FF0010C4DF804CDE1 -:10F0E0004FEA40024FEA41037FEA226C18BF7FEAF1 -:10F0F000236C11D001B052EA530C18BF90EA010FF3 -:10F1000058BFB2EB030088BFC81738BF6FEAE17081 -:10F1100018BF40F0010070477FEA226C02D15FEA1D -:10F12000402C05D17FEA236CE4D15FEA412CE1D089 -:10F130005DF8040B704700BF844608466146FFE750 -:10F140000FB5FFF7C9FF002848BF10F1000F0FBD32 -:10F150004DF808EDFFF7F4FF0CBF012000205DF82B -:10F1600008FB00BF4DF808EDFFF7EAFF34BF0120B0 -:10F1700000205DF808FB00BF4DF808EDFFF7E0FF49 -:10F1800094BF012000205DF808FB00BF4DF808ED9A -:10F19000FFF7D2FF94BF012000205DF808FB00BFFD -:10F1A0004DF808EDFFF7C8FF34BF012000205DF8DF -:10F1B00008FB00BF4FEA4002B2F1FE4F0FD34FF001 -:10F1C0009E03B3EB12620DD94FEA002343F00043D4 -:10F1D00010F0004F23FA02F018BF404270474FF082 -:10F1E0000000704712F1610F01D1420205D110F009 -:10F1F000004008BF6FF0004070474FF000007047BC -:10F2000042000ED2B2F1FE4F0BD34FF09E03B3EB90 -:10F21000126209D44FEA002343F0004323FA02F0BC -:10F2200070474FF00000704712F1610F01D14202A8 -:10F2300002D14FF0FF3070474FF00000704700BF21 -:10F2400073B96AB9002908BF0028BCBF00204FF07D -:10F250000041C4BF6FF000414FF0FF3000F03CB8F8 -:10F2600082B0EC462DE9005000F006F8DDF804E02D -:10F2700002B00CBC704700BF2DE9704F089E1446C9 -:10F280001D468046894600F029F804FB01F3A4FBE3 -:10F2900000AB00FB05329344B8EB0A0869EB0B099D -:10F2A000C6E90089BDE8708F2DE9704F089E1446AD -:10F2B0001D468046894600F061F900FB05F5A0FB7C -:10F2C00004AB04FB0154A344B8EB0A0869EB0B0937 -:10F2D000C6E90089BDE8708F704700BF00292DE99D -:10F2E000F00FC0F2A1800024002BC0F298801546D8 -:10F2F00006460F46002B3FD18A4258D9B2FA82F314 -:10F300004BB1C3F1200201FA03F720FA02F29D404B -:10F3100000FA03F61743290CB7FBF1F201FB127751 -:10F32000A8B200FB02F34FEA164C4CEA0747BB4277 -:10F3300009D97F1902F1FF3C80F00581BB4240F200 -:10F340000281023A2F44FF1AB7FBF1F301FB13715C -:10F3500000FB03F0B6B246EA0141884208D94919D8 -:10F3600003F1FF3780F0F180884240F2EE80023BEB -:10F3700043EA0242002303E08B420AD900231A46E3 -:10F380001046194614B1404261EB4101BDE8F00F4F -:10F390007047B3FA83F8B8F1000F40F088808B42D1 -:10F3A00002D3824200F2E28000230122E8E712B990 -:10F3B0000123B3FBF2F5B5FA85F2002A3AD17F1B9F -:10F3C000280C1FFA85FC0123B7FBF0F100FB117735 -:10F3D0000CFB01F24FEA164848EA0747BA4207D940 -:10F3E0007F1901F1FF3802D2BA4200F2C4804146CF -:10F3F000BF1AB7FBF0F200FB12700CFB02FCB6B2B6 -:10F4000046EA0040844507D9401902F1FF3702D28D -:10F41000844500F2AE803A4642EA0142B0E7E44356 -:10F42000524263EB430362E7404261EB41014FF01C -:10F43000FF3459E79540C2F1200927FA09F126FA6D -:10F4400009F99740280CB1FBF0F800FB18111FFADE -:10F4500085FC0CFB08F349EA07094FEA194747EA1C -:10F4600001418B4206FA02F608D9491908F1FF3228 -:10F470007AD28B4278D9A8F102082944C91AB1FB83 -:10F48000F0F300FB13170CFB03F21FFA89F949EAAA -:10F490000747BA4207D97F1903F1FF3160D2BA4258 -:10F4A0005ED9023B2F44BF1A43EA08438CE7C8F1F8 -:10F4B000200225FA02F103FA08FC27FA02F320FAE7 -:10F4C00002F207FA08F741EA0C0C4FEA1C49B3FBB9 -:10F4D000F9F109FB11331FFA8CFA0AFB01FB174300 -:10F4E0003A0C42EA03439B4505FA08F008D913EBAE -:10F4F0000C0301F1FF3235D29B4533D90239634405 -:10F50000CBEB0303B3FBF9F209FB12330AFB02FA5C -:10F51000BFB247EA0347BA4508D917EB0C0702F117 -:10F52000FF331BD2BA4519D9023A674442EA014572 -:10F53000A5FB0001CAEB07078F424FF000030AD377 -:10F5400005D02A461CE76246FDE63B4610E706FA70 -:10F5500008F68642F5D26A1E002311E71A46E5E74F -:10F560000B46A0E71146CBE7904687E74346424665 -:10F5700006E7023A50E702392F4439E72DE9F00F48 -:10F58000144605460E46002B43D18A4253D9B2FA9F -:10F5900082F757B1C7F1200620FA06F601FA07F301 -:10F5A00002FA07F400FA07F51E43210CB6FBF1F24C -:10F5B00001FB1266A0B200FB02F32F0C47EA0646DD -:10F5C000B34209D9361902F1FF3780F0FD80B3420A -:10F5D00040F2FA80023A2644F61AB6FBF1F301FB38 -:10F5E000136100FB03F0ADB245EA0141884208D93E -:10F5F000091903F1FF3680F0E980884240F2E68085 -:10F60000023B43EA0242002310461946BDE8F00FD0 -:10F6100070478B424CD8B3FA83F6002E4FD18B4201 -:10F6200002D3824200F2DD80BDE8F00F0023012208 -:10F6300010461946704712B90124B4FBF2F4B4FA2B -:10F6400084F2002A40F08280091B260CA7B2012315 -:10F65000B1FBF6F006FB101107FB00F24FEA154C68 -:10F660004CEA01418A4207D9091900F1FF3C02D254 -:10F670008A4200F2C8806046891AB1FBF6F206FBA6 -:10F68000121107FB02F7ADB245EA0145AF4208D9B6 -:10F690002C1902F1FF3180F09B80A74240F2988044 -:10F6A000023A42EA004210461946BDE8F00F7047A0 -:10F6B00000231A4610461946BDE8F00F7047C6F100 -:10F6C000200522FA05F703FA06F421FA05F301FAF8 -:10F6D00006FB20FA05F53C434FEA1448B3FBF8FC5F -:10F6E00008FB1C331FFA84F909FB0CFA45EA0B0BE3 -:10F6F0004FEA1B4545EA03439A4502FA06F204D94C -:10F700001B190CF1FF356FD3AC46CAEB0303B3FBF7 -:10F71000F8F508FB153309FB05F91FFA8BFB4BEADB -:10F720000347B94504D93F1905F1FF3362D31D469C -:10F7300045EA0C4CACFB0223C9EB07079F424FF094 -:10F7400000054AD346D062462B465DE79440C2F19D -:10F75000200921FA09FC914020FA09F9260CBCFB8A -:10F76000F6F806FB18CCA7B207FB08F349EA010933 -:10F770004FEA194141EA0C4C634500FA02F509D9F8 -:10F780001CEB040C08F1FF323BD2634539D9A8F1D8 -:10F790000208A444C3EB0C0CBCFBF6F306FB13C13C -:10F7A00007FB03F21FFA89F949EA01418A4207D9A6 -:10F7B000091903F1FF3022D28A4220D9023B2144A9 -:10F7C000891A43EA084343E73A4605E7334618E710 -:10F7D0000A4666E7B0409042B5D20CF1FF320023F2 -:10F7E00012E7334632460FE79A458DD9ACF1020C49 -:10F7F00023448AE7B9459AD9023D274498E703464E -:10F80000DEE79046C6E70238214435E74FF0FF3C7B -:10F8100006E000BF4FF0010C02E000BF4FF0010C0A -:10F820004DF804CD4FEA410C7FEA6C5C4FEA430C83 -:10F8300018BF7FEA6C5C1BD001B050EA410C0CBFD2 -:10F8400052EA430C91EA030F02BF90EA020F002034 -:10F85000704710F1000F91EA030F58BF994208BF9B -:10F8600090422CBFD8176FEAE37040F00100704758 -:10F870004FEA410C7FEA6C5C02D150EA013C07D1AF -:10F880004FEA430C7FEA6C5CD6D152EA033CD3D0FA -:10F890005DF8040B704700BF8446104662468C46F4 -:10F8A0001946634600E000BF01B5FFF7B7FF002827 -:10F8B00048BF10F1000F01BD4DF808EDFFF7F4FF50 -:10F8C0000CBF012000205DF808FB00BF4DF808EDDB -:10F8D000FFF7EAFF34BF012000205DF808FB00BFFE -:10F8E0004DF808EDFFF7E0FF94BF012000205DF820 -:10F8F00008FB00BF4DF808EDFFF7CEFF94BF0120D5 -:10F9000000205DF808FB00BF4DF808EDFFF7C4FFCD -:10F9100034BF012000205DF808FB00BF1C481D49D2 -:10F92000026800608A4200F01D80002100F004B8E7 -:10F93000194B5B58435004311848194B42189A42EE -:10F94000FFF4F6AF174A00F003B8002342F8043B77 -:10F95000154B9A42FFF4F9AFFEF7B0FC00F038F80F -:10F96000FFF7FEBF114E124830601248016821F0C7 -:10F9700070610160410201600F4C182020600F4946 -:10F980000F4808600F48D0F800D0406800470000DA -:10F99000F04F0020EFBEADDE107E01080000002019 -:10F9A0003401002038010020AC270020181002404C -:10F9B0000900000004000140140C0140000C01404B -:10F9C0004434434400F0FF1FFFF7FEBF0000000077 -:10F9D0002DE9804893B0F0F79BFBB14EB14CD6F8BF -:10F9E0000880002318F0080F2370374600F0E780E6 -:10F9F00063681B7A042B00F2E080DFE803F0030366 -:10FA0000058AB100237AD9E0627AA64B002A00F079 -:10FA1000D48000225A7293F82020120700F1CD8082 -:10FA2000D97A9A7A01F0070042EA00225A621A7BD8 -:10FA300002F03F00400140EAD1019962597B890000 -:10FA400041EA92119A7B02F0010041EA8021D962D9 -:10FA5000D97B01F00F00C00140EA52021A631A7C00 -:10FA600002F07F00000140EA11115963597C4900FE -:10FA700041EAD212997C01F0030042EA40229A63E3 -:10FA8000DA7C02F01F00800140EA9101D963197D00 -:10FA9000C90041EA5212997D1A645A7D01F00700AB -:10FAA00042EA00225A64DA7D02F03F00400140EA57 -:10FAB000D1019964197E890041EA92115A7E02F0BF -:10FAC000010041EA8021D964997E01F00F00C00154 -:10FAD00040EA52021A65DA7E02F07F00000140EA35 -:10FAE00011115965197F490041EAD212597F01F07D -:10FAF000030042EA40229A659A7F02F01F008001CB -:10FB000040EA9101D965D97FC90041EA52121A66CB -:10FB100051E094F86420634B002A4ED0002283F811 -:10FB2000642093F86620012A47D193F88A20102A8E -:10FB300084BF102283F88A2094F88A105A4A00233E -:10FB4000D8B2884202F1020235D212F8010C12F842 -:10FB5000025C40EA0525554840F823500133EFE7A1 -:10FB600094F8CC204F4B42B3002283F8CC2093F87A -:10FB7000CD20A82A21D193F8E050F5B9494901EBED -:10FB8000450393F8D00093F8D13003EB0020FEF743 -:10FB90001DFD3FA3D3E90023FEF7B8FE3EA3D3E942 -:10FBA0000023FEF7D5FBFEF7C1FF414B43F82500CC -:10FBB0000135082DE2D1012300E00023237018F461 -:10FBC000804F08D094F8043123B1364B002283F8DB -:10FBD000042101232370237843B118F4807F05D0DA -:10FBE000304BD3F808311B681B689847314B22789B -:10FBF0001B6832B92B4AD2F80C219A1AD243D20F81 -:10FC000000E0012292B3F3F7C3FA94F81021254BD8 -:10FC1000002A00F0CC83D3F814114D0742F12B8059 -:10FC2000D3F81821100707D4B3F81C2122F00802DA -:10FC3000A3F81C2102F01FB8B3F81C0100F0080261 -:10FC400092B2002A42F0178040F00800A3F81C018D -:10FC5000D3F82401C3F83421C3F82001B3F83001EC -:10FC6000C3F83821A3F8280102F005B8D4F83C21E4 -:10FC7000511CC4F83C11052A00F29183DFE812F010 -:10FC80001C00AE006E031C0168038A03AFF3008002 -:10FC90009A9999999999194000000000007077404D -:10FCA000E41F002070080020D8080020FC08002075 -:10FCB000540900207C270020D4F81421784D120725 -:10FCC00040F16D83D5F840219A1A002AC0F267836B -:10FCD00003F5C33805F5A27008F1A008C5F8408106 -:10FCE000F9F712FF6F4B05F5A27001461A78F6F787 -:10FCF00019FA95F84A1105F5A27011F0040F17D002 -:10FD0000C5F84C810022BB180025A3F8FE50644BB7 -:10FD1000855A03F5A87E22F80E5003F5AB7E22F833 -:10FD20000E500232062AEED121F0040183F84A1166 -:10FD300094F85C315A4AA3B1B2F84411B6F8FE30D7 -:10FD4000CB1AA2F84431B2F84611B6F80031CB1AFA -:10FD5000A2F84631B2F84811B6F80231CB1AA2F82F -:10FD60004831D4F84C314E4A002B00F018834E49EC -:10FD7000C3EB08038B4202F5A87502F5AB7119D8E5 -:10FD80004A4BDA6882F00802DA600023C25A35F979 -:10FD900003E017B2BE45C4BFDFF818E123F80E2018 -:10FDA00031F903E0BE45BCBF414FDA530233062BA5 -:10FDB000ECD1F4E20023C2F84C3135F903E0C85E1F -:10FDC000FA1870444FF0020E734490FBFEF0062BBD -:10FDD000A2F8FE00F1D1FBF7E1FDE0E2D4F8142136 -:10FDE0002F4D500740F1DB82D5F860219A1A002A86 -:10FDF000C0F2D582C5F8603195F86431012B14D07A -:10FE000002D3022B29D0CAE2D5F870319847D5F831 -:10FE100074319847012385F86431B5F86A21D5F823 -:10FE200060311344C5F86031B9E2D5F878319847AC -:10FE3000D5F86C319847D5F86031B5F8682105F5EB -:10FE4000C0701344C5F8603105F5C271D5F87C3136 -:10FE50009847022385F86431A1E2D5F89001D5F8DE -:10FE60008C1100784B1C0027834285F86471D5F80B -:10FE700088E1D5F8802103D1012385F894313B46F0 -:10FE80000748C4F88C3100EB8101C1F8982100EBE0 -:10FE90008301D1F898117244521AC4F888217EE285 -:10FEA000700800208B2700207FC3C901000C01408F -:10FEB000C6090020C0090020D4F81421510703D539 -:10FEC000B04991F8941111B9D70640F16882D4F87D -:10FED0005822AC4DC2EB030B46F2A712934540F2F9 -:10FEE0005E82A94FC5F85832B7F80080B8F1000F0C -:10FEF0002FD0D5F89031D5F85C221878D5F8883114 -:10FF00000138B3FBF0F0082392FBF3F1521A1044CE -:10FF1000C5F85C0290FBF3F0FEF732FF9B49FFF758 -:10FF200037F89B4902F048FA01464FF07E50FEF741 -:10FF300071FE9849FEF778FFFFF73CF908F1FF38AA -:10FF40000023C5F86002A7F80080C5F86432C5F840 -:10FF50006832D4F89051D4F8883128780138B3FB4E -:10FF6000F0F0FEF709FF8949FFF712F8884902F01F -:10FF700023FA01464FF07E50FEF74CFE8549FEF70E -:10FF800053FF02F04BF96F688146D4F86C02FEF71C -:10FF9000F7FE3946FEF748FF8046D4F86002C0EB12 -:10FFA0000900FEF7EDFE394681464FF07E50FEF720 -:10FFB00031FE01464846FEF737FF01464046FEF750 -:10FFC0002BFE02F02BF9B4F97072B4F97232002FE3 -:10FFD000B8BF7F42002BB8BF5B429F42B8BF1F46ED -:10FFE000DFF8C4813FB2FA2F8246D8F8000014DC53 -:10FFF000FEF7C6FE81463846FEF7C2FE0146664859 +:101D1000032B0BD0012013E0042009F00EF901463B +:101D2000042008F0D9FF0028F0D1E9E7082009F0E5 +:101D300004F90146082008F0CFFF003018BF012049 +:101D4000144B36681870337863BB134B1E604DE03C +:101D5000E80300208C050020444601085046010895 +:101D6000A0000020802100209406002040070020D1 +:101D7000840600200008014000040040A400002068 +:101D800000366E0134040040984401089806002093 +:101D9000AC050020A8050020D4050020A80A0020DA +:101DA00000100240012B21D1434F002138462C2244 +:101DB000C4F87C6610F009F88E237B704FF07C0A23 +:101DC000E0234FF07D09FB7087F800A087F82B9087 +:101DD0003A4F002138462C220FF0F7FF8A237B7000 +:101DE000A02387F800A0FB7087F82B903378022B94 +:101DF00008BFC4F8806608F015FC08B1C4F8846612 +:101E00000BF0B8F8AB6813F4002300D0012384F87A +:101E10008A3602F0ADFE2A4B18606B79052B03D190 +:101E2000284B4FF4C8721A80274B4FF47A721A80ED +:101E3000264BC8221A8098F8003043F0080388F82F +:101E40000030234B1A7822F002021A70AB689A070E +:101E50001ED5204B204A1D461A6002F093FD282013 +:101E600002F091FF069901390691F6D129681B4BC2 +:101E700048781E7802460123964203D30133082B8B +:101E80000244F9D1164A13708A785343A4F888366D +:101E9000144B9B689B030CD594F8633043F001030B +:101EA00084F86330032384F8643002E0032002F0F6 +:101EB000A1FF1FB0BDE8F08FE80500201406002048 +:101EC000000500206C040020C8270020C027002047 +:101ED000D6270020BC05002030210020C0050020AE +:101EE000940000202C200020A14A2DE9F04F136817 +:101EF000A04903F59C43A04D20330B60AB6885B02F +:101F000013F4807F174604D09C4B1B681B681B6929 +:101F10009847AB6842F201041C405CB9984E337894 +:101F200073B1964B1B681B681B6898470BF050FCFD +:101F3000347005E0934B1A7801321A700BF048FCAC +:101F4000AB68DA0405D5904B1B68DB0701D40CF0B5 +:101F50003FF88E4B3C681868037CCBB18C4A013B40 +:101F600032F91300A0F57A70B0F57A7FA8BF4FF46C +:101F70007A7020EAE0700CF007FE86490CF00CFF46 +:101F800085490CF055FE0DF03FF87E4B588039E046 +:101F9000AA68160436D57B4A5168611A002931DBDC +:101FA00004F59C41203151607C494E797C4931F8DF +:101FB0001660417CB6B296FBF1F0117A013101F066 +:101FC0000F0111720A44507218466E4E06F1090252 +:101FD0009A5C01331044102B80B2F6D100B290FB12 +:101FE000F3F000B26428A8BF642020EAE0700CF08F +:101FF000CBFD6C490CF0D0FE67490CF019FE0DF0DA +:1020000003F87080AB68D80510D5674B9C42674CCD +:1020100008D923681B681B6A984718B923681B688E +:102020005B6A984723681B685B699847AA68DFF872 +:1020300060A112F4805F504BB5F8DC10BAF90620AD +:1020400007D0B3F81A31581A824207DD19448A4280 +:1020500002E0B3F81C319A42C0F2548401220021FC +:1020600095F8238195F82401B5F81C61B5F81E7127 +:102070000B463AF901409B08B442C4BF63F07F03AA +:10208000DBB20231BC42B8BF43F040030829F0D1B3 +:102090003C4C617E994204D1A17EF92903D80131DB +:1020A00000E00021A1766376414B374F1978A1B942 +:1020B0003B68D90707D582B93E4B1B78DB070CD5A7 +:1020C0000BF0E6F809E03B4B1B785E0705D510B135 +:1020D0000BF07EFF01E0002AFAD0A37E294A142BE0 +:1020E000354E40F09980334B18F100081B7818BF2B +:1020F0004FF0010803F0040303F0FF0093B12C49F3 +:102100000B78002B00F08880537E5F2B01D10BF001 +:102110005FFFB8F1000F7FD0637E7D2B7CD10BF089 +:1021200057FF79E0537E572B0BD1244B4FF47A7233 +:102130001A80234B1B6813F008036DD1214A1380CA +:102140006AE0A968490745D55A2B43D11E4B197837 +:1021500019B1187001221D4B4DE0D17E1C4B81F04E +:102160000101D17609B1042245E0062243E000BF17 +:10217000BC270020440200202C2000204002002028 +:1021800038010020E40D0020500200203C01002016 +:102190001A07002000007A4400C07F44780700201E +:1021A000880700200000C842404B4C00580A00201D +:1021B00048000020D6270020E8030020C827002080 +:1021C0004C020020E0040020990400209B04002021 +:1021D0009A0400205D2B00F01D835B2B00F01C8314 +:1021E0005E2B0AD1032218E3A72B40F05F83AA4B92 +:1021F0001A7842F004021A700EE0562B01D10AF050 +:1022000069FDA64A1378002B00F01D83637E6F2BB7 +:1022100040F013830BF03CF8AB685B0731D5E37EED +:102220009BB19F4B1B7858070FD59E4BBAF90620E0 +:10223000B3F81C319A4208DD3B6813F0010304D166 +:10224000994A32211180994AD3763B68D9030AD53D +:10225000974B1A782AB9974A127812B9924A3221C2 +:10226000118001220CE0934B1A7852B18C4A1278FB +:1022700002F0040202F0FF011AB919708E4B01221C +:102280001A70D6F80090002309F1750B3B6009F134 +:10229000770698460BF1020303EB080113F80820B8 +:1022A0004B7816F8010C9A420AD2314609F0CCFB61 +:1022B00030B116F8023C01229A403B6813433B6060 +:1022C00008F10408B8F1A00F06F10406E2D17B4B37 +:1022D0001B7843B13B68DFF8FC8113F0020F784EA6 +:1022E00040F09A818FE109F21512019209F58B767F +:1022F0009846019A16F8010C531C03EB080113F8D9 +:1023000008204B789A4228D2314609F09DFB20B331 +:10231000B0786C4B013800EB400096F804B01844DC +:102320004FF00C0CF3780CFB0BFC00935F4B03F1AC +:102330001C0909EB0C014A6882420ED0009A09F888 +:102340000C2000228A60012202FA0BFB93F84C2039 +:10235000486022EA0B0B83F84CB008F10608B8F18C +:10236000480F06F10606C4D1574BDFF86C811E6892 +:10237000564B4FF00009D3F800B0D8F80030002BCE +:1023800000F038811978002900F03481D8F8042051 +:10239000C2EB0B02002A0CDB0BF5FA72C8F8042022 +:1023A000012202FA09F294F84C0020EA020284F8B1 +:1023B0004C2018F8040C5A780430C0B2002A40F0BF +:1023C000E1803AF91020B5F81A0100F1C80C624515 +:1023D00001DD9B7813E0C838824202DA9B785B42C9 +:1023E0000DE0012303FA09F394F84C2022EA0303D9 +:1023F00084F84C300BF5FA73C8F80430FAE094F81E +:102400004C2042FA09F2D20700F1F480002B304A46 +:10241000CCBF02200120013910700A2900F2E280AD +:10242000DFE801F0060F1B28315C6E80929CA6004D +:1024300032781344FA2BA8BFFA2323EAE3733370EC +:1024400007E072781344642BA8BF642323EAE37384 +:102450007370304602F064FBC4E0F27830461344F7 +:10246000642BA8BF642323EAE373F370216D02F0A9 +:1024700013FBB7E032791344642BA8BF642323EA2B +:10248000E3733371AEE072791344642BA8BF642305 +:1024900023EAE3737371A5E0820200204800002064 +:1024A000D62700202C20002080040020E40D0020EE +:1024B00098040020990400209B040020D0270020CD +:1024C000540200204C4B01089805002028200020D1 +:1024D0009A0400204C020020040E0020616D4A780E +:1024E0001A44C82AA8BFC82222EAE2724A700A78AF +:1024F0001344C82BA8BFC82323EAE3730B7071E011 +:10250000616DCA7A1A44C82AA8BFC82222EAE272B8 +:10251000CA728A7A1344C82BA8BFC82323EAE3737C +:102520008B725FE0616D4A7D1A44C82AA8BFC82239 +:1025300022EAE2724A750A7D1344C82BA8BFC82359 +:1025400023EAE3730B754DE0626D91780B44C82B61 +:10255000A8BFC82323EAE373937043E0626D117B45 +:102560000B44C82BA8BFC82323EAE373137339E0D5 +:10257000626D917D0B44C82BA8BFC82323EAE37387 +:1025800093752FE0012A2DD13AF910009B784FF472 +:102590009662B0F5617F92FBF3F305DB40F6330200 +:1025A0009042B8BF024601E04FF46172A2F5617239 +:1025B00092FBF3F3DBB2A84A581C0C29107011D11E +:1025C00094F858209A420DD0A44A042B28BF022325 +:1025D0000A2184F8583001FB0323A14A0633136013 +:1025E00002F0B8FA012303FA09F394F84C201343DC +:1025F00084F84C3009F10109B9F1040F08F10C0815 +:102600007FF4BBAE66E6AB68D80514D5954B1B6866 +:102610001B689B68984770B1D8F800309B070AD5B3 +:10262000338813F001020CD18F4943F00103E265B6 +:1026300022660B8006E03388012223F001033380F9 +:1026400000E000223B68590710D57AB1328822F0A9 +:10265000010102F0020289B292B2318052B9E26500 +:102660002266814A41F00201118003E0328822F0A3 +:102670000202328032887D4912F0030F4FF01000C1 +:1026800014BF48610861D8F8001011F00A0F21D07A +:10269000D80609D550070AD442F004023280744AA1 +:1026A0001088744A108002E022F0040232809806FA +:1026B000328806D5500607D46B4842F040020280AB +:1026C00002E022F040023280580603D5684A1288A0 +:1026D000A4F86420890640F18880674A127892073E +:1026E0007CD5664A1278042A78D913F4007C3288A3 +:1026F00012D002F010039BB2002B76D15A4922F07F +:10270000200242F010025E480A805E4A011D5370AA +:1027100008F09DFA022366E022F0100189B2580504 +:1027200031802ED5584B1B685889584BB3F900801F +:10273000B8F1000FB8BFC8F10008804509DAB3F955 +:102740000230002BB8BF5B428342ACBF00230123A1 +:1027500000E06346DB0714D502F0200292B2002AA3 +:1027600043D1484B4A485A704A4B41F020011A68FD +:102770005B683180011DA367626708F068FA012376 +:1027800031E022F0300232803E4A53786BBB0121A7 +:1027900051701A464049002050524049404C505216 +:1027A000404904EB030C5052002119510232CCF87D +:1027B0000400CCF8081004F1280C503443F80C1035 +:1027C00019519C441C44042ACCF80400CCF808108D +:1027D0006060A16003F11403DCD106E0338823F0CC +:1027E00030033380002384F870303B6813F4006FAB +:1027F000338814BF43F4807323F4807333806B7980 +:10280000082B02D00E2B40F09080338823F0400339 +:1028100033808AE0012200E002225FFA82F808F1A8 +:10282000FF3385F8543708F067FC0BF02BF90220D2 +:102830002821424602F0B8FAEEE4B8F1000F02D0C7 +:102840007E2B3FF4E7AC637E972B7FF4CDAC164B29 +:102850004FF4C8721A80DFE49A0400207C2700201D +:1028600098050020580A002054020020000C014066 +:10287000E00400207A05002082020020D00500201C +:102880004C0E0020480000208C0500206202002031 +:10289000580E0020DC050020D227002090050020E3 +:1028A000600E0020940500206C0400200022BB2B49 +:1028B000039201D1022303E0B72B04D14FF6FE733C +:1028C000ADF80E300AE0BE2B01D1022304E0BD2B8F +:1028D0007FF4A2AC4FF6FE73ADF80C303368BDF850 +:1028E0000C10B3F854200A44A3F85420BDF80E107D +:1028F000B3F856200A44A3F856200AF0EBF9002357 +:10290000A37689E40A4B00220021DA651A66C3F82F +:10291000F420C3F8F820C3F8FC20C3F80011C3F872 +:102920000411C3F80811FFF79ABB05B0BDE8F08F9A +:10293000E40D0020664B2DE9F04FB3F90600654B1E +:1029400087B01D682B8998420EDBB0F5FA6FAF791E +:1029500007DAC21A5743A3F5FA6397FBF3F7643714 +:1029600003E0C7F1640700E064275B4B5B4AB3F800 +:102970001A1193F9EC3016685B4204919BB2002166 +:10298000059334460A46524BDDF810C0CB5E40F248 +:10299000E63E0393CCEB030303F2F31CF44503D8A8 +:1029A000002BB8BF5B4201E04FF4FA73022ADFF854 +:1029B000388131D096F85DE1BEF1000F04D0734547 +:1029C000CCBFCEEB030300234FF0640EDFF814A15D +:1029D00093FBFEFC6FF0630B3AF81C900BFB0C3B77 +:1029E0000CF1010C3AF91CA00FFA89FCCCEB0A0C93 +:1029F0000CFB0BFC9CFBFEFCCC4428F801C095F8BA +:102A000004C003FB0CFC364B9CFBF3F373449BB2FA +:102A10007B4393FBFEFE1BE096F85EE1BEF1000FE8 +:102A200004D07345CCBFCEEB03030023DDF814C004 +:102A300003FB0CFEA8F804E095F805E0002BB8BFF6 +:102A40005B4203FB0EFE264B9EFBF3FE0EF1640E73 +:102A5000B31893F80480DFF894C00EFB08F86423E1 +:102A600098FBF3F802F80C8094F80E900CF1030830 +:102A70000EFB09F999FBF3F902F8089094F8188015 +:102A80000CF1060C0EFB08FE9EFBF3F302F80C3073 +:102A9000DDF80CE0049B9E45DFF84CE004DA3EF8DC +:102AA00001305B422EF801300132032A01F10201AC +:102AB00004F101047FF467AF074EB6F81C31984269 +:102AC00016DBB0F5FA6FA8BF4FF4FA6011E000BF53 +:102AD0001A070020980500202C200020E803002081 +:102AE0000CFEFFFFF00E002062020020FE0E002010 +:102AF0001846C01A4FF47A725043C3F5FA63B0FB1C +:102B0000F3F36427A34C93FBF7F204EB42016FF05D +:102B1000630000FB0233098B04EB4202B2F91A0096 +:102B20000AB2821A534393FBF7F739449A4F9B4DED +:102B30003B88AEF806105A063DD5994B1888994B3C +:102B40001B88C01A00B20CF01FF897490CF070F8FF +:102B500080460FF069FB814640460FF0D9FB804666 +:102B6000B5F902000CF010F88246B5F900000CF03F +:102B70000BF8494683460CF05BF841460346504645 +:102B800002930CF055F8029B014618460BF046FFE5 +:102B90000CF014FA4946288050460CF049F841469A +:102BA000814658460CF044F8014648460BF038FF81 +:102BB0000CF004FA6880B26840F602031340002B60 +:102BC00053D07A4B06211D88236B1D4494F8343072 +:102BD00025630133DBB2B3FBF1F084F8343001FB41 +:102BE000103313F0FF0F40D1930706D501F0CAFE52 +:102BF00001F0B2FE674B83F83500B368180532D593 +:102C00006B4BA16B5A7B6B4B33F81200082391FB83 +:102C1000F3F280B28A1A0244A26392FBF3F292B2F8 +:102C200040F6E4435A43644B40F6FF71B2FBF1F2C5 +:102C300019684FF47A73C8888988121A5A4392FB2C +:102C4000F1F255435D4995FBF3F30A60D4E91001B5 +:102C5000C01841EBE371C4E910010023584A0CF09D +:102C6000F3F9584B1860002323635749494A0B680E +:102C700094F8358013F4805318BF012382F848304C +:102C8000B3688A4613F4807F504D2CD0DFF8509102 +:102C90002878D9F80030C0F380001B685B6898473B +:102CA00060B1012384F84930D9F800301B68DB6833 +:102CB000984718B1374B022283F84920D9F80030E1 +:102CC0001B689B68984728B12B7859075CBF022383 +:102CD00084F84930D9F800301B689B69984710B1D7 +:102CE000002384F849303A4B1A6892060DD5DAF879 +:102CF000003013F4C06F05D0364B1B789B0701D40E +:102D0000012300E0002384F84A3094F84920214B45 +:102D1000022A02D14C204E211EE0012A06D1532066 +:102D20004D214C220B4608F009FF2BE093F84A2076 +:102D3000012A03D1532001464E2206E093F8482091 +:102D4000012A04D15320014602464D23EBE7B8F196 +:102D5000000F04D053204D210A464423E3E73A886C +:102D6000170603D553204D210246DBE71A4A127895 +:102D70001AB1192008F0B6FE04E0404683F84B80F3 +:102D800002F00BF82B7858072CD5144B08225A6107 +:102D900083E000BFF00E00205402002062020020F9 +:102DA000E0040020480E002035FA8E3CFC04002090 +:102DB0007807002088070020BC050020C4050020FB +:102DC000407E0500C805002050020020D6270020C4 +:102DD0004C020020820200209A040020000C0140D6 +:102DE0005C0A0020DAF80020D10703D4B74943F089 +:102DF00001030B70B6490B6813F0020302D0B5490A +:102E00000988A1B9B449098801B12BB9B34B1B8812 +:102E1000003318BF012300E0012343B1B04BD96850 +:102E200081F00801D9602B7823F001032B70AD4BA2 +:102E30001B781F0703D42B7823F001032B70D002DB +:102E400003D52B7823F001032B702B78A64A13F0BF +:102E5000010F05D00023E364A14B082119610BE0A9 +:102E6000E16C136841B9A14903F5F42303F59073AC +:102E7000CB649B4B08215961E36C12686BB1D21A89 +:102E8000002A0ADB964A03F5F423D16803F5907310 +:102E900081F00801D160954AD3640AF06BF8944B35 +:102EA0001B7813B105F098FAF9E3012008F0E6F871 +:102EB000002800F0F483DFF8589299F84A30012B8B +:102EC00040F0E7838B4A8C4BD9F80010C2F8009091 +:102ED00019609246884A106801F0C2FF002800F08D +:102EE000D283854B186801F0B6FFDAF8003093F80A +:102EF0004820DAB9B0F124014A424A4183F8482017 +:102F0000002AE7D12B785B07E4D4232802D105F00F +:102F100063FADFE7D4F8E8301B7D8342DAD1774AE1 +:102F2000774B1A60774A784BDA60D3E7012A04D1ED +:102F30004D2814BF00220222A2E3022A04D13C2819 +:102F400014BF002203229BE3032A0AD140284FF03A +:102F5000000200F295831A71DA7158719871042297 +:102F60008EE3042A06D19A7983F84900504098717B +:102F7000052285E3052AADD159791A7991429979CB +:102F800006D941409971511C197113441872A1E777 +:102F9000814240F0728393F8490006F079F90028E5 +:102FA00040F06683DAF8003093F84930C82B00F01F +:102FB000DD8043D82D2B00F0F08224D8252B00F0A3 +:102FC000CD8206D8212B00F02382232B00F06881CC +:102FD00086E3292B00F0CD822B2B00F0D682272B05 +:102FE00040F07E83002001F081FF01F019FD474F82 +:102FF000A7F8E60001F014FDA7F8E80001F010FDC5 +:10300000A7F8EA0031E3332B00F0DB820CD82F2B3A +:1030100000F0ED82312B40F063833C4FC02001F083 +:1030200065FF07F18008F8E2412B00F0D282442BC3 +:1030300000F01583352B40F0538353E1D02B00F083 +:10304000F58169D8CC2B00F07B8106D8C92B00F024 +:103050002782CA2B00F0A28042E3CE2B00F012821E +:1030600040F2EF8101F0DCFC01F0DAFC274FDFF8E1 +:10307000A480A7F8D00001F0D3FCA7F8D20001F09B +:10308000CFFCD8F800B0A7F8D40001F0C9FCABF829 +:10309000A80101F0C5FC01F0CDFCD8F8008001F0DA +:1030A000BFFC00EB80004000A8F8520001F0AEFC2D +:1030B00087F8040101F0AAFC87F8060101F0A6FCDC +:1030C00087F8050101F0A2FCCFE200BFD62700205F +:1030D0004C020020C02700206C040020C8270020DC +:1030E000000C014082020020BC270020F00E0020CE +:1030F000D02700206006002064060020EFBEADDE71 +:10310000F04F00200400FA0500ED00E02C20002024 +:10311000400F0020E8030020D42B00F0438108D8A2 +:10312000D22B10D040F2E18101F07AFCC94B18801B +:103130009BE2EF2B25D0FA2B00F0AE81D62B40F08E +:10314000CF82002726E12B7803F0040303F0FF076A +:10315000002B40F08A8201F059FCBF4B022883F813 +:10316000540740F2698183F8547765E1002701F044 +:1031700057FCBA4BD8530237102FF8D10122B84B65 +:1031800088E1B84FD7F8008001F04AFCA8F8560053 +:103190003F6801F045FCA7F8540066E2B14B0027F8 +:1031A0001A6898461278022A61D1D8F800B001F066 +:1031B0002DFC07F108020BEB820B0BF0E1FCAA4996 +:1031C0000BF0EAFDCBF80400D8F800B001F01EFCCB +:1031D00007F10A020BEB820B0BF0D2FCA3490BF0B8 +:1031E000DBFDCBF80800D8F800B001F00FFC07F1C8 +:1031F0000E020BEB820B0BF0C3FC9D490BF0CCFDD8 +:103200000137032FCBF80400CFD1072FD8F800B037 +:1032100016D101F0FBFB0BF0B3FC93490BF0BCFDA6 +:10322000CBF84800D8F800B001F0F0FB0BF0A8FC98 +:103230008D490BF0B1FDCBF84C0001F0E7FB12E03B +:1032400001F0E4FB0BEB07031871D8F800B001F0B4 +:10325000DDFB0BEB07039873D8F800B001F0D6FB49 +:103260000BEB0703187601370A2FCED1FDE1D8F812 +:1032700000B001F0CBFB0BEB07031871D8F800B0DE +:1032800001F0C4FB0BEB07039873D8F800B001F012 +:10329000BDFB0BEB070301370A2F1876E7D1E4E1FA +:1032A00001F0B4FB272821D86E4B00F11C081B68E5 +:1032B00003EB880801F0AAFB6E4B08F1050703F544 +:1032C0008A72197A814203D00C339342F9D10DE00E +:1032D0001B7888F8053001F099FB787001F096FBB7 +:1032E000B87053E001F092FB0B2804D901200021B3 +:1032F00001F0DEFDB9E14FF0060808FB00F0594B84 +:1033000000F588701B6803EB000801F07FFB0328C1 +:10331000ECD888F80A0001F079FB88F8050001F084 +:1033200075FB88F8060001F071FB88F8070001F0D2 +:103330006DFB88F8080001F069FB88F8090094E14A +:103340004D4FD7F8008001F061FB88F80000D7F8F6 +:10335000008001F05BFB88F80100D7F8008001F0E5 +:1033600055FB88F80400D7F8008001F04FFB88F87F +:103370000500D7F8008001F049FB88F80600D7F86F +:10338000008001F043FB88F802003F6801F03EFB3B +:10339000F8706AE101F044FB384BD8530237102F24 +:1033A000F8D162E14FF000082E4F08F12C0B39687C +:1033B000029101F035FB02994FEACB021144C8801B +:1033C00039680192029101F02BFB019A0299114494 +:1033D0000881019201F024FB0728019A02D839687C +:1033E0000A445073A0F57A7292B2B2F57A7F03D88C +:1033F0003A6802EBCB0250813F6801F007FB08F10D +:10340000010807EBCB03B8F1080F1873CCD12CE1FE +:103410000027144BD3F8008001F0F8FA08EBC7033B +:103420000137082F83F86D01F3D11EE12B785F0778 +:1034300000F11B8105F0D8F807F05EFE0AF022FBD0 +:1034400013E12B78580700F110810D4B4FF4C8722F +:103450001A800AE17A0500202C2000201A0700209B +:103460003C020020E8030020000020410000C84288 +:1034700000007A44704B010898050020DC0F002002 +:103480006C0400202B78590700F1EF80984B1A78D4 +:1034900042F004021A70E8E02B785A07CCD51FE1FD +:1034A00001F0B4FA924B1A7810B142F0020201E036 +:1034B00022F002021A7001F0A9FA8E4B8E4F18709A +:1034C00001F0B8FA386001F0B5FA786001F0A8FAB6 +:1034D0008A4B188001F0A4FA894B188094F80431C3 +:1034E00043F0020384F80431BFE001F08FFA019049 +:1034F00001F0A0FA029001F09DFA804601F09AFADC +:10350000074601F08DFA01F08BFA01F07FFA019A7B +:10351000029B92B97B4A82E808017B4B1A8822F011 +:1035200010021A80724B1A7842F001021A70002FB2 +:1035300000F09B80754B1F6097E0102A40F095804B +:10354000734A82E808010FB1704B1F607048714BDD +:103550000222011D1A7007F07AFB86E0002001F0BC +:10356000C5FC0023B36001F065FAB3681843B0608E +:103570007BE0002001F0BAFC01F052FAA6F8080145 +:1035800001F04EFAA6F80A016FE0002001F0AEFC4F +:1035900001F03CFA604B587167E0002001F0A6FC96 +:1035A00001F034FA86F8180101F03AFAA6F81E0183 +:1035B00001F036FAA6F81A0101F032FAA6F81C0159 +:1035C00053E0002001F092FC01F020FA86F820017F +:1035D0004BE0002001F08AFC002701F017FA4E4B67 +:1035E0003B440137082F83F81001F6D13DE000205D +:1035F00001F07CFC484F07F1400801F011FAA7F8F0 +:10360000D40101F003FA87F8D60101F0FFF904377D +:1036100087F8D3014745F0D127E001F001FA00F027 +:103620003F00A7F8560101F0FBF9B7F856218001D9 +:1036300000F4F8631343A7F8563101F0E7F90001ED +:1036400087F8540101F0E2F997F8543100F00F00C7 +:10365000184387F8540104374745DED105E00020C0 +:1036600001F044FC012384F80531002001F03EFC08 +:10367000DAF80030987901F00AFCDAF8003000221C +:1036800083F8482026E494F8053113B1234A244BEB +:10369000DA60244B09F14C0999457FF40EAC2249BC +:1036A0000B689B0616D5214BD4F808211B689A1A83 +:1036B000002A0FDB0F4A1278042A0BD91C4A03F5A3 +:1036C000123303F5F873C2F808311A4BDA6882F046 +:1036D0001002DA60184B9B683BB11848984704E029 +:1036E0000120002101F0E4FBC2E707B0BDE8F08F44 +:1036F00082020020D0050020DC050020CE0500203D +:10370000CC0500204C0E002054020020580200205E +:10371000580E0020540E00202C2000200400FA0532 +:1037200000ED00E0D80F00204C020020BC27002054 +:10373000F00E0020000C0140EC030020FC0F0020E4 +:103740002DE9F04F974B91B01B68BBB9964C23788D +:10375000013B042B00F2F086DFE813F00B060B06AA +:103760000B06DE06C406206801F075FB8F4B04468D +:103770001B681B784BB1012B00F0ED80894C206851 +:1037800001F06EFB0028EED1E0E72428884D0CD034 +:1037900006D80A2800F08E800D2800F08B80C6E045 +:1037A0002A2806D02C2804D0C1E02B706B70AB7097 +:1037B000CEE06A782E782A4400217D4BD170EEB994 +:1037C000DA789E74472A19D11A79502A16D15A7973 +:1037D000472A07D19A79472A04D1DA79412A01D1B7 +:1037E00001229A746A79724B522A07D19A794D2A2A +:1037F00004D1DA79432A04BF02229A74AB7C6C4F5D +:10380000012B02D0022B36D049E0B31E072B46D83D +:10381000DFE803F0040810141C27452C02F0E6FA38 +:1038200068613CE0EA78624B532A38D15A695242C7 +:103830005A6134E002F0DAFAA86130E0EA785C4BD1 +:10384000572A2CD19A6952429A6128E0EB78302BA2 +:10385000584B1A788CBF42F0020222F002021A7012 +:103860001DE0002002F01CFB287718E0002002F089 +:1038700017FBE88313E0072E06D0082E0FD1012096 +:1038800002F00EFB78840AE0012002F009FB41F20D +:10389000184358434FF47A72B0FBF2F33B8401367D +:1038A00000232A2C424A2E706B704CD1012182F8E1 +:1038B00024104DE095F82430002B34D03C4BDB78BD +:1038C000402B04D9A3F137021201D2B202E01B014E +:1038D00003F0F0022B79A978402B8CBF373B303BAB +:1038E000DBB21344DBB29942314A1BD1937C012BEA +:1038F00008D0022B16D1118C2F4B528C19802F4BD4 +:103900001A800FE02B4909788E070CD52C49506995 +:10391000086090694860107F2A490870D18B2A4A54 +:10392000118000E00023002285F8242010E06B784D +:103930001F4A0E2B03D8591C13445170DC7095F8A4 +:1039400024301B4A1BB991784C40947000E000234E +:1039500003F0010361E1164B002193F82520082AAA +:1039600000F25A81DFE802F00B0514324353718DE7 +:103970009A00622801D1022207E083F82510B52CB5 +:1039800040F04A8193F82520013283F8252043E155 +:10399000032283F8252083F8260083F8270083F884 +:1039A000280039E1A00A0020800A00209C0A00209B +:1039B0000010002082020020CC0500202A140020E4 +:1039C000DC050020D0050020CE050020042283F86D +:1039D000252093F8272093F828100244D2B283F8C8 +:1039E00027200A4483F8282083F8290014E10522BF +:1039F00083F8252093F8272093F828100244D2B2A8 +:103A000083F827200A4483F82820588504E10621FA +:103A100083F8251093F8271093F828002144C9B2A1 +:103A200083F82710014483F82810598D6C4A01EB64 +:103A30000424A4B2B4F5007F89BF002154855185C8 +:103A400082F8251000229A85E6E093F8272093F863 +:103A500028100244D2B283F827200A4483F8282091 +:103A60009A8DC72A03D85E49114481F8300001328B +:103A700092B29A855B8D934240F0CE800722584BDC +:103A800083E7082283F8252093F82730834200F04B +:103A9000C380534A002382F82530BEE083F8251006 +:103AA00093F828104E4A814240F0B68092F82910CF +:103AB000062947D004D8022912D003292CD0ABE024 +:103AC00012295CD0302940F0A78092F83410454A82 +:103AD000102988BF102111701078434900225CE042 +:103AE0004249506B4860906B0860116C4FF47A70DB +:103AF00091FBF0F13E48018092F8F8103D4A19B16F +:103B0000117841F0020102E0117821F002011170F8 +:103B1000012283F8F92055E092F8351011F00101E7 +:103B200005D092F83420D41E6242624100E00A4679 +:103B300083F8F820002A45D12E4A117821F002019D +:103B400011703FE092F83B1011F0010105D092F89E +:103B50003A20D01E4242424100E00A4683F8F82053 +:103B600022B9244A117821F00201117093F85F10F4 +:103B7000214A1170B3F85C10204A118022E0516C88 +:103B80001F480180916C42F2107091FBF0F11D48CA +:103B90000180012182F8FA1014E0824201F10C0147 +:103BA00010DA11F8045C184C155511F8035C174C29 +:103BB000155511F8015C164C15550D78154C155519 +:103BC0000132EAE793F8F930054A2BB392F8FA305C +:103BD00013B3002382F8F93082F8FA3001231CE095 +:103BE000001000202C14002030100020DC050020E4 +:103BF000CE05002082020020D00500209C0000207D +:103C0000CC0500202A1400202D1400203D14002093 +:103C10004D1400205D1400200023002B3FF4AEADB6 +:103C2000A54BA64E9A68DA6032689A60A44B1A686F +:103C300042F020021A60A34B1A78012A0CBF00221E +:103C400001221A70A04B1A7891077FF597AD9F4912 +:103C5000097804297FF692AD9D49097801F00401A5 +:103C600001F0FF0011B922F001021A701B78964F83 +:103C700013F0010F974C984D11D180B19B070ED5D1 +:103C8000964B28686A6818605A6006F08BFD944B62 +:103C90001B88A4F8FC303B7843F001033B7094F898 +:103CA000FE304FF00509013393FBF9F909EB89095F +:103CB000C9EB03098B4B8C481B7884F8FE90059365 +:103CC000831D03EB890907900023DFF80CE2874A84 +:103CD00053F80E00864F985090FBF7FC02F108074E +:103CE00043F807C0834F03EB0E0107FB0C0742F2BA +:103CF000107097FBF0F00691079980B221F8020F3F +:103D000002F1100A03EB830B0490079153F80A00A9 +:103D100059F80B1049F80B70C1EB000808EB0700CD +:103D2000734F4FF0050843F80A0090FBF8F007FBCB +:103D30000C000599183201299850774608D1DDF812 +:103D400010E0AEF10202B2F5797F9CBF06990860DF +:103D50000433082BB9D1DFF87C813068D8F84C31B6 +:103D6000C01A0AF00DFF64490BF016F833684FF0E3 +:103D70007E51C8F84C3181460BF0F8F810B94FF07D +:103D80007E5000E048460CAAC4F85001534B009204 +:103D90000DAA019297E803000CCB06F0C1FC0C9B26 +:103DA00056496422B3FBF2F30D980B80544B90FB01 +:103DB000F2F21A80444A474E127812F0010208BF0C +:103DC0001A8098F8543108BF0A80002B3AD0D6F8F0 +:103DD00050114FF07E500AF0DFFFD6F8583181467F +:103DE0002868C01A0AF0D0FE49460AF021FF0BF0FD +:103DF000E5F8D6F85C211FFA80FA68680FFA8AFAAB +:103E0000801A0AF0C1FE3F4B19680AF011FF4946BB +:103E10000AF00EFF0BF0D2F8B6F9623100B2C21808 +:103E2000B6F960310221534492FBF1F293FBF1F3B6 +:103E300092B29BB2A6F86621A6F86431A6F8622178 +:103E4000A6F86031012388F854312F4B79681B881C +:103E5000386803F030031F4E1F4DC8F85C11C8F8D6 +:103E60005801002B3FF48AAC06F5B873009306F5B1 +:103E7000BA730193D6F86821D6F86C3106F050FC7D +:103E80006B68D6F86C01C01A0AF07EFE1D4B1968EB +:103E90000AF0CEFE0BF092F8D6F868312A68C6F820 +:103EA0007C019B1AC6F878310E4B1B78012B2DD064 +:103EB000022B00F0F58061E4800A00202820002019 +:103EC0004C020020F40F002082020020D0050020C8 +:103ED000D627002000100020DC0500204C0E00201A +:103EE000E0040020540E0020FE1000202C110020C1 +:103EF00080969800806967FF00007A4440060020A1 +:103F0000420600204C00002054020020D6F89C41BC +:103F1000D6F89031D6F88021D6F8947104F100409B +:103F20000593049207970BF049F8074620460BF0DB +:103F300045F88C4BD6F850511B68D6F898618A4CDE +:103F40000890069609934FF0000ADFF83C9259F862 +:103F50001A60A9F1140230463AF802800AF014FE01 +:103F600004990AF065FE0BF029F8C8EB000080B256 +:103F700009F128092AF809000FFA80F948460AF0E1 +:103F800003FE05990AF054FE0BF018F81FFA80FBA7 +:103F900009EB06000AF0F8FD07990AF049FE2946E8 +:103FA0000AF046FE21680AF03BFD0BF007F8B84224 +:103FB00004DB089A9042A8BF104600E038460AF099 +:103FC000E3FD20600AF0FAFF58441FFA80FB6068A6 +:103FD00008F13108301A0AF0D7FD29460AF0DCFE54 +:103FE000099B206102469878D4F8089003920AF061 +:103FF000C7FD5E490AF01CFE01464FF07E500AF0F4 +:10400000CBFE29460AF00CFD014628460AF0C4FE04 +:10401000039A844649461046CDF80CC00AF0FEFCCF +:10402000DDF80CC0014660460AF002FE0146484633 +:104030000AF0F6FC1FFA88F8B8F1620F0146206119 +:104040006660A0600ED906980AF0F2FD0AF0B6FF8D +:10405000474AB0F5FA6FA8BF4FF4FA609042B8BF74 +:10406000104600E00020834440F6B8320FFA8BFB84 +:104070009345A8BF93463F4A0A219345B8BF93464C +:1040800001FB0AF13C4A54F8140B2AF802B03B4AEF +:104090000AF1020ABAF1040F88503FF46FAB54E7FB +:1040A000304BD6F870911F68B6F8A451B7F808A045 +:1040B0004FEA59039A4528BF9A462BB29A4502DC2B +:1040C0001FFA8AFA0BE02E49D6F850010AF0B0FD2B +:1040D0000AF074FF28441FFA80FAA6F8A4A1D8F8C1 +:1040E0007451D8F8A861AE1B304606F0C9FB002811 +:1040F000D8BF404241F293139842CCBF0020012028 +:10410000002843D030460AF03FFD1E490AF090FDDA +:104110000EF0FEF8064648460AF032FD01463046EB +:104120000AF086FD0AF04AFF80B240F6B83203B2C8 +:104130009342A8BF13460F4AA8F8AC019342ACBF04 +:10414000EB18AB1848F6A042934203DDA3F50C43ED +:10415000A03B04E0002BBCBF03F50C43A033C8F820 +:10416000B03115E08C050020880E0020DB0FC9401F +:1041700030F8FFFF48F4FFFF94050020B00E002048 +:104180000000C842D302373978110020C8F8B05176 +:10419000D4F8B021C2F50C50283004920AF0F4FC97 +:1041A000AA490AF045FD05460EF03EF80F90284654 +:1041B0000EF0AEF8D4F8C051D4F8B431D4F8B82128 +:1041C0000E9005F1004007930A920AF0F7FE059061 +:1041D00028460AF0F3FED4F85081D4F8BC410B9085 +:1041E00009949B4C002550460AF0CEFC0EAB53F8C8 +:1041F00015100AF01DFDDFF894B206463BF90500E4 +:104200000AF0C2FC014630460AF008FC0AF0D6FE6D +:10421000904B06B2B6F57A7FA8BF4FF47A769E42ED +:10422000B8BF1E46B0B20BF13C0B25F80B0000B234 +:104230000AF0AAFC079983460AF0FAFC0AF0BEFECF +:1042400080B208900A9958460AF0F2FC41460AF0FA +:10425000EFFC21680AF0E4FB0AF0B0FE059B9842EF +:1042600004DB0B9A9042A8BF104600E005980AF0C4 +:104270008BFC8346206060681434301A0AF084FC9A +:1042800041460AF089FD54F80C3C44F8040C0246FF +:10429000B878069303920AF073FC6F490AF0C8FCE1 +:1042A00001464FF07E500AF077FD41460AF0B8FB18 +:1042B000014640460AF070FD039A8446069910466E +:1042C000CDF80CC00AF0AAFBDDF80CC00146604630 +:1042D0000AF0AEFC014606980AF0A2FB44F8106C06 +:1042E000014644F8040C44F80C0C09980AF0A0FCB0 +:1042F0000AF064FE089E064458460AF05FFE304409 +:1043000040F6B83200B29042A8BF1046534A0A2184 +:104310009042B8BF10466943514AA852514A0235EB +:10432000042D41F802B07FF45EAF3B792BB1049BC2 +:10433000642293FBF2F24C4B1A803B884B4C99451C +:104340000ED9D4F8A831D4F87401C01A06F098FA3E +:1043500042F210730028B8BF404298427FF70EAA7D +:10436000434B01221A70B4F8FC203F4B1A80FFF730 +:1043700005BA404A116890460F7817B1012F0DD049 +:10438000ADE0012B00F2AB8062783B4B03EB0213F4 +:104390003A4A5968106800F059FD9DE0374E306880 +:1043A00000F04FFDB146002800F099802378344D8D +:1043B000022B29D0032B31D0012B40F09080314BC0 +:1043C0001F686B69FB1A632B40F289802B69042BF1 +:1043D00018D8DFF8A480306808EB0313596800F0A0 +:1043E00035FD6B78366808EB03139D6815F8011BE3 +:1043F00019B1304600F046FDF8E7236967610133E3 +:1044000023616CE0022068E06A781B4B306803EBA4 +:104410000213596800F01AFD03205EE02B7E03B9F9 +:104420002F76227E164B012A36D11A697B2A2FD885 +:10443000D8F800309B782BB9134BD9F80000995C61 +:1044400000F020FD23690133236125E0D3023739D1 +:10445000B00E002018FCFFFFDB0FC94048F4FFFF3F +:1044600094050020880E00207A050020001000200E +:10447000540E00209C0A0020F4450108A00A0020E8 +:10448000800A002028200020844C010864110020AC +:1044900000221A6102221A76227E294B022A18D1A2 +:1044A0001A690F2A13D8D8F80030997859B95B786F +:1044B000244903EB03130B441A44D9F8000092F883 +:1044C0007D1000F0DFFC23690133236101E003224A +:1044D0001A76237E022B02D9042007F07FFB0023EB +:1044E000636029E06368052201336360637801201B +:1044F0000133DBB2B3FBF2F202EB82029B1A637070 +:10450000114B00221B68A360104B1A70104B1A78D5 +:1045100022F002021A700DE00B4B1A68A368D21A3F +:1045200040F6C4139A4207D90A4B05201A6822F0B4 +:1045300020021A6007F052FB11B0BDE8F08F00BFF7 +:10454000800A0020844C010828200020D00500208B +:10455000820200204C0200201E4B2DE9F0431A7805 +:104560001D460AB31C4B07781E781C4B93F800C0FD +:1045700002231B4A03F10108D45C344104F00F0408 +:10458000BC420CD20B2C0AD812F8039012F8088007 +:1045900002EB840209EA0C0408EB042414610233E0 +:1045A000102BE6D100232B7003788B420FD90C4BD4 +:1045B00093F8400060B10B4A890012780B441869E7 +:1045C00002B1400800F5777080B2BDE8F0830020AA +:1045D000BDE8F08340010020600A0020610A00204D +:1045E000C4110020620A002007299ABF024B33F849 +:1045F00021000020704700BF1C020020024B53F82E +:104600002100C0F3CF007047C401002008B5074B5C +:1046100053F821000AF0B4FA05490AF009FB0549EC +:104620000AF0FEF90AF0F0FC80B208BD5C0100203F +:104630000000203F00005C44014B33F8110070473C +:104640001A070020014B33F8110070474C19002065 +:10465000034B4FF4805208B11A6170475A6170479A +:1046600000080140034B4FF4805208B15A61704773 +:104670001A6170470008014038B50C6805462046AD +:104680000DF0E4FB214602462868BDE838400DF0F5 +:10469000E5BB094BDA68D10709D4DA68520708D4B8 +:1046A000DB6813F0100F0CBF0420032070470120BB +:1046B00070470220704700BF002002408A6810B592 +:1046C0000C6A036814430A6923F4FF4314434A69DC +:1046D00023F0700314438A691443CA6914434A6A75 +:1046E00014438A6A224313430360CB6843600B6818 +:1046F00083604B68C36010BD02684FF6FE731340C1 +:1047000003600023036043608360C3602A4B9842C8 +:1047100022D02A4B984229D0294B984230D0294B9D +:10472000984237D0284B98423ED0284B984206D129 +:1047300053F8682C42F4700243F8682C7047244BFD +:10474000984206D153F87C2C42F0706243F87C2CDE +:104750007047204B984206D153F8042C42F00F02C8 +:1047600043F8042C70471C4B984206D153F8182C80 +:1047700042F0F00243F8182C7047184B984206D1CB +:1047800053F82C2C42F4706243F82C2C7047144BD5 +:10479000984206D153F8402C42F4704243F8402C22 +:1047A0007047104B984205D153F8542C42F47022B4 +:1047B00043F8542C704700BF080002401C00024020 +:1047C0003000024044000240580002406C000240A9 +:1047D00080000240080402401C04024030040240F1 +:1047E00044040240580402402DE9F843574B0C465C +:1047F0000168013AC3F842108188A3F84610072ADD +:1048000042D8DFE802F0040A101822292F35B3F845 +:1048100042202280B3F8442013E0B3F844202280E1 +:10482000B3F8422005E0B3F8422052422280B3F8A8 +:104830004420524205E0B3F8442052422280B3F8AB +:1048400042206280B3F846301DE0B3F84220524265 +:104850002280B3F8442012E0B3F844202280B3F859 +:1048600042200CE0B3F842202280B3F8442005E057 +:10487000B3F8442052422280B3F842205242628070 +:10488000B3F846305B42A380314B1B78002B5AD1E2 +:10489000B4F900000AF078F98046B4F902000AF091 +:1048A00073F90746B4F904000AF06EF9294D06467B +:1048B000296840460AF0BCF9E968814638460AF0A2 +:1048C000B7F9014648460AF0ABF8A9698146304677 +:1048D0000AF0AEF9014648460AF0A2F80DF0DAFCFB +:1048E0006968208040460AF0A3F929698146384664 +:1048F0000AF09EF9014648460AF092F8E9698146B5 +:1049000030460AF095F9014648460AF089F80DF05C +:10491000C1FCA968608040460AF08AF9696980464E +:1049200038460AF085F9014640460AF079F8296AC6 +:10493000074630460AF07CF9014638460AF070F81E +:104940000DF0A8FCA080BDE8F88300BFC4110020D2 +:104950003800002090070020074B084A1B78128877 +:104960009A4207D3064A1268907898428CBF00207A +:104970000120704700207047C0050020E00D002096 +:10498000BC05002010B5194B93F84820511C83F842 +:104990004810174902F007024878164903EB420312 +:1049A00031F81010A3F84A1000231846124A9A5AF8 +:1049B00002331044102B80B2F8D1C0080AF0E4F89A +:1049C0000E490AF035F90E490AF0E6F90D4B044696 +:1049D0001B6818780AF0D8F8014620460AF028F932 +:1049E0000AF012FB084B187010BD00BFC411002064 +:1049F00078070020880700200E1200203333534030 +:104A000000F07F45BC050020C0050020034B1B685B +:104A1000DA79511CD9711344187A70476006002066 +:104A200010B5FFF7F3FF0446FFF7F0FF04EB00209B +:104A300080B210BD10B5FFF7F3FF0446FFF7F0FF9B +:104A400004EB004010BD0B4AA2F13003197A8142F9 +:104A50000BD00C339342F9D1074B197A014004D1A2 +:104A60000C339342F9D1084603E018460BB158685D +:104A7000704770479400002064000020002305491F +:104A8000DAB2595C814203D001330C2BF7D11A46BC +:104A900010467047036B01082DE9F0478278C6780D +:104AA0001E4BC2F1640802EB820C54425FFA88F894 +:104AB0004FEA4C0CC6F16409A4B203F11807A5B281 +:104AC00028B2002804DC002D14BF1546012500E0A3 +:104AD000454600FB00FA6D430AFB06FA9AFBF5F522 +:104AE0004D4468434FF00A0A90FBFAF0604480B2EC +:104AF00058800D88B1F802A000B2C5EB0A0A00FB8D +:104B00000AF04FF47A7A90FBFAF0054423F8025F3A +:104B10000A34BB42A4B2D2D1BDE8F087060F002010 +:104B200010B544780078002303FB03F11939614381 +:104B300001F6C4115943414340F6C41291FBF2F10E +:104B4000034A22F813100133072BEDD110BD00BF2B +:104B5000F00E002010B5044C2068FFF7E1FF20683C +:104B60000249BDE8104097E798050020FC2000208E +:104B700010B5094A094913688C6812689342F8D144 +:104B8000074A106811684FF47A725043001BB0FB5B +:104B9000F1F002FB030010BD2820002010E000E02F +:104BA0006007002038B5124B124C9968124B1A68F6 +:104BB0001D465288114203D0FFF7DAFFE06511E08D +:104BC000FFF7D6FFE36D98420CD9C01A0B4B3B227E +:104BD000B0FBF2F01B68B0F5967FC8BF4FF0FF3016 +:104BE00003B118602B685A68054B5A6138BD00BF85 +:104BF000000C0140C4110020E0030020DC03002071 +:104C00000004014038B5104C0123054684F84030BB +:104C1000FFF7AEFF236E41F28832C31A93426366F8 +:104C200084BF002384F8683094F86830EDB20F2B0D +:104C30002066E55403D1054B01221A7038BD024AA3 +:104C4000013382F8683038BDC411002040010020D3 +:104C500010B50446FFF78CFF0D4B41F28831DA6E38 +:104C6000D866821A8A421A6784BF002283F87420A9 +:104C700093F87430074A142BD45403D1064B012205 +:104C80001A7010BD024A013382F8743010BD00BFA3 +:104C9000C4110020050200200402002010B50446C3 +:104CA000FFF766FF164A936F9067C31AB3F57A6FE2 +:104CB00084BF002382F87C3092F87C3023B9A82C82 +:104CC0001CD110490B7006E0022B02D10E490C706A +:104CD00001E0242B01D80D49CC540133DBB282F81A +:104CE0007C30094A127852000532934206D1044BB7 +:104CF000002283F87C20034B01221A7010BD00BFF4 +:104D0000C41100209C010020C20100209D01002050 +:104D100038B50446FFF72CFF124B40F6C411D3F808 +:104D20008020C3F88000821A8A4284BF002283F860 +:104D3000842093F884200AB90F2C11D10A4800214D +:104D4000017052B1094D182A154405F8014C04D1DF +:104D5000012283F88410027038BD013283F8842068 +:104D600038BD00BFC41100204101002042010020D5 +:104D700038B50446FFF7FCFE0546FFF7F9FE401B79 +:104D8000A042FAD338BD10B504462CB14FF47A7066 +:104D9000FFF7EEFF013CF8E710BD08B5014B1B68BB +:104DA000984708BDDC2700202DE9F04106460F4654 +:104DB00090460025EBB2434518D20024E3B2B3423B +:104DC0000FD20B4B0120DA68013482F00802DA605E +:104DD000FFF7E3FF3846FFF7D6FF0020FFF7DDFFC0 +:104DE000ECE73C20FFF7CFFF0135E3E7BDE8F081BA +:104DF000000C014040F2DB14604308B50D4B10225B +:104E00005A6108221A61841E0A4B2046DA6882F031 +:104E10001002DA60DA6882F00802DA60FFF7B3FFA6 +:104E20000120FFF7BAFF1920FFF7ADFF0020FFF7C1 +:104E3000B4FFE9E7000C014008B503685B699847D7 +:104E400008BD08B503681B69984708BD08B5036825 +:104E5000DB68984708BD08B503689B68984708BD9C +:104E600008B503685B68984708BD10B5044C206816 +:104E7000FFF7F6FF18B12068FFF7EDFFF6E710BD6A +:104E80004806002008B503681B68984708BD064B14 +:104E900010B5044621461868FFF7F4FF034B1B6862 +:104EA0009A7954409C7110BD640600206006002071 +:104EB00038B5044624200D46FFF7E9FF4D20FFF7E3 +:104EC000E6FF002C084C0CBF3E202120FFF7DFFF3F +:104ED0002368002228469A71FFF7D9FF236893F8C8 +:104EE0004900BDE83840D2E76006002001460020B6 +:104EF000DEE7F8B50E4E0F4C0F4DC1B207463068D5 +:104F000084F88510FFF7BEFF2B6894F885109A7916 +:104F100030684A409A71C7F3072184F88510FFF77B +:104F2000B1FF2B6894F885109A794A409A71F8BDC0 +:104F300064060020C411002060060020F8B51B4D57 +:104F40001B4C1C4F0646C1B2286884F88610FFF738 +:104F500099FF3B6894F886109A7928684A409A71BC +:104F6000C6F3072184F88610FFF78CFF3B6894F89E +:104F700086109A7928684A409A71C6F3074184F8E6 +:104F80008610FFF77FFF3B6894F886109A792868AF +:104F90004A409A71310E84F88610FFF773FF3B6820 +:104FA00094F886109A794A409A71F8BD64060020F8 +:104FB000C41100206006002010B5441E14F8011F23 +:104FC00021B1034B1868FFF75DFFF7E710BD00BF85 +:104FD0008C1C0020014B186854E700BF60130020B0 +:104FE000014B014618684DE71820002010B5044613 +:104FF0007F2C06D964F07F00C0B2FFF7F1FFE4090F +:10500000F6E7E0B2BDE81040EAE7430083EAE0706B +:10501000ECE770B5104E114C114D4720FFF7E0FF43 +:105020003078FFF7E3FF23682868C01AFFF7EDFF29 +:1050300063686868C01AFFF7E8FF0A4B1888FFF733 +:10504000D5FF094B1888FFF7D1FF337823742B68FD +:10505000A3606B68E36070BDD0050020C01C002019 +:10506000DC050020CE050020CC050020014B18688F +:1050700008E700BF18200020A0F17D03012B70B5C8 +:1050800004460D460A4E05D830687D21FFF7FAFE2A +:1050900084F0200430682146FFF7F4FE35B12B88F8 +:1050A0001C4404EB142404F0FF042C8070BD00BFEA +:1050B0007006002038B5054C05465E212068FFF7D4 +:1050C000E1FE20682946BDE83840DBE6B005002057 +:1050D000014B5E211868D5E6B005002010B50A4CDA +:1050E0005E280146206805D15D21FFF7CBFE2068D0 +:1050F0003E2105E05D2903D1FFF7C4FE20683D2174 +:10510000BDE81040BEE600BFB005002010B5044663 +:10511000C0B2FFF7E3FFC4F30720BDE81040FFF77C +:10512000DDBF064B1B6803EBC00090F90630194247 +:105130000CBF01204FF0FF30704700BFA41E0020BD +:105140000A4B1A6802EBC002D379FF2B07D008493B +:105150000978994203D9074A32F8130004E0072876 +:10516000D4BF908840F2DC5000B27047A41E0020EB +:10517000630A00201A07002010B5054C0020218882 +:1051800005F015FC61880120BDE8104005F00FBC5A +:10519000120000202DE9F04F0C68836889B0D0F828 +:1051A00000A0D0F804800646204603938B460DF0FD +:1051B0003BF8074620460DF0ABF8DBF8044081468B +:1051C00020460DF031F8054620460DF0A1F8DBF839 +:1051D00008200446104601920DF026F8019A8346F5 +:1051E00010460DF095F839460290584609F020FD1A +:1051F00039460490029809F01BFD5946059048462F +:1052000009F016FD02990690484609F011FD29465D +:105210000790584609F00CFD0146504609F008FD7C +:1052200021468346069809F003FD0146059809F0DA +:10523000F7FB0146404609F0FBFC0146584609F0E1 +:10524000EFFB21468346049809F0F2FC01460798DB +:1052500009F0E4FB0146039809F0EAFC01465846D0 +:1052600009F0DEFB3060029905F1004009F0E0FC36 +:105270000146504609F0DCFC21468346079809F0B8 +:10528000D7FC0146049809F0C9FB0146404609F0E5 +:10529000CFFC0146584609F0C3FB214683460598DA +:1052A00009F0C6FC0146069809F0BAFB01460398CE +:1052B00009F0BEFC0146584609F0B2FB2146706079 +:1052C000504609F0B5FC2946044609F1004009F0B2 +:1052D000AFFC0146404609F0ABFC0146204609F010 +:1052E0009FFB39460446284609F0A2FC0146039874 +:1052F00009F09EFC0146204609F092FBB06009B01F +:10530000BDE8F08F2DE9F84F2E4E04463768384639 +:105310000CF08AFF054638460CF0FAFF76688046A6 +:1053200030460CF081FF834630460CF0F1FFD4F894 +:10533000049006462946484609F07AFCA76882464A +:105340004146384609F074FC0146504609F066FBB8 +:1053500021688246584609F06BFC4146044648469F +:1053600009F066FC314609F063FC0146204609F06D +:1053700057FB31460446384609F05AFC294609F0E5 +:1053800057FC0146204609F04BFB014650460DF004 +:105390004DF80D4909F04CFC0C4909F0FDFC0C4B93 +:1053A000196809F03DFB0B4909F0F6FC0CF072FF9F +:1053B00083B21A0444BF00F5B4739BB218B2BDE8BF +:1053C000F88F00BFCC0400200000E144DB0F49400F +:1053D0000408002000002041064B1B7803F0040362 +:1053E00003F0FF001BB1044B1888C0F3C01000F09D +:1053F00001007047D62700205402002007B5064B55 +:1054000006480093064B074A1968074B06F0BAFC9A +:1054100003B05DF804FB00BF04630108D362010818 +:10542000C4000020EF620108FB62010810B50748C4 +:10543000FFF7C2FD0024064B0648E218E158526807 +:105440000C3406F09FFCFC2CF5D110BD0C63010858 +:10545000185401082263010837B58288044683681E +:1054600010060D4606D529494FF4E07091F85417FF +:1054700000FB0133D10504D525490A20097800FB3A +:10548000013302F03F02042A12D006D8012A0DD0BF +:10549000022A2FD193F900102DE0102A0AD0202AD9 +:1054A0000AD0082A26D1B3F9001024E0197822E0A6 +:1054B000198820E019681EE06946186806F0F2FDB8 +:1054C0000146144806F05EFCF5B1E06809F05CFBAB +:1054D000694606F0E7FD01460F4806F053FC2069D7 +:1054E00009F052FB694606F0DDFD01460A4806F068 +:1054F00049FC09E00021094806F044FC25B10848B0 +:10550000E168226906F03EFC03B030BD2C2000208B +:105510003C0E0020316A0108306A01086E710108F2 +:105520002A6301082DE9F041002407462546114B66 +:105530003946E65804EB030830460CF0C3FC58B17A +:105540000D48314606F01EFC40460021FFF784FF5F +:105550000A4806F017FC0135143440F604339C4227 +:10556000E5D125B90648BDE8F041FFF725BDBDE806 +:10557000F08100BF58550108A06401085B63010871 +:10558000316301082DE9F74F04460CF05FFC054636 +:1055900020B1012819D123782A2B16D15648FFF7BC +:1055A0000BFD0024554B5648E618E15806F0EAFB7F +:1055B00030462946FFF750FF5248FFF7FDFC1434F0 +:1055C00040F604339C42EDD192E020463D210CF0A0 +:1055D00030FC002800F08780034613F8012C202AB5 +:1055E00001D1013BF9E7451C2846C4EB030A0CF046 +:1055F00082FC8346284604F08DFE002605461423CF +:105600007343DFF8F89053F8097003EB0908384644 +:105610000CF01CFC03461A462046394601930CF058 +:105620001DFC019B002855D15FFA8AF29A4251D1A4 +:10563000D8F80C0009F0A8FA0146284609F0AAFC9F +:10564000002845D0D8F8100009F09EFA01462846F7 +:1056500009F096FC00283BD0B8F804309B064FF0C8 +:10566000140303FB0696B28858BF5D46140629460C +:10567000B36806D524484FF4E07490F8540704FB4F +:105680000033D00504D521480A24007804FB0033F8 +:1056900002F03F02042A0BD004D8013A012A0CD8A8 +:1056A00019700AE0102A05D0202A05D0082A04D152 +:1056B000198002E0196000E01D603946144806F0C8 +:1056C00061FB3046002103B0BDE8F04FFFF7C4BED8 +:1056D000104803E001368D2E91D10F4803B0BDE88C +:1056E000F04FFFF769BC204603B0BDE8F04F19E763 +:1056F00003B0BDE8F08F00BF4963010858550108A9 +:10570000A06401085B6301082C2000203C0E0020EF +:105710005E63010869630108316301082DE9F04304 +:1057200089B004460CF092FBC6B2002E6CD18B48B7 +:10573000FFF742FC8A4C2069002109F00DFC40BBB8 +:1057400001368848314606F01DFB206904A906F0A1 +:10575000A9FC0146844806F015FB606904A906F01F +:10576000A1FC0146804806F00DFBA06904A906F0E3 +:1057700099FC01467C4806F005FBE06904A906F0A7 +:1057800091FC0146794806F0FDFA0C2E04F1100454 +:10579000D1D10025764C2F462B464FF00008B0455E +:1057A00004F1100415DA184654F8101C09F038F901 +:1057B00054F80C1C8146284609F032F954F8081CAC +:1057C0000546384609F02CF908F101084B46074612 +:1057D000E5E76848019302950397FFF7EDFB002486 +:1057E00001ABE058644920F0004009F0DDFB634B59 +:1057F000634A0434002814BF10461846FFF7DCFB48 +:105800000C2CEDD15F4891E020465F4905220CF059 +:1058100025FB38B9524B002203441030C0281A61CE +:10582000F8D197E02046594904220CF017FB0646B0 +:105830002046002E40D120210CF0FBFA002800F079 +:105840008980451C28460CF001FB34468046504BAD +:1058500053F824600EB94F4868E0284631465FFA95 +:1058600088F20CF0FBFA671C20BB3D4B0021C218EC +:105870001030C02811619C46F7D1474B002403EB40 +:10588000C702D2F804E09846BEF1000F04D14348A5 +:10589000314606F077FA55E018F837309C42F6DAD0 +:1058A00023010CEB0305103573440FCB013485E85D +:1058B0000F00F1E73C46CAE70CF01DFB461E0B2E1D +:1058C000074643DC204620210CF0B3FA054640B1E0 +:1058D000451C284604F01EFD214B3F01D8510124F0 +:1058E00000E00446284620210CF0A3FA054640B10A +:1058F000451C284604F00EFD194B013403EB06133A +:105900005861284620210CF094FA054640B1451C08 +:10591000284604F0FFFC124B013403EB0613986198 +:10592000284620210CF085FA18B91D48FFF744FBE2 +:1059300010E0013004F0EEFC094B032C03EB0616DB +:10594000F061F2D11748FFF7E9FE03E016480C2199 +:1059500006F018FA09B0BDE8F08300BF91630108B2 +:105960002C200020BC630108C263010825630108E4 +:1059700040200020C66301080AD7233C8D6301083C +:10598000896301085B630108D5630108DB630108D3 +:1059900068530108E063010804450108F563010844 +:1059A000056401080D6901083F6401087FB50446DC +:1059B0000CF04CFA082824D100231F49E25C096846 +:1059C0001144497801F00301022908BF203AE2544A +:1059D0000133082BF1D10025665D184831460CF0E3 +:1059E00028FA28B10135601931460CF022FA18B1B5 +:1059F0001348FFF7E1FA1CE0082DEDD1204606F030 +:105A000039FB1048FFF7D8FA00230F4A04A91A44BB +:105A100092F810210A440949595C0133082B02F815 +:105A20000C1CF2D10023094801A98DF80C3006F0B6 +:105A3000A9F904B070BD00BFC8000020AA6E01081B +:105A400067640108876401082C2000202563010891 +:105A500070B5064600240B4BE518AA8816420AD0FA +:105A6000E158094806F08EF928460021FFF7F4FCBA +:105A70000648FFF7A1FA143440F604339C42EAD1F9 +:105A800070BD00BF585501089C6401085B630108A4 +:105A90002DE9F04F624C23686249581C0A78894608 +:105AA00002F0FF0C0AB10346F6E7277A667AA57A78 +:105AB000E1682360E0461FFA88F213B21F2B00F35F +:105AC0009380594901EB8300C278807831F8231024 +:105AD000C0F1FF0080B2002861D0C0F1FF00504348 +:105AE0003C23B1FBF3FA0012BAF1050F5AD8DFE8F4 +:105AF0000AF0030B1A283846161A4E43C5B2B6FBF5 +:105B0000F3F62E44F6B248E0B1FBF3F703FB1717A8 +:105B1000BFB2C5B2C7F13C07101A4743B7FBF3F752 +:105B20002F44164629E0B1FBF3F503FB1515C7B268 +:105B3000ADB2101A4543B5FBF3F53D44EDB2164640 +:105B400030E0B1FBF3F603FB1616B6B2C7B2C6F1EE +:105B50003C06101A4643B6FBF3F63E441546F6B231 +:105B600020E0B1FBF3F703FB1717C6B2BFB2101A60 +:105B70004743B7FBF3F737441546FFB212E0B1FBDA +:105B8000F3F503FB1515ADB2C6B2C5F13C05101A0D +:105B90004543B5FBF3F53544EDB2174602E0154633 +:105BA000164617464FEA072A4AEA064A4AEA050A0B +:105BB0001723012199400CF1170211EA0A0FC3EBD8 +:105BC00002021A490CBF0920112092B213F1FF33CF +:105BD0008854EED20CF1180C08F101081FFA8CFC65 +:105BE0001FFA88F8124966E7012389F80030114B43 +:105BF000E28040F22A3227726672A572E160A4F850 +:105C000004C05A600C4A00219184118889B241F085 +:105C1000010111801A6842F001021A60BDE8F08F9C +:105C20004C120020CA27002098060020A80A002055 +:105C3000541200206C000240000400400D4B02781A +:105C4000D9684378C943C1F30221C1F1040103FAC1 +:105C500001F1094B0901C9B21A4482F80013027814 +:105C60000120510902F01F0200FA02F243F821203C +:105C7000704700BF00ED00E000E100E00C4B07B50D +:105C80001B68196819B10B4A9069014391619A88A0 +:105C90009868ADF8042002228DF8072004220DEB4D +:105CA00002018DF8062004F08DFE03B05DF804FBC0 +:105CB000C40700200010024010B50A4C23681BB135 +:105CC000FFF7DCFF00232360074B1B7813B1012B88 +:105CD00003D010BD4FF4006201E04FF48052034B3B +:105CE0001A8010BDC4070020C90700200000002052 +:105CF000134B026810B51C68D1430C401C605C68F3 +:105D00002140596019680A431A6002689C68D143AF +:105D10000C409C60DC682140D9604179102906D193 +:105D2000996811439960D9680A43DA6010BD01F19E +:105D3000804303F5823319680A431A6010BD00BF1F +:105D400000040140254B10B55343254A254C1268E9 +:105D50000139B2FBF3F20388013AA04289B292B250 +:105D60009BB212D004F50064A0420ED0B0F1804F77 +:105D70000BD0A4F59834A04207D004F58064A0426B +:105D800003D004F58064A04202D123F070039BB2DB +:105D9000154CA04206D004F58064A0421CBF23F439 +:105DA00040739BB203800F4B8185984202850FD0D0 +:105DB00003F5006398420BD003F54063984207D087 +:105DC00003F58063984203D003F58063984201D1C4 +:105DD000002303860123838210BD00BF40420F00D1 +:105DE000A4000020002C014000100040284BF0B51A +:105DF0001D6800222748165C1418AB19597801F069 +:105E0000040101F0FF0371B10132102AF2D1002028 +:105E1000F0BD1BB103EB83035B00DBB210F8012B79 +:105E2000303A1344DBB2221A022AF2DC0021844207 +:105E30000AD919B101EB81014900C9B210F8012B4F +:105E4000303A1144C9B2F2E72E2E14D1601C002260 +:105E50000424067802EB8202AF197F7852007F0794 +:105E600092B203D5303A3244013092B2013C14F080 +:105E7000FF04EED100E000220748062441436420DD +:105E800000FB02120548B2FBF4F200FB0320F0BD58 +:105E9000C80000200310002040420F0080969800A8 +:105EA00030B5002213460D495C5C9CB12E2C04D108 +:105EB000013378B11C1800250D550A246243C95CD2 +:105EC000A1F13004092C9CBF303A52180E2B03D894 +:105ED0000133E8E7104630BD002030BD031000203C +:105EE0000FB407B504AB53F8042B00200449019309 +:105EF00005F082FE03B05DF804EB04B0704700BF0C +:105F00006D5000080EB40FB505AB53F8042B01908B +:105F1000064901A8039305F06FFE019B00221A7049 +:105F200004B05DF804EB03B0704700BFB19E0008F9 +:105F30002DE9F0438DB005460BF088FFC0B2002874 +:105F400058D104467F4B00211E68142207A80BF08D +:105F50003CFFA500002303A905A803930593771927 +:105F60000B7183801A46DFF8F0E1B7F802C03EF803 +:105F7000138018EA0C0F0CD00EF10A0E0DF1300848 +:105F800013F80EE002F1010C424402F824EC5FFA2F +:105F90008CF20133052BE6D100231A46DFF8C0E16D +:105FA000B7F802C013F80E8018EA0C0F0CD00EF1EF +:105FB000060E0DF1300813F80EE002F1010C424418 +:105FC00002F81CEC5FFA8CF20133062BE6D1735D0C +:105FD0008DE803001A0907A85B4903F00F03FFF7D8 +:105FE00091FF2146594807AA013405F0CBFE202C29 +:105FF000A8D1A3E028460BF07EFF1F28044600F33B +:10600000918028462021E4B20BF013FF1F2C01D908 +:106010004F4888E04B4B471C1B68002103EB84046E +:10602000204604220BF0D1FE00254A4B07AE304635 +:1060300000210A2215F803905FFA85F80BF0C5FEDF +:106040000023FA5CF91832B10A2B04D04A4502D079 +:10605000F2540133F5E74A4501F1010767D1B8F180 +:10606000020F0DD0B8F1030F0CD0B8F1010F0BD017 +:1060700030460BF040FF2378C0B243EA00100AE03C +:10608000002219E0002226E030460BF034FF23788E +:1060900000F00F001843207038E00133062B0AD0BF +:1060A0002D4800F115069E5D8E42F6D10344D97B42 +:1060B00063880B43638001320CA9D3B20B4413F8FD +:1060C000141C19B30023EBE7412B1DD0542B08BF40 +:1060D00004230ED00132D3B20DF13008434413F83B +:1060E000143C9BB1492B01D1002302E0572B07D16F +:1060F0000123194931F8131063880B436380E9E7E2 +:10610000462BE1D10223F4E70323F2E70135042D06 +:106110008BD1012404F0A0FA04F0DAFA04F0B4FA06 +:1061200064B975E70D48202105F02CFE06E02046F5 +:10613000002104220BF049FE0024EBE70DB0BDE87E +:10614000F08300BF94060020A6640108B264010831 +:10615000BE640108714D0108564D0108CC64010868 +:10616000654D01082DE9F04FAE4E85B03778032F0D +:1061700014D9AD4BAD48B3F90410B0F9042000298F +:10618000B8BF49426FF063035B1A9A4204DB01F126 +:1061900064039342A8BF134683801FE0012F1DD8DC +:1061A000A34BA44C1B78013B142B00F2E181DFE8E8 +:1061B00013F09100DF01DF0168009F00DF01DF01C4 +:1061C0002F01DF01DF01DF01DF01DF01BD00DF01A2 +:1061D000DF01DF01DF01DF01A101B801924B964928 +:1061E000B3F806A0914B0968B3F80280B3F80090A9 +:1061F000B3F904B0914C02910025BD4204F11004A2 +:10620000CED20FFA8AF008F0BFFC54F8101C08F048 +:106210000FFD03460FFA88F0019308F0B5FC54F81F +:10622000081C08F005FD019B0146184608F0F8FB24 +:1062300003460FFA89F0019308F0A6FC54F80C1CF1 +:1062400008F0F6FC019B0146184608F0E9FB029AAB +:10625000034692F90000019340420BFB00F008F066 +:1062600093FC54F8041C08F0E3FC019B014618461B +:1062700008F0D6FB08F0A2FE714B23F8150001359B +:10628000BBE702210420FEF74CFF684D0121AF88D7 +:1062900078431FFA80F80420FEF743FF6D8800FB67 +:1062A00005801FFA80F80420FEF74AFF4044208151 +:1062B00002210520FEF735FF7843012187B2052032 +:1062C000FEF72FFF00FB057087B20520FEF738FFB1 +:1062D00038440BE005200121FEF723FF534B9D8836 +:1062E000684385B20520FEF72BFF284460813FE11B +:1062F000544B00201D68FEF723FFDFF8648195F9F9 +:106300000630B8F902203227534393FBF7F31844C1 +:1063100020800120FEF714FF95F90E30B8F9002017 +:10632000534393FBF7F73844608021E1464B1B78D9 +:1063300013F0040F454B02D11B689B880BE01968D2 +:10634000394A0B88B2F9062049889A4203DB914208 +:10635000B4BF0B461346E381E289394B394F1A80AB +:106360003B4B1B681D7845B30220FEF7E9FE3A68F7 +:10637000B2F91030518A984203DB0BB29842B8BF91 +:106380000346344909684889C3EB000E324B0FFAC3 +:106390008EFE19880FFA81FCF44501DA0D4401E004 +:1063A00001DD4D1B1D8092F91620B3F900305343D7 +:1063B000642293FBF2F31844A080284B1B88DB0572 +:1063C0000CD5194B1A88D7F80090E28022819A8860 +:1063D000184F62815B880325A38101E0134BF1E72D +:1063E00009EBC50393F90630B7F90680284608FB88 +:1063F00003F8642398FBF3F8A7F80680FEF7A0FEE5 +:1064000001354044072DF88007F10207E8D1AFE0DD +:106410000D4B1B7813F0040F0C4B23D11B689B888A +:106420002CE000BFE127002062020020F0120020D3 +:10643000A005002012000020A405002088090020EB +:10644000A4270020A41E0020D6270020AC1E002078 +:10645000B01E0020B41E00205C1200205402002058 +:10646000A80300201968AD4A0B88B2F906204988B4 +:106470009A4203DB9142B4BF0B461346E381E289A3 +:10648000A74BA84D1A80A84B03201B880121DF05CC +:1064900003D5FEF746FEA14F02E0FEF742FEA34FF2 +:1064A000B7F80280022100FB08F01FFA80F90320F0 +:1064B000FEF737FE3F88012100FB0790E8800420AB +:1064C000FEF72FFE00FB08F002211FFA80F80420DF +:1064D000FEF727FE00FB078028810320FEF730FE31 +:1064E000E3881844E0800420FEF72AFE238918443C +:1064F00020813DE001210420FEF713FE8B4D6F88C3 +:10650000784387B204202781FEF71AFE38442081A1 +:1065100001210520FEF705FE2D88684385B26581BF +:10652000E0E6824B0325B3F8049098462846022102 +:10653000FEF7F7FD00FB09F0012187B22846FEF7C0 +:10654000F0FDC5F106035B0838F8133000FB03705B +:1065500087B224F815702846FEF7F2FD384424F877 +:1065600015000135072DE1D16C4BDA886C4B1A8090 +:106570006F4DDFF8E491AB6813F0200F34D00020AA +:10658000FEF7DEFD208080460120FEF7D9FD694B35 +:10659000644F1B6860801A0626D5674B1B681B7802 +:1065A00013F0020F654B23D0D9F800C0B3F90010E7 +:1065B0009CF90E209CF906C0B3F902304A43CCF195 +:1065C000000C03FB0CF3322192FBF1F26FF0310C63 +:1065D00092B293FBFCFC9444E04493FBF1F1A7F8E6 +:1065E00000800A4410447880D9F80010002319E094 +:1065F000D9F80010B3F902C091F90620B3F90030C0 +:106600000CFB02FC32229CFBF2FCE044A7F8008069 +:1066100091F90E104B4393FBF2F2E3E7E25202339F +:10662000102B0CD0E05E31F9232001EB8307904260 +:106630007F88F3DB3AB28242A8BF0246EEE73E4BC8 +:106640001B681B785B0704D435493478088801231C +:106650001BE03B4B00241F780423043FFFB25FFA8A +:1066600087F84FFA88F2D4420BD4364A03F1010975 +:10667000381932F813105FFA89F9C0B204F097F9AB +:106680004B460134042CECD1DEE7A34208D231F9A9 +:10669000132000B28242A8BF104680B20133F4E753 +:1066A000294B4FEA44081A68AB6803F480550395F8 +:1066B000244D03F01009254BB5F90660244D1B78D5 +:1066C0002F68244D03F00403DBB2D5F800C0029319 +:1066D0000023434562D0B2F802A004B2544505DD60 +:1066E0000F4CC0EB0A0A1D5B55441D53039D0C4C17 +:1066F000002D33D07D8931F903A0AE42CBBFBCF869 +:1067000002509588B2F802B0BCF800B0AA4503DB8D +:10671000DA45B4BF55465D46E55238E062020020D6 +:10672000A42700201200002054020020F0120020B4 +:106730002C20002050020020B81E0020A8030020BA +:106740000F0800201A070020AC1E0020D6270020CA +:10675000B41E0020A81E0020A41E002031F903A0B2 +:106760001588B2F802B0AA4503DBDA45B4BF554636 +:106770005D46E55204EB030ABC89A64207DAB9F18B +:10678000000F01D1148800E09488AAF80040029C10 +:1067900014B9044C1C5BCC5202339AE705B0BDE837 +:1067A000F08F00BFDC0F00202DE9F04F8E4C8BB036 +:1067B0002378023B042B00F25983DFE813F0070033 +:1067C0002C0005009A00D50010267CE0874B1A6843 +:1067D000874B1B6864339A4240F248831026854DEC +:1067E000854B2A689846985C2F4638B1FEF7F8FB2F +:1067F0002A68013E02F101022A60F0D13B6818F8D4 +:106800000330002B40F0328303222270794A136058 +:106810007A4A53602AE3774D794B2E6893F80080CB +:10682000052E3FD8744FC8F1080807EB8603586E51 +:106830000BF00CFB002E14BF022309236F4E08FB44 +:106840001308746873680F33A34202DA444527D1F2 +:106850000AE04445FADA2B6807EB83035B6E185DA8 +:10686000FEF7BEFB0134EDE7664B5B79012B08D0E8 +:106870000A20FEF7B5FB2B6801332B600023736001 +:10688000F4E22C20FEF7ACFB2B6807EB8307FC6FD0 +:10689000013C14F8010F0028EAD0FEF7A1FBF8E74D +:1068A0007460E3E2574B9B681A064CBF0423052330 +:1068B0002370002356E0FEF793FB2A68013E02F1A5 +:1068C00001022A6009D04B4D4B4B2A6898461A4466 +:1068D00092F894002F460028EDD13B68434493F88A +:1068E0009430002B40F0C28205222270414A13608E +:1068F000BCE2404D2B68072B30D8DFE803F00408DA +:106900000B111D22272B4048FFF7EAFA28E03F48E9 +:106910003F490EE03F484049404AFFF7E1FA1FE097 +:10692000384B0A2193F854273D4801FB023393F872 +:106930005617FFF7D5FA13E0324B3A48B3F8D010A8 +:10694000F7E7304B3848B3F8D210F2E7374B384806 +:10695000D968EEE7374B38481988EAE706232370F1 +:106960002B6801332B6081E2344D354B2C681B685A +:106970002360344B1A6862605A689B68A260E360C7 +:10698000314B1A6822615A689B686261A3612F4B80 +:106990001A68E2615A689B68226263622C4B1A880B +:1069A00022855A8862859A88DB88A285E385294BEF +:1069B0001A8822865A889B886286A386264B1A8864 +:1069C000E2865A889B8822870D4A638711780023C4 +:1069D00091468B4244DA214804EB430230F813001D +:1069E00001339087F5E700BFE20D0020282000204A +:1069F000B41C0020B81C0020784D01085C12002057 +:106A0000E12700202C200020EE6401080B6501081E +:106A10000463010823650108EF620108FB620108B5 +:106A20003A6501084765010859650108EC03002033 +:106A30006B650108000000207E650108D41C002061 +:106A4000BC270020F812002004130020101300209F +:106A500062020020F4040020B4040020A4270020D7 +:106A6000D14BD24F5B89D7F80080A4F85E3018F084 +:106A70001F03019340F087804920FEF7B1FA386880 +:106A8000FEF7B4FA2068FEF7B1FA6068FEF7BDFAC7 +:106A9000A068FEF7BAFAE068FEF7B7FA2069FEF7D9 +:106AA000B4FA6069FEF7B1FAA069FEF7AEFAE069E0 +:106AB000FEF7ABFA206AFEF7A8FA606AFEF7A5FABD +:106AC000B4F92800FEF7A1FADFF8F082B4F92A0041 +:106AD000FEF79BFAB4F92C00FEF797FAB8F8D0301D +:106AE000B4F92E000126C01AFEF780FAB4F930007E +:106AF000FEF78BFAB4F93200FEF787FAB4F93400E6 +:106B0000FEF783FAB4F93600FEF77FFAB4F93800DD +:106B1000FEF77BFAB4F93A00FEF777FAB4F93C00D5 +:106B2000B8F8D030C01AFEF761FA99F800309E42EA +:106B30000ADA04EB4603B3F93C00B4F93C30013601 +:106B4000C01AFEF762FAF0E798F80530012B06D17B +:106B50002B68B3F95E00A0F2DC50FEF756FA2B6802 +:106B6000934A94496B60AB609B1A9B104B43032183 +:106B7000013393FBF1F101EB41015B1A642101FB4D +:106B800003222A606FE150206E68FEF729FAAA6896 +:106B90002B6810681B684FF0000B18446B681B686B +:106BA000A0EB4300FEF731FA04EB0B0206EB0B03FC +:106BB00050685B680BF1040BC01AFEF726FABBF1B4 +:106BC0000C0FF1D14FF0000B04EB0B0206EB0B03A3 +:106BD00010691B690BF1040BC01AFEF716FABBF122 +:106BE0000C0FF1D14FF0000B04EB0B0206EB0B0383 +:106BF000D069DB690BF1040BC01AFEF706FABBF192 +:106C00000C0FF1D10023E218B2F92810F218B2F9F2 +:106C100028208A1A02A941F813200233082BF2D146 +:106C2000654B0DF1180E03F1100C18685968724687 +:106C300003C2083363459646F7D105AA01A800238D +:106C400052F804199B00DBB271B101F1080EBEF1DC +:106C50000F0F02D843F0010306E08031FF2994BFF3 +:106C600043F0020343F003038242E9D10AA901EB96 +:106C7000131203F00F030B4412F810BC13F8103C6E +:106C80004FF0000A43EA0B1B5FFA8BFB5846FEF7F6 +:106C9000A7F90BF00302022A16D0032A1AD0012A00 +:106CA00026D10AAB03EB8A0252F8200C52F81C1CC6 +:106CB00000F00F0040EA0110C0B2FEF791F90AF1AE +:106CC000010A4FEA9B0B13E00AA901EB8A0212F8B2 +:106CD000200C0BE00AAB03EB8A0252F8202CD0B256 +:106CE0000092FEF77DF9009AC2F30720FEF778F9CB +:106CF0000AF1010ABAF1030F4FEA9B0BC9DD4FF00D +:106D0000000B2A680BF1180332F913006A680BF1C3 +:106D1000010B32F91310AA6832F9133002220B4426 +:106D200093FBF2F3C01AFEF770F9BBF1030FE8D141 +:106D30004FF0000B2A680BF118035B001A44B2F9FC +:106D400006006A680BF1010B1A44B2F90610AA6832 +:106D50001344B3F9063002220B4493FBF2F3C01A3A +:106D6000FEF753F9BBF1030FE4D14FF0000B99F894 +:106D700000309B4524DA2A680BF11C035B001A449F +:106D8000B2F904006A680BF1010B1A44B2F904105D +:106D9000AA681344B3F9043002220B4493FBF2F3C4 +:106DA000C01AFEF732F9E2E712000020BC1C0020F6 +:106DB000E01C0020295C8FC2194F01082C20002004 +:106DC0002C4B5A799946012A06D1B4F95E00B6F9DE +:106DD0005E30C01AFEF719F96B682A68AB60264B63 +:106DE00026496A60D21A92104A430321013292FB6B +:106DF000F1F101EB4101521A642101FB02332B60D6 +:106E0000D9F808301B062ED51D4C1E4D22682B6864 +:106E10009A4209D162686B689A4205D1019A0F2A99 +:106E200010D118F47E6F0DD14820FEF7D9F82068F4 +:106E3000FEF7EBF86068FEF7E8F823682B606368FC +:106E40006B600EE0104A0F4B11782A7C914208D1FA +:106E50000E4A99681068884203D15268DB689A42EA +:106E600001D0FEF7D6F83B6801333B600BB0BDE8BC +:106E7000F08F00BF2C200020E01C0020295C8FC276 +:106E80004C0E0020C01C0020D0050020DC05002096 +:106E9000642928BF6421F8B501FB00F7642497FB3F +:106EA000F4F40546E4B20026F3B2A34204D29F20D4 +:106EB00000F082F90136F7E7AC420BD2142097FBC1 +:106EC000F0F0C4EB84136638C4EB83031844C0B2FB +:106ED00000F072F90134E4B2AC4238BF9A20F7D323 +:106EE000F8BD0F4B10B50446185C00F065F90D4B6A +:106EF00033F91430B3F57A7F05DBB3F5FA6FA8BF29 +:106F00004FF4FA6301E04FF47A73A3F57A730A221F +:106F100093FBF2F10920C9B2BDE81040B8E700BF09 +:106F2000AA6E01081A07002010B5441E14F8010FBC +:106F300010B100F041F9F9E710BD00BF2DE9F04FA5 +:106F4000012828BF0120142101FB00F389B0DFF8DC +:106F5000BCB101900BEB03025BF803706548019B29 +:106F6000654E0760F469037110691589B2F80A90DB +:106F70002043546849EA0508F0610222C4F81080F1 +:106F800020468DF80E1003A9ADF80C808DF80F2067 +:106F900003F018FD4FF0080AA268154203D10A2039 +:106FA000FDF7E6FEF8E70A206561FDF7E1FE2561E1 +:106FB0000A20FDF7DDFEBAF1010AEDD10A20C4F87E +:106FC0001490FDF7D5FE0A206561FDF7D1FE0A2079 +:106FD0002561FDF7CDFE0222C4F8109020468DF801 +:106FE0000F2003A91C228DF80E20ADF80C8003F0B1 +:106FF000E9FC424A9742326905D142F400123261FB +:107000004FF4001004E042F4800232614FF480003B +:1070100005F058FABA8803A822F440721204120C40 +:10702000BA803A88012592B242F001023A80BC88C7 +:1070300005F0FEF924F03F04059831492404B0FB23 +:10704000F1F1240C0C43A4B2BC803A88142322F042 +:1070500001021204120C3A802A4A0024B0FBF2F218 +:107060004FF49670414392B24FF47A70002A91FB2C +:10707000F0F108BF0122013142F4004289B23984A3 +:10708000BA833A8803A892B242F001023A803A8861 +:1070900022F4816222F002021204120C3A804FF4B0 +:1070A00080423A81019A8DF80D4003FB02B77B7B49 +:1070B0008DF80E408DF80C308DF80F50FEF7BEFDA8 +:1070C0003B7B9DF80F208DF80C308DF80D408DF82E +:1070D0000E401AB103A8FEF7B1FD07E0590903F00D +:1070E0001F039D40084A203142F8215009B0BDE8F5 +:1070F000F08F00BF641200200010024000540040D6 +:1071000040420F00804F120000E100E02C4F0108C8 +:1071100008B5054B1A88013292B21A80034B1879D0 +:10712000FFF70CFF002008BD281400206412002087 +:1071300013B51E4B4000C0B2587102AC186899716B +:1071400004F8012D00210122DA71DC6019721C6142 +:107150001A755A75997538B38288920515D40288C4 +:10716000D4050DD447F230520188890502D5013A81 +:10717000FAD112E08AB1028892B242F4807202809F +:10718000828892B242F44072828047F23052597D36 +:1071900011B1013AFBD100E012B9FFF7B9FF03E0EA +:1071A000024B987D80F0010002B010BD64120020F7 +:1071B000024640213C20BBE770B50A4E00EB800040 +:1071C00006440024331913F8A00C074B01341D7832 +:1071D0006840FFF7EDFF052CF4D12846BDE870406C +:1071E000E6E700BF544F0108E02700200246802157 +:1071F0003C209DE710B5AE20FFF7F8FFD420FFF745 +:10720000F5FF8020FFF7F2FFA820FFF7EFFF3F20F8 +:10721000FFF7ECFFD320FFF7E9FF0020FFF7E6FFC1 +:107220004020FFF7E3FF8D20FFF7E0FF1420FFF77A +:10723000DDFFA120FFF7DAFFC820FFF7D7FFDA2034 +:10724000FFF7D4FF1220FFF7D1FF8120FFF7CEFF19 +:10725000CF20FFF7CBFFD920FFF7C8FFF120FFF7C2 +:10726000C5FFDB20FFF7C2FF4020FFF7BFFFA420D0 +:10727000FFF7BCFFA620FFF7B9FFAF20FFF7B6FF6F +:10728000A620FFF7B3FFAE20FFF7B0FF2020FFF7E7 +:10729000ADFF0020FFF7AAFFB020FFF7A7FF4020B7 +:1072A000FFF7A4FF0020FFF7A1FF1020FFF79EFFCC +:1072B0004FF48064013C0020A4B2FFF779FF002C5A +:1072C000F8D18120FFF792FFC820FFF78FFFBDE8BC +:1072D0001040AF208AE708B55038C0B2FFF786FFEC +:1072E0000020FFF783FFBDE8084010207EE77720ED +:1072F000482101221CE777205821012218E7064B7C +:10730000002193F82020054B920134321970772028 +:10731000F42102F0FC020BE7E0070020142000201B +:10732000034B00221A707720F4212E2200E700BFC1 +:107330001420002010B5174C23681BB1FEF79EFCEB +:10734000002323606B2180226820FFF7F1FE642078 +:10735000FDF719FD192100226820FFF7E9FE6B21D6 +:1073600003226820FFF7E4FE372102226820FFF79E +:10737000DFFE094B1A211A786820FFF7D9FE1B217E +:1073800018226820FFF7D4FEBDE8104068201C21B9 +:107390001022CDE6C40700203900002008B51920CE +:1073A000FDF7F1FC682015210022FFF7C1FE10B99E +:1073B0000320FDF71FFD0C4B16211A78682042F0C0 +:1073C0001802FFF7B5FE172100226820FFF7B0FE74 +:1073D0003D2101226820FFF7ABFEBDE80840682090 +:1073E0003E210122A4E600BF3A00002013B500228E +:1073F0002A211C20FFF79CFE0E2102221C20FFF7F1 +:1074000097FE0F2103221C20FFF792FE2B21122250 +:107410001C20FFF78DFE164B02249A69154842F096 +:1074200004029A612023ADF8043004230DEB03011C +:107430008DF806308DF8074003F0C4FA22462C215F +:107440001C20FFF775FE2D2101221C20FFF770FE86 +:107450002E2100221C20FFF76BFE2A2105221C2072 +:10746000FFF766FE044B4FF480721A8002B010BD25 +:1074700000100240000801400000002008B50F2164 +:1074800008221820FFF754FE0E2218201021FFF7C3 +:107490004FFE024B4FF480521A8008BD00000020BE +:1074A00008B5134B53201B782D2108227BB1FFF721 +:1074B0003FFE31210A225320FFF73AFE2C210C22F5 +:1074C0005320FFF735FE53203821902209E0FFF7C3 +:1074D0002FFE31210A225320FFF72AFE53202C21B0 +:1074E0000A22FFF725FE034B40F209121A8008BD5D +:1074F000C80700200000002010B540001C4CC0B29E +:107500006071A17101200021E17120722275607506 +:1075100020682361E360A17540B383889B0515D47F +:107520000388D9050DD447F230530288920502D55D +:10753000013BFAD112E08BB103889BB243F4807314 +:10754000038083889BB243F44073838047F23053B7 +:10755000627D12B1013BFBD100E01BB9BDE81040D8 +:10756000FFF7D6BD024B987D80F0010010BD00BF33 +:107570006412002037B50622044603216B461E2004 +:10758000FFF7BAFF9DF801309DF80000154D43EA62 +:10759000002000B207F0F8FA296807F049FB07F06D +:1075A0000DFD9DF8033020809DF8020043EA002085 +:1075B00000B207F0E9FAA96807F03AFB07F0FEFC11 +:1075C0009DF80530A0809DF8040043EA002000B239 +:1075D00007F0DAFA696807F02BFB07F0EFFC608030 +:1075E00003B030BD3C00002007B5002101AB0322F1 +:1075F0007720FFF781FF9DF805009DF80430000219 +:1076000040EA03409DF80630184303B05DF804FBE0 +:1076100008B5FFF7E9FF014B986108BD641200202F +:1076200008B5FFF7E1FF014BD86108BD64120020E7 +:10763000104B13B51B78104C13B9238C01332384E2 +:1076400001ABF62103227720FFF756FF9DF80530A6 +:107650009DF804201B0243EA02439DF806201343D1 +:10766000064AB2F92020C2F10802D340636202B098 +:1076700010BD00BF1420002064120020E00700208D +:107680000B4B13B51B780B4C13B9238C013323849C +:1076900001ABF62102227720FFF72EFF9DF8042090 +:1076A0009DF8053043EA0223238502B010BD00BFD8 +:1076B000142000206412002013B5062204466B46F5 +:1076C0003B216820FFF718FF9DF800209DF801304E +:1076D00043EA022323809DF802209DF8033043EA09 +:1076E000022363809DF804209DF8053043EA0223BD +:1076F000A38002B010BD13B5062204466B46432199 +:107700006820FFF7F9FE9DF800209DF8013043EA5C +:10771000022323809DF802209DF8033043EA0223D0 +:1077200063809DF804209DF8053043EA0223A3807E +:1077300002B010BD07B52320FDF725FB6820752199 +:1077400001220DF10703FFF7D7FE28B19DF80700CE +:10775000B0F168035842584103B05DF804FB13B51B +:107760000222044601AB1B216820FFF7C5FE9DF8ED +:1077700004209DF8053043EA022303F54E534FF4ED +:107780008C72103393FBF2F32333238002B010BDCD +:1077900013B5062204466B461D216820FFF7ACFE98 +:1077A0009DF800209DF8013043EA022323809DF8D4 +:1077B00002209DF8033043EA022363809DF80420F1 +:1077C0009DF8053043EA0223A38002B010BD13B533 +:1077D000062204466B4601211C20FFF78DFE9DF812 +:1077E00001309DF800209DF8021043EA022242F386 +:1077F0008D02042392FBF3F222809DF8032042EADB +:10780000012242F38D0292FBF3F262809DF8041094 +:107810009DF8052042EA012242F38D0292FBF3F328 +:10782000A38002B010BD13B5062204466B460221A8 +:107830001820FFF761FE9DF800309DF801209B089D +:1078400003EB022323809DF802309DF803209B0860 +:1078500003EB022363809DF804309DF805209B080C +:1078600003EB0223A38002B010BD2F4B2DE9F3419F +:107870001B780546002B39D0002426462746A04613 +:1078800008226B4653203221FFF736FE9DF8012077 +:107890009DF80030013403EB02231BB29DF8032056 +:1078A00098449DF80230E4B203EB02231BB21F445C +:1078B0009DF805209DF80430202C03EB02231BB219 +:1078C0001E449DF8073003F07F0301D0002BD7D171 +:1078D000164B98FBF4F897FBF4F796FBF4F6A5F833 +:1078E00000806F80AE8083F82A401AE006226B4643 +:1078F00053203221FFF700FE9DF801209DF8003053 +:1079000003EB02232B809DF803209DF8023003EB4C +:1079100002236B809DF805209DF8043003EB0223C1 +:10792000AB8002B0BDE8F081C807002064120020DF +:1079300013B5224C23689A8A92B20192019A12F4EA +:10794000706F1CBF0122A275019A12F4E06F29D05A +:107950001A8B9A8822F480621204120C9A80019A7F +:1079600091051FD41A8892051CD41A88D0050ED50B +:107970001A88D105FCD41A8892B242F400721A8097 +:107980001A889205FCD42079FFF7D8FA0AE01A8801 +:1079900092B242F400721A809A8822F44072120461 +:1079A000120C9A802268938A23F470631B041B0CC8 +:1079B00093820023637502B010BD00BF64120020E3 +:1079C000954B2DE9F74F1B78013B012B00F22081ED +:1079D000924B1E78864240F01B81914B1B78022B04 +:1079E00000F016818F4B904D13F806808F4B83F873 +:1079F00000808F4B1A7801921AB18E4B33F9160022 +:107A000007E08C4A2B6832F9160003F100432B6023 +:107A1000404207F0B9F8884907F0BEF9DFF838A20C +:107A20000446DAF800B00021584607F095FA00271E +:107A3000DFF82C92002859D0D9F800B020465946DA +:107A400007F0B2FA68B17D4B2A687B491A60C9F821 +:107A50000040204607F0ECF807F0B0FA784BD880E9 +:107A6000BDE05846394607F09FFA002800F0B7807D +:107A7000744B1A78002A31D12046296806F0CEFFCF +:107A80004FF07E5107F072FA6F4C28B160686F4971 +:107A900007F0CEF860600FE06D49606807F0C8F845 +:107AA000DFF8CCA18346514607F060FA10B9C4F85C +:107AB00004B001E0C4F804A0624A01231370654BCE +:107AC00000221B68C9F8007043449A72019A82F040 +:107AD0000103574A1370604B1F6080E05F4BCAF888 +:107AE00000401A68554BFA325A6078E020465946F1 +:107AF00007F03CFA48B1584A4F491460204607F055 +:107B000097F807F05BFA4E4BD880534BD9F80090AA +:107B1000D3F800A04846514606F080FF4F4B8346FD +:107B20001968464B5A688A1A002A0BDA4FF07E51C0 +:107B300007F03AFA002852D02046514607F034FAAE +:107B400000284CD03D4A4846116807F02DFA3E4CBB +:107B500038B120683E4907F06BF83C492060A068C6 +:107B600007E058464FF0804107F01EFA28B1A068A0 +:107B7000374907F05DF8A06004E02068334907F05A +:107B800057F82060334B2C492068D3F8009007F059 +:107B90004FF807F039FA09F80800A06807F034FA3E +:107BA000019AC84482F00103214A88F81400137036 +:107BB000294B1F602A4B1F60224B1A780132D2B228 +:107BC000032A01D01A700AE000221A701E4B2549C0 +:107BD000586807F02DF807F017FA88F80A001EB960 +:107BE000174B1A8864321A80114A13780BB11E4B56 +:107BF00000E01E4B2B600F4B33F9160006F0C4FF5C +:107C00000D4907F0C9F80146286806F007FF00E0B3 +:107C1000084603B0BDE8F08F040500205805002099 +:107C20006805002048440108080500206905002077 +:107C300059050020A80300200000204190120020D8 +:107C40006E1400205A0500206C0500200AD7833FDF +:107C5000EC51783F640500205C05002028200020BE +:107C60006005002000007A440000A0410000A0C18F +:107C70006F12833A10B50848FDF79EF9074B1C6850 +:107C80002046FDF7DEF818B90A20FDF77CF8F7E783 +:107C9000034A044BDA6010BD516801088C1C0020B7 +:107CA0000400FA0500ED00E008B50748FDF784F987 +:107CB000064A002313729363054A137005F076FE9B +:107CC000BDE80840FFF7D6BF5D68010890120020AC +:107CD000D027002008B50448FDF76EF903F00CFA30 +:107CE000BDE80840FFF7C6BF896801082DE9F04FDD +:107CF000002487B0074604919246059380462546A6 +:107D0000022DDFF888914FEA450607D104984379A0 +:107D1000B9F904001B3343435B1148E0524B39F976 +:107D2000151033F9153003EB4101CAF100039942F4 +:107D300003DB5145B4BF0B4653464C49059A31F914 +:107D400006B0915FCBEB030303EB010BFDF744FBA4 +:107D500098B1474B58465B5D039306F015FF4549C4 +:107D600007F01AF8039B01461846FFF729FE414920 +:107D700006F05EFF07F022F983463F4B1988C807DB +:107D800011D404988A07037939F9060003F11B031B +:107D900000FB03F34FEA231309D57A7C02FB0BFBAC +:107DA00003EB2B2303E0FB7903FB0BF31B11334A9B +:107DB00098F80AB0905F042290FBF2F0181A7B5DED +:107DC0002F4A4343DB1101932E4B01351988A358E9 +:107DD00001FB00FC4FEAEC2C0BFB0C33DFF8B0C0CE +:107DE000B3F5001FA8BF4FF400136345B8BF634647 +:107DF000A3504FEA633C244B0909E258E050821A31 +:107E00004FF6FF70B0FBF1F14A4303F10C0003F1B0 +:107E1000180B215854F80B90921189442250CDF838 +:107E20000890914498F8142044F80B1002FB09F1D3 +:107E300001980912084403F1240260449053019808 +:107E400003F12C02A050032D03F1380203F1440387 +:107E500044F802C0E15008F1010804F104047FF481 +:107E60004FAF07B0BDE8F08FD2270020A803002055 +:107E7000D45101080000204154020020F4040020E5 +:107E8000D80E0020FC040020CC120020620200204A +:107E90000000E0FF2DE9F04F89B00793994B06925F +:107EA000B3F90220B3F90030002AB8BF5242002BC8 +:107EB000B8BF5B4200249A42B8BF1A4603900592AD +:107EC0002646A04627460494A3462546DFF860923E +:107ED000B9F8003099075AD0022D58D0894BDDF8F7 +:107EE00018C0F25E884BF35E03EB4202CCF1000354 +:107EF0009A4203DB63469A42B8BF1346834ADDF8D1 +:107F00001CC036F902A03CF90620CAEB030303EBC0 +:107F1000020AFDF761FA90B17D4B504615F803B0A7 +:107F200006F032FE7B4906F037FF01465846FFF760 +:107F300047FD784906F07CFE07F040F8824603983A +:107F40006423C2796FF0040102FB0AF292FBF3F2A0 +:107F5000C37E01FB03FB5A4505DB03EB83039A4217 +:107F6000B4BF93469B466C4A42F21071A3585344E7 +:107F70008B42A8BF0B4669498B42B8BF0B46039999 +:107F8000A35091F811A00AFB03F31B130493B9F853 +:107F9000003003F00302012A01D1022D3DD1594ADC +:107FA0005F49B75E895F039A81EAE170A0EBE170F7 +:107FB00012F805C05B4AB0F5206F54F802801DDC52 +:107FC000022D15D05020784390FBFCFC042091FB3F +:107FD000F0F1C1EB0C0CE0445348B8F57A5FA8BF50 +:107FE0004FF47A588045ACBF42F80480105107E046 +:107FF00087EAE770A0EBE7706428E3DD0021115108 +:10800000484AA1587D2291FBF2F8039A2A44927AB9 +:1080100002FB08F8402298FBF2F89A0716D5022DC9 +:1080200014D0059BDDF814C0C3F5FA720CFB08F000 +:108030007B43DDF810C002FB0B3302FB0C024FF454 +:10804000FA7193FBF1F392FBF1F208E0DB0701D543 +:10805000022D02D142463B4601E0049A5B4630497C +:10806000DFF8D0A0715A4FF0040C0FFA81F915F81F +:108070000AA099FBFCF00AFB00F06FF04F0A90FB9E +:10808000FAF01844294B019036F903A0F152CAEBDB +:10809000090999FBFCF903F1140A03F1080C54F8DF +:1080A0000C0054F80A1044F80C90DFF88CC001441E +:1080B00015F80CC0494402910CFB01F14FF0200C63 +:1080C00091FBFCF144F80A000198C1EB0209A3F10D +:1080D0002C0C814426F80C900135A3F1240C44F8B3 +:1080E0000C004942A3F11800032DA3F10C03225008 +:1080F000E15006F1020604F104047FF4E7AE09B092 +:10810000BDE8F08F62020020D2270020A8030020E3 +:10811000D451010800002041400E0020F0D8FFFF9C +:10812000F4040020D80E002080C1FFFF1C130020A3 +:1081300054020020FE0E0020040F00202DE9F04F15 +:1081400089B007937A4B814618880491059206F00E +:1081500017FD784906F06CFD002403904F46254634 +:108160002646022EDFF80CA20BD10499BAF90400BE +:108170004B790A33584306F007FD6F4906F00CFEB1 +:1081800044E06E4B3AF90520EB5E05991A444B42E8 +:108190009A4203DB0B469A42B8BF1346684AAA5E6E +:1081A0009B1A079A505F184406F0EEFC654906F0EA +:1081B000F3FD8046FDF710F928B1634B4146985D09 +:1081C000FFF7FEFB8046614B1A88D10705D5404674 +:1081D000D9F8441006F02CFD18E004993AF905008E +:1081E0000B7901921433584306F0CEFC524906F045 +:1081F000D3FD019A8346930709D5D9F84810404624 +:1082000006F016FD0146584606F00AFC8346504A21 +:10821000505F06F0B9FC4F4AD16806F009FD82466E +:108220005146584606F0FAFB396A804606F000FDD2 +:10823000DFF844B106900399404606F0F9FCF96A6C +:1082400006F0F6FC54F80B1006F0EAFB42498046B3 +:1082500006F08CFE38B94046404906F0A5FE20B134 +:10826000DFF8F88001E0DFF8F0804BF80480DFF8F9 +:108270000CB1504654F80B1006F0D0FB44F80BA09C +:10828000034603994FF07E50029306F085FD029B52 +:108290000146184606F0CCFC0BF10C03E2580BF13A +:1082A000180B54F80B10824610460192029306F008 +:1082B000B7FB514606F0B4FB019A029B44F80B2031 +:1082C00044F803A0264906F067FDB96B06F0B0FC40 +:1082D0002449824606F04AFE38B95046224906F043 +:1082E00063FE20B1DFF880A001E0DFF878A00698F7 +:1082F000414606F095FB514606F090FB09F0CAFF97 +:108300001A4BB0F57A7FA8BF4FF47A709842B8BF85 +:1083100018460136164B032EE85204F1040405F109 +:10832000020507F104077FF41CAF09B0BDE8F08F28 +:10833000FC040020BD37863500004842D2270020CB +:10834000A803002000002041D4510108540200205D +:10835000F4040020EC03002000007AC300007A43FC +:1083600000004040000096C30000964318FCFFFF49 +:10837000F012002062020020E40E00203C130020D6 +:1083800010B50446204609F061FD10F0FF0F06D13C +:108390000C4B0D481978BDE8104003F0F3BC2046A3 +:1083A00009F0A9FD02280CD8064B0A221870074BC9 +:1083B000074C02FB0030074B06301860FCF7CAFB85 +:1083C000E0E710BD3C0E0020906801087C270020EB +:1083D0000D690108980500202DE9F047734A86B021 +:1083E00013789146DFF8D881C3B90122D8F800107C +:1083F00089F800206E4A1A445068884203D00C3332 +:10840000302BF7D10022022353726A4B6A48C3F81B +:10841000D010FCF7D1FD6948FCF7CEFDD8F800007C +:10842000FCF71EFD002800F0BE80654B614C18680B +:10843000FCF711FD0928014601D03F284FD14FF02C +:10844000000AA56B5F4F56462DB15F4839682A4632 +:1084500009F004FD10B9BA4606B93E465B4B0C372D +:108460009F42F1D3CEB13768DAF800E02B46F85CD2 +:108470001EF80310814201D0A3630EE05A1C41B9DB +:108480002D2B06D8A2632344202022441872117297 +:1084900003E04D4958541346E9E7A36B0BB1564529 +:1084A00012D04B48FCF788FD564509D856F80C0BFE +:1084B000FCF782FDD8F800000921FCF7E3FCF3E7A4 +:1084C0003E48FCF779FD0025A36B9D42A6D23E4BAA +:1084D000D8F80000595DFCF7D5FC0135F4E7A36B33 +:1084E00033B904283BD104F10800FFF7DDFB5AE063 +:1084F0000C2801D137488CE70A2901D00D2949D130 +:108500003548FCF759FDA36BE21800231372227A59 +:10851000232A17D00493314B2B4E009303A82949EB +:1085200015220C23039609F0EAFC054638B10068D1 +:1085300009F08CFC0130AB683044984702E02848D1 +:10854000FCF73AFD20480021302209F03EFC0023D0 +:10855000A36399F80030002B7FF45DAF23E00C2873 +:10856000C8D07F2903D159E72F2B3FF657AFA1F190 +:108570002002D2B25E2A3FF651AF13B920293FF450 +:108580004DAF5A1CA263D8F800001C442172FCF7BE +:1085900079FC43E77F29E7D1013BA3630022234411 +:1085A0001A72104838E706B0BDE8F087D0270020DF +:1085B0006400002090120020A1680108D968010819 +:1085C0008C1C002018540108981200201455010832 +:1085D000DE680108E36801085B630108794600086A +:1085E000EE6801080A6901082DE9F04FD84AD94C14 +:1085F00085B01068516802AB03C3DFF89083002197 +:108600004FF4EF62204609F0E0FB04F50573C8F86B +:108610000030D14B0025DFF878A31D7004F25673AB +:10862000CAF80030032363710223A36040F24C4078 +:108630004FF41673A4F8F030A4F81C01FA2340F2AA +:108640006C70A4F8F230A4F81E012A231920A4F8B3 +:10865000EE3084F825014FF4FA7340F27E40A4F81E +:10866000F630A4F8D000202340F23A7084F8F430B9 +:10867000A4F8D2006E234FF47A7084F80431A4F881 +:10868000D4002B2340F27E5084F80531A4F8D600A4 +:10869000212340F2EA500126552240F2DC514FF0EE +:1086A0001E0B4FF0320984F80631A4F8D8004FF4BD +:1086B000C87340F2B4502270A4F80831A4F81A111B +:1086C000A4F8DA00A4F8DE3084F8EC6084F821B174 +:1086D00084F8246184F82761A4F8DC90A4F8E09081 +:1086E0008DE8060003F0A6FC40F6AC53A381D8F851 +:1086F000003028271720A57318761F7183F80EB055 +:108700005F7183F80FB058761D700B20019A1872B4 +:10871000142058721875502098776420D8774FF03D +:10872000080E782083F813E05873DFF868C28B488E +:108730004FF00E0E9A7183F80AE02D224FF05A0E78 +:108740004FF00A0B1A745A7783F80BE01F73DA752F +:1087500083F821609D7683F807905D74DD769D74C3 +:108760001D7783F815B0C3F824C0D86318644FF0A0 +:108770008240D8624FF07C5098637948C3F828C093 +:108780005864784A7848DFF810C200991A635A632F +:108790009864C3F84CC084F856E74FF0410EA4F833 +:1087A0005E1784F857E784F85A5784F85B5784F8C3 +:1087B000589784F8595784F85C579A666B4A042195 +:1087C000DA666B4A83F858101521D86583F8607013 +:1087D00083F861701A6783F87460A3F85450A3F8A3 +:1087E0005650A3F8525083F86410624803F042FCDC +:1087F000D8F800304FF44872A3F86221C82283F8F9 +:10880000A7214FF49662A3F8A82140F2D932A3F829 +:10881000AA2140F6430283F85F7183F86061A3F8F0 +:10882000AC2183F85D5183F85E5183F8645183F87D +:10883000A6B11A46474656464FF47F71A2F8661114 +:108840004FF4FA61A2F8681102A840F2DC51A2F8D4 +:108850006A11415D013582F86C11082D4FF0FF015E +:1088600082F86D1102F10802E6D1012283F8AE21EF +:1088700083F8AF2183F8B021C82183F8B6216422A0 +:10888000A3F8B211A3F8B82114214FF4967283F81B +:10889000B411A3F8BA211E21282283F8B511A3F838 +:1088A000BC210023E21810330021C02B1161F9D143 +:1088B00031480021402209F088FA00232F49E218AC +:1088C000595804330868382BC2F8D401F6D12C4823 +:1088D0000021802209F079FA2A4B294D03F1300E4C +:1088E000186859682A4603C2083373451546F7D1FC +:1088F000254D01F0B1FE01F0EBFE01F0C5FE3F6831 +:10890000284639464FF4E07209F056FA394605F523 +:10891000E0704FF4E07209F04FFA336805F56372C6 +:108920005968186803C2198911801A68C5F8962316 +:108930005A68C5F89A231B89A5F89E33012384F849 +:108940002434022384F8E43505B0BDE8F08F00BF7D +:10895000D65101082C2000203C0E00208FC2753D0E +:10896000CDCC4C3D9A99193F0000A040F6287C3FA1 +:108970003D0A773F0E690108002200209C4401084F +:1089800080210020DE51010800240020E80300209F +:1089900098050020000020400000404008B5054830 +:1089A000FCF70AFBFFF720FE02F0A6FBBDE808403B +:1089B000FFF760B917690108F0B5884C884A236849 +:1089C0009D8AADB2E9B211F0010F32D0198821F4BD +:1089D00000610904090C1980198889B241F4806189 +:1089E0001980002111707F4908787F49A8B150781B +:1089F00018B97E480078FF280FD1012050707C48BC +:108A00000078022804D1188880B240F400601880F1 +:108A1000097841F00101198202E1097801F0FE01B3 +:108A20001982724B1B78FF2B00F0FA80FF23137022 +:108A3000F6E08F073CD5BFF35F8F6D490878C0B271 +:108A4000012814D1674D2D788DB155787DB11988E5 +:108A500021F480610904090C1980BFF35F8F198B21 +:108A60001988907089B241F4007119801BE0188B4D +:108A7000BFF35F8F087802280BD15A48007840B1C5 +:108A8000507830B1198821F480610904090C1980EB +:108A9000C0E00978032906D15249097819B1517803 +:108AA000002940F0B780998889B241F48061B6E02E +:108AB0004E075BD5012191704A49097800293AD0C7 +:108AC0005178002937D04A4910780978494D022950 +:108AD00019881ED921F480610904090C19801F8AA4 +:108AE0002E68C1B2FFB240B23754188880B240F449 +:108AF000007018808B1C1370236828681D8A013150 +:108B000049B2EDB24554998889B241F480619980A7 +:108B100027E089B241F4007119801E8A2D68C1B224 +:108B2000F6B240B22E541B8A481C40B2DBB203316D +:108B30002B54117015E0517811B92F49097841B1C2 +:108B4000198889B241F400711980137801331370C8 +:108B500007E0198889B241F480711980204B012106 +:108B6000597021680B88D805FCD459E001F0400108 +:108B700001F0FF061E48F1B11E49B3F810C00F689E +:108B800011785FFA8CFCCDB26E1C49B2F6B207F8D0 +:108B900001C01670077876B2F11C8F4205D1998812 +:108BA00021F480610904090C99800378B34237D11C +:108BB0000235157034E0290632D511784DB26F1C9C +:108BC0001ED00E4E01313668C9B2755D1170EDB21E +:108BD0001D82007849B2884222D11BE06412002035 +:108BE000641300206C120020691200206A12002019 +:108BF00078120020741200206B12002070120020E6 +:108C0000134916700978C9B219821249097809B94D +:108C1000017829B9998821F480610904090C9980A7 +:108C20000D4B92F9001018780C4B421C91420DD15B +:108C300000225A709B7833B12268938823F44073E2 +:108C40001B041B0C9380064B00221A70F0BD00BF62 +:108C50006A1200206C120020781200206413002099 +:108C60007912002070B5046D4279A38902F00401E5 +:108C700023F400531B041B0C0546866886B0A381B1 +:108C800001F0FF0021B14FF480604FF4005100E08B +:108C9000014612F0010F14BF0423002312F0020F4B +:108CA0001CBF43F008039BB212F0080F228A18BFC2 +:108CB0000C2392B222F4405211432182A28992B233 +:108CC00022F4B05222F00C02104303439BB2A38162 +:108CD000A38A01A823F440731B041B0CA38203F096 +:108CE000A7FB1949049A039B8C4208BF1346A2892B +:108CF0001921594312B2002AB4BF7600B600B1FB65 +:108D0000F6F16423B1FBF3F21201100903FB101119 +:108D1000A08900B2002806DAC9003231B1FBF3F3B2 +:108D200003F0070305E009013231B1FBF3F303F06F +:108D30000F031A4392B22B6D22819A8992B242F4A8 +:108D400000529A8106B070BD00380140417189E738 +:108D5000816087E7F8B50468054620460E46174649 +:108D600001F0E3FD032845D82B7B9B089AB246B956 +:108D70004FF0020C0CFA03F3A18989B221EA030334 +:108D8000A3810A2101FB00211B4B43F82160043120 +:108D900043F8217046B12A7B0225920805FA02F2B7 +:108DA000A1890A4392B2A281282202FB003000F17D +:108DB0002002EFF31286502383F312880023C11898 +:108DC0000D6915B115600A6904320433102BF6D110 +:108DD00000231360F3B283F31188036A23B1A389DC +:108DE0009BB243F0010304E0A38923F001031B04B9 +:108DF0001B0CA381F8BD00BFCC1E0020826A8169D4 +:108E0000436B1144D960416A914203D98A1A5A606E +:108E1000816204E001698A1A5A600022826200229B +:108E200080F844201A6842F001021A6070474B88AB +:108E300010B5DC0607D52D4B14791B6853F8244078 +:108E40002B4B43F820404B889B0607D5274B547982 +:108E50001B6853F82440264B43F820404B881C07DE +:108E60000DD5244B0C781B78B3EB141F07DB1F4B7D +:108E7000D4781B6853F824401D4B43F820404B889E +:108E80009B070DD51C4B0C781B78B3EB141F07DC2C +:108E9000164B54781B6853F82440154B43F8204078 +:108EA0004B88DC070ED5154B0C781B7804F00F04AB +:108EB0009C4207DC0D4B14781B6853F824400C4B84 +:108EC00043F820404B885B070ED50D4B09781B7883 +:108ED00001F00F01994207DB044B92781B6853F8AD +:108EE0002220034B43F8202010BD00BFA40A00201D +:108EF000980600204F0700204D0700204C07002057 +:108F00004E0700202DE9F74FA24F0C46FE7805468C +:108F10001146006891469B462246731CFB70FCF785 +:108F200011FFAB686868ADF8043018238DF806307F +:108F300001A902238DF8073001F044FD2B7B043793 +:108F4000360107EB060A2C680C2B00F2F280DFE8F2 +:108F500013F00D00F000F000F0004D00F000F00004 +:108F6000F0008200F000F000F000B600238C8A4888 +:108F700023F001031B041B0C2384218CA288238B68 +:108F8000844223F073034FEA03434FEA134389B249 +:108F900092B243F0700314D000F50060844210D008 +:108FA00000F5406084420CD000F58060844208D017 +:108FB00000F58060844204D021F0020141F00301F9 +:108FC00007E021F00E0122F4407241F0030142F467 +:108FD0008072A2802383A4F834B02184238B23F0F1 +:108FE00008031B041B0C43F0080332E0238C6A487F +:108FF00023F010031B041B0C2384218CA288238BD9 +:10900000844223F4E6434FEA03434FEA134389B211 +:1090100092B243F4E04308D000F50060844204D0EB +:1090200021F0200141F0300107E021F0E00122F4BD +:10903000406241F0300142F48062A2802383A4F8B0 +:1090400038B02184238B23F400631B041B0C43F4EE +:10905000006323836DE0238C4F4823F480731B044B +:109060001B0C2384218CA288A38B844223F07303DE +:109070004FEA03434FEA134389B292B243F07003BD +:1090800008D000F50060844204D021F4007141F45E +:10909000407107E021F4606122F4405241F44071D4 +:1090A00042F48052A280A383A4F83CB02184A38B15 +:1090B00023F008031B041B0C43F0080338E0B4F84A +:1090C00020C0354A2CF4805C4FEA0C4C4FEA1C4C13 +:1090D000A4F820C0B4F820C0A388B4F81C802CF4F5 +:1090E000005C28F4E6484FEA08484FEA0C4C4FEA87 +:1090F00018484FEA1C4C94429BB248F4E0484CF4A8 +:10910000405C03D002F50062944203D123F4804313 +:1091100043F48043A380A4F81C80A4F840B0A4F8D2 +:1091200020C0A38B23F400631B041B0C43F40063D7 +:10913000A383AB7B43B1B4F844306FEA43436FEA97 +:1091400053439BB2A4F8443023889BB243F00103FD +:1091500023802B7B0C2B14D8DFE803F007131313A9 +:109160000A1313130D131313100004F1340307E053 +:1091700004F1380304E004F13C0301E004F140038E +:10918000BB515046AAF80890CAF8044003B0BDE8A5 +:10919000F08F00BF64130020002C01402DE9F04740 +:1091A000054608F053FE2E4B0446D3F808809A4635 +:1091B00090B92C48FBF700FF2B4B53F8241049B112 +:1091C0000123A34013EA080F02D0284802F0DAFD79 +:1091D0000134F1E7264821E028462649224608F0D6 +:1091E0003DFE58B92448FBF7E7FE244C54F8041F11 +:1091F0000029EFD01D4802F0C5FDF7E72B780026C7 +:109200002D2B03BF013504F1FF344FF001094FF05E +:109210000009154B53F8267027B91948BDE8F047E7 +:10922000FBF7CABE28463946224608F017FEA8B901 +:109230000120B040B9F1000F03D001F098F91148B6 +:1092400004E040EA0800CAF808000F48FBF7B4FE43 +:1092500039460E48BDE8F04702F094BD0136D8E724 +:109260002C2000202D690108C45301084069010821 +:109270005B6301085470010844690108C053010888 +:1092800059690108706901087A69010825630108B4 +:109290002DE9F04F692887B0044600F0A78200F25C +:1092A00096802E2800F03A8562D8242800F00A859E +:1092B0002BD8202800F08282222800F0BE830128CB +:1092C00040F05D852C20FBF711FE0020FBF7DFFD51 +:1092D0002046FBF7DCFD0020FBF7D9FD4320FBF720 +:1092E000D6FD4C20FBF7D3FD4620FBF7D0FD4C20EC +:1092F000FBF7CDFD2046FBF7CAFD0020FBF7C7FDBD +:109300000020FBF7C4FD0024F0E0282800F0E284F0 +:1093100012D8262840F03385924C0320FBF7E6FD57 +:10932000B4F9E600FBF7E5FDB4F9E800FBF7E1FD71 +:10933000B4F9EA0000F034BC2A2800F0D6842C28C6 +:1093400040F01D85874C0720FBF7D0FD94F81801ED +:10935000FBF79DFDB4F91E01FBF7CBFDB4F91A0133 +:10936000FBF7C7FDB4F91C01FBF7C3FD00F0C3BC5C +:10937000642800F0E3801AD8322800F0BC840AD8B0 +:10938000302840F0FC84774C8020FBF7AFFD04F1DF +:10939000800500F0D9BC342800F06F83402840F0ED +:1093A000EE840820FBF7A2FD002400F0ADBC662887 +:1093B00000F09C81C0F0F080672800F0D081682820 +:1093C00040F0DD841020FBF791FD002406E27328B5 +:1093D00000F0BA8355D86D2800F01B8212D86B2894 +:1093E00000F0008440F2BB835F4C0620FBF77EFD5B +:1093F000B4F90000FBF77DFDB4F90200FBF779FD3D +:109400005A4B0EE26F2800F06782C0F00D82702880 +:1094100000F08182722840F0B284524C1620FBF793 +:1094200065FD0020FBF765FDB4F9D000FBF761FD99 +:109430004F4DB4F9D200FBF75CFDB4F9D400FBF753 +:1094400058FD2B68B3F9A801FBF753FD0020FBF78B +:1094500050FD0020FBF772FD2B68B3F952000A2380 +:1094600090FBF3F0FBF745FD94F80401FBF70FFDCB +:1094700094F80601FBF70BFD94F80501FBF707FDD7 +:10948000E6E3782800F0778110D8752800F0C982CB +:10949000C0F01483762800F0B783772840F06F84FB +:1094A000344D00242878FBF721FD42E3A42800F086 +:1094B000D18310D8A02840F062840C20FBF716FD61 +:1094C0002D4B1868FBF73AFD2C4B1868FBF736FD5F +:1094D0002B4B1868FBE3F02800F0E783FE2840F0F0 +:1094E0004E840820FBF702FD0024D6E3254B1B68C1 +:1094F000185D0134FBF7CBFC042CF7D1224B002480 +:109500001878FBF7F6FC214B185D0134FBF7BFFC24 +:109510000B2CF8D100241E4B185D0134FBF7B7FC6F +:10952000082CF8D10720FBF7B2FC0024194B185D7A +:109530000134FBF7ACFC072CF8D189E30720094C78 +:10954000FBF7D4FCE620FBF7A2FC6079FBF79FFC5D +:109550000020FBF79CFC94F82631002B0CBF042064 +:109560000C20B4E32C200020A8030020E0040020FD +:10957000E80300208A1C0020E8F7FF1FECF7FF1F1C +:10958000F0F7FF1FA8000020D7270020EF62010896 +:10959000FB620108046301080B20FBF7A7FCB64B34 +:1095A000B3F90000FBF7A5FCB44B188800B2FBF739 +:1095B000A0FCB34B1B68C3F3C000C3F38002800060 +:1095C00040EA4200C3F340021043C3F3401240EAB2 +:1095D000C20003F010031843FBF78BFCA94B1A8859 +:1095E00012F0010F0CBF0020022012F0020F0CBF7E +:1095F0000021042112F0040F0CBF0023102312F0ED +:10960000400F0CBF00242024019312F0100F9E4B3A +:1096100002940CBF00244FF4007412F0200F1B685A +:1096200003940CBF00244FF4806412F4807F0494F0 +:109630000CBF00244FF4006402F0080B03F4807A9E +:10964000059403F4805903F4005803F4004C03F428 +:10965000803E03F4003703F4802603F4002503F46E +:10966000801403F0C00343EA0B0343EA0A0343EA0E +:10967000090343EA080343EA0C0343EA0E0E834B53 +:109680004EEA07073E431B7835432C43C3F3800360 +:10969000234303430B430199029C0B430399234348 +:1096A000049C0B430599234312F4007F43EA010312 +:1096B0000CBF00224FF400121A43754B00201C7897 +:1096C0000346A3420CD273495D5C012101FA05F502 +:1096D000154218BF994003F1010318BF0843F0E792 +:1096E000FBF72CFC6C4B93F854070AE31220FBF7B2 +:1096F000FDFB6A4B6A4C1B88B3F5806F22D90025AD +:10970000605F082390FBF3F00235FBF7F2FB062DB8 +:10971000F6D1644CB4F90000FBF7EBFBB4F902009E +:10972000FBF7E7FBB4F904005F4CFBF7E2FBB4F98D +:109730000000FBF7DEFBB4F90200FBF7DAFBB4F93B +:1097400004002DE2B4F90000FBF7D3FBB4F90200EA +:10975000FBF7CFFBB4F90400FBF7CBFBD9E71020F4 +:10976000FBF7C4FB0024514B185D0134FBF78FFB62 +:10977000102CF8D116E23820FBF7B8FB00254C4E30 +:1097800005F12C043368E4002344B3F90600FBF729 +:10979000B0FB336801352344B3F90800FBF7A9FB9C +:1097A00033682344B3F90A00FBF7A3FB33681C4476 +:1097B000207BFBF76CFB082DE1D1F3E10820FBF7E0 +:1097C00095FB00243A4B1B6803EBC40393F86D012F +:1097D0000134FBF75CFB082CF4D1E3E1354B185D59 +:1097E0000134FBF754FB102CF8D1DBE1324D00249F +:1097F0002878400000F0FE00FBF778FB2B789C42B5 +:1098000080F0D0812D4B33F91400FBF772FB01344B +:10981000F4E70620FBF76AFB294B1868FBF78EFB81 +:10982000284BB3F90000BBE10720FBF75FFB264B99 +:109830004FF6FF741878FBF72AFB244B1868A042F8 +:10984000A8BF204620EAE07000B2FBF752FB204B95 +:10985000B3F90000FBF74DFB0F4B93F80C211D4BA8 +:1098600018680028B8BF40420AB10A235843A042F2 +:10987000A8BF204600B293E1FC0400202814002079 +:109880004C0200205402002050020020D627002065 +:109890008A1C0020741C00202C20002000000020C6 +:1098A000B4040020F40400207C02002012000020F8 +:1098B000E8030020A4270020630A00201A070020E4 +:1098C0005C020020C8030020C0050020C80500205D +:1098D000E60D0020C4050020B34C0720FBF706FB73 +:1098E00023681878FBF7D3FA23685878FBF7CFFA88 +:1098F00023681879FBF7CBFA23685879FBF7C7FA86 +:1099000023689879FBF7C3FA23689878FBF7BFFAC6 +:109910002368D878F5E1A54D1E20FBF7E7FA2B6800 +:1099200000241B78022B69D12B68A14903EB840327 +:10993000586A05F07DF908F0ADFCFA28A8BFFA20B6 +:1099400020EAE070C0B2FBF7A2FA2B68994903EB5A +:109950008403186B05F06CF908F09CFCFA28A8BF8A +:10996000FA2020EAE070C0B2FBF791FA2B68924926 +:1099700003EB8403D86B05F05BF908F08BFC6428DB +:10998000A8BF642020EAE070C0B20134FBF77FFA80 +:10999000032CC9D1072C2B681ED1986C844905F083 +:1099A00047F908F077FCFA28A8BFFA2020EAE0700F +:1099B000C0B2FBF76CFA2B687D49D86C05F038F91A +:1099C00008F068FCFA28A8BFFA2020EAE070C0B2CC +:1099D000FBF75DFA00200BE023441879FBF757FAF8 +:1099E0002B682344987BFBF752FA2B682344187E9C +:1099F0000134FBF74CFA0A2CCCD1D3E02B6823447A +:109A00001879FBF744FA2B682344987BFBF73FFA5D +:109A10002B682344187E0134FBF739FA0A2CEDD168 +:109A2000C0E02F20FBF762FA644C14F8010F002805 +:109A300000F0B880FBF72BFAF7E7A020FBF756FA07 +:109A400000245A4B04F11C021B680C2103EB820317 +:109A50005D1D5B4A5B79013401FB0323187AFBF738 +:109A600016FA6878FBF713FAA878FBF710FAE8788B +:109A7000FBF70DFA282CE4D194E04820FBF736FAE6 +:109A8000002506266E43494B06F588761B6801358E +:109A90001E44B07AFBF7FBF97079FBF7F8F9B0795F +:109AA000FBF7F5F9F079FBF7F2F9307AFBF7EFF90C +:109AB000707AFBF7ECF90C2DE3D173E00027012459 +:109AC0000025404B1B789D4222DA3F4BE95C002386 +:109AD0003B4A03EB02089A5C8A4204D00C33B3F58C +:109AE0008A7FF5D112E0D8F8040008F0AFF981467A +:109AF0000CB9264601E0074408E04E4506DAD8F8DE +:109B00000430985DFBF7C3F90136F6E70135D8E775 +:109B1000002C47D0F8B2FBF7E9F90024D0E7284A37 +:109B200099189A5C82420BD00C33B3F58A7FF6D138 +:109B300001342B789C4235D2234BE05C0023EEE7C6 +:109B4000087AFBF7A4F9F3E70820FBF7CFF9012423 +:109B5000E0B20134FBF79BF9092CF9D122E0102087 +:109B6000FBF7C4F9194B1A4C187800F00200FBF708 +:109B70008EF9184B1878FBF78AF92068FBF7DEF9A5 +:109B80006068FBF7DBF9144BB3F90000FBF7B1F9A0 +:109B9000124BB3F90000FBF7ACF9114BB3F902001B +:109BA000FBF7A7F90120EBE098050020E80300206F +:109BB000000020410000C84200007A440F52010812 +:109BC000704B01088A1C0020741C002082020020B7 +:109BD000DC050020D0050020CE050020CC050020AB +:109BE000281400200520FBF781F9674BB3F900002A +:109BF000FBF77FF9654BB3F90000FBF77AF9644B8B +:109C0000187800F001007CE0FAF700FF0646122009 +:109C1000FBF76CF90EB95F4B02E0102E03D15E4BDF +:109C20001D685C6801E0002425463046FBF72FF9EB +:109C30002846FBF783F92046FBF780F9574B186855 +:109C4000FBF77CF90020FBF754F90020FBF751F9F2 +:109C5000002056E0524D002428792E468000013025 +:109C6000C0B2FBF743F92879FBF711F933799C422D +:109C700098D24C4D285DFBF70AF905F11003185DE9 +:109C8000FBF705F905F12003185D3035FBF7FFF808 +:109C9000285DFBF7FCF80134E8E7434B185F02341A +:109CA000FBF727F9082CF8D17CE7404C0420FBF7A0 +:109CB0001DF92368B3F95600FBF71BF92368B3F9C4 +:109CC00054006DE70420FBF711F9394B9868FBF756 +:109CD00035F967E7364C0420FBF708F9B4F90801B9 +:109CE000FBF707F9B4F90A015AE70120FBF7FEF880 +:109CF0002F4B587905E00120FBF7F8F82C4B93F82F +:109D00002001FBF7C4F84DE7294B234493F81001D9 +:109D10000134FBF7BCF8082CF6D143E74020FBF7F1 +:109D2000E5F8234C04F14005B4F9D401FBF7E1F860 +:109D300094F8D601FBF7ABF8043494F8D301FBF7A1 +:109D4000A6F8AC42F0D12DE7B4F85601043400F087 +:109D50003F00FBF7CEF8B4F85201C0F38410FBF7D4 +:109D6000C8F894F850010009FBF791F894F85001F5 +:109D700000F00F00FBF78BF8AC42E5D112E70020B2 +:109D800007B0BDE8F08F00BF40060020420600206B +:109D9000F40F00204C0E0020580E00205802002026 +:109DA000281400202D1400206E140020E803002049 +:109DB0002C200020032810B50F4B0DD80F4A126835 +:109DC00094888C4208D2D2888A4205D9012202FAAC +:109DD00000F01A78104318701B780F2B0BD1064B2C +:109DE00000221A70064B998808B2142802DD143933 +:109DF000998010BD9A8010BD761400202420002088 +:109E00004C0A0020024B9A8801329A80704700BFAA +:109E10004C0A0020074B1A68074B1178B3F904006D +:109E200053780B4403EB83039842D4BF00200120F6 +:109E3000704700BF242000204C0A0020064BB3F9D5 +:109E40000400064B1B681B7803EB83039842D4BFC6 +:109E500000200120704700BF4C0A00202420002071 +:109E600010B50446FFF7EAFF002814BF2046002083 +:109E700000F0010010BD024B01221A72704700BFB2 +:109E80004C0A0020014B187A704700BF4C0A002092 +:109E9000034BB3F90400D0F1010038BF0020704734 +:109EA0004C0A0020014B00229A8070474C0A002087 +:109EB00003685A1C026019707047016B0346C26840 +:109EC00010B5406941B1196C541A005D013918BFD1 +:109ED0000A46C0B21A6410BD196A405C0131B1FB78 +:109EE000F2F402FB1412C0B21A6210BD026B0369D5 +:109EF0001AB15168013B026C02E0C169026A013B80 +:109F0000881A1840C0B27047436B13B190F84400F0 +:109F10007047826A436AD31A58425841704743795E +:109F20009B070AD5436A8269D154426A03690132A8 +:109F3000B2FBF3F103FB112343627047437913F043 +:109F4000010307D0C368C169026A013B881A18403F +:109F5000C0B2704718467047437910B513F001033B +:109F600004460DD0FFF7EAFF58B1226A6369985C96 +:109F7000E3680132B2FBF3F103FB1123236210BD4E +:109F8000184610BD426A806A131A584258417047F9 +:109F90004171704710F80A3C0133DBB20A2B00F81C +:109FA0000A3C0AD910F8123C23B910F8131C034AD2 +:109FB00022F81130002300F80A3C70474C190020A9 +:109FC000334A10B5136C90681944081A40F68C2374 +:109FD00098429160D060516013463CD9127893F951 +:109FE00045108A420BD1111F082908D893F8461052 +:109FF000182901D8013103E083F8442002E0002150 +:10A0000083F8461093F944108A421CD1204991F8F4 +:10A010004710C1B1002191421E4806DA03EB8104CA +:10A02000246920F811400131F5E7511E00EB410190 +:10A030001630814203D0002421F8024FF9E7164977 +:10A0400008780130087083F84520002201211A7039 +:10A0500083F8471010BD92F84710B9B1A0F2EF2471 +:10A0600040F2DA518C4208D811780B2905D80B1D23 +:10A070000131117042F8230010BD002283F84720FF +:10A08000991804320020302A0861F9D110BD00BFB0 +:10A09000100800204C190020281E0020024B1A6CCA +:10A0A000013211441964704710080020024B53F824 +:10A0B00020301B681980704738090020074BA1F534 +:10A0C0007A7153F820304FF47A701A681B894B4329 +:10A0D00093FBF0F39BB21380704700BF3809002058 +:10A0E0002DE9F04F504A514E1768738984463089E4 +:10A0F000A7EB032785B0039187FB0001B288CB1142 +:10A100001404C209F08842EA416287FB000114EBA3 +:10A11000020872884FF000054FEAC2344FEA10225D +:10A12000B08945EB030942EA01620B1287FB00018B +:10A1300014EB020A4FEAD05242EA41224FF00005E6 +:10A1400045EB030B12F5FA604FEAE15343F10001CE +:10A15000CDE90001B0F5FA6F71F1000147DAA2FB19 +:10A16000024502FB03F1052605EB4105A4FB0601B0 +:10A1700006FB05114D104FEA3004B8EB040869EBFB +:10A18000050984082A4844EA81748D104FF0FF3194 +:10A19000BAEB040A6BEB050BDDE9004584428D4107 +:10A1A00025DA40F6AC5012184FF0000143EB0103E2 +:10A1B00002FB03F1A2FB02236FF0060003EB410355 +:10A1C000544200FB0344A2FB000118EB00082144A9 +:10A1D0004FF00B0449EB0109A2FB040104FB03113E +:10A1E00049104FEA3000BAEB000A6BEB010B114B40 +:10A1F0001A68A2FB0A0102FB0B11420D42EAC122BE +:10A200004B15B2EB080263EB0903D00B40EA434065 +:10A21000BCF1000F01D0CCF80000039808B1009900 +:10A22000016005B0BDE8F08F7C120020CC07002053 +:10A2300024FAFFFF80120020324B2DE9F0411C88E8 +:10A24000314B0A265A89B3F91250A41A1A89ED0221 +:10A250005443B3F91420E413224495FBF2F2224450 +:10A26000DA615643A2F57A6202FB02F4B3F9048084 +:10A27000B3F902C0B3F90E7002FB0CFC02FB08F24A +:10A28000B3F90C802413674304FB08F4241404EB93 +:10A2900062320232DC88921002F50042B3F920509B +:10A2A0006243B3F900304FEAEC2404EBE72404EBFB +:10A2B0008304AC40154B02341B68D20BA3EBA404FF +:10A2C0004CF250332B41634355BF5B00B3FBF2F3B9 +:10A2D000B3FBF2F35B001A12524340F6DE346243E2 +:10A2E0000B4C08365C43241404EB224202F6CF6286 +:10A2F000361103EB221300B1036001B10E60BDE81B +:10A30000F08100BF8C120020E0070020881200209E +:10A3100043E3FFFF2DE9F04102780346202A00F1D4 +:10A320000100F9D0092AF7D02D2A02D10346414D68 +:10A3300004E02B2A08BF03464FF07E551E4600243A +:10A34000334616F8012BA2F13007F9B209290DD8CE +:10A350003949204604F06CFC0446384604F014FCED +:10A360000146204604F05CFB0446E9E72E2A17D19B +:10A37000314F334616F8010B3038C2B2092A0FD8D4 +:10A3800004F002FC394604F007FD0146204604F0C3 +:10A3900047FB29490446384604F04AFC0746E8E7EB +:10A3A0001A7802F0DF02452A38D15A782D2A02D1D4 +:10A3B0000233012604E02B2A14BF013302330026A6 +:10A3C000013B002713F8012F303AD1B2092903D8F5 +:10A3D0000A2101FB0727F5E7B7F59A7F28BF4FF45D +:10A3E0009A77B8464FF07E51B8F1070F07D9084663 +:10A3F000124904F01DFCA8F108080146F4E707F033 +:10A40000070737B108460C4904F012FC013F01462A +:10A41000F7E72EB1204604F0BFFC04E04FF07E5178 +:10A42000204604F005FC0146284604F001FCBDE886 +:10A43000F08100BF000080BF0000204120BCBE4C66 +:10A44000F0B50124B0FBF4F58D4201D34C43F9E79C +:10A450000026DCB1B0FBF4F504FB1500B4FBF1F40D +:10A460001EB9002D01DC002CF3D1092D03F10107E9 +:10A470005FFA85FC04DD002A0CBF5725372500E074 +:10A48000302565441D7001363B46E2E71C70F0BD87 +:10A49000F0B50124B0FBF4F58D4201D34C43F9E74C +:10A4A0000026DCB1B0FBF4F504FB1500B4FBF1F4BD +:10A4B0001EB9002D01DC002CF3D1092D03F1010799 +:10A4C0005FFA85FC04DD002A0CBF5725372500E024 +:10A4D000302565441D7001363B46E2E71C70F0BD37 +:10A4E00070B50646B6FBF2F40846154614B1204690 +:10A4F000FFF7F6FF05FB1464024B1B5D00F8013B00 +:10A5000070BD00BF886901082DE9F041069C002B51 +:10A5100006460F460CBF4FF020084FF03008234688 +:10A5200013F8011B09B9154603E0002AFBDD013AC7 +:10A53000F6E7002D04DD30464146B847013DF8E717 +:10A5400014F8011B11B13046B847F9E7BDE8F081B6 +:10A5500080EAE073A3EBE0738B4206DB002801DDA9 +:10A56000401A704702D00844704700207047034BE0 +:10A570009A6822EA00009860704700BF2C200020F3 +:10A580000E4B1B78BBB10E4B1B681A78032A06D101 +:10A590000C4B187802288CBF0020012070475B7894 +:10A5A00023B1094B1868C0F3C0407047074B1878B7 +:10A5B000C0F3800070470120704700BFD20D00201B +:10A5C000AC0500206C06002050020020D627002099 +:10A5D000114A30B50028B8BF4042104C90FBF2F34E +:10A5E00004FB03003C2568430D4D90FBF2F22D68FF +:10A5F0002D7B25B903EB830303EB830301E0C3EB5E +:10A60000031302EB830304FB02020B804FF47A7303 +:10A6100092FBF3F24A8030BD80969800806967FF14 +:10A62000D4050020034B1B681878C31E58425841BC +:10A63000704700BFAC05002008B5064807F006FCCF +:10A64000C0B2142805D8034A431C20211154D8B2A3 +:10A65000F7E708BD111E0020094A0A48002310B57B +:10A66000116803701A46CC1864880CB9CC5C24B10C +:10A6700004330132802BD2B2F5D1027010BD00BF7D +:10A68000940600201807002010B50B4B0B481978D2 +:10A690000B4B5A784B085C1E047001F0010109480D +:10A6A0000B44037008495308581E087002F0010259 +:10A6B000064913440B7010BD510700204C070020C1 +:10A6C000761400204E0700204F0700204D07002081 +:10A6D000F0B50F4A0F4816780F4A002317684370E9 +:10A6E0001A4619460546D0B2B0420CD217F82200DD +:10A6F000013204099C4200F00F00A8BF631C88428D +:10A70000A8BF411CEFE76B70044B1970F0BD00BF90 +:10A71000180700207614002094060020510700201E +:10A72000F8B5101A0C461F4604F02EFA0546381BE1 +:10A7300004F02AFA174B079E196804F079FA2946A3 +:10A740000446284604F074FA21460746204604F0E1 +:10A750006FFA0146384604F063F907F0F1FF0E493D +:10A7600004F066FA04F050FC069B2146186005F1DF +:10A77000004007F05BFE094904F05AFA084904F06A +:10A780004FF904F01BFC0028BCBF00F50C40A030C2 +:10A790003060F8BD4C0000202C7D8E3FA00CB345EE +:10A7A00000A00C4610B504F0EFF90021044604F0B7 +:10A7B000FBFB08B1204601E004F10040054904F02C +:10A7C000EBFA054904F034FA07F02EFD034B18604C +:10A7D00010BD00BF8096184B35FA8E3C4C0000200F +:10A7E00070B50446007904F0CBF91E4904F0D4FAA0 +:10A7F0001D4D1E4E2860A07B04F0C2F9194904F0DB +:10A80000CBFAEE606860607904F0BAF9184904F098 +:10A81000C3FA184D2860E07B04F0B2F9114904F046 +:10A82000BBFA6860607E04F0ABF9134904F0B4FA37 +:10A83000EE60A860A07904F0A3F90D4904F0ACFA29 +:10A840000E4D2860207C04F09BF9064904F0A4FA20 +:10A850006860A07E04F094F9074904F09DFAEE6068 +:10A86000A86070BD0000C842801100200000FA44BA +:10A87000000020419011002000007A44B411002013 +:10A8800044F25063984203DDA0F50C40A0387047B5 +:10A89000034B9842BCBF00F50C40A030704700BF8E +:10A8A000B0B9FFFF2DE9F041038A87890446BFB2A2 +:10A8B0000D461F40002F36D0B7FA87F34FF0004205 +:10A8C000DA40D24391B21B3B21821740042BF1D8CE +:10A8D000DFE803F0221F1C1903006B6A33B103F198 +:10A8E000FF3800231FFA88F86B6203E0B4F82C806D +:10A8F0001FFA88F82E6A002EDCD0336830464146B5 +:10A9000098477668F7E72868A18E08E06868218F85 +:10A9100005E0A868A18F02E0E868B4F84010036879 +:10A9200089B29847C6E7BDE8F0810C4B800A98428F +:10A930000CD003D8B0F5801F0ED00BE0084B984226 +:10A9400006D04933984205D1002070470220704755 +:10A9500003207047FE20704701207047010010005F +:10A960000200100090F83B3210B57BB990F83A32F3 +:10A9700090F83922934209D201219940B0F840421F +:10A9800001332143A0F84012DBB2F3E710BD837915 +:10A99000012B03D1D1F1010138BF0021D0F83431AE +:10A9A0005A681B8909B11361704753617047044BA2 +:10A9B00053F820301BB107289CBF1B6819807047D3 +:10A9C000680900202DE9F0410F88002347FA03F2BF +:10A9D000D2072BD58A7803F0070512F0100F18BFA5 +:10A9E00091F803C002F00F0618BF46EA0C06AD004E +:10A9F0004FF00F0C0CFA05FC06FA05F5DC0850F8D0 +:10AA00002480282A28EA0C0C45EA0C0540F824503A +:10AA100005D101229A40C46824EA020205E0482ACE +:10AA200004D101229A40C4682243C2600133102B32 +:10AA3000CCD1BDE8F08100BF1FB50123ADF80830CF +:10AA4000ADF80410002301A9ADF80A30ADF80C30C0 +:10AA5000ADF8062001F090FB05B05DF804FB10B5E1 +:10AA6000A0F5127494F83C22C2B9A36A616A9942B3 +:10AA700029D0591CA069A162C05C2369C0B2994267 +:10AA80004FEA400343F40073A4F83E324FF00A0348 +:10AA900084F83D3228BFA262012312E094F93D32CE +:10AAA0007BB1B4F83E1220464B08A4F83E3201F0C8 +:10AAB0000101FFF76CFF94F83D32013B84F83D3211 +:10AAC00001E084F83C3294F83832002B4FD194F8EE +:10AAD00039320133DBB2092B84F8393204D12046F4 +:10AAE000BDE81040FFF73EBF0A2B40D194F83B323F +:10AAF0002BB9B4F8403243F00103A4F84032637933 +:10AB0000D9071CD5B4F84002820501D4C30705D487 +:10AB1000B4F844320133A4F8443210E0E36AC0F3DD +:10AB200047000BB198470AE0E3696269D054E269D3 +:10AB3000E3680132B2FBF3F103FB1123E36101226D +:10AB400084F8382294F83B220023012A84F8393211 +:10AB50000DD1A27984F83B32236B012A1868197B46 +:10AB600014BF02220022BDE81040FFF765BF10BDF0 +:10AB700010B5A0F513746379DB074CD594F838321F +:10AB800013B3236B1868828DC2F34E02828494F84B +:10AB90003C2222B1B4F842220132A4F84222A27926 +:10ABA000197B012A0CBF02220022FFF745FF012377 +:10ABB00084F83B32002384F8393284F83A3284F83E +:10ABC0003832A4F8403210BD94F83B322046012BB5 +:10ABD00004BF94F8393284F83A32FFF7C3FE94F890 +:10ABE0003B12236BA27949B9012184F83B128A42B6 +:10ABF0001868197B0CBF0222002208E0002184F8AB +:10AC00003B12012A1868197B14BF02220022BDE8FA +:10AC10001040FFF711BF10BD426A10B58469A154FE +:10AC2000416A02690131B1FBF2F402FB1412426283 +:10AC3000426B32B11368DB0708D4BDE81040FEF761 +:10AC4000DDB8036DDA6842F08002DA6010BDF7B556 +:10AC50000368174C174D23600B68174E636000683C +:10AC6000FFF7A0FD95E80300144B0196009394E8CC +:10AC70000C00FFF755FD3668114B60681E606B686D +:10AC8000104FC01A03F080FF0F4B196803F0D0FF7C +:10AC900004F094F922682B687860D31A3B600B4B60 +:10ACA0001E600B4B1B68DA880A4B1A8003B0F0BD9C +:10ACB00068110020DC0500207411002070110020B4 +:10ACC000B0110020781100204C000020A8110020B5 +:10ACD0008C050020A41100202DE9F043142285B03A +:10ACE000814688461B48002107F06FF803261A4B5F +:10ACF0000027B74224DA13F8042C0021C8B201312E +:10AD000012B1501E0240F9E71C7AD1B2013214B1DF +:10AD1000611E0C40F9E7421A002A0EDD01ACA3F1D6 +:10AD20000C0595E8070084E8070093E8070085E82C +:10AD3000070094E8070083E8070001370C33D8E7E1 +:10AD4000013ED4D1034A4846414605B0BDE8F04330 +:10AD500002F0CEBD7C140020700000200022064BC3 +:10AD600013445968814203D00C32302AF7D10023B2 +:10AD700000225A725A6070476400002038B50E4DA8 +:10AD800004462B68834207D10121FFF7E7FF2846DD +:10AD900000214C2207F019F8EB6CA3420AD120469F +:10ADA0000121FFF7DBFFBDE83840044800214C22B9 +:10ADB00007F00BB838BD00BF400F00208C0F0020FB +:10ADC00010B50023054A1A445468844203D00C335A +:10ADD000302BF7D10022517210BD00BF640000205B +:10ADE0002DE9F34706461F464FF414737343474853 +:10ADF0009246C41880460EB9454A02E0012E04D19D +:10AE0000444A22631032C4F83421434A0025C25018 +:10AE1000032363714FF480734FF00109E3602361F2 +:10AE2000D4F8343184F83C5284F8389284F839529A +:10AE300084F84662586804F134029B68626104F544 +:10AE40009C72A261E1622562E561A5626562A4F877 +:10AE50004252A4F84452ADF804300225102301A94F +:10AE6000C4F808A0A7718DF806308DF80750FFF7D9 +:10AE7000A9FD236B01A958689B688DF80750ADF8B0 +:10AE8000043048238DF80630FFF79CFD49462046E4 +:10AE9000FFF77DFD3220F9F776FF204BD4F834918F +:10AEA0001B681D46B5FBFAF1B1F5803F03D3012DB8 +:10AEB000F8D96D08F6E71A4A4846B3FBF2F289B2B0 +:10AEC000D2B200F0FFFC4FF414735E43154B06F54D +:10AED000127608EB060548F8063048462946002257 +:10AEE000FDF738FF266B012F14BF022200223068C5 +:10AEF000317BFFF7A1FD0C4B30466B60291D002212 +:10AF0000FDF728FF204602B0BDE8F087901400202E +:10AF1000A0600108C06001084C520108A400002094 +:10AF200040420F005FAA000871AB000803460A46C2 +:10AF300090F84602D96A9B7952E7F8B50022074695 +:10AF40003749130101F11800185CB84204D00132EE +:10AF5000082AF5D10020F8BD324E0B44183306F212 +:10AF6000B445082F0FCB344685E80F001BD009D815 +:10AF7000022F0ED0042F16D0012F4FD12A4B1B6861 +:10AF80005B6847E0202F42D0402F06D0102F45D1DC +:10AF900022E0254B1B689B6802E0234B1B681B6962 +:10AFA000C6F8B83436E0214B1B681B7853B1013B1F +:10AFB000012B0AD9FFF736FB002814BF4FF4614379 +:10AFC000002304E04FF4165301E04FF49643C4F815 +:10AFD000B834C4F8BC3421E0154B1B681B7A042B31 +:10AFE0001CD8DFE803F00A0A030A0A00114BC6F86E +:10AFF000B834C6F8BC34032306E04FF4E133C6F896 +:10B00000B834C6F8BC34012384F8C13406E0064BDA +:10B010001B68DB68C6F8BC342846F8BD0648F8BD96 +:10B020004C5201087C140020D80F0020AC050020F1 +:10B030003C010020A08601003019002010B5044614 +:10B04000FFF77BFF01462046FFF746FE4368187A6C +:10B0500010F0010018BF586810BD38B505460C4601 +:10B06000FFF76BFF01462846FFF736FE28B143681D +:10B070001B7A1C420CBF0020012038BD38B50B4B99 +:10B0800005469B685A050ED5FFF7CCFA044650B129 +:10B090000820E9B2FFF7E1FF30B1054B1C78231F10 +:10B0A0005C425C4100E00124204638BD2C20002099 +:10B0B0006C0600200E4B1A78552A16D15A88B2F524 +:10B0C000EF6F12D11A79BE2A0FD193F8742700209E +:10B0D000EF2A0CD113F8012B5040064A9342F9D1C4 +:10B0E000D0F1010038BF0020704700207047704742 +:10B0F00000F8010878FF01084A4B55222DE9F34179 +:10B100001A704FF4EF625A80BE221A71EF2283F850 +:10B110007427002283F8752711461E46B35C01325E +:10B12000B2F5EF6F81EA0301F8D13E4B3E4A83F856 +:10B1300075173E4B04275A6002F188325A6000208E +:10B14000013F17F0FF075DD0384B3422384CDA60EE +:10B15000C4F309037BB1331903F17843A3F5FC333E +:10B16000D3F800804FF400500023019301F000FA5F +:10B170000428E5D11BE04FF4302001F0F9F9042850 +:10B18000DED12A4D4FF430202B6943F002032B61AE +:10B190006C612B6943F040032B6101F0E9F92A69E6 +:10B1A00041F6FD73134004282B61D4D0C8E71F4D2E +:10B1B0004FF400502B6943F001032B611FFA88F311 +:10B1C000238001F0D5F9042812D1A31C0193019B1F +:10B1D0004FEA1848A3F800804FF4005001F0C8F976 +:10B1E0002B6941F6FE721A4004282A6106D0A7E7AF +:10B1F0002B6941F6FE721A402A61A1E70D4B043417 +:10B200009C42A5D1094B04281A6942F080021A61B8 +:10B2100002D1FFF74FFF10B90A20F9F7EBFD02B09A +:10B22000BDE8F0812C20002023016745002002406A +:10B2300000F8010878FF01088A2802D08E2809D07A +:10B240007047094B1B689B060DD5084B1B7853B9FB +:10B25000074A03E0054B1B782BB9064A064B1A60D8 +:10B26000064B2D221A7070474C0200204406002025 +:10B2700014060020E8050020500600205906002092 +:10B28000234B70B519684FF47A73B1FBF3F1214B7E +:10B2900021481A78214B224D1B7800F073FD214B79 +:10B2A00021481968214B2E68B1FBF3F100F06AFDCB +:10B2B00000241F4BE2B253F8221049B1012303FAD4 +:10B2C00002F2324202D01B4800F05CFD0134F0E78C +:10B2D0002A6892070DD5184A1848127803EB8203A2 +:10B2E000196A00F04FFD164B197A11B1154800F09C +:10B2F00049FD1548F9F760FEBDE87040134B14484E +:10B300001A88144B92B219884FF4EF6300F03ABDDB +:10B3100028200020C0050020CE69010894000020EC +:10B320004C020020A40000200C6A010840420F00DB +:10B33000E452010840690108D82700202A6A010860 +:10B3400058040020346A01085B63010828140020B7 +:10B35000386A0108FC04002070B50E46202115460D +:10B3600006F067FD0446B8B1441C204606F0C3FD54 +:10B37000B0F5617F05DB40F634039842A8BF18465C +:10B3800001E04FF461701923A0F5617090FBF3F0B8 +:10B3900030702B7801332B702046202106F049FDB8 +:10B3A0000446B8B1441C204606F0A5FDB0F5617F07 +:10B3B00005DB40F634039842A8BF184601E04FF47D +:10B3C00061701923A0F5617090FBF3F070702B7819 +:10B3D00001332B70204670BD70B586B0054606F06F +:10B3E00035FDC0B208BB044606236343444A03F557 +:10B3F0008873126819201344591D4D789A7A454371 +:10B4000005F561755B7900958D78684300F561708D +:10B410000190C878029009793A4803912146013495 +:10B4200000F0B0FC0C2CDFD168E0284606F063FD8C +:10B430000B285FDC06267043314B00F588701E68D0 +:10B44000202106440023681C8DF8173006F0F1FC1B +:10B45000741D054658B1451C284606F04CFD0328CE +:10B4600005D89DF81730607101338DF817302846E4 +:10B47000202106F0DEFC054658B1451C284606F0A2 +:10B480003AFD0D2805D870719DF8173001338DF8FD +:10B4900017302846611C0DF11702FFF75DFF2021D0 +:10B4A00006F0C7FC054658B1451C284606F023FDAA +:10B4B0000C2805D89DF81730E07001338DF817304F +:10B4C0002846202106F0B5FC50B1013006F013FDEE +:10B4D0000D2805D89DF81730207101338DF81730ED +:10B4E0009DF81730062B09D020460021062206F0D1 +:10B4F0006CFC03E004480C2100F044FC06B070BD75 +:10B50000E80300206A6A0108D8640108F0B585B034 +:10B51000074606F09BFCC0B2E0B90446324B04F18A +:10B520001C021B68192003EB8203591D8D785A7980 +:10B53000454305F561759B790095C978484300F549 +:10B540006170019021462948013400F01BFC282C31 +:10B55000E4D146E0384606F0CEFC27283DDC224BFD +:10B5600000F11C061B68781C03EB860620210023D3 +:10B570008DF80F3006F05DFC751D044658B1441C73 +:10B58000204606F0B8FC152805D870719DF80F30DC +:10B5900001338DF80F302046202106F04AFC044686 +:10B5A00058B1441C204606F0A6FC0D2805D89DF88D +:10B5B0000F30687001338DF80F302046A91C0DF153 +:10B5C0000F02FFF7C9FE9DF80F30042B09D0284663 +:10B5D0000021042206F0F9FB03E00548282100F0D1 +:10B5E000D1FB05B0F0BD00BFE80300208A6A010866 +:10B5F000D864010830B585B004AC002524F8025D9C +:10B600000091ADF8060021461020F9F735FD9DF8B0 +:10B6100006002146F9F730FD9DF807002146F9F7AD +:10B620002BFD9DF800002146F9F726FD9DF801004D +:10B630002146F9F721FD9DF802002146F9F71CFD8E +:10B640009DF803002146F9F717FD9DF80E002946E5 +:10B65000C043C0B2F9F710FD024B1A68024B1A60E2 +:10B6600005B030BD282000208006002038B5834B6F +:10B67000834A197832F8110010B918704FF403603A +:10B680001978B0F5C06F01F10101C9B27B4A197098 +:10B690004CD019D8B0F5007F44D006D8B0F5807FE3 +:10B6A00042D0B0F5887F63D038BDB0F5806F72D0DE +:10B6B000B0F5826F00F0AC80B0F5047F40F0DC8024 +:10B6C000704B53211B78D1E0B0F5006F30D00DD80E +:10B6D000B0F5E26F54D0B0F5E46F55D0B0F5E06F3F +:10B6E00040F0CA80684BB3F9001050E0B0F5036F2A +:10B6F00007D0B0F5046F3ED0B0F5026F40F0BC80CB +:10B70000A8E0624B1B689A0640F1B680604B1B783C +:10B710009B0740F1B1805F4B24211B885943642370 +:10B72000123135E05C4B24E05C4B22E05C4B20E0C6 +:10B73000564B1B689D0640F19F80554B1B789C071C +:10B7400040F19A8011F0010F564B08D0596800293A +:10B75000BCBF494241F0804141F0004105E0196819 +:10B760000029BCBF494241F080414FF400607EE0B7 +:10B770004D4B19687BE04D4B6421B3F9003075E007 +:10B78000414BB3F9021002E03F4BB3F904102C23F4 +:10B7900091FBF3F16BE051780131C9B2032988BF05 +:10B7A000012151705B7842F210715943404B1B7874 +:10B7B000D80748BF01319A0748BF02315D073D4BAA +:10B7C00048BF04311B88DC0748BF0A31980748BFCF +:10B7D00014311A0648BF2831DD0548BF28315C07FF +:10B7E00048BF6431180748BFC8319A0548BF01F502 +:10B7F000C8719D0648BF01F57A71DC0648BF01F5A6 +:10B80000FA61580648BF01F57A614FF480602EE076 +:10B810001E4B294C1D6815F0200516D01C4B1B78BB +:10B8200013F0020F0CBF00214FF47A7113F0010FD7 +:10B830000CBF00234FF4FA631944204B1B781944C2 +:10B84000FFF7D8FE0023237038BD2946FFF7D2FE4C +:10B85000257038BD0D4B1B689A060DD50C4B1B7817 +:10B860009B0709D5164B4FF47A711B885943FFF794 +:10B87000C1FE114B00221A7038BD00BF40190020D4 +:10B88000AE690108C0050020B40400204C0200206D +:10B8900082020020CC050020C4050020A403002063 +:10B8A000C8050020DC050020C8030020E0040020BB +:10B8B000D6270020540200207C060020D00500205E +:10B8C000CE05002013B504460068FAF73BFA23685A +:10B8D00001A81A8892B242F001021A80637B00220A +:10B8E0008DF8043001238DF805308DF806208DF891 +:10B8F0000730FAF7A3F902B010BD40F2E9330F4A5E +:10B900001189890709D5908140F2E9330B4A1189E1 +:10B91000C9070DD59089C0B27047013B9BB2002B7F +:10B92000EDD1074BFF201A88013292B21A8070477E +:10B93000013B9BB2002BE9D1F3E700BF0038004088 +:10B94000760700207FB52B4B2B4C9A69206042F084 +:10B9500001029A61294D03881026ADF8043028466B +:10B96000022301A98DF807308DF80660FFF72AF849 +:10B97000236828465B88ADF8043004230DEB0301EF +:10B980008DF80630FFF71EF822680F20137A03F0B7 +:10B9900003018900884003F0FC0303F1804303F5B1 +:10B9A00080339D6825EA0000012505FA01F19860C1 +:10B9B0009868014399605368114A02A85361029341 +:10B9C00000238DF80C308DF80E508DF80D60FAF7CD +:10B9D0008FF923680B4A5B7A59B203F01F039D402D +:10B9E0004909094B42F821501A68084B3C3A1A6041 +:10B9F00004B070BD00100240E0030020000C0140C4 +:10BA00000004014000E100E028200020D8030020CD +:10BA10000B4B07B59A690B4842F010029A614FF43C +:10BA20000053ADF8043002238DF8073001A910232C +:10BA30008DF80630FEF7C6FF03B05DF804FB00BFCB +:10BA40000010024000100140104B043033F9103058 +:10BA5000B3F5617F05DB40F633029342A8BF13467E +:10BA600001E04FF4617308781922504300F28330EB +:10BA7000984208DA4878504300F283309842B4BFC5 +:10BA80000020012070470020704700BF1A070020E7 +:10BA9000114B70B51B685E89104B186880F310005D +:10BAA000301A02F0A7FC00220D4B02F009FD0446FB +:10BAB00030460D4602F09EFC02460B4620462946C3 +:10BAC00002F028FE02F00EFF6428A8BF642020EADE +:10BAD000E070C0B270BD00BFBC050020C8050020EA +:10BAE0000000594038B5114B114D1A78114C296896 +:10BAF0008AB162680244914217D300201870F9F7A6 +:10BB00004CF92B6863600C4B1A780AB1013A1A7031 +:10BB10000123237238BD6268C832914205D30120E7 +:10BB20001870F9F73AF92B68636038BD3B0F0020B5 +:10BB300028200020401900209A04002037B5224D0B +:10BB40008DF807306B7A8DF8062002AA8DF8040074 +:10BB50008DF805101A4412F8042C443AD2B20F2A78 +:10BB60002BD81A49022B01EB4202B2F84C4003D801 +:10BB700014B12046FFF7B6FF6B7A134A022B09D99E +:10BB8000134B19685368091B8B4203D2002353726D +:10BB9000104A13702B7A012B00D09CB96B7A022BC0 +:10BBA00002D8094A013353720B4B002028721870D7 +:10BBB00003B0BDE83040F9F7F0B8022B4FF0C804ED +:10BBC000D7D9D9E703B030BD40190020E4520108AD +:10BBD000282000209A0400203B0F00200449054B38 +:10BBE0000968002218701A6159611A76704700BFFF +:10BBF00028200020800A00202DE9F04F064689B059 +:10BC00000F4615469B462978002900F0B880252963 +:10BC100002D001353046B0E06C78302C03D00235CC +:10BC20004FF0000903E0AC784FF001090335A4F1AF +:10BC30003003092B4FF000081AD8A4F13003DAB210 +:10BC4000092A07D80A2B13DC0A2202FB083815F848 +:10BC5000014BF2E7A4F16103052B02D8A4F15703CD +:10BC6000F0E7A4F14103052B02D8A4F13703E9E77B +:10BC70006C2C03BF2C78012201350022632C66D086 +:10BC800006D8252C77D0582C3FD0002C77D0BAE797 +:10BC9000732C63D002D8642C11D0B4E7752C02D079 +:10BCA000782C32D0AFE70BF1040A05ACDBF80000CA +:10BCB0000A2112B10022234613E0234620E00BF1B3 +:10BCC000040A05ACDBF8000072B1002806DA2D2367 +:10BCD0008DF8143040420DF1150300E023460A218F +:10BCE0000022FEF7D5FB0DE0002806DA2D238DF8A3 +:10BCF000143040420DF1150300E023460A210022D2 +:10BD0000FEF79EFBD34600941AE00BF10403039365 +:10BD10000DF1140ADBF80000102132B1583C6242E8 +:10BD200062415346FEF7B4FB06E0B4F158035A42B1 +:10BD30005A415346FEF784FBDDF80CB0CDF800A065 +:10BD40003046394642464B46FEF7DEFB5BE730465F +:10BD50009BF800100BF10404B8470AE0DBF8003050 +:10BD6000304600933946424600230BF10404FEF7A7 +:10BD7000CBFBA34647E730462146B84743E709B027 +:10BD8000BDE8F08F0FB407B50A4904AB08680A494B +:10BD900053F8042B09680193FFF72EFF074B18682F +:10BDA000F9F74FF80028F9D003B05DF804EB04B0C0 +:10BDB000704700BF5C070020580700206013002078 +:10BDC000F8B5074606F042F8044638B9194B1A4848 +:10BDD0005A791A4B013A53F8221028E0384618498C +:10BDE000224606F03BF860B91648F9F7E5F8164C1C +:10BDF00054F8041F19B11548FFF7C4FFF8E71448B9 +:10BE000005E000250D4B53F8256026B91148BDE823 +:10BE1000F840F9F7D1B838463146224606F01EF808 +:10BE200001350028EED1034B0B485D713146BDE86A +:10BE3000F840A7E72C2000200F6B01086853010889 +:10BE400054700108236B010864530108406901081C +:10BE50005B630108E0630108366B010870B50446B6 +:10BE600005F0F4FF08B91E482EE020461D4906F0F3 +:10BE700067F800242646254678B12CB1012C06D15E +:10BE800006F039F8064602E006F035F80546154991 +:10BE90000020013406F054F8EEE70B2D04D9BDE87C +:10BEA000704011480C216DE7012C07DC0F4B29462F +:10BEB00033F915200E48BDE8704063E7A6F57A73A4 +:10BEC000B3F57A7F03D90B48BDE870405AE70A48BA +:10BED00029463246FFF756FF044B23F8156070BD24 +:10BEE000486B0108DC680108826B0108DC0F002048 +:10BEF000A86B0108C06B0108E26B01082DE9F7434C +:10BF0000044605F0A3FFC0B290B9304C054694F842 +:10BF1000D711B4F8D42194F8D6312D480091294690 +:10BF20000135FFF72FFF102D04F10404EFD14AE093 +:10BF3000204605F0E0FF0F28054636DC204620218C +:10BF400005F077FF234FEDB2D7F80090441CAD0009 +:10BF50000026204605F0CFFF5FFA86F8B8F1010F02 +:10BF600083B208D0B8F1020F0BD0B3F5B47F1ED264 +:10BF70003A6853530AE0FF2B19D83B682B4498705A +:10BF800004E0FF2B13D83B682B44D87020462C21AB +:10BF900005F04FFF044608B1441C02E0B8F1020F5F +:10BFA00005D10136032ED4D10DE00B4806E009EB94 +:10BFB00005000021042205F008FF0848102103B005 +:10BFC000BDE8F043DEE603B0BDE8F0832C2000209E +:10BFD000FB6B0108A40A00200F6C0108BE64010875 +:10BFE000F0B500231946CEB200220C2505FB02F75E +:10BFF0000D48D4B23F5CB74203D00132042AF4D1D9 +:10C000000BE0FF2C09D0094A05FB04001A4492F802 +:10C010002C21074C0133A25C02720131052901D0A9 +:10C02000032BE0D9F0BD00BF640000202C200020CD +:10C03000036B010810B54F20F8F720FD0C4C84F875 +:10C040002C010020F8F71AFD4FF4E133C4F8303129 +:10C05000C4F83431C4F83831C4F83C31522384F880 +:10C060002D0184F82E0184F82F0184F8403110BD91 +:10C070002C20002070B50546441E14F8011F61B144 +:10C08000064E304605F0D5FE0028F6D0861B044843 +:10C09000631B304480F81031EFE770BDAA6E0108D1 +:10C0A0002C20002030B587B005460C4603A800219F +:10C0B0000C2205F08AFE2846002102F075FF20B10F +:10C0C00028462A4902F0ACFC03E02846274902F042 +:10C0D000A5FC274902F0ACFD02F070FF054685EA99 +:10C0E000E570A0EBE57069460A22FEF7F9F9002336 +:10C0F0009D420370ACBF20232D2368468DF80C3081 +:10C1000005F0A4FE012807D130238DF80D308DF8FD +:10C110000E308DF80F300CE0022805D130238DF859 +:10C120000D308DF80E3004E0032804BF30238DF865 +:10C130000D30694603A805F06FFE03A805F086FEE2 +:10C140000338C5B22A4603A9204605F0A9FE0023FC +:10C1500063552046074905F05FFE03A920462944A0 +:10C1600005F05AFE204607B030BD00BF6F12033AFB +:10C1700000007A44336C01080A88F0B54B888F8838 +:10C180000E89CD88002A3AD1048C834A24F0010418 +:10C190002404240C0484018B048C89B221F0F30163 +:10C1A00041EA0616B6B29042A4B246EA070743F047 +:10C1B000010315D002F50062904211D0B0F1804F1A +:10C1C0000ED0A2F5983290420AD002F580629042D9 +:10C1D00006D002F58062904218BF24F00A0401D113 +:10C1E00024F00204234307830384038B23F00C030E +:10C1F0001B041B0C0383038B9BB21D4344E0042AE6 +:10C2000044D1048C644A24F010042404240C0484D3 +:10C21000018B048C21F440710905090D41EA0631B6 +:10C2200089B241EA07279042A4B2BFB212D002F508 +:10C23000006290420ED0B0F1804F0BD0A2F5983240 +:10C24000904207D002F58062904203D002F58062EE +:10C25000904207D124F0200444EA03139BB243F038 +:10C26000100304E024F0A00443F0100323430783E9 +:10C270000384038B23F440631B041B0C0383038B95 +:10C280009BB243EA0525ADB20583F0BD082A018CB7 +:10C290003ED121F480710904090C0184818B3E4A4E +:10C2A00089B221F0F301048C41EA0616B6B290423D +:10C2B000A4B246EA070712D002F5006290420ED0FF +:10C2C000B0F1804F0BD0A2F59832904207D002F522 +:10C2D0008062904203D002F58062904207D124F43C +:10C2E000007444EA03239BB243F4807304E024F413 +:10C2F000206443F48073234387830384838B23F078 +:10C300000C031B041B0C8383838B9BB21D4341E0F6 +:10C3100021F480510904090C0184828B048C22F4DD +:10C3200040721205120D42EA072242EA06361A4A04 +:10C33000A4B29042B6B212D002F5006290420ED082 +:10C34000B0F1804F0BD0A2F59832904207D002F5A1 +:10C350008062904203D002F58062904207D124F4BB +:10C36000005242EA033292B242F4805205E047F6AC +:10C37000FF52224043F480531A4386830284838B06 +:10C3800023F440631B041B0C8383838B9BB243EA1F +:10C390000525ADB28583F0BD002C01401FB50123FA +:10C3A000ADF808300023ADF80C30ADF80A30094B79 +:10C3B000ADF804101B7801A9012B08BF0323ADF8C9 +:10C3C000062008BFADF80C30FFF7D6FE05B05DF8CB +:10C3D00004FB00BF0C08002038B510F80E2C0446F2 +:10C3E00050F8043C52B9012200F80E2C20F80C1C25 +:10C3F000197B18680222BDE83840CFE730F80C2CD2 +:10C4000020F80A1C891A89B220F8081C074A10F87B +:10C410000F0C002522F8101004F80E5C1868197B28 +:10C420002A46FFF7BBFF04F8065C38BD4C19002014 +:10C430001F4B10B55A6802F00C02042A03D0082AD8 +:10C4400004D01C4A14E01C4A126811E05A6859686A +:10C45000C2F38342C90302F1020201D4174906E084 +:10C46000596811F4003F1449096818BF49084A4344 +:10C4700002605968124AC1F30311545C0168E1403B +:10C4800041605C68C4F30224145D21FA04F4846002 +:10C490005C68C4F3C224145DE140C1605B68C3F30F +:10C4A00081331A44137CB1FBF3F1016110BD00BF6D +:10C4B0000010024000127A002400002000093D0014 +:10C4C00050000020024B1A6922EA000018617047F0 +:10C4D00000100240CB78F0B5DA0648BF8A780988A8 +:10C4E00003F00F0548BF154311F0FF0F1DD004687E +:10C4F00000220127974007EA0106BE4211D19700AA +:10C500004FF00F0C0CFA07FC05FA07F724EA0C04AD +:10C51000282B44EA070401D1466102E0482B08BFFA +:10C5200006610132082AE4D10460FF291FD944685A +:10C53000002202F108060127B74007EA0106BE42C1 +:10C5400011D197004FF00F0C0CFA07FC05FA07F712 +:10C5500024EA0C04282B44EA070401D1466102E0D6 +:10C56000482B08BF06610132082AE2D14460F0BDC1 +:10C5700010B50446F8F78DF8012806D11CB1F8F77C +:10C5800088F8013CF8E7052010BD002C08BF052005 +:10C5900010BD00BF2DE9F0418CB01D469DF848301C +:10C5A0008846012B174608D1A84B984240F0468197 +:10C5B000042203F548431A6165E0A54B98425ED119 +:10C5C000A448A54B87600360A44BA907436103F10E +:10C5D000C00383614FF0C003C36003619C4B0365DC +:10C5E00003F104038364C36403F5484303F1540374 +:10C5F0000363A3F11403D3F8D42F436342F48042BE +:10C60000C3F8D42FD3F8D02F42F00102C3F8D02FB3 +:10C610004FF002038DF803304FF40073ADF8003093 +:10C620004FF018038DF8023003D58D486946FEF7A8 +:10C63000C9F91C232A078DF8023003D588486946BA +:10C64000FEF7C0F94FF48063ADF8003048238DF851 +:10C650000230EB0703D582486946FEF7B3F90E2393 +:10C660008DF804300022012301A88DF805308DF8E3 +:10C6700006208DF80730774CF9F7E0FA55E0734B58 +:10C68000984240F0DF80774B734A9F601A60C02267 +:10C69000DA601A61744AAE075A6102F1C0029A6107 +:10C6A0006A4A1A6502F104029A64DA646F4BDA6925 +:10C6B00042F40032DA615A6942F001025A614FF0E5 +:10C6C00002038DF803304FF00403ADF800304FF053 +:10C6D00018038DF8023003D561486946FEF772F9F8 +:10C6E0001C232C078DF8023003D55D486946FEF700 +:10C6F00069F90823ADF80030E8074FF048038DF8DA +:10C70000023003D556486946FEF75CF926238DF8BA +:10C7100004300022012301A88DF805308DF8062091 +:10C720008DF80730F9F78AFA4E4C0026012384F879 +:10C7300044302662E661A6626662C4F82C806571A8 +:10C74000A760A6712046FCF78DFA15F0090F31D0CD +:10C75000206B002826D0E36C039601934FF480539E +:10C760000A9380230693E368059604932023099394 +:10C7700063690796029308960B96F7F7BDFF01A928 +:10C78000206BF7F79BFF236B1A6842F001021A60D7 +:10C79000226D918A89B241F0400191825B689BB21F +:10C7A000236407E0236D4FF6DF721A80DA6842F0E7 +:10C7B0002002DA6015F00A0F2CD0606B28B3A36C4E +:10C7C000002601934FF480530A9380230693236934 +:10C7D00002960493102303930596079608960996EC +:10C7E0000B96F7F789FF606B01A9F7F767FF636B9B +:10C7F0001A6842F002021A605E605E60236D9A8AD7 +:10C8000092B242F080029A8204E0236DDA6842F02C +:10C810008002DA60236D29079A8992B242F40052AD +:10C820009A819A8A03D592B242F0080203E022F07C +:10C8300008021204120C9A82204604E0044B98422B +:10C840003FF4BEAE00200CB0BDE8F08100440040D3 +:10C8500000380140C01F0020505301086419002017 +:10C86000000801406C1F0020E41A00200010024064 +:10C8700010B50446204605F0E9FA10F0FF0F07D185 +:10C880000B4B0C4893F85417BDE81040FFF77ABAE9 +:10C89000204605F030FB022808D8054B064C83F8EB +:10C8A0005407FEF729FC01F0EDF8E3E710BD00BFE7 +:10C8B0002C200020946801080D6901082DE9F04F33 +:10C8C000844985B0054605F089FA83490028284641 +:10C8D0000CBF0124072405F081FA8049002828466E +:10C8E00008BF022405F07AFA002808BF0424E107F3 +:10C8F00040F1BE807A48FFF745FA0020F8F77EFD48 +:10C90000784F7948FFF73EFA7848FFF73BFA7A7993 +:10C91000774B784803EB82035969FFF733FA38699C +:10C92000002102F019FB00285CD13D460646D5F8EF +:10C9300010800021404602F00FFB00284ED1013646 +:10C940006D483146D5F814B0D5F818A0D5F81C902C +:10C95000FFF718FA4046002102F008FB10B16748C3 +:10C96000FFF710FA69464046FFF79CFB0146644812 +:10C97000FFF708FA5846002102F0F8FA10B15F48B4 +:10C98000FFF700FA69465846FFF78CFB01465C4802 +:10C99000FFF7F8F95046002102F0E8FA10B15748C5 +:10C9A000FFF7F0F969465046FFF77CFB0146544813 +:10C9B000FFF7E8F94846002102F0D8FA10B14F48D5 +:10C9C000FFF7E0F969464846FFF76CFB01464D4822 +:10C9D000FFF7D8F90C2E05F11005A8D14A48711CB3 +:10C9E000FFF7D0F94948FFF7CDF9494DD7F808804E +:10C9F00055F8041F19B14748FFF7C4F9F8E70D4689 +:10CA0000454B53F8256056B10123AB4013EA080F9C +:10CA100003D042483146FFF7B5F90135F0E7404809 +:10CA2000FFF7B0F931467B1893F8103104AA13448C +:10CA30003C4A8A5C0131082903F8102CF3D1002309 +:10CA4000694639488DF80830FFF79CF93748FFF7F9 +:10CA500099F93748F9F76CFA3648FFF793F93448F3 +:10CA6000FFF74CFA3448FFF78DF94020F8F7F0FF54 +:10CA7000A2071AD53148FFF785F93148FFF782F947 +:10CA80002B48FFF7F5FE2F48FFF77CF92848FEF703 +:10CA90003DFD2D48FFF776F92548FEF79DFC264819 +:10CAA000FFF770F98020F8F7D3FF63070FD5274809 +:10CAB000FFF768F92648FFF765F91D48FBF760FCAA +:10CAC0001D48FFF75FF94FF48070F8F7C1FF05B01C +:10CAD000BDE8F08F356C01081B7701083C6C01083C +:10CAE000426C01082C200020506C0108626C010887 +:10CAF000505301086E6C0108796C0108DC6801086C +:10CB0000316A010825630108816C0108936C0108F2 +:10CB1000C0530108A36C0108C4530108B16C01089B +:10CB2000BE6C0108AA6E0108CA6C0108D36C01082A +:10CB30000D690108DF6C01085B630108ED6C0108F9 +:10CB4000006D01080E6D0108186D0108276D0108C0 +:10CB5000386D01082DE9F04F87B0984682460F46A0 +:10CB600016469DF84040FEF7E8F90DF1080E05461F +:10CB7000034600F1100C18685968724603C2083366 +:10CB800063459646F7D12B7B0BB903960496504626 +:10CB900002A9FEF7A1F8054640B14368586830B1D4 +:10CBA000504602A92A4600F0A3FEF4E733E0AB6842 +:10CBB00095F800B093F80090B9F1040F2BD8DFE896 +:10CBC00009F003062A0F11000094144801E01448EC +:10CBD0000094394632464346FFF7DCFC04460BE03E +:10CBE000002000E00120394623463246FEF7F8F8DF +:10CBF00041460446F8F720F964B10A4B84F80490E2 +:10CC000003EB8B03C3F800436B6820465C6051461E +:10CC1000FEF7D6F8204607B0BDE8F08F0038014097 +:10CC20000044004064190020F7B5274C274DE36904 +:10CC3000284643F48043E361236901A943F4804318 +:10CC4000236118238DF806304FF42043ADF80430EB +:10CC500003238DF80730FDF7B5FE04234FF480461B +:10CC60000DEB030128468DF806304FF48057ADF8E0 +:10CC70000460FDF7A7FE1023284601A98DF80630B1 +:10CC8000ADF80470FDF79EFE2F61236930463343F3 +:10CC90002361FFF717FC0E4B1A8802F4415242F44D +:10CCA000457242F003021A809A8B22F40062120449 +:10CCB000120C9A8307221A821A8892B242F040021A +:10CCC0001A8003B0F0BD00BF00100240000C01400C +:10CCD0000038004008B5FEF70FFA00F0D3FEBDE8BB +:10CCE00008400F2014210122F8F75EB82DE9F34126 +:10CCF0002D4B1B78042B50D14020F7F7A4FE04469F +:10CD000070B12046F8F79DF818B90A20F8F73BF8FB +:10CD1000F7E7264B20461B681969F8F797F80BE0F0 +:10CD2000224B21461B6800901A6940200323FFF71D +:10CD300011FF0446002830D01D4D286841798B072B +:10CD400003D441F00201F8F777F81A4B08221A6170 +:10CD500010221A612868F8F783F858B1144B154E61 +:10CD6000082718687761F8F776F801462046F8F743 +:10CD700089F837612046F8F773F80028EAD00D4E9D +:10CD8000102777612046D5F80080F8F764F801464F +:10CD90004046F8F777F83761DCE7074802B0BDE8AE +:10CDA000F041F8F709B900BF800A00207C0A002092 +:10CDB000A00A0020000C0140BF6E01082DE9F743D6 +:10CDC000124C814604F1980894F84A60C6B9D9F823 +:10CDD000042000250095012029460323FFF7BAFE11 +:10CDE000074620B97EB94FF496420126F1E7204666 +:10CDF00029464C2204F0E9FF0123276084F84A30D9 +:10CE00004C344445E0D103B0BDE8F083400F00202E +:10CE1000F7B5524B524C2360FFF7E2F80120FEF7C2 +:10CE20002DF9002800F084804E4BFF211846162271 +:10CE3000256804F0CAFF002202704B4A01211268E3 +:10CE400003469707817504D541700321817502213E +:10CE50008170560704D5997D481C98750320585455 +:10CE600012F00A0F0CD09A7D04219954511CC9B2BA +:10CE700005205854D11C02329975D2B2062199541A +:10CE80003A4FBA68900604D5997D481C98750720DA +:10CE90005854110608D5997D09205854881C013131 +:10CEA0009875C9B20A2058547979082901D00E29F9 +:10CEB00004D1997D481C98750B205854997D4FF0EA +:10CEC0000C0E481CC0B212F0040F264E987503F8E1 +:10CED00001E003D00231B17510213154997D97F8EA +:10CEE0004571481CC0B24FF0120E002F0CBF002736 +:10CEF00002F001071B4E987503F801E01FB10231E3 +:10CF0000B17513213154997D1427481CC0B298750E +:10CF10005F549305134E03D502311523B175335475 +:10CF200013480021982204F050FF2846FFF746FFDF +:10CF30000220FEF7A3F870B10220F7F784FD256800 +:10CF4000084C0146A06130B90090AA680220032372 +:10CF5000FFF700FEA06103B0F0BD00BF5821002024 +:10CF6000D80F0020741C00204C0200202C20002030 +:10CF7000400F0020A94B2DE9F7431B78002B00F050 +:10CF80008181FDF7FDFAA64E05463378834200F015 +:10CF90007981A44C23681B78002800F0F08063BBE3 +:10CFA0000420F7F750FDA04F01463860DFF8848277 +:10CFB00090B143794FF4165188F81C308368C8F853 +:10CFC0002030F7F743FF38680221F7F735FF38685C +:10CFD0000421FDF7F5FE10E0944B04201B684FF48C +:10CFE00016529B7800930223FFF7B4FD4379386013 +:10CFF00088F81C308368C8F8203023681F78012F18 +:10D0000034D10420F7F71FFDDFF844820146C8F849 +:10D010000000DFF82092A0B143794FF4964189F8DF +:10D0200024308368C9F82830F7F710FFD8F80000DB +:10D030003946F7F701FFD8F800000421FDF7C0FEDC +:10D0400014E000903B4604204FF49642FFF782FD27 +:10D050004379C8F8000089F824308368C9F828307B +:10D060000379033B012B9CBF714B1F7023681F7812 +:10D07000022F41D10420F7F7E6FC6E4C0146E06236 +:10D0800088B143794FF4964184F830308368636304 +:10D09000F7F7DCFEE06A3946F7F7CEFEE06A0421D6 +:10D0A000FDF78EFE0CE000903B4604204FF49642C4 +:10D0B000FFF750FD4379E06284F8303083686363A2 +:10D0C000E76A5D4C94F84A30022B09D094F8962018 +:10D0D000022A00F0D5801BB14C34002A18BF00246E +:10D0E000564B1C6044B1204600214C2204F06DFEDA +:10D0F0000223276084F84A30FDF794FA002800F0F4 +:10D10000BD804F4F3B78002B40F0B8800820F7F7E8 +:10D110009AFC4C4C0146206090B1464B42794FF44A +:10D12000614183F838208268DA63F7F78FFE206860 +:10D130000821F7F781FE20680821FDF741FE9DE0F8 +:10D14000414B08201B684FF461429B7800930346D3 +:10D15000FFF700FD206040B1012342793B70354B61 +:10D1600083F838208268DA6388E0384B1B78002B1C +:10D1700000F0848004233B70FFF74AFE7EE083B911 +:10D18000294FDFF8B080386898F81C10F7F754FE84 +:10D190003868D8F82010F7F759FE38680421FDF7F1 +:10D1A000DDFD23681B78012B10D1294FDFF8848027 +:10D1B000386898F82410F7F73FFE3868D8F8281038 +:10D1C000F7F744FE38680421FDF7C8FD23681B7893 +:10D1D000022B0DD1174CE06A94F83010F7F72CFEB3 +:10D1E000E06A616BF7F732FEE06A0421FDF7B6FDF5 +:10D1F000FDF718FA002841D0114F3B7813F0FB0FD0 +:10D200003CD0124B0F4C1B7823B320680821FDF74C +:10D21000A5FD04233B70FFF7FBFD2DE0A8050020D2 +:10D22000A9050020AC050020B0050020D405002091 +:10D2300055070020741C0020400F00205C060020D1 +:10D240006C06002070060020DC0D0020D20D0020AE +:10D2500048060020DFF83480206898F83810F7F787 +:10D26000EBFD2068D8F83C10F7F7F0FD20680821A6 +:10D27000FDF774FD04233B7000232360357001E04B +:10D280004C342DE703B0BDE8F08300BF741C0020D0 +:10D2900037B53D490B7813F0010F03F0040268D055 +:10D2A000002A6FD1980764D443F004030B70374B06 +:10D2B0001A88374B1A80374B9A681C4612F4806FD5 +:10D2C00005D00420FDF7BAFE08B1FDF757FDA368AD +:10D2D0001B0357D58020FDF7B1FE08B1FDF74EFDC9 +:10D2E0002D4D2B78012B4DD18020F7F7ACFB2B4C2B +:10D2F0000146206090B14279294B4FF4E1311A7018 +:10D300008268284B1A60F7F7A1FD20680221F7F721 +:10D3100093FD20688021FDF753FD0EE000904FF44F +:10D32000E13280200223FFF715FC206028B142790A +:10D330001B4B1A7082681B4B1A6023680BB92B7049 +:10D3400020E0194B194C1B680021236404F14C00A8 +:10D35000022314222B706164A16404F036FD04F1F1 +:10D360006C03236604F1D003636604F59A73A36625 +:10D3700008E03AB90220FF21012203B0BDE83040A5 +:10D38000F7F712BD03B030BDD6270020E00400201F +:10D39000480E00202C200020E20D00201820002044 +:10D3A0001C2000202020002028200020741C0020A9 +:10D3B0002DE9F341F7F7DCFBA94D07462B68C31AAB +:10D3C000002BC0F2ED8100F5C333A0332B60A54BD9 +:10D3D0002A791E78C6F38006B21A18BF01222E7170 +:10D3E0004EB1002A00F0DC819F4B5A789A700122DE +:10D3F0005A701A701EE09C4B2AB1DA7842F0020291 +:10D40000DA709A785A70D9788A0705D4964A906863 +:10D41000381AC043C00F00E00120934A187048B189 +:10D42000CC0707D513799149013303F00303137136 +:10D43000CB5C53708C4C23784BB3F9F7DBFEB020F8 +:10D44000F9F7D4FE4020F9F7D1FE0020F9F7CEFE1F +:10D450001020F9F7CBFE4FF4806808F1FF38002068 +:10D460001FFA88F8F9F7A4FEB8F1000FF5D140468D +:10D47000F9F731FF7E4B627853F82200F9F754FD3B +:10D48000E37823F00203E3707A4B3B44A3606378B4 +:10D49000052B00F27281DFE813F0080070011B0019 +:10D4A000770006001B010024D5E07349734A7448D5 +:10D4B000F8F728FD0120F9F70EFF7148F9F734FD60 +:10D4C000704B6F4870491A68F8F71CFD02204FE155 +:10D4D0006E4B9A68984612F0020F2ED06C4C0A23BD +:10D4E00021786C4FB1FBF3F203FB12133978DBB2F6 +:10D4F000634800916849F8F705FDFDF79DF80120A4 +:10D50000F9F7E9FE5E48F9F70FFD644B3A781868C1 +:10D5100024788378642102FB13444C434178022031 +:10D52000CB1A5A43B4FBF2F4E4B2F9F7D4FE214625 +:10D530001520F9F7ADFC032400E00124D8F80830E9 +:10D54000180540F11A81564B56491F680968642333 +:10D5500097FBF3F203FB1273009149485249F8F725 +:10D56000D1FCFDF769F82046F9F7B5FE4448F9F714 +:10D57000DBFCFEF78DFA0746601CF9F7ACFE1520C0 +:10D580003946F9F785FCF8E00120484FF9F7A3FE8A +:10D590004748F9F7C9FC3B68990715D5454938480C +:10D5A000B1F90020B1F90230B1F90410032400915F +:10D5B0004149F8F7A7FCFDF73FF80220F9F78BFE89 +:10D5C0002F48F9F7B1FC00E002243B68DA0718D5D0 +:10D5D0003A492B48B1F90020B1F90230B1F90410F1 +:10D5E00004F1010800913649F8F78CFCFDF724F8A6 +:10D5F0002046F9F770FE2248F9F796FC5FFA88F8A2 +:10D6000044463B681B0740F1B8802E491C48B1F9DD +:10D610000020B1F90230B1F9041000912A49F8F75D +:10D6200071FCFDF709F82046A2E00E2C00F0A58061 +:10D6300060080130F9F74FFE2046F9F752FC3B78BD +:10D64000A34206D92020F9F7B7FD601CC0B2F9F754 +:10D6500048FC0234E4B21D4F3B78A342E5D88CE08D +:10D660000C1E0020D6270020B80700201455010802 +:10D67000AC000020404B4C00DF700108046301083F +:10D68000111E0020C4000020E77001082C2000209B +:10D69000C005002094000020F2700108BC050020A5 +:10D6A000C4050020C80500200A7101084C020020B2 +:10D6B0001F710108B404002035710108FC0300202B +:10D6C000457101087C02002055710108630A0020A1 +:10D6D000354C364994F854273548F8F713FC0120A7 +:10D6E000F9F7F9FD3248F9F71FFC324B32491F7840 +:10D6F0002F483A46F8F706FC0220F9F7ECFD2C48D3 +:10D70000F9F712FC0A2303FB07472C4997F8572720 +:10D710002748F8F7F7FBFCF78FFF0320F9F7DBFD4D +:10D720002348F9F701FC264997F856272048F8F7CF +:10D73000E9FBFCF781FF0420F9F7CDFD1C48F9F760 +:10D74000F3FB204997F85A271948F8F7DBFBFCF759 +:10D7500073FF0520F9F7BFFD1548F9F7E5FB1448FD +:10D76000194997F85B27F8F7CDFBFCF765FF062012 +:10D77000F9F7B1FD0E48F9F7D7FB8EB9B020F9F7EC +:10D7800035FD0820F9F732FD1720F9F72FFDEC7E63 +:10D790000E4B185D013404F00304F9F70DFDEC762F +:10D7A00002B0BDE8F08100BF2C20002065710108A7 +:10D7B000111E00203C0E00207171010882710108C9 +:10D7C0008E7101089A710108A7710108B4710108EE +:10D7D0003F4A2DE9F84F916840F201130B4040F2A7 +:10D7E00001118B4293460AD13A4B1A7F93F81D9050 +:10D7F0005A77B9EB020918BF4FF0010901E04FF069 +:10D8000001094FF00008344B5FFA88F41B78A342FB +:10D810005CD9324B324E1B68324F23B93B685B896F +:10D8200026F814304FE03A68072C94BF12F804A091 +:10D83000A246294851469847DBF808300546DB05E3 +:10D8400009D5B9F1000F06D0274B50461B68294671 +:10D850001B68DB699847A5F2EE2240F2DC5392B2D6 +:10D860009A4288BF3B68DBF8082088BF5D8942F296 +:10D87000010313402BB31D4B1978164B01F0030223 +:10D8800002EB840293F87E0003EB4202D5831A4632 +:10D8900020B9032915D9012183F87E1002EBC403B6 +:10D8A000198CDD8B02EB44020D44598C9B8C0D448A +:10D8B0001D44ADB2A2F8805004232DB295FBF3F5C0 +:10D8C000ADB226F8145008F101089CE7BDE8F88FC6 +:10D8D0002C2000200C1E0020630A00206C0A00206F +:10D8E0001A0700203C01002040020020E40D002027 +:10D8F0002DE9F74F2A4B157C9B68019003F04009F6 +:10D9000003F4007C03F40058032D45D80C246C4329 +:10D91000244B0198E618377A013538423AD0E35C57 +:10D920004BB1012B07D0032B04D0042B14BF0423CD +:10D93000032300E00223DFF870A01F010AEB0704B5 +:10D94000B9F1000F06D11AF807B0ABF1030BBBF128 +:10D95000010F1FD9BCF1000F06D0B8F1000F03D1A1 +:10D960001AF80770042F15D04F7B94F80CA007EA23 +:10D970000A0ABA450ED14F68606887420AD38F6899 +:10D98000A068874206D8137094605660D160157401 +:10D99000104602E0EDB2B7E7002003B0BDE8F08F1B +:10D9A0002C2000206400002018550108094B30B5D8 +:10D9B0009D68094B05F480551868084B1C680023C6 +:10D9C0000DB1828800E0A28805495A520233182B13 +:10D9D000F6D130BD2C200020A81E0020AC1E002057 +:10D9E000DC0F0020F8B50024204BE0B21F78B842CD +:10D9F0000CD21F4B33F810101E4B53F820301BB1C4 +:10DA00000B2801D8DB6898470134EDE71A4B9B6877 +:10DA10005B032AD50025194E2B46EAB2BA4224D21E +:10DA2000726854689C4218D02046FCF77EFFEFF3E2 +:10DA30001283502282F3128811494FF0280CA28CD5 +:10DA40000CFB001092B201324262A28ADBB292B2A7 +:10DA500042F00102A28283F3118856F8043F0022AB +:10DA60001B6801351A802346D7E7F8BDE12700205F +:10DA7000A4270020380900202C2000203409002091 +:10DA8000CC1E00202DE9F041FDF714FB10B90A204F +:10DA9000F7F7B0F9824C4FF4EF622046814904F069 +:10DAA0008BF994F854374FF4E072022B84BF0023B3 +:10DAB00084F8543794F854377B4E02FB034303F544 +:10DAC000057393F850203360022A84BF002283F844 +:10DAD000502093F85030754A13700A2202FB03431A +:10DAE000734A03F256731360A36842F201021A40AC +:10DAF0003AB944F208021A401AB9694A43F4005389 +:10DB00009360A368D90703D54FF40050FCF72FFDAD +:10DB1000A3685A0409D50820FCF729FD4FF40050EA +:10DB2000FCF725FD0120FCF722FDA3681B0706D5A5 +:10DB30004FF40050FCF71BFD0120FCF718FDA36813 +:10DB40009F040ED54FF40040FCF711FD4FF4006028 +:10DB5000FCF70DFD4FF48030FCF709FD4020FCF789 +:10DB600006FDA3685D0603D54FF48030FCF7FFFC8B +:10DB7000A368980408D503F42063B3F5206F03D19C +:10DB80004FF40060FCF7F3FC4A4D4B4B2F461D60F1 +:10DB9000FEF726FA494B05F11C0201201A60FDF739 +:10DBA000CCF901460120FDF797F8002849D0022062 +:10DBB000FDF7C3F901460220FDF78EF8002840D09A +:10DBC0002020FDF7BAF901462020FDF785F8A3686B +:10DBD000190601D5002834D01020FDF7AEF9014612 +:10DBE0001020FDF779F8A3681A0700D548B3042080 +:10DBF000FDF7A3F901460420FDF76EF830B90820BF +:10DC0000FDF79BF901460820FDF766F8A3685B0560 +:10DC100003D400231A46194609E00028F9D110E080 +:10DC200079B90121C00708D40C33302B0BD024481C +:10DC30001844007A8507F5D5F2E70132D2B2022AFC +:10DC4000F2D9FEF7F7F9F6F785FF1E4D1E4B326845 +:10DC50001D601E4B101D186002F175010023A846BF +:10DC6000CD5C55B901EB030E9EF802C09EF803E0AF +:10DC7000F44502D2164B1D7002E00433A02BEFD105 +:10DC8000144B15490B60154950330B601178144B38 +:10DC9000012903D0022929D0124928E0124926E09F +:10DCA0002C20002000F80108E80300203C0E002092 +:10DCB000980500203C2100203C010020D80F0020C6 +:10DCC00064000020FC200020340E0020380E0020CC +:10DCD000480000202021002004040020AC05002082 +:10DCE00098000020957E0008ED7C000833491960FB +:10DCF000334B02F5D9721A60FCF772FD3568314B6F +:10DD000005F5D3721A60304B00229A802F4B304AAF +:10DD1000304E136005F5B3723260A3F122027260D7 +:10DD20002E332D4A05F5D771F36005F5D8731160D0 +:10DD30007361C6F808803761B4F8F00000F020FF86 +:10DD4000F061B4F8F20000F01BFF95F85830306233 +:10DD5000337695F874301836737094F825312A1D8F +:10DD600033731E4BB5F862011E601D4B1A601D4BCC +:10DD700005F160021A601C4B05F164021A601B4B2E +:10DD800005F25D121A601A4BC3F8008000F0FCFE29 +:10DD90000146184801F000F8174900F049FF174BF9 +:10DDA00017491860E86D00F043FF01464FF07C50C2 +:10DDB00000F0F2FF134B1860BDE8F0813D810008D0 +:10DDC0008C050020242000204C0A00202421002063 +:10DDD00070040020A41E0020A4050020A40400203C +:10DDE000D4030020F0040020C80200207C0500209D +:10DDF00084050020000061444C3D0F44880500204C +:10DE0000DB0F4940EC04002001480249FCF74ABD01 +:10DE100000080040441F002001480249FCF742BDB1 +:10DE2000000400401C1F00204FF080400149FCF717 +:10DE300039BD00BFF41E002001480249FCF732BD85 +:10DE4000002C0140CC1E002001480249FCF72ABDED +:10DE5000002C0140CC1E002038B5204CD4F8F03006 +:10DE60001D88ADB2AA0618D5D4F8CC201AB198886E +:10DE700080B2904711E09B88D4F8BC20D4F8B4104D +:10DE8000DBB28B54D4F8BC20D4F8AC300132B2FBF6 +:10DE9000F3F103FB1123C4F8BC302B061DD5D4F8D5 +:10DEA000C820D4F8C4100D4B8A4210D0D3F8B80063 +:10DEB000D3F8F010805C0132C0B28880D3F8B01083 +:10DEC000B2FBF1F001FB1022C3F8C82038BDD3F833 +:10DED000F030DA6822F08002DA6038BDCC1E002013 +:10DEE0000F4BD3F844211188090618D5D3F81C111B +:10DEF000D3F8180181420ED0D3F80C01405C0131F7 +:10DF0000C0B29080D3F80421B1FBF2F002FB1011F3 +:10DF1000C3F81C117047D36823F08003D3607047A7 +:10DF2000CC1E00200C480D4B4FF400525A60D0F824 +:10DF300028214FF6FE7311680B401360D0F81821AA +:10DF4000D0F81C319A4202D0F430FAF757BF0123BF +:10DF500080F83831704700BFCC1E0020000002401E +:10DF6000F6F720BEF6F71EBE084A13689B020BD5D3 +:10DF7000074B0021197007494FF6FE7308680340EC +:10DF80000B604FF400135360704700BF0000024065 +:10DF9000CA2700206C000240F9F7CABCF9F7C8BCD8 +:10DFA000FAF70ABDFAF708BD074B1A685969490420 +:10DFB00008D5520406D54FF480425A61034B012222 +:10DFC00083F84821704700BF00040140CC1E0020A8 +:10DFD00010B51B4B1A78510731D51A4C22F00402A8 +:10DFE0001A70A3685A050AD5FEF7C4FF0420012160 +:10DFF000FDF733F818B104F59670FEF7DFFEA3685D +:10E000001B031CD5104B1A78012A0ED90F4C012284 +:10E01000206821791A70F6F70FFF2068A168F6F7DB +:10E0200015FF20688021FCF799FE80200121FDF773 +:10E0300014F820B10648BDE81040FEF7BFBE10BD81 +:10E04000D62700202C200020E20D002018200020E0 +:10E050005821002070B5FBF7F1FE38B3144C237A39 +:10E060000BB9A38070BD134D2E78C6F38000FBF76B +:10E07000F7FE90B1104B46F002061A680F4B51891B +:10E080002E7019805189598052899A800C4AD26821 +:10E090005288DA80E3880133E380FBF7BBFE10B9D6 +:10E0A0002B785B0702D4BDE8704091E770BD00BFDC +:10E0B0004C0A0020D6270020480A00201A0700201A +:10E0C000182000200F4B1A6842F001021A605968AC +:10E0D0000D4A0A405A601A6822F0847222F4803293 +:10E0E0001A601A6822F480221A605A6822F4FE022A +:10E0F0005A604FF41F029A60044B4FF000629A601E +:10E10000704700BF001002400000FFF800ED00E083 +:10E11000024B1A6801321A60704700BF28200020A5 +:10E1200008B5084BB3F8D800074B1A780023D9B2CA +:10E13000914204D2054921F813000133F7E7FFF7B4 +:10E1400051FCFEE728200020E1270020A427002022 +:10E1500081F0004102E000BF83F0004330B54FEA98 +:10E1600041044FEA430594EA050F08BF90EA020F05 +:10E170001FBF54EA000C55EA020C7FEA645C7FEA98 +:10E18000655C00F0E2804FEA5454D4EB5555B8BFBB +:10E190006D420CDD2C4480EA020281EA030382EA2C +:10E1A000000083EA010180EA020281EA0303362DBE +:10E1B00088BF30BD11F0004F4FEA01314FF4801C91 +:10E1C0004CEA113102D0404261EB410113F0004FA3 +:10E1D0004FEA03334CEA133302D0524263EB43035A +:10E1E00094EA050F00F0A780A4F10104D5F1200EF8 +:10E1F0000DDB02FA0EFC22FA05F2801841F1000153 +:10E2000003FA0EF2801843FA05F359410EE0A5F126 +:10E2100020050EF1200E012A03FA0EFC28BF4CF057 +:10E22000020C43FA05F3C01851EBE37101F000450D +:10E2300007D54FF0000EDCF1000C7EEB00006EEB1A +:10E240000101B1F5801F1BD3B1F5001F0CD34908A4 +:10E250005FEA30004FEA3C0C04F101044FEA4452FB +:10E2600012F5800F80F09A80BCF1004F08BF5FEA82 +:10E27000500C50F1000041EB045141EA050130BD62 +:10E280005FEA4C0C404141EB010111F4801FA4F105 +:10E290000104E9D191F0000F04BF01460020B1FA5A +:10E2A00081F308BF2033A3F10B03B3F120020CDA92 +:10E2B0000C3208DD02F1140CC2F10C0201FA0CF070 +:10E2C00021FA02F10CE002F11402D8BFC2F1200CD5 +:10E2D00001FA02F120FA0CFCDCBF41EA0C0190408B +:10E2E000E41AA2BF01EB0451294330BD6FEA0404D4 +:10E2F0001F3C1CDA0C340EDC04F11404C4F12002BF +:10E3000020FA04F001FA02F340EA030021FA04F3D0 +:10E3100045EA030130BDC4F10C04C4F1200220FA27 +:10E3200002F001FA04F340EA0300294630BD21FA65 +:10E3300004F0294630BD94F0000F83F4801306BF2B +:10E3400081F480110134013D4EE77FEA645C18BF1F +:10E350007FEA655C29D094EA050F08BF90EA020FB6 +:10E3600005D054EA000C04BF1946104630BD91EAAE +:10E37000030F1EBF0021002030BD5FEA545C05D1B1 +:10E380004000494128BF41F0004130BD14F58004F0 +:10E390003CBF01F5801130BD01F0004545F0FE4164 +:10E3A00041F470014FF0000030BD7FEA645C1ABF99 +:10E3B000194610467FEA655C1CBF0B46024650EAD0 +:10E3C000013406BF52EA033591EA030F41F40021FC +:10E3D00030BD00BF90F0000F04BF0021704730B582 +:10E3E0004FF4806404F132044FF000054FF0000157 +:10E3F00050E700BF90F0000F04BF0021704730B518 +:10E400004FF4806404F1320410F0004548BF4042EC +:10E410004FF000013EE700BF42004FEAE2014FEA41 +:10E4200031014FEA02701FBF12F07F4393F07F4F1C +:10E4300081F06051704792F0000F14BF93F07F4F4E +:10E44000704730B54FF4607401F0004521F0004191 +:10E4500020E700BF50EA010208BF704730B54FF017 +:10E4600000050AE050EA010208BF704730B511F01C +:10E47000004502D5404261EB41014FF4806404F154 +:10E4800032045FEA915C3FF4DCAE4FF003025FEAD6 +:10E49000DC0C18BF03325FEADC0C18BF033202EB5E +:10E4A000DC02C2F1200300FA03FC20FA02F001FAB8 +:10E4B00003FE40EA0E0021FA02F11444C1E600BF57 +:10E4C00070B54FF0FF0C4CF4E06C1CEA11541DBF0A +:10E4D0001CEA135594EA0C0F95EA0C0F00F0DEF8D5 +:10E4E0002C4481EA030621EA4C5123EA4C5350EABA +:10E4F000013518BF52EA033541F4801143F480130B +:10E5000038D0A0FB02CE4FF00005E1FB02E506F09B +:10E510000042E0FB03E54FF00006E1FB03569CF0F0 +:10E52000000F18BF4EF0010EA4F1FF04B6F5007FF6 +:10E5300064F5407404D25FEA4E0E6D4146EB060668 +:10E5400042EAC62141EA55514FEAC52040EA5E50F1 +:10E550004FEACE2EB4F1FD0C88BFBCF5E06F1ED89B +:10E56000BEF1004F08BF5FEA500E50F1000041EBD2 +:10E57000045170BD06F0004646EA010140EA02007F +:10E5800081EA0301B4EB5C04C2BFD4EB0C0541EAA1 +:10E59000045170BD41F480114FF0000E013C00F3B6 +:10E5A000AB8014F1360FDEBF002001F0004170BDDA +:10E5B000C4F10004203C35DA0C341BDC04F11404F3 +:10E5C000C4F1200500FA05F320FA04F001FA05F27F +:10E5D00040EA020001F0004221F0004110EBD3704C +:10E5E00021FA04F642EB06015EEA430E08BF20EA78 +:10E5F000D37070BDC4F10C04C4F1200500FA04F31B +:10E6000020FA05F001FA04F240EA020001F00041AC +:10E6100010EBD37041F100015EEA430E08BF20EA1F +:10E62000D37070BDC4F1200500FA05F24EEA020E67 +:10E6300020FA04F301FA05F243EA020321FA04F096 +:10E6400001F0004121FA04F220EA020000EBD3704D +:10E650005EEA430E08BF20EAD37070BD94F0000F4D +:10E660000FD101F00046400041EB010111F4801F81 +:10E6700008BF013CF7D041EA060195F0000F18BF32 +:10E68000704703F00046520043EB030313F4801F6E +:10E6900008BF013DF7D043EA0603704794EA0C0F28 +:10E6A0000CEA135518BF95EA0C0F0CD050EA41063E +:10E6B00018BF52EA4306D1D181EA030101F00041BB +:10E6C0004FF0000070BD50EA410606BF10461946E3 +:10E6D00052EA430619D094EA0C0F02D150EA0136EF +:10E6E00013D195EA0C0F05D152EA03361CBF104630 +:10E6F00019460AD181EA030101F0004141F0FE41CF +:10E7000041F470014FF0000070BD41F0FE4141F452 +:10E71000780170BD70B54FF0FF0C4CF4E06C1CEA52 +:10E7200011541DBF1CEA135594EA0C0F95EA0C0F07 +:10E7300000F0A7F8A4EB050481EA030E52EA0335C2 +:10E740004FEA013100F088804FEA03334FF08055E3 +:10E7500045EA131343EA12634FEA022245EA111510 +:10E7600045EA10654FEA00260EF000419D4208BFC1 +:10E77000964244F1FD0404F5407402D25B084FEA6E +:10E780003202B61A65EB03055B084FEA32024FF41A +:10E7900080104FF4002CB6EB020E75EB030E22BF77 +:10E7A000B61A754640EA0C005B084FEA3202B6EB37 +:10E7B000020E75EB030E22BFB61A754640EA5C00E6 +:10E7C0005B084FEA3202B6EB020E75EB030E22BF76 +:10E7D000B61A754640EA9C005B084FEA3202B6EB77 +:10E7E000020E75EB030E22BFB61A754640EADC0036 +:10E7F00055EA060E18D04FEA051545EA16754FEA98 +:10E8000006164FEAC30343EA52734FEAC2025FEAB5 +:10E810001C1CC0D111F4801F0BD141EA00014FF044 +:10E8200000004FF0004CB6E711F4801F04BF014315 +:10E830000020B4F1FD0C88BFBCF5E06F3FF6AFAE31 +:10E84000B5EB030C04BFB6EB020C5FEA500C50F1C1 +:10E85000000041EB045170BD0EF0004E4EEA113144 +:10E8600014EB5C04C2BFD4EB0C0541EA045170BD4B +:10E8700041F480114FF0000E013C90E645EA060E8F +:10E880008DE60CEA135594EA0C0F08BF95EA0C0FBD +:10E890003FF43BAF94EA0C0F0AD150EA01347FF405 +:10E8A00034AF95EA0C0F7FF425AF104619462CE7DC +:10E8B00095EA0C0F06D152EA03353FF4FDAE10463F +:10E8C000194622E750EA410618BF52EA43067FF490 +:10E8D000C5AE50EA41047FF40DAF52EA43057FF420 +:10E8E000EBAE12E74FEA410212F5001215D211D534 +:10E8F0006FF47873B3EB625212D94FEAC12343F03D +:10E90000004343EA505311F0004F23FA02F018BFBE +:10E91000404270474FF00000704750EA013005D187 +:10E9200011F0004008BF6FF0004070474FF000004A +:10E93000704700BF4A0011D212F5001211D20DD556 +:10E940006FF47873B3EB62520ED44FEAC12343F0F5 +:10E95000004343EA505323FA02F070474FF000009F +:10E96000704750EA013002D14FF0FF3070474FF04E +:10E97000000070474FEA4102B2F1E04324BFB3F513 +:10E98000001CDCF1FE5C0DD901F0004C4FEAC00226 +:10E990004CEA5070B2F1004F40EB830008BF20F00A +:10E9A0000100704711F0804F21D113F13872BCBFC4 +:10E9B00001F00040704741F480114FEA5252C2F119 +:10E9C0001802C2F1200C10FA0CF320FA02F018BF62 +:10E9D00040F001004FEAC1234FEAD32303FA0CFCB5 +:10E9E00040EA0C0023FA02F34FEA4303CCE77FEA44 +:10E9F000625307D150EA01331EBF4FF0FE4040F48E +:10EA00004000704701F0004040F0FE4040F400003C +:10EA1000704700BF80F0004002E000BF81F000417D +:10EA200042001FBF5FEA410392EA030F7FEA226CB4 +:10EA30007FEA236C6AD04FEA1262D2EB1363C1BF44 +:10EA4000D218414048404140B8BF5B42192B88BFB3 +:10EA5000704710F0004F40F4000020F07F4018BFD6 +:10EA6000404211F0004F41F4000121F07F4118BFF6 +:10EA7000494292EA030F3FD0A2F1010241FA03FC9E +:10EA800010EB0C00C3F1200301FA03F100F0004386 +:10EA900002D5494260EB4000B0F5000F13D3B0F14E +:10EAA000807F06D340084FEA310102F10102FE2ABD +:10EAB00051D2B1F1004F40EBC25008BF20F001002D +:10EAC00040EA03007047490040EB000010F4000FDB +:10EAD000A2F10102EDD1B0FA80FCACF1080CB2EB6E +:10EAE0000C0200FA0CF0AABF00EBC25052421843CD +:10EAF000BCBFD0401843704792F0000F81F4000172 +:10EB000006BF80F400000132013BB5E74FEA410344 +:10EB10007FEA226C18BF7FEA236C21D092EA030FB0 +:10EB200004D092F0000F08BF0846704790EA010F2A +:10EB30001CBF0020704712F07F4F04D1400028BF57 +:10EB400040F00040704712F100723CBF00F5000039 +:10EB5000704700F0004343F0FE4040F4000070476F +:10EB60007FEA226216BF08467FEA2363014642021B +:10EB700006BF5FEA412390EA010F40F4800070472E +:10EB80004FF0000304E000BF10F0004348BF4042D4 +:10EB90005FEA000C08BF704743F0964301464FF010 +:10EBA00000001CE050EA010208BF70474FF000036C +:10EBB0000AE000BF50EA010208BF704711F00043AD +:10EBC00002D5404261EB41015FEA010C02BF84467D +:10EBD0000146002043F0B64308BFA3F18053A3F5DC +:10EBE0000003BCFA8CF2083AA3EBC25310DB01FA23 +:10EBF00002FC634400FA02FCC2F12002BCF1004FA7 +:10EC000020FA02F243EB020008BF20F00100704737 +:10EC100002F1200201FA02FCC2F1200250EA4C008B +:10EC200021FA02F243EB020008BF20EADC707047D1 +:10EC30004FF0FF0C1CEAD0521EBF1CEAD15392EADF +:10EC40000C0F93EA0C0F6FD01A4480EA010C4002BB +:10EC500018BF5FEA41211ED04FF0006343EA501015 +:10EC600043EA5111A0FB01310CF00040B1F5000F57 +:10EC70003EBF490041EAD3715B0040EA010062F106 +:10EC80007F02FD2A1DD8B3F1004F40EBC25008BFF0 +:10EC900020F00100704790F0000F0CF0004C08BF0E +:10ECA00049024CEA502040EA51207F3AC2BFD2F1DB +:10ECB000FF0340EAC250704740F400004FF00003E9 +:10ECC000013A5DDC12F1190FDCBF00F00040704723 +:10ECD000C2F10002410021FA02F1C2F1200200FA61 +:10ECE00002FC5FEA310040F1000053EA4C0308BF28 +:10ECF00020EADC70704792F0000F00F0004C02BF79 +:10ED0000400010F4000F013AF9D040EA0C0093F0F3 +:10ED1000000F01F0004C02BF490011F4000F013B4D +:10ED2000F9D041EA0C018FE70CEAD15392EA0C0FBB +:10ED300018BF93EA0C0F0AD030F0004C18BF31F026 +:10ED4000004CD8D180EA010000F00040704790F0FC +:10ED5000000F17BF90F0004F084691F0000F91F0A0 +:10ED6000004F14D092EA0C0F01D142020FD193EA66 +:10ED70000C0F03D14B0218BF084608D180EA0100EE +:10ED800000F0004040F0FE4040F40000704740F0CA +:10ED9000FE4040F4400070474FF0FF0C1CEAD05298 +:10EDA0001EBF1CEAD15392EA0C0F93EA0C0F69D0F4 +:10EDB000A2EB030280EA010C49024FEA402037D05F +:10EDC0004FF0805343EA111143EA10130CF0004056 +:10EDD0008B4238BF5B0042F17D024FF4000C8B4246 +:10EDE00024BF5B1A40EA0C00B3EB510F24BFA3EB26 +:10EDF000510340EA5C00B3EB910F24BFA3EB9103F6 +:10EE000040EA9C00B3EBD10F24BFA3EBD10340EA4F +:10EE1000DC001B0118BF5FEA1C1CE0D1FD2A3FF695 +:10EE200050AF8B4240EBC25008BF20F0010070474A +:10EE30000CF0004C4CEA50207F32C2BFD2F1FF03ED +:10EE400040EAC250704740F400004FF00003013A1E +:10EE500037E792F0000F00F0004C02BF400010F4C2 +:10EE6000000F013AF9D040EA0C0093F0000F01F0D6 +:10EE7000004C02BF490011F4000F013BF9D041EAF8 +:10EE80000C0195E70CEAD15392EA0C0F08D142022B +:10EE90007FF47DAF93EA0C0F7FF470AF084676E7FE +:10EEA00093EA0C0F04D14B023FF44CAF08466EE7D7 +:10EEB00030F0004C18BF31F0004CCAD130F00042A5 +:10EEC0007FF45CAF31F000437FF43CAF5FE700BFFD +:10EED0004FF0FF3C06E000BF4FF0010C02E000BF26 +:10EEE0004FF0010C4DF804CD4FEA40024FEA4103C8 +:10EEF0007FEA226C18BF7FEA236C11D001B052EA7E +:10EF0000530C18BF90EA010F58BFB2EB030088BF43 +:10EF1000C81738BF6FEAE17018BF40F001007047B2 +:10EF20007FEA226C02D15FEA402C05D17FEA236C94 +:10EF3000E4D15FEA412CE1D05DF8040B704700BFDB +:10EF4000844608466146FFE70FB5FFF7C9FF002872 +:10EF500048BF10F1000F0FBD4DF808EDFFF7F4FFAB +:10EF60000CBF012000205DF808FB00BF4DF808ED44 +:10EF7000FFF7EAFF34BF012000205DF808FB00BF67 +:10EF80004DF808EDFFF7E0FF94BF012000205DF889 +:10EF900008FB00BF4DF808EDFFF7D2FF94BF01203A +:10EFA00000205DF808FB00BF4DF808EDFFF7C8FF33 +:10EFB00034BF012000205DF808FB00BF4FEA40028B +:10EFC000B2F1FE4F0FD34FF09E03B3EB12620DD997 +:10EFD0004FEA002343F0004310F0004F23FA02F001 +:10EFE00018BF404270474FF00000704712F1610FA8 +:10EFF00001D1420205D110F0004008BF6FF000407F +:10F0000070474FF00000704742000ED2B2F1FE4F41 +:10F010000BD34FF09E03B3EB126209D44FEA0023E7 +:10F0200043F0004323FA02F070474FF000007047AE +:10F0300012F1610F01D1420202D14FF0FF3070474F +:10F040004FF00000704700BF73B96AB9002908BFCC +:10F050000028BCBF00204FF00041C4BF6FF000414A +:10F060004FF0FF3000F03CB882B0EC462DE9005084 +:10F0700000F006F8DDF804E002B00CBC704700BFF9 +:10F080002DE9704F089E14461D468046894600F0C3 +:10F0900029F804FB01F3A4FB00AB00FB0532934409 +:10F0A000B8EB0A0869EB0B09C6E90089BDE8708F67 +:10F0B0002DE9704F089E14461D468046894600F093 +:10F0C00061F900FB05F5A0FB04AB04FB0154A3446C +:10F0D000B8EB0A0869EB0B09C6E90089BDE8708F37 +:10F0E000704700BF00292DE9F00FC0F2A180002475 +:10F0F000002BC0F29880154606460F46002B3FD1E4 +:10F100008A4258D9B2FA82F34BB1C3F1200201FA14 +:10F1100003F720FA02F29D4000FA03F61743290C88 +:10F12000B7FBF1F201FB1277A8B200FB02F34FEA42 +:10F13000164C4CEA0747BB4209D97F1902F1FF3C44 +:10F1400080F00581BB4240F20281023A2F44FF1A4F +:10F15000B7FBF1F301FB137100FB03F0B6B246EA13 +:10F160000141884208D9491903F1FF3780F0F18045 +:10F17000884240F2EE80023B43EA0242002303E071 +:10F180008B420AD900231A461046194614B1404250 +:10F1900061EB4101BDE8F00F7047B3FA83F8B8F1B5 +:10F1A000000F40F088808B4202D3824200F2E2805E +:10F1B00000230122E8E712B90123B3FBF2F5B5FA07 +:10F1C00085F2002A3AD17F1B280C1FFA85FC012307 +:10F1D000B7FBF0F100FB11770CFB01F24FEA164888 +:10F1E00048EA0747BA4207D97F1901F1FF3802D22E +:10F1F000BA4200F2C4804146BF1AB7FBF0F200FBEE +:10F2000012700CFB02FCB6B246EA0040844507D9F6 +:10F21000401902F1FF3702D2844500F2AE803A462F +:10F2200042EA0142B0E7E443524263EB430362E740 +:10F23000404261EB41014FF0FF3459E79540C2F184 +:10F24000200927FA09F126FA09F99740280CB1FBA1 +:10F25000F0F800FB18111FFA85FC0CFB08F349EAD3 +:10F2600007094FEA194747EA01418B4206FA02F6BD +:10F2700008D9491908F1FF327AD28B4278D9A8F11E +:10F2800002082944C91AB1FBF0F300FB13170CFB69 +:10F2900003F21FFA89F949EA0747BA4207D97F19E9 +:10F2A00003F1FF3160D2BA425ED9023B2F44BF1A4C +:10F2B00043EA08438CE7C8F1200225FA02F103FA79 +:10F2C00008FC27FA02F320FA02F207FA08F741EAEB +:10F2D0000C0C4FEA1C49B3FBF9F109FB11331FFA7F +:10F2E0008CFA0AFB01FB17433A0C42EA03439B45A5 +:10F2F00005FA08F008D913EB0C0301F1FF3235D2FF +:10F300009B4533D902396344CBEB0303B3FBF9F2DA +:10F3100009FB12330AFB02FABFB247EA0347BA45B8 +:10F3200008D917EB0C0702F1FF331BD2BA4519D9E4 +:10F33000023A674442EA0145A5FB0001CAEB070710 +:10F340008F424FF000030AD305D02A461CE76246DD +:10F35000FDE63B4610E706FA08F68642F5D26A1E3D +:10F36000002311E71A46E5E70B46A0E71146CBE775 +:10F37000904687E74346424606E7023A50E702399D +:10F380002F4439E72DE9F00F144605460E46002BB1 +:10F3900043D18A4253D9B2FA82F757B1C7F1200656 +:10F3A00020FA06F601FA07F302FA07F400FA07F565 +:10F3B0001E43210CB6FBF1F201FB1266A0B200FB6A +:10F3C00002F32F0C47EA0646B34209D9361902F177 +:10F3D000FF3780F0FD80B34240F2FA80023A2644C3 +:10F3E000F61AB6FBF1F301FB136100FB03F0ADB2BB +:10F3F00045EA0141884208D9091903F1FF3680F036 +:10F40000E980884240F2E680023B43EA0242002360 +:10F4100010461946BDE8F00F70478B424CD8B3FA3E +:10F4200083F6002E4FD18B4202D3824200F2DD8060 +:10F43000BDE8F00F0023012210461946704712B9AB +:10F440000124B4FBF2F4B4FA84F2002A40F0828082 +:10F45000091B260CA7B20123B1FBF6F006FB101125 +:10F4600007FB00F24FEA154C4CEA01418A4207D9EA +:10F47000091900F1FF3C02D28A4200F2C8806046BE +:10F48000891AB1FBF6F206FB121107FB02F7ADB2C7 +:10F4900045EA0145AF4208D92C1902F1FF3180F04D +:10F4A0009B80A74240F29880023A42EA004210460E +:10F4B0001946BDE8F00F704700231A46104619465A +:10F4C000BDE8F00F7047C6F1200522FA05F703FAF0 +:10F4D00006F421FA05F301FA06FB20FA05F53C4390 +:10F4E0004FEA1448B3FBF8FC08FB1C331FFA84F9FD +:10F4F00009FB0CFA45EA0B0B4FEA1B4545EA0343AF +:10F500009A4502FA06F204D91B190CF1FF356FD3A4 +:10F51000AC46CAEB0303B3FBF8F508FB153309FB54 +:10F5200005F91FFA8BFB4BEA0347B94504D93F198C +:10F5300005F1FF3362D31D4645EA0C4CACFB0223B8 +:10F54000C9EB07079F424FF000054AD346D06246F9 +:10F550002B465DE79440C2F1200921FA09FC914055 +:10F5600020FA09F9260CBCFBF6F806FB18CCA7B26A +:10F5700007FB08F349EA01094FEA194141EA0C4C3B +:10F58000634500FA02F509D91CEB040C08F1FF32BF +:10F590003BD2634539D9A8F10208A444C3EB0C0C53 +:10F5A000BCFBF6F306FB13C107FB03F21FFA89F954 +:10F5B00049EA01418A4207D9091903F1FF3022D2F1 +:10F5C0008A4220D9023B2144891A43EA084343E78F +:10F5D0003A4605E7334618E70A4666E7B0409042E8 +:10F5E000B5D20CF1FF32002312E7334632460FE763 +:10F5F0009A458DD9ACF1020C23448AE7B9459AD9D2 +:10F60000023D274498E70346DEE79046C6E7023806 +:10F61000214435E74FF0FF3C06E000BF4FF0010CFE +:10F6200002E000BF4FF0010C4DF804CD4FEA410C51 +:10F630007FEA6C5C4FEA430C18BF7FEA6C5C1BD01E +:10F6400001B050EA410C0CBF52EA430C91EA030F9F +:10F6500002BF90EA020F0020704710F1000F91EAFC +:10F66000030F58BF994208BF90422CBFD8176FEACA +:10F67000E37040F0010070474FEA410C7FEA6C5C98 +:10F6800002D150EA013C07D14FEA430C7FEA6C5C9F +:10F69000D6D152EA033CD3D05DF8040B704700BFCB +:10F6A0008446104662468C461946634600E000BF19 +:10F6B00001B5FFF7B7FF002848BF10F1000F01BDEB +:10F6C0004DF808EDFFF7F4FF0CBF012000205DF8B6 +:10F6D00008FB00BF4DF808EDFFF7EAFF34BF01203B +:10F6E00000205DF808FB00BF4DF808EDFFF7E0FFD4 +:10F6F00094BF012000205DF808FB00BF4DF808ED25 +:10F70000FFF7CEFF94BF012000205DF808FB00BF8B +:10F710004DF808EDFFF7C4FF34BF012000205DF86D +:10F7200008FB00BF1C481D49026800608A4200F0C7 +:10F730001D80002100F004B8194B5B584350043180 +:10F740001848194B42189A42FFF4F6AF174A00F0D6 +:10F7500003B8002342F8043B154B9A42FFF4F9AF7B +:10F76000FEF7B0FC00F038F8FFF7FEBF114E12486C +:10F7700030601248016821F070610160410201604F +:10F780000F4C182020600F490F4808600F48D0F830 +:10F7900000D0406800470000F04F0020EFBEADDE13 +:10F7A000B07E010800000020340100203801002054 +:10F7B000F427002018100240090000000400014056 +:10F7C000140C0140000C01404434434400F0FF1F7E +:10F7D000FFF7FEBF000000002DE9804893B0F0F76E +:10F7E00097FCB14EB14CD6F80880002318F0080FF2 +:10F7F0002370374600F0E78063681B7A042B00F221 +:10F80000E080DFE803F00303058AB100237AD9E042 +:10F81000627AA64B002A00F0D48000225A7293F834 +:10F820002020120700F1CD80D97A9A7A01F00700E2 +:10F8300042EA00225A621A7B02F03F00400140EA8D +:10F84000D1019962597B890041EA92119A7B02F0B9 +:10F85000010041EA8021D962D97B01F00F00C0018B +:10F8600040EA52021A631A7C02F07F00000140EA6B +:10F8700011115963597C490041EAD212997C01F077 +:10F88000030042EA40229A63DA7C02F01F00800102 +:10F8900040EA9101D963197DC90041EA5212997D6C +:10F8A0001A645A7D01F0070042EA00225A64DA7DA8 +:10F8B00002F03F00400140EAD1019964197E8900BD +:10F8C00041EA92115A7E02F0010041EA8021D96496 +:10F8D000997E01F00F00C00140EA52021A65DA7EFB +:10F8E00002F07F00000140EA11115965197F4900BB +:10F8F00041EAD212597F01F0030042EA40229A65A0 +:10F900009A7F02F01F00800140EA9101D965D97FFA +:10F91000C90041EA52121A6651E094F86420634B20 +:10F92000002A4ED0002283F8642093F86620012A32 +:10F9300047D193F88A20102A84BF102283F88A20A6 +:10F9400094F88A105A4A0023D8B2884202F102027F +:10F9500035D212F8010C12F8025C40EA0525554830 +:10F9600040F823500133EFE794F8CC204F4B42B3DB +:10F97000002283F8CC2093F8CD20A82A21D193F837 +:10F98000E050F5B9494901EB450393F8D00093F8ED +:10F99000D13003EB0020FEF71DFD3FA3D3E9002388 +:10F9A000FEF7B8FE3EA3D3E90023FEF7D5FBFEF732 +:10F9B000C1FF414B43F825000135082DE2D1012359 +:10F9C00000E00023237018F4804F08D094F804312D +:10F9D00023B1364B002283F80421012323702378BE +:10F9E00043B118F4807F05D0304BD3F808311B6841 +:10F9F0001B689847314B22781B6832B92B4AD2F8E2 +:10FA00000C219A1AD243D20F00E0012292B3F2F7EE +:10FA10006BFA94F81021254B002A00F0CC83D3F820 +:10FA200014114D0742F16881D3F81821100707D44B +:10FA3000B3F81C2122F00802A3F81C2102F05CB9E3 +:10FA4000B3F81C0100F0080292B2002A42F054817F +:10FA500040F00800A3F81C01D3F82401C3F83421B6 +:10FA6000C3F82001B3F83001C3F83821A3F8280106 +:10FA700002F042B9D4F83C21511CC4F83C11052ACB +:10FA800000F29183DFE812F01C00AE006E031C014F +:10FA900068038A03AFF300809A999999999919405C +:10FAA00000000000007077402C200020380100206A +:10FAB000A0010020C40100201C020020BC2700205F +:10FAC000D4F81421784D120740F16D83D5F8402108 +:10FAD0009A1A002AC0F2678303F5C33805F5A270AD +:10FAE00008F1A008C5F84081F7F744FD6F4B05F514 +:10FAF000A27001461A78F4F777FE95F84A1105F5D9 +:10FB0000A27011F0040F17D0C5F84C810022BB1869 +:10FB10000025A3F8FE50644B855A03F5A87E22F811 +:10FB20000E5003F5AB7E22F80E500232062AEED1BB +:10FB300021F0040183F84A1194F85C315A4AA3B1C8 +:10FB4000B2F84411B6F8FE30CB1AA2F84431B2F83C +:10FB50004611B6F80031CB1AA2F84631B2F8481176 +:10FB6000B6F80231CB1AA2F84831D4F84C314E4ADB +:10FB7000002B00F018834E49C3EB08038B4202F5BB +:10FB8000A87502F5AB7119D84A4BDA6882F0080201 +:10FB9000DA600023C25A35F903E017B2BE45C4BF8C +:10FBA000DFF818E123F80E2031F903E0BE45BCBFB1 +:10FBB000414FDA530233062BECD1F4E20023C2F8B2 +:10FBC0004C3135F903E0C85EFA1870444FF0020E6C +:10FBD000734490FBFEF0062BA2F8FE00F1D1FDF776 +:10FBE00079F8E0E2D4F814212F4D500740F1DB8280 +:10FBF000D5F860219A1A002AC0F2D582C5F8603182 +:10FC000095F86431012B14D002D3022B29D0CAE21B +:10FC1000D5F870319847D5F874319847012385F8A5 +:10FC20006431B5F86A21D5F860311344C5F8603104 +:10FC3000B9E2D5F878319847D5F86C319847D5F8BE +:10FC40006031B5F8682105F5C0701344C5F860311E +:10FC500005F5C271D5F87C319847022385F86431E7 +:10FC6000A1E2D5F89001D5F88C1100784B1C002743 +:10FC7000834285F86471D5F888E1D5F8802103D1F5 +:10FC8000012385F894313B460748C4F88C3100EBDA +:10FC90008101C1F8982100EB8301D1F898117244D9 +:10FCA000521AC4F888217EE238010020CB270020B8 +:10FCB0007FC3C901000C01408E0200208802002091 +:10FCC000D4F81421510703D5B04991F8941111B912 +:10FCD000D70640F16882D4F85822AC4DC2EB030B32 +:10FCE00046F2A712934540F25E82A94FC5F85832FA +:10FCF000B7F80080B8F1000F2FD0D5F89031D5F8C3 +:10FD00005C221878D5F888310138B3FBF0F008236D +:10FD100092FBF3F1521A1044C5F85C0290FBF3F029 +:10FD2000FEF732FF9B49FFF737F89B4902F080FB53 +:10FD300001464FF07E50FEF771FE9849FEF778FFBE +:10FD4000FFF73CF908F1FF380023C5F86002A7F877 +:10FD50000080C5F86432C5F86832D4F89051D4F800 +:10FD6000883128780138B3FBF0F0FEF709FF8949A4 +:10FD7000FFF712F8884902F05BFB01464FF07E5016 +:10FD8000FEF74CFE8549FEF753FF02F083FA6F68D9 +:10FD90008146D4F86C02FEF7F7FE3946FEF748FFBD +:10FDA0008046D4F86002C0EB0900FEF7EDFE39464C +:10FDB00081464FF07E50FEF731FE01464846FEF781 +:10FDC00037FF01464046FEF72BFE02F063FAB4F916 +:10FDD0007072B4F97232002FB8BF7F42002BB8BFE7 +:10FDE0005B429F42B8BF1F46DFF8C4813FB2FA2F83 +:10FDF0008246D8F8000014DCFEF7C6FE814638467D +:10FE0000FEF7C2FE01466648FEF708FE0146484678 +:10FE1000FEF70EFF6249FEF7BFFFFFF7CFF8074678 +:10FE200001E04FF0FF377B1EC62BC8F8007006D8E4 +:10FE3000C7EB0A03C4F87432C4F86C722EE0D4F82D +:10FE40007432002FDFF84491C3EB0A0A02DCC9F8D0 +:10FE50006CA223E0C7F59670FEF796FE5149FEF7B7 +:10FE60009BFF80463846FEF78FFE4146FEF7E0FED8 +:10FE700007465046FEF788FE414682464FF07E50C8 +:10FE8000FEF7CCFD01465046FEF7D2FE014638464D +:10FE9000FEF7C6FDFFF792F8C9F86C02424B1868EE +:10FEA0000193FEF76DFE41490746FEF7C1FE82460B +:10FEB000D4F88002FEF768FE8046D4F88402FEF78C +:10FEC00063FE01464046FEF767FFD4F888120490AF +:10FED000FEF7AEFE3946FEF7ABFE4FF07C51D4F88C +:10FEE0006482D5F80C90D4F86C720290FEF7A0FEF4 +:10FEF0005146FEF79DFE5146024640460392FEF7EC +:10FF000097FE039A01461046FEF78AFDD4F8681260 +:10FF1000FEF786FD4946FEF78BFE82463846FEF721 +:10FF200033FE494602464FF07E500392FEF776FDBF +:10FF3000039A01461046FEF77BFE01465046FEF747 +:10FF40006FFDDDF808C0C4F868028146614640468E +:10FF5000FEF766FD0022C4F86402C4F87822C4F8F3 +:10FF60007C22C4F88022C4F88422019B80461A6057 +:10FF7000074B1B88002B40F016810D4B1B68013B83 +:10FF8000C62B17D80149C1F8247119E038010020A7 +:10FF9000C027002080E6C547B1DC423ED048874AF2 +:10FFA000000061440000C842C4270020BD378635E8 +:10FFB000A00000204846FFF701F8A54AC2F8240136 +:10FFC000D4F88C02381AFEF7DFFDA249FEF730FEA6 +:10FFD00081465846FEF7D4FD01464846FEF7DCFE52 +:10FFE000FEF7ECFF40F2DC539B4A9842A8BF18464C +:10FFF0009042B8BF10460A21C4F88C72FAF7A8FAEA :020000040801F1 -:10000000FEF708FE01464846FEF70EFF6249FEF77E -:10001000BFFFFFF7CFF8074601E04FF0FF377B1E29 -:10002000C62BC8F8007006D8C7EB0A03C4F87432B0 -:10003000C4F86C722EE0D4F87432002FDFF84491CB -:10004000C3EB0A0A02DCC9F86CA223E0C7F596707C -:10005000FEF796FE5149FEF79BFF80463846FEF7B5 -:100060008FFE4146FEF7E0FE07465046FEF788FE4B -:10007000414682464FF07E50FEF7CCFD0146504689 -:10008000FEF7D2FE01463846FEF7C6FDFFF792F8AE -:10009000C9F86C02424B18680193FEF76DFE4149A6 -:1000A0000746FEF7C1FE8246D4F88002FEF768FEDE -:1000B0008046D4F88402FEF763FE01464046FEF710 -:1000C00067FFD4F888120490FEF7AEFE3946FEF7BB -:1000D000ABFE4FF07C51D4F86482D5F80C90D4F884 -:1000E0006C720290FEF7A0FE5146FEF79DFE51464F -:1000F000024640460392FEF797FE039A01461046D9 -:10010000FEF78AFDD4F86812FEF786FD4946FEF731 -:100110008BFE82463846FEF733FE494602464FF0D4 -:100120007E500392FEF776FD039A01461046FEF7D5 -:100130007BFE01465046FEF76FFDDDF808C0C4F8AF -:100140006802814661464046FEF766FD0022C4F81B -:100150006402C4F87822C4F87C22C4F88022C4F86F -:100160008422019B80461A60074B1B88002B40F0BD -:1001700016810D4B1B68013BC62B17D80149C1F8EE -:10018000247119E0700800208027002080E6C54710 -:10019000B1DC423ED048874A000061440000C842BA -:1001A00084270020BD378635A40000204846FFF78D -:1001B00001F8A54AC2F82401D4F88C02381AFEF7D7 -:1001C000DFFDA249FEF730FE81465846FEF7D4FD1A -:1001D00001464846FEF7DCFEFEF7ECFF40F2DC533A -:1001E0009B4A9842A8BF18469042B8BF10460A21C1 -:1001F000C4F88C72F2F74AFDAD6881462946404644 -:10020000FEF712FE07464846FEF7BAFD294680462D -:100210004FF07E50FEF7FEFC01464046FEF704FE1E -:1002200001463846FEF7F8FCC4F8640201F0F6FF18 -:1002300005218046F2F72AFDB4F8702240F23E63B1 -:1002400002F21F3292B29A42C4F89002D4F8947229 -:100250000AD87D4AB2F8720200F21F3080B298428A -:100260008CBF0020012000E0002000286AD094F814 -:100270009832754D13BBD5F82021D5F82431754837 -:10028000D31AB3F5FA7FA8BF4FF4FA738342A8BF1D -:1002900018460A21F2F7FAFCD5F89C328022DB7866 -:1002A000584390FBF2F3B3F5967FA8BF4FF49673D3 -:1002B000A2F5D6729342B8BF134601E0664B1B68A5 -:1002C000D4F89C22C8EB0303517A20205943D57CF3 -:1002D00091FBF0F1D4F83401B1F5967FA8BF4FF44B -:1002E000967103FB05005D4BB0F5C81FA8BF4FF426 -:1002F000C8109842B8BF18464FF40055C4F83401EE -:1003000090FBF5F0564DA942ACBF45184519507FFA -:10031000FEF736FD394680460498FEF77DFC01461F -:100320004046FEF781FD4FF06C51FEF77DFDFEF774 -:1003300041FF6FF095039628A8BF96209842B8BF5A -:100340001846281A049BC4F83801C4F8943226E0F1 -:10035000B3681D0623D5F4F747FB20E0D4F8142139 -:10036000394BD0061BD53F4AD3F8A01212683C3156 -:100370008A4214D3C3F8A022D3F8A8723A4A3B4D5C -:10038000C3F8A4223B880B202B61F2F7F3F83B88DB -:100390006B6104E0B368990301D5F9F715F9D4F856 -:1003A0003C31052B03DD284B0022C3F83C21F2F73A -:1003B000C7F82F4B1860B3892BB1D4F8AC22821A3E -:1003C000002AC0F2568718441F4D7379C4F8AC0256 -:1003D000059305F53170D4F8B832D4F8B072984767 -:1003E00005F53170014694F8CA22F5F79BFE214BC2 -:1003F0001B88002B00F0B880D5F8CC324FF00009F4 -:100400001B7805F534750493C8461A4BB3F800A061 -:10041000194BBAF57A7F03D1002243F809202A61EB -:10042000164A32F9080053F80920024443F809201B -:10043000FEF7A6FC2A690132012A2A6120D1002395 -:1004400068602860AB6046E07008002000247449B2 -:1004500024FAFFFF0CFEFFFF8C2700200000E7FFBF -:10046000D4FEFFFFE01F0020A4000020000C01408C -:100470007C270020882700207C0B0020340B0020E4 -:10048000D5F800C003926146CDF808C00190FEF790 -:10049000C1FB039A83461046FEF772FC014658469C -:1004A000FEF776FDDDF808C001466046FEF7B4FBB6 -:1004B000019B02461146686018460392FEF7AAFBAC -:1004C00001465846FEF7B0FCA968FEF7A5FB039A63 -:1004D000E8602A60A860684A002302F1540BBAF170 -:1004E000010F28F8023028F80B30DFF89CA12CD13E -:1004F0002869012807DD0138FEF742FC0146E8685B -:10050000FEF746FD00E0002002F0DEF80346049806 -:1005100058B10193FEF734FC019B01461846FEF7E3 -:100520003FFE10B14FF47A731CE0544B4FF47A72D3 -:1005300059F803300A2003F5FA7393FBF2F32BF812 -:1005400008300F210122F5F7FFFE08F10208B8F18B -:10055000060F09F1040905F114057FF456AFBAF846 -:100560000030013BAAF800300023454D05F53172FB -:1005700005F54671985A595A411A99520233062B79 -:10058000F3D1D5F8143113F0020300F00583D5F848 -:10059000243305F54B70984705F54B70014695F8E7 -:1005A0003223F5F7BFFDB5F8343305F54B78002B52 -:1005B00045D00022D5F838031346314D38F902C032 -:1005C000B5F8341305F54F7EB1F5C87F04BF00219F -:1005D0004EF803105EF80310294D61444EF80310E5 -:1005E000043300210C2B28F80210815202F1020280 -:1005F000E3D1B5F83433012B1CD1D5F83C334FF49B -:10060000C872C83393FBF2F30380D5F84033C83384 -:1006100093FBF2F34380D5F84433C83393FBF2F2F3 -:10062000184B1B88D21A8280A7F85410A7F85610CE -:10063000FBF7B4F9B4F83433013BA4F83433B368AE -:100640005A0740F18480B4F848230D4B322A1DD15B -:10065000D3F838231188A3F84A1351889288A3F855 -:100660004C13A3F84E23B7F85420A3F85023B7F83F -:100670005620A3F852230BE0340B00207C0B002003 -:10068000700800202400002088270020002A3CD089 -:100690000021D4F838530A46914E38F901E0B6F8F3 -:1006A000483306F55576322B04BF0023B350B058BB -:1006B0008B4B7044B050043200200C2A28F8010003 -:1006C000685201F10201E7D1B3F84823012A17D19A -:1006D00083F86123052283F86223B3F84A2383F861 -:1006E00060032A80B3F84C236A80B3F84E23AA80B3 -:1006F000B3F85023B3F85233A7F85420A7F8563074 -:10070000B4F84833013BA4F8483394F86323744B9E -:10071000EAB1D3F85453D3F838133220002295FBB2 -:10072000F0F583F863230D80D3F8585395FBF0F56B -:100730004D80D3F85C3393FBF0F06A4B1B88C01AF2 -:100740008880A7F85420A7F85620FBF727F9D4F89B -:100750003833B4F82C131A8800268A1AA4F82C23EC -:10076000B4F82E135A88B1468A1AA4F82E239B880F -:10077000B4F83023D31AA4F83033F1F7E1FED4F8FB -:1007800064330546C31A18460493FEF7F5FAD4F805 -:1007900068130690FEF748FBD4F86C83C4F86453E2 -:1007A00098F800A0079035464F4F785FFEF7E8FABB -:1007B0000799FEF739FB09A98851BAF1000F2DD02E -:1007C0005046FEF7DDFA01464FF07E50FEF7E0FBA3 -:1007D0000246114607F1AC0B4FF07E500392FEF734 -:1007E00019FA56F80B10FEF71FFB07F16801844653 -:1007F000485FCDF808C0FEF7C3FA039AB837114630 -:10080000FEF712FBDDF808C001466046FEF704FA69 -:100810004BF80600FEF7CEFC785304E007F1B8026F -:100820006837E95BA952314F0436EA5F0235062D7D -:1008300002FB0299B8D12B4D4FF0640A2A880AFBBB -:1008400009F3524393FBF2FAAAF1490A07F10800AF -:1008500009A91FFA8AFAF1F7C7FFBAF13B0FD8F8D6 -:10086000046011D9B4F99003FEF78AFAD4F88C63C6 -:1008700001463046FEF794FC194F94F84A3100289F -:1008800038D043F0080337E04FF07E513046FEF792 -:10089000C3F901464FF07E50FEF77AFB4FF0000B94 -:1008A0008246134B304653F81B100193FEF7BCFAF7 -:1008B000024637F90B000392FEF762FA039A0146EB -:1008C0001046FEF7A9F95146FEF7AEFA019B43F830 -:1008D0001B000BF1020BBBF1060FE2D1C2E700BF18 -:1008E0007008002024000020340B0020EC0B0020B6 -:1008F000F40B002023F008033146D4F8880387F86E -:100900004A3101F057FD0746C4F89403D4F8840334 -:10091000D4F88CB300F10046D4F888030146FEF702 -:1009200083FA594682465846FEF77EFA01465046FB -:10093000FEF772F901F0C8FE0146304601F03AFDBB -:10094000A6490646C4F898033846FEF76DFA01F04A -:1009500065FCA249A4F870023046FEF765FA01F082 -:100960005DFCD4F81431A4F872021B0739D59C48F9 -:1009700009A9F1F739FFD8F808904FF07E514846A1 -:10098000FEF74AF901464FF07E50FEF701FB4FF0AB -:10099000000B8246934D484605F5677353F81B10CC -:1009A0000193FEF741FA05F5A271024631F90B00F9 -:1009B0000392FEF7E5F9039A01461046FEF72CF97B -:1009C0005146FEF731FA019B43F81B000BF1020B75 -:1009D000BBF1060FDED11846F1F7BEFFA5F8A8035C -:1009E00041E0DFF814A209A90AF10400F1F7FCFEC6 -:1009F0006868D5F808B00146FEF716FAD5F80C90ED -:100A0000594605465846FEF70FFA01462846FEF7B6 -:100A100003F9494605464846FEF706FA01462846C8 -:100A2000FEF7FAF801F050FE00210546FEF790FBB4 -:100A3000A0B9DAF804002946FEF7AAFA2946CAF84E -:100A40000400DAF80800FEF7A3FA2946CAF80800FD -:100A5000DAF80C00FEF79CFACAF80C006248F1F7CD -:100A60007BFFA4F8A80361490698FEF7DDF907F1BA -:100A70000047814606F10046B4F9A8030C970D968D -:100A8000FEF77EF95A4900F10040FEF7CDF90E90CD -:100A9000B4F97C03FEF774F90F90B4F97E03FEF706 -:100AA0006FF91090B4F98003FEF76AF90CA9119060 -:100AB0000FA8F1F799FE98F801304A4D012B19D192 -:100AC0004C4B1B785E070ED4D5F8AC33402093FB1B -:100AD000F0F0181AFEF754F91199FEF79DF8FEF799 -:100AE00069FBC5F8AC033F4BD3F8AC03402390FB44 -:100AF000F3F001E0404B1888FEF742F901461198E7 -:100B0000FEF788F8D4F8B41311904846FEF784F83D -:100B100001464846FEF73CFAD4F8B053064629464B -:100B20001198FEF777F801463046FEF77DF9014649 -:100B30002846FEF771F80646C4F8B0030F98D4F8BB -:100B4000787201F06BFBD4F8B8532978F2F79EF86D -:100B50003844C4F878021098D4F87C7201F05EFB37 -:100B60002978F2F793F83844C4F87C023046D4F878 -:100B7000807201F053FB6978F2F788F81F4B049DEF -:100B80001A6838442A441A60D4F88432C4F88002BF -:100B90000133C4F8843205E0A5F82C33A5F82E33D0 -:100BA000A5F830330F4F059EB7F8C432012EA7F8D1 -:100BB000BC33B7F8C632A7F8BE3321D1B7F9C22388 -:100BC000B7F9C83203EB4203032293FBF2F39BB263 -:100BD000A7F8C033A7F8C23316E000BF4C3D0F445E -:100BE0000C0C00207008002028000020BD3786353E -:100BF00035FA8E3C96270020240000208427002010 -:100C0000B7F8C832A7F8C033F1F79AFCC04B0126F9 -:100C10001860D7F8C833C7F8C803C31AA7F8C43395 -:100C2000F2F7DCFFD7F81831BA4D13F4801387F8C8 -:100C3000106100F08C80B5F81C31180600F1D380EB -:100C4000B54B1B7859076FD595F8CC23B34B12B130 -:100C500095F8CD233AB10022C7F8D02301221A74A7 -:100C6000002287F8CD231B7CD7F8B052032B95F8D0 -:100C70000080A84E05F1040987F8CC3306D1484618 -:100C800006F575714C2201F05BF843E0012B07D1AA -:100C900006F5757049464C2201F052F8002302E037 -:100CA000022B02D1012386F82034012384F8213459 -:100CB00084F822340023C4F82434C4F82834984A31 -:100CC00094F82034C4F82C94D35C964A1D4484F8DC -:100CD0003134C4F8D023287984F83084FEF750F8F2 -:100CE0009149FEF755F9C4F83404A87BFEF748F89B -:100CF0008E49FEF74DF9C4F83804287EFEF740F817 -:100D00008B49FEF791F8C4F83C04FEF779FA00230A -:100D10002876AB73B7F81C3143F08003A7F81C3179 -:100D2000012387F840345EE04FF00009D5F8D00386 -:100D30004946FEF70DFA8046002854D1FAF72EFEF8 -:100D4000764BC5F8D09385F8CC831E744BE0B5F88C -:100D50001C9119F0800F3BD095F8CC23DFF8BCA193 -:100D6000511E012924D87149D5F83804FEF75CF8E2 -:100D7000FEF746FAD5F82C6495F831846D49B044F5 -:100D800088F80A00D5F83C04FEF74EF8FEF738FA6A -:100D900088F814003078FDF7F3FF0146FDF73CFFBB -:100DA000FEF72EFAB37AB0703373337DB37506E075 -:100DB000032A04D185F8CC338AF8106004E09AF84D -:100DC000103001338AF8103029F08009A7F81C91FF -:100DD000514B1B785A0706D497F840341BB14D4B42 -:100DE000012283F8CD23D7F814914A4A19F0080F4D -:100DF000514D38D0B2F82E1101F145039BB28A2B28 -:100E00002DD8B2F81C315B0729D5B2F8A803B2F887 -:100E1000423497F84A61C21A92B293B218B2B33010 -:100E2000BCBF02F5B4739BB21AB2B32AC4BFA3F518 -:100E3000B4739BB2360795F8EC00364A13D540B22E -:100E400040424343D2F8B0021BB2007B43436FF0F1 -:100E50001D0093FBF0F31944A2F82E1103E0B7F83C -:100E6000A833A7F8423419F0140F00F09780B7F8B0 -:100E70001C21284B02F40272002A00F08F8093F8A4 -:100E80004A2102F0100202F0FF0052B1B3F82C1117 -:100E900095F92701D3F8382100FB0212A3F82C2181 -:100EA0007CE0D3F84424D1789278002946D0B3F876 -:100EB00030E1B3F928110FFA8EF6C1EB0608B8F14C -:100EC000000FB8BFC8F1000890450FDD8E42C8BFC3 -:100ED00052421FFA8EFEC8BF92B2C3F83401724468 -:100EE000012083F84804A7F8302157E093F84824FC -:100EF0002AB1D3F8242183F84804C3F82021D7F875 -:100F00003831D7F84C2419441388528899423EE06E -:100F10007C27002070080020962700202400002055 -:100F2000A44A01080000A0410000204100007A44CA -:100F30005555553F9A99993FE41F0020B3F9280170 -:100F4000B3F93061361A86EAE67EAEEBE67E964568 -:100F50000ADD022296FBF2F6A84A1660012283F807 -:100F6000982283F848240AE093F848243AB1D3F849 -:100F7000242183F89812C3F8202183F84814D7F865 -:100F80004C14D7F838210B88024449889A4203DB75 -:100F90008A42B4BF13460B46A7F83031D7F8B032B7 -:100FA000974E93F864810493B8F1000F55D0B6F8CA -:100FB0001C319A0751D0D6F88403D6F8882301460D -:100FC000D6F88CB3B6F830A10392FDF72DFF039A43 -:100FD0000346114610460193FDF726FF019B01468B -:100FE0001846FDF719FE5946034658460193FDF78A -:100FF0001BFF019B01461846FDF70EFE01F064FB46 -:1010000001465846FDF7C4FF7E498346FEF7B4F813 -:10101000F8B9584601F07EF9D6F85014FDF704FFF0 -:1010200001F0FCF8B0F5617FA8BF4FF46170FDF7E7 -:10103000A7FE7549FDF7ACFF01F02EF906464046C4 -:10104000FDF79EFE3146FDF7EFFE01F0E7F880B2B6 -:1010500000E000208244A7F830A119F0200F00F032 -:101060008B80B7F81C31DFF898A103F03003002B18 -:1010700000F082809AF84A31DB077DD5BAF9A803DF -:10108000FDF77EFE6149FDF7CFFE064601F004F94B -:101090008046304601F08CF8DAF85434814693F8F3 -:1010A00003B0BAF95E045A4EBBF1000F34D0BAF85F -:1010B0005A24CBF1000A93B212B2801A0193F1F7CD -:1010C0007DFF5045019B03DB5845A8BF584600E013 -:1010D0005046B7F858140344B7F95C048AB209B211 -:1010E0009BB2401AA7F85A3403920193F1F766FFB6 -:1010F0005045039A019B03DB5845B4BF8246DA464C -:1011000092441FFA8AFAA4F858A418B2FDF738FEE0 -:1011100083460FFA8AF004E0FDF732FE8346BAF9FF -:101120005C04FDF72DFE494682465846FDF77CFEDD -:101130004146034650460193FDF776FE019B01466A -:101140001846FDF767FD3349FDF722FFFEF732F839 -:10115000414630805846FDF767FE49468046504676 -:10116000FDF762FE01464046FDF756FD2949FDF7B1 -:101170000FFFFEF71FF87080049E274B301DD3F839 -:1011800000C0D7F8601406F15403B5F8F620E04724 -:10119000F6F796FBD7F86434002B60D0184B93F821 -:1011A0006834013B142B55D8DFE803F00B54543C52 -:1011B0005754541F54545454544454545454543C49 -:1011C0004400D7F86C345B782BB1144B0020998B1A -:1011D000F1F78BFF43E0124B1B7803F0040303F09D -:1011E000FF00002BF1D10146F2E70C4E0020318BBD -:1011F000F1F77BFF0120718BEAE700BF8C2700200D -:10120000700800208FC2753CEFB6B04435FA8E3CB2 -:1012100092270020000020419C0000202400002094 -:1012200096270020A44E0020718BF1F75EFF01206D -:10123000B18BCDE7A04E0020318BF1F756FF012096 -:10124000718BF1F752FF0220B18BF1F74EFF0320B3 -:10125000F18BBDE7AB689F0601D5F1F751FFFCF7B5 -:1012600029F8964B1B7823B9AB681E0301D5F6F716 -:1012700049FE924B1B78002B40F0E984DFF8509236 -:10128000D9F808305D0540F1E2848D4D95F8703451 -:10129000002B00F0DC84F1F711FD002800F0D7846A -:1012A00095F87134002B00F0D284D5F874341B7893 -:1012B000002B40F01C82D5F87804F1F7ADF9002836 -:1012C00040F01582DFF80C82D5F87C24D8F8003085 -:1012D0009A1A7C2A40F20B82C5F87C3495F8803447 -:1012E0000746013385F8803407F12400744EC0B2FC -:1012F000F1F718FA06F55F7333F91700FDF740FDB3 -:101300006D4B82461888FDF73BFD01465046FDF7C0 -:101310003FFE6C49FDF788FDFDF74CFF013700B239 -:10132000F1F72CFA032FDFD13020F1F7FBF9B6F9F2 -:101330009002F1F723FAF1F703FA96F88034980750 -:101340002FD1D6F87C3441F2883293421AD910203A -:10135000F1F7E8F9D6F86C02642790FBF7F000B2D9 -:10136000F1F70CFA2120F1F7DDF9D6F86C3293FB96 -:10137000F7F007FB103787EAE770A0EBE77000B2E1 -:10138000F1F7FCF91420F1F7CDF9B5F9A803F1F75D -:10139000F5F91C20F1F7C6F90020F1F7EFF9F1F7A4 -:1013A000CFF995F88034464E590740F07A810220F3 -:1013B000F1F7B8F9D6F884316422323393FBF2F0B6 -:1013C00000B2F1F7DBF90320F1F7ACF93E4B1B78E3 -:1013D00013F0040F4FF0050304D0B6F9300190FB71 -:1013E000F3F005E0D6F884245289B2FBF3F000B2A2 -:1013F000F1F7C4F9D9F808309A0775D5334E94F847 -:101400008824337840F63401B2FBF3F24A432A21B0 -:10141000B2FBF1F2B4F88A14062091FBF3F703FB58 -:1014200017173F01BFB247EA0227BFB2C2F3032238 -:101430001743F1F777F938B2F1F7A0F9B4F88A2435 -:101440003378013292B292FBF3F103FB1123A4F83B -:101450008A3494F888346E265E43152396FBF3F69F -:101460003A204FF06409F1F75DF9B6FBF9F7384619 -:10147000F1F784F93B20F1F755F909FB176080B2C9 -:101480000A27053090FBF7F000B2F1F777F9282032 -:10149000F1F748F9D4F88C0490FBF7F000B2F1F7BB -:1014A0006DF90420F1F73EF9D4F884345B899BB1DF -:1014B000F5F7D2FA15E000BF2400002090270020A5 -:1014C0007008002000007A44962700209800002031 -:1014D000E41F0020E01F0020A94BD3F8900480F304 -:1014E000100000B2F1F74AF9D5F81431A44E9B066A -:1014F0006BD596F84A319F071AD51120F1F712F9EA -:10150000B6F89404FDF772F899A3D3E90023FDF728 -:10151000D3F800229B4BFCF71DFFFDF7DFFA00B26A -:10152000F1F72CF91920F1F7FDF80020F1F726F971 -:1015300095F84A31B5F8966413F0020F08BF0026FB -:101540000120F1F7EFF830B2F1F718F90920F1F7BF -:10155000E9F80020F1F712F98B4B95F898641B8895 -:10156000B3F5967F0BD9864A92F8802402F00F02D9 -:10157000072A04D842F20F76B342B8BF1E460520B0 -:10158000F1F7D0F8D5F89C345B7B0BB930B21AE098 -:10159000A6F12000FDF72AF877A3D3E90023FDF791 -:1015A000B5F9FDF7E3FA00210646FDF7DBFD10B1C2 -:1015B0004FF03F4101E04FF07C513046FDF72CFBEE -:1015C000FDF7F8FD00B2F1F7D9F8D5F81431980617 -:1015D0000ED46B4B0021D3F89C647068FDF7B8FD06 -:1015E00000285CD1B0680021FDF7B2FD002856D17B -:1015F00095F84A21624B910703D493F8A024012A5D -:1016000007D10123D5F8A474D5F8A86485F8A034CF -:101610000FE0D3F89C645D497068FDF705FCFDF7A9 -:10162000C9FD5A490746B068FDF7FEFBFDF7C2FD4C -:1016300006460FA93846F1F769FB1320F1F772F857 -:10164000BDF93C00F1F79AF81B20F1F76BF8BDF9F2 -:101650003E00F1F793F82320F1F764F8002FACBFB8 -:101660004E205320F1F78AF80FA93046F1F74EFBD0 -:101670001220F1F757F8BDF93C00F1F77FF81A2076 -:10168000F1F750F8BDF93E00F1F778F82220F1F7B4 -:1016900049F8002EACBF45205720F1F76FF8F1F75D -:1016A0004FF895F88034282B21D1354B0022D8F8FB -:1016B000006083F880244FF47A73B6FBF3F81720A8 -:1016C0003C26F1F72FF8B8FBF6F7B7FBF6F006FB70 -:1016D0001070000200B2F1F751F81820F1F722F86B -:1016E00006FB178000B2F1F749F8F1F729F8D5F8B1 -:1016F0007434234E1B78012B40F02681F0F720FF35 -:10170000D6F8AC34224AC31A9342074640F2BE8050 -:1017100096F88824002386F8CE2486F8C424D6F8C8 -:101720008C2486F8B23486F8B43486F8CF3486F840 -:10173000C5340A2392FBF3F286F8CC24121286F801 -:10174000CD24D6F8902492FBF3F386F8D03496F8A3 -:101750004A211B1286F8D13496F89834920786F8FD -:10176000F63417D42D2386F8F7348CE0AFF30080DD -:101770007B14AE47E17A843FCDCCCCCCCCCCFC3FC3 -:10178000700800200000E03FA00000208096184B69 -:101790003F0D0300042BD4F8A454CF488CBF33234F -:1017A0003223DFF84CC386F8F73495FBF0F60CFBD8 -:1017B00006584FF0060E0EFB08F8C84B06EB8606DF -:1017C00098FBF3F903FB198806EB86064FFA89F9B3 -:1017D000D4F8A81409EB8606B6B291FBF0F084F8B1 -:1017E000E664360A84F8E7640CFB00160EFB06F686 -:1017F000ED0F84F8E55496FBF3F503FB15636422C3 -:1018000093FBF2F384F8ED341B12C90F84F8EE3425 -:10181000B4F8943484F8EA1424214B4398FBF2F88A -:1018200093FBF2F2B4F8083584F8E324C2F30722FC -:1018300084F8E42484F8EF34B4F896241B0A84F87E -:10184000F0340A23B2FBF3F300EB800003F5FA73E4 -:101850009BB26DB200EB800005EB800084F8F134A0 -:101860001B0A80B284F8F234B4F80A3584F8E884AC -:1018700084F8EB044FEA2828000A84F8E98484F805 -:10188000EC0484F8F834964BC3F8AC74944D95F896 -:101890000C355BB9D5F81005F0F7BEFE95F84F355D -:1018A000002B40F01282012800F21782D5F818258B -:1018B0008B4C002A48D094F80C653EB1D4F81C3506 -:1018C00040F6B731FB1A8B420BD83DE00123D4F828 -:1018D0001005022184F80C35F0F78AFE84F82065A3 -:1018E00030E094F821355BB9D4F810050121C4F833 -:1018F000183584F80C35F0F77BFEF0F792FE21E006 -:10190000013BDBB284F8213594F8201594F82205C8 -:1019100043B901304B1C84F8220584F82035D4F8F3 -:1019200010050DE0134613F8012B0130114484F823 -:101930002205D4F8100584F82015C4F8183511468E -:10194000F0F77CFEC5F81C75654DD5F874342E464D -:101950001B78022B1BD1D5F82435C3B1C5F8283527 -:101960001B68604AC5F82C35D5F830351344987893 -:10197000F8F794F9D5F828359879F4F728FDD5F8D3 -:1019800030350133092B88BF0023C5F83035F1F716 -:10199000E7F9002800F05B8195F83435013B012B15 -:1019A00000F25581D6F83805F0F736FE4C4C4E4F14 -:1019B000D8B1D4F83805F0F72AFE94F83C253B68F6 -:1019C0007E2A0FD102221B2884F83425C4F8403522 -:1019D00005D00D2803D0342801D0672802D1012377 -:1019E00086F8443586F83C05DCE73B68D4F84025AA -:1019F00041F658319A1A8A4203D9032384F83435C0 -:101A000025E1D4F848259B1A042B40F2208194F854 -:101A10004435002B00F01B8194F84C25334B33F8F0 -:101A2000120018B984F84C054FF4036095F84C3552 -:101A3000B0F5C06F03F10103DBB2294C85F84C35DA -:101A40005ED01CD8B0F5007F54D009D8B0F5807FA7 -:101A500053D0B0F5887F40F0FA80D4F89012F1E0CE -:101A6000B0F5806F7CD0B0F5826F00F0BB80B0F530 -:101A7000047F40F0EC8094F888345321E1E0B0F525 -:101A8000006F40D00CD8B0F5E26F60D0B0F5E46FD5 -:101A900063D0B0F5E06F40F0DA80B4F97C1358E021 -:101AA000B0F5036F07D0B0F5046F4CD0B0F5026FFE -:101AB00040F0CD80B9E0D4F814319B0640F1C780E6 -:101AC00094F84A319F0740F1C280B4F8943424213D -:101AD0005943642312313DE08096980040420F0044 -:101AE00070080020A44A0108E01F00208A61010854 -:101AF000806967FFD4F88C14A4E0D4F86C12A1E0DC -:101B0000D4F890149EE0D4F81421960640F19F80FA -:101B100094F84A21900740F19A80D90709D5D4F862 -:101B2000A8140029BCBF494241F0804141F0004166 -:101B300006E0D4F8A4140029BCBF494241F080411A -:101B40004FF4006065E0B4F9A833642179E0B4F99A -:101B50007E132C2391FBF3F174E0B4F98013F8E7C2 -:101B600094F84D3542F210710133DBB2032B84F847 -:101B70004D3584BF012384F84D3595F84D355943D3 -:101B80006A4B1B78DA0748BF01319F0748BF023113 -:101B90005E07B5F81C3148BF0431DC0748BF0A3185 -:101BA000980748BF14311A0648BF2831DF0548BFDF -:101BB00028315E0748BF64311C0748BFC83198050B -:101BC00048BF01F5C8719A0648BF01F57A71DF0672 -:101BD00048BF01F5FA615E0648BF01F57A614FF42E -:101BE000806016E0D4F8141111F0200617D094F894 -:101BF0004A3113F0020F0CBF00214FF47A7113F039 -:101C0000010F0CBF00234FF4FA63194495F8983480 -:101C10001944F4F7D7FE002385F8443517E0314620 -:101C2000F4F7D0FE84F8446511E0D4F814319D0631 -:101C30000DD594F84A31990709D5B4F896344FF484 -:101C40007A715943F4F7BEFE002384F84435384BCB -:101C50009B68DA037DF5C1AE364B93F84E35002B09 -:101C60003DF4BBAE344B1B78002B7DF4B6AEF5F7DC -:101C700081FBFDF7B2BECB067EF599ABD4F81821F7 -:101C80002C4B910207D4B3F81C2122F40072A3F864 -:101C90001C21FEF78CBBB3F81C1101F4007292B248 -:101CA000002A7EF484AB41F40071A3F81C11D3F830 -:101CB0002411C3F83421C3F82011B3F83011C3F84C -:101CC0003821A3F82811FEF772BB00283FF4EEADCF -:101CD000D5F81005F0F79BFC24E00228174C03D040 -:101CE000F0F79FFC012304E094F8222022B1C5F80C -:101CF000147584F82230D9E5D5F81435FB1AB3F5FC -:101D00007A6FFFF4D3AD0123D5F8100584F82230A3 -:101D1000F0F77DFC0446D5F81005F0F778FC802C30 -:101D20007FF4C4ADFAF704FBC0E500BF962700209E -:101D3000E41F0020700800208A27002024000020D3 -:101D400010B50023934203D0CC5CC4540133F9E7AF -:101D500010BD02440346934202D003F8011BFAE788 -:101D6000704700000D4B70B51D680022845C2B1974 -:101D70005B7803F00303012B8B5C08BF2034EE1863 -:101D8000767806F00306012E08BF2033E41A02D14C -:101D90000132002BEAD1204670BD00BFC8000020F0 -:101DA00010B50446224613780134002BFAD1CC5CDE -:101DB000D4540133002CFAD110BDC9B2024610F838 -:101DC000013B1BB18B42F9D1104670470029FBD073 -:101DD00018467047034613F8012B002AFBD1181A46 -:101DE000013870470F4BF0B51E680023934215D0A1 -:101DF000C55C7419647804F00304012CCC5C08BF42 -:101E0000203537197F7807F00307012F08BF2034EA -:101E10002D1B04D10133002CE8D100E00025284619 -:101E2000F0BD00BFC800002010B5034632B111F864 -:101E3000014B013A03F8014B002CF7D11A449342AD -:101E400003D0002103F8011BF9E710BD30B503787A -:101E50000BB1044604E00B78002B18BF002030BD06 -:101E600022461078013438B10023C85C28B1D55C13 -:101E70008542F5D10133F8E730BD104630BD002171 -:101E80000A2200F001B92DE9F04E82468B461F462A -:101E9000144612B90020BDE8F08E002BFAD00026BF -:101EA000A642F7D2A5196D0807FB05B95046494669 -:101EB000089B9847002802DB03D06E1C25462C4661 -:101EC000EEE74846BDE8F08E174B2DE9F0411D685E -:101ED0000646AC6D0F46FCB9502000F0E3F8A8654B -:101EE0008460AB6D046044601C61DC60AB6D9C6120 -:101EF0005C61AB6DDC629C62AB6D5C631C63AB6D63 -:101F0000DC639C63AB6D5C641C64AB6DDC649C64E3 -:101F1000AB6D1C77AB6D5C6230463946AA6D012310 -:101F2000BDE8F04100F002B82C010020F0B508B97E -:101F3000106828B3044614F8015B0F4617F8016BCC -:101F40003EB1B542FAD10BB12046F3E714600370FD -:101F5000F0BD4DB915602846F0BD17F8016BAE42D3 -:101F600007D0002EF9D11C46234613F8015B0F461B -:101F7000F3E715B10021217000E02B461360F0BD9E -:101F8000F0BD000084463F482DE9F04FD0F80080B6 -:101F90000E46344614F8015B08EB0500407800F06B -:101FA000080000F0FF0708B12646F2E72D2D03D107 -:101FB000B41C7578012703E02B2D04BF7578B41C81 -:101FC00033F010000DD1302D08D1207800F0DF0063 -:101FD000582851D165781023023402E0002B08BF45 -:101FE0000A23002F0CBF6FF0004A4FF0004ABAFBE3 -:101FF000F3F903FB19AA0026304608EB050B9BF802 -:1020000001B01BF0040F01D0303D0BE01BF0030BBF -:102010001BD0BBF1010F14BF4FF0570B4FF0370B24 -:10202000CBEB05059D4210DAB6F1FF3F0AD04845DB -:1020300006D801D1554503DC03FB0050012601E021 -:102040004FF0FF3614F8015BD7E7731C0CD1002F5B -:102050004FF022030CBF6FF000404FF00040CCF86F -:1020600000302AB9BDE8F08F07B1404242B106B155 -:10207000611E1160BDE8F08F002B08BF0823B0E798 -:10208000BDE8F08FC800002030B51346044A05466D -:102090000C46106829462246BDE83040FFF772BF63 -:1020A0002C010020024B0146186800F003B800BF65 -:1020B0002C01002070B5CD1C25F0030508350C2D32 -:1020C00038BF0C25002D06463FDB8D423DD3214B0A -:1020D0001C6818462146A1B10B685B1B0ED40B2B64 -:1020E00003D90B60CC18CD501FE08C4202D162683E -:1020F00002601AE04B6863600C4616E00C464968C3 -:10210000E9E7154C23681BB9304600F027F820603A -:102110002946304600F022F8431C014615D0C41C65 -:1021200024F0030484420AD1256004F10B00231D2E -:1021300020F00700C31A0BD05A42E25070BD30465F -:10214000611A00F00BF80130EED10C23336000204F -:1021500070BD00BFA02700209C27002038B5064C8A -:10216000002305460846236000F008F8431C02D10E -:10217000236803B12B6038BDA8270020094A1368E3 -:1021800063B118446946884202D810601846704707 -:10219000054B0C221A604FF0FF307047034B136061 -:1021A000EFE700BFA4270020A8270020AC270020CD -:1021B00000B5194A20F00043934283B0014617DD71 -:1021C000B3F1FF4F04DBFCF725FD03B05DF804FB22 -:1021D000694601F03BF800F00302012A00980199DA -:1021E00011D0022A0AD09AB1012201F0F3FDECE7E6 -:1021F000002101F0F3F903B05DF804FB01F0EEF902 -:1022000000F10040E1E701F0E5FD00F10040DCE70E -:1022100001F0E4F9D9E700BFD80F493F30B5C0F36A -:10222000C754A4F17F031E2B83B0014620DC581C49 -:102230001BDB162B4FEAD17509DDC1F3160040F404 -:102240000000963CA04005B1404203B030BD114BA8 -:1022500053F825402046FCF7DFFC01900198214609 -:10226000FCF7D8FC20F0004333B9002003B030BDA8 -:10227000FCF7A0FF03B030BDC0F31604C0F3C75095 -:1022800044F40004C0F1960024FA00F0002DDCD0E4 -:10229000DAE700BFD079010800B51D4A20F00043FD -:1022A000934283B0014618DDB3F1FF4F04DBFCF726 -:1022B000B1FC03B05DF804FB694600F0C7FF00F015 -:1022C0000300012818D002280ED0D0B1009801993F -:1022D00001F084F900F10040EBE70021002201F059 -:1022E00079FD03B05DF804FB00980199012201F02B -:1022F00071FD00F10040DCE70098019901F06EF9F2 -:10230000D7E700980199012201F064FDD1E700BFF1 -:10231000D80F493F70B58AB0054600F023FA224C29 -:10232000064694F90030013303D0284601F0C4FF7B -:1023300010B930460AB070BD284601F06BFF4FF06F -:102340007E51FCF72DFF0028F3D01849012200230D -:102350002846009208930191FCF75AF902460B4671 -:102360001348CDE90423CDE9022301F0ABFD94F934 -:102370000030CDE90601022B0BD0684601F0A0FD2C -:1023800038B1089B53B9DDE90601FCF7EFFB0AB051 -:1023900070BD02F00FF821230360F2E702F00AF8A3 -:1023A000089B0360EFE700BF30010020D8790108E7 -:1023B000E479010800F03EBB2DE9F0418AB0074600 -:1023C0000C4600F0C7FB9B4E054696F900300133E2 -:1023D00003D0204601F070FF18B928460AB0BDE8C6 -:1023E000F081384601F068FF8046002832D120464F -:1023F0000021FCF7ADFE0028EFD08F4A01233846BC -:1024000001920093CDF82080FCF702F9CDE902019A -:102410002046FCF7FDF8894B96F900400022CDE9F3 -:102420000623631CCDE904010DD0022C0BD06846B5 -:1024300001F046FD002800F09A80089B1BB101F0D6 -:10244000B9FF089B0360DDE90601FCF78FFB0AB0CA -:10245000BDE8F08138460021FCF77AFE18B320462B -:102460000021FCF775FE8046002855D072490122F4 -:1024700000233846009208930191FCF7C9F8CDE992 -:1024800002012046FCF7C4F896F900400022002320 -:10249000CDE90401CDE90623002CC8D0674B00220A -:1024A000CDE90623CFE7284601F0B8FE8046002894 -:1024B00062D028460021FCF74BFE00288DD038461C -:1024C00001F0ACFE002888D0204601F0A7FE0028CD -:1024D00083D0594904220023384600920893019181 -:1024E000FCF796F8CDE902012046FCF791F896F941 -:1024F000004000220023022CCDE90401CDE906238F -:1025000000F08880684601F0DBFC002800F0828043 -:10251000089B002B97D092E7204601F07FFE002811 -:102520003FF45BAF20460021FCF71CFE00283FF47F -:1025300054AF414A0123384601920093CDF82080E0 -:10254000FCF766F8CDE902012046FCF761F8347823 -:10255000CDE904010022002C30D0394B022CCDE90A -:1025600006232ED101F026FF21230360D0E701F0DE -:1025700021FF2123036060E7384601F04FFE002869 -:1025800097D0204601F04AFE002892D0284601F05C -:1025900093FE0346D8B92849012238460893009291 -:1025A0000191FCF735F8CDE902012046FCF730F83F -:1025B0003478CDE90401002C31D100220023CDE98B -:1025C0000623684601F07CFC0028A1D1CAE71A4A1C -:1025D0000323384600930192CDF82080FCF718F8C9 -:1025E000CDE902012046FCF713F896F90030CDE959 -:1025F0000401384643BB134B4FF060420021CDE944 -:102600000623FCF7AFFD00283FD196F90030022BDE -:102610007FF478AF01F0CEFE2223036078E700203C -:10262000002102460B46FCF771F9022CCDE90601A8 -:1026300098D0C6E730010020E07901080000F03FA3 -:102640000000F0FFFFFFEF471C4B00220021CDE907 -:102650000623FCF787FD0028D7D020464FF07C5199 -:10266000FCF7E2FBFBF7D4FF04460D4601F030FC1B -:1026700002460B4620462946FDF71EF90028C4D124 -:102680000F4B0022CDE90623BFE720464FF07C51D7 -:10269000FCF7CAFBFBF7BCFF04460D4601F018FC33 -:1026A00002460B4620462946FDF706F90028ACD124 -:1026B000044B4FF06042CDE90623A6E70000F07F0F -:1026C0000000F0FFFFFFEFC770B58AB0054600F0CD -:1026D00031FF224C064694F90030013308D02846D9 -:1026E00001F0EAFD20B128460021FCF73BFD10B9BE -:1026F00030460AB070BD1A490122002328460191D4 -:1027000000920893FBF784FF2478CDE90401CDE91A -:1027100002017CB900220023CDE90623684601F0BE -:10272000CFFB88B1089BA3B9DDE90601FCF71EFACF -:102730000AB070BD0020002102460B46FCF7E6F807 -:10274000022CCDE90601E9D101F034FE212303601A -:10275000E8E701F02FFE089B0360E5E73001002069 -:10276000E8790108F8B520F00043B3F17E5F044634 -:1027700010D008DCB3F17C5F11DAB3F10C5F00F329 -:1027800084809D48F8BD0146FCF744FA0146FCF7F9 -:10279000FFFBF8BD002840F3CD800020F8BD0028E5 -:1027A000C0F2CA8001464FF07E50FCF733FA4FF07A -:1027B0007C51FCF739FB044600F0BCFE8F4906460D -:1027C0002046FCF731FB8E49FCF726FA2146FCF740 -:1027D0002BFB8C49FCF71EFA2146FCF725FB8A49A6 -:1027E000FCF71AFA2146FCF71FFB8849FCF712FA9E -:1027F0002146FCF719FB8649FCF70EFA2146FCF747 -:1028000013FB844905462046FCF70EFB8249FCF782 -:1028100001FA2146FCF708FB8049FCF7FDF9214647 -:10282000FCF702FB7E49FCF7F5F92146FCF7FCFAC0 -:102830004FF07E51FCF7F0F901462846FCF7A8FB63 -:102840003146FCF7F1FA26F47F6525F00F050746BF -:1028500029462846FCF7E8FA01462046FCF7DAF953 -:10286000294604463046FCF7D7F901462046FCF7D6 -:102870008FFB01463846FCF7CFF901462846FCF7A6 -:10288000CBF90146FCF7C8F9F8BD0146FCF7CCFAD4 -:102890005A490546FCF7C8FA5949FCF7BDF92946DB -:1028A000FCF7C2FA5749FCF7B5F92946FCF7BCFA20 -:1028B0005549FCF7B1F92946FCF7B6FA5349FCF73C -:1028C000A9F92946FCF7B0FA5149FCF7A5F92946C0 -:1028D000FCF7AAFA4F4906462846FCF7A5FA4E49E6 -:1028E000FCF798F92946FCF79FFA4C49FCF794F954 -:1028F0002946FCF799FA4A49FCF78CF92946FCF776 -:1029000093FA4FF07E51FCF787F901463046FCF709 -:102910003FFB01462046FCF787FA01464148FCF799 -:1029200079F901462046FCF775F901463E48FCF767 -:1029300071F9F8BD3D48F8BD4FF07E51FCF76CF9D8 -:102940004FF07C51FCF770FA2C490446FCF76CFA06 -:102950002B49FCF761F92146FCF766FA2949FCF797 -:1029600059F92146FCF760FA2749FCF755F9214649 -:10297000FCF75AFA2549FCF74DF92146FCF754FAC1 -:102980002349FCF749F92146FCF74EFA0646204652 -:1029900000F0D0FD1F4905462046FCF745FA1E49C8 -:1029A000FCF738F92146FCF73FFA1C49FCF734F9EB -:1029B0002146FCF739FA1A49FCF72CF92146FCF7B5 -:1029C00033FA4FF07E51FCF727F901463046FCF709 -:1029D000DFFA2946FCF728FA1249FCF71BF90146F1 -:1029E0002846FCF719F90146FCF716F9014610488C -:1029F000FCF710F9F8BD00BFDB0FC93F08EF113835 -:102A0000047F4F3A4611243DA80A4E3E90B0A63EA0 -:102A1000ABAA2A3E2EC69D3D6133303F2D57014063 -:102A200039D119406821A233DA0FC93FDB0F494081 -:102A3000DA0F494021F00042B2F1FF4FF8B50446E9 -:102A400014DC20F00045B5F1FF4F06460EDCB1F175 -:102A50007E5F3AD08F1707F0020747EAD07755B963 -:102A6000022F2FD0032F2FD13148F8BD0846214621 -:102A7000FCF7D2F8F8BDFAB1B2F1FF4F29D0B5F1A9 -:102A8000FF4F19D0AA1AD2153C2A19DC002938DBCD -:102A90002046FCF77DFA01F0BDFB01F0A5FA012FFD -:102AA0002CD0022F22D0002F2FD02249FCF7B4F8CF -:102AB0002149FCF7AFF8F8BD002E15DB1F48F8BD23 -:102AC0001E48ECE71C48F8BDF8BDBDE8F84001F031 -:102AD0008BBAB5F1FF4F19D0022FF3D0032FC3D01B -:102AE000012F1BD00020F8BD1548F8BD1149FCF797 -:102AF00093F801461048FCF78DF8F8BD00F100404E -:102B0000F8BD3C32C4DA0020C9E7F8BD022F0CD072 -:102B1000032F08D0012F04D00A48F8BD4FF0004021 -:102B2000F8BD0948F8BD0948F8BD0948F8BD00BF1F -:102B3000DB0F49C02EBDBB33DB0F4940DB0FC93F64 -:102B4000DB0FC9BFDB0F493FDB0F49BFE4CB16C02A -:102B5000E4CB16402DE9F04F31F0004987B00D4627 -:102B60000C46074611D020F0004ABAF1FF4F8046CC -:102B700005DD514807B0BDE8F04F01F0B7BBB9F132 -:102B8000FF4F07DDBAF17E5FF3D14FF07E5007B003 -:102B9000BDE8F08F002840DB0026B9F1FF4F34D0AC -:102BA000B9F17E5F4CD0B4F1804F384655D0B4F1C6 -:102BB0007C5F1BD001F02EFB0146BAF1000F1DD047 -:102BC00028F04043B3F17E5F18D04FEAD87808F17F -:102BD000FF3856EA080166D0B9F19A4F74DD374BD9 -:102BE0009A4533DC002C37DB0020D0E7B8F1000F2A -:102BF000E0DB07B0BDE8F04F00F09CBC002C41DBEF -:102C0000B8F1000F32DB0846C1E7BAF17E5FBCD0F5 -:102C100027DD002CE8DB2846B9E7B9F1974F13DA36 -:102C2000B9F17E5F0ADB4FEAE953C3F1960349FA33 -:102C300003F202FA03F34B4500F044820026AFE7AB -:102C4000002C25DB3846A2E70226A6E71C4B9A4556 -:102C500040F39D82002CC7DD1A480146FCF7E4F8DA -:102C600095E7002CC0DA05F1004090E7AAF17E5A02 -:102C700056EA0A0A12D10846FBF7CCFF0146FCF7D8 -:102C800087F984E74FF07E50FCF782F90146B7E7F9 -:102C900039464FF07E50FCF77BF978E7012EB2D130 -:102CA00001F1004073E739463846FBF7B3FF0146B0 -:102CB000FCF76EF96BE700BFE4790108F7FF7F3F8F -:102CC0000700803FCAF24971BAF5000F80F2028214 -:102CD0004FF09741FCF7A8F86FF017028246B34B0C -:102CE0004FEAEA51CAF3160A7F399A4501EB020C02 -:102CF0004AF07E5740F3EB81AD4B9A4540F3428258 -:102D000000220CF1010CA7F5000705920599A94BCB -:102D1000384653F82130CDF804C019460392049385 -:102D2000FBF778FF049981463846FBF775FF0146AB -:102D30004FF07E50FCF72CF90346194648460293A3 -:102D4000FCF772F87910039A41F00051BB4601F587 -:102D5000802120F47F6727F00F070A44824611463E -:102D600038460392FCF760F801464846FBF752FFED -:102D7000039A814604991046FBF74CFF01465846DA -:102D8000FBF748FF01463846FCF74EF80146484637 -:102D9000FBF740FF029B1946FCF746F85146834675 -:102DA0005046FCF741F801468146FCF73DF8824960 -:102DB000034648460293FCF737F88049FBF72CFF9F -:102DC0004946FCF731F87E49FBF726FF4946FCF7F8 -:102DD0002BF87C49FBF720FF4946FCF725F87A4998 -:102DE000FBF71AFF4946FCF71FF87849FBF714FF79 -:102DF000029B01461846FCF717F8394681465046B3 -:102E0000FBF70AFF5946FCF70FF84946FBF704FFAA -:102E1000394604903846FCF707F86D490390FBF7F4 -:102E2000FBFE0499FBF7F8FE20F47F6929F00F09F7 -:102E300049463846FBF7F8FF494607465846FBF730 -:102E4000F3FF634983464846FBF7E4FE039A1146C5 -:102E5000FBF7E0FE01460498FBF7DCFE5146FBF76A -:102E6000E3FF01465846FBF7D7FE834659463846EE -:102E7000FBF7D2FE20F47F6A2AF00F0A504655492C -:102E8000FBF7D2FF544981465046FBF7CDFF394648 -:102E9000034650460293FBF7BDFE01465846FBF73A -:102EA000B9FE4E49FBF7C0FF029B01461846FBF7EF -:102EB000B3FE4B4B059A53F82210FBF7ADFEDDF83D -:102EC00004C007466046FBF75BFF464B059A04903B -:102ED00053F822B039464846FBF79EFE5946FBF7A9 -:102EE0009BFE0499FBF798FE20F47F6A2AF00F0AF4 -:102EF00004995046FBF78EFE5946FBF78BFE494678 -:102F0000FBF788FE01463846FBF784FE24F47F6415 -:102F100024F00F04013E56EA080681462146284661 -:102F20000CBF314F4FF07E57FBF774FE5146FBF755 -:102F30007BFF494606462846FBF776FF01463046AA -:102F4000FBF76AFE214606465046FBF76DFF054635 -:102F500001463046FBF760FE00288146044620F01B -:102F60000048AA4640F3F880B8F1864F00F3C280CB -:102F700000F0B280B8F17C5F00F3C4804FF000092C -:102F8000C84624F47F6424F00F0420461749FBF759 -:102F90004BFF514605462046FBF73CFE01463046B6 -:102FA000FBF738FE1249FBF73FFF23E071C41C001A -:102FB000D6B35D00007A010842F1533E55326C3EB3 -:102FC00005A38B3EABAAAA3EB76DDB3E9A99193F8B -:102FD000000040400038763FA0C39D364F38763F12 -:102FE000F8790108F0790108000080BF0072313FD4 -:102FF0001872313F864906462046FBF715FF014609 -:103000003046FBF709FE064631462846FBF704FE2C -:1030100029460446FBF7FEFD01463046FBF7FAFD64 -:10302000214606462046FBF7FFFE7A490546FBF798 -:10303000FBFE7949FBF7EEFD2946FBF7F5FE7749E4 -:10304000FBF7EAFD2946FBF7EFFE7549FBF7E2FDCA -:103050002946FBF7E9FE7349FBF7DEFD2946FBF73E -:10306000E3FE01462046FBF7D5FD054629462046EE -:10307000FBF7DAFE4FF0804182462846FBF7CAFD97 -:1030800001465046FBF784FF314605462046FBF7D4 -:10309000CBFE3146FBF7C0FD01462846FBF7BAFDE3 -:1030A0002146FBF7B7FD01464FF07E50FBF7B2FD1E -:1030B0008144B9F5000FC0F2A58049463846FBF7B8 -:1030C000B3FE64E502F00102C2F1020668E50022E7 -:1030D00005921BE6002202E653493046FBF79CFDB1 -:1030E000294682464846FBF795FD01465046FCF7C7 -:1030F00057F838B138464D49FBF796FE4B49FBF778 -:1031000093FE44E54FEAE858A8F17E084FF4000327 -:1031100043FA08F32344C3F3C7524548C3F31608E0 -:10312000A2F17F0140FA01F1C2F1960248F40008D1 -:1031300048FA02F8002C23EA01012846B8BFC8F17A -:103140000008FBF767FD824651463046FBF764FDF9 -:103150004FEAC859044614E7364B98450ADC7FF419 -:1031600009AF2946FBF756FD01463046FCF704F847 -:103170000028C7D038463049FBF756FE2E49FBF7EA -:1031800053FE04E501234FF400120593BEE54FF012 -:103190007E51FBF73FFD29490746FBF745FE2849CD -:1031A00081463846FBF740FE394682463846FBF7F3 -:1031B0003BFE4FF07A5183463846FBF735FE014619 -:1031C0002048FBF727FD3946FBF72EFE01464FF05E -:1031D0007C50FBF71FFD01465846FBF725FE1A49B8 -:1031E000FBF722FE01465046FBF714FD0746394621 -:1031F0004846FBF711FD20F47F6A2AF00F0A494682 -:1032000050467DE6414601F075F8014656E700BF9D -:103210008CBEBF354CBB31330EEADD3555B38A3831 -:10322000610B363BABAA2A3E3CAA3833CAF249713D -:10323000FFFF7F00000016436042A20D00AAB83FC6 -:1032400070A5EC36ABAAAA3E3BAAB83F2DE9F04FD9 -:10325000AB4A20F00044944289B006460D4664DD36 -:10326000A84A94421CDC0028A74940F3EC80FBF7F5 -:10327000D1FCA64B24F00F049C42064664D0A4491E -:10328000FBF7C8FC014628603046FBF7C3FCA049A9 -:10329000FBF7C0FC01236860184609B0BDE8F08F59 -:1032A0009C4A944262DDB4F1FF4F46DAE715863F4F -:1032B000A4EBC7542046FBF77DFFFBF761FD0346F7 -:1032C000014620460593FBF7A5FC4FF08741FBF72D -:1032D000ABFD8046FBF76EFFFBF752FD014604464F -:1032E00040460694FBF796FC4FF08741FBF79CFDA8 -:1032F00000210790FBF72CFF002800F0C580204636 -:103300000021FBF725FF002814BF01230223824878 -:103310000221019000913A4605A8294600F022FAC0 -:10332000002EC0F2A780034603E00022286000239D -:103330004A60184609B0BDE8F08F0146FBF76AFC09 -:10334000002368602860F4E77449FBF763FC744964 -:103350000446FBF75FFC014628602046FBF75AFC59 -:103360006F49FBF757FC01236860E2E700F052FF6A -:103370006C490746FBF758FD4FF07C51FBF74CFCBE -:10338000FBF718FF8246FBF7FBFC5F498346FBF720 -:103390004BFD01463846FBF73DFC5D4980465846EB -:1033A000FBF742FDBAF11F0F81464946404618DC43 -:1033B0005D4B0AF1FF3253F8223024F0FF029A42AB -:1033C0000FD0FBF727FC07462F6039464046FBF736 -:1033D00021FC4946FBF71EFC002E686056DB534675 -:1033E000A7E7FBF717FCE315C0F3C7529A1A082AA0 -:1033F0000746E9DD494958460393FBF715FD0746A3 -:1034000039464046FBF706FC044621464046FBF79A -:1034100001FC3946FBF7FEFB414907465846FBF7DE -:1034200003FD3946FBF7F6FB814649462046FBF78C -:10343000F1FB039BC0F3C7529B1A192B074641DCD3 -:103440002860A046C1E7FBF7E7FB304B24F00F04F0 -:103450009C42064623D02E49FBF7DEFB014628603E -:103460003046FBF7D7FB2A49FBF7D6FB4FF0FF337B -:1034700068605EE795E80C0003F1004102F100424C -:1034800043422A60696054E7032340E707F100479D -:1034900000F100402F606860CAF1000349E71F494E -:1034A000FBF7BAFB1E490446FBF7B6FB0146286052 -:1034B0002046FBF7AFFB1A49FBF7AEFB4FF0FF339B -:1034C000686036E719495846FBF7AEFC07463946AF -:1034D0002046FBF79FFB804641462046FBF79AFBC0 -:1034E0003946FBF797FB124904465846FBF79CFC0C -:1034F0002146FBF78FFB81464946404661E700BF06 -:10350000D80F493FE3CB1640800FC93FD00FC93FCA -:1035100043443537800F4943887A010800443537E2 -:1035200008A3852E84F9223F087A010800A3852E7E -:1035300032318D2420F00042B2F1FF4FF8B504463D -:1035400003462DD25AB300283DDBB2F5000F4FEAF7 -:10355000E0502CD37F38C3F31603C20743F40003B3 -:1035600048BF5B00002740105B003E4619244FF027 -:103570008072B5189D4202DC5B1BAE181744013CFB -:103580004FEA43034FEA5202F3D113B107F00103AC -:103590001F447F1007F17C5707EBC050F8BDF8BD02 -:1035A0000146FBF741FC2146FBF736FBF8BD14F45E -:1035B00000020FD15B00190202F10102FAD5C2F13B -:1035C00001021044C6E70146FBF724FB0146FBF766 -:1035D000DFFCF8BD01221044BCE700BF2DE9F84331 -:1035E00020F00046B6F1485F05460F4649DAFBF782 -:1035F000E1FD002800F09D8029462846FBF714FCD9 -:103600004E490446FBF710FC4D49FBF705FB2146EC -:10361000FBF70AFC4B49FBF7FDFA2146FBF704FCDC -:103620004949FBF7F9FA2146FBF7FEFB4749FBF74F -:10363000F1FA2146FBF7F8FB4549FBF7EDFA214685 -:10364000FBF7F2FB804620464FF07C51FBF7ECFB8A -:10365000414606462046FBF7E7FB39460446284626 -:10366000FBF7E2FB01462046FBF7D4FA0146304661 -:10367000FBF7D0FA01464FF07E50FBF7CBFABDE8DE -:10368000F8830146FBF7D0FB2C490446FBF7CCFB43 -:103690002B49FBF7C1FA2146FBF7C6FB2949FBF78B -:1036A000B9FA2146FBF7C0FB2749FBF7B5FA2146DB -:1036B000FBF7BAFB2549FBF7ADFA2146FBF7B4FB54 -:1036C0002349FBF7A9FA2146FBF7AEFB214B8046C5 -:1036D0009E42B8DD204B9E4227DC06F17F463146F4 -:1036E0004FF07E50FBF796FA814620464FF07C5112 -:1036F000FBF79AFB3146FBF78DFA4146064620461A -:10370000FBF792FB394604462846FBF78DFB014642 -:103710002046FBF77FFA01463046FBF77BFA01466D -:103720004846FBF777FABDE8F883DFF834900B4E94 -:10373000DBE74FF07E50BDE8F88300BF4ED747ADC2 -:10374000F6740F317CF29334010DD037610BB63A29 -:10375000ABAA2A3D9999993E0000483F0000903E4F -:103760000000383F2DE9F04FDFB00B93013B02938F -:10377000D31E48BF131DB84C06466898DB1054F89A -:10378000204023EAE3730C93DB4302EBC30308946A -:103790000693089C029B0C9A1D190991C3EB020722 -:1037A0001DD4699C3D4404EB870901354FF00008A6 -:1037B00022AC0AE059F80800FBF7E2FA0137AF4201 -:1037C00044F8080008F1040809D0002FF2DA0137A4 -:1037D0000020AF4244F8080008F10408F5D1089A27 -:1037E000002AC0F2DF82089A0B9B02F101089C00BC -:1037F00022AF4FEA880827440025029A002AC0F227 -:10380000F28105EB070B4FF000094FF0000A56F864 -:1038100009005BF8041DFBF707FB01465046FBF768 -:10382000FBF909F10409A1458246F0D14AA840F804 -:1038300005A004354545E0D1089A0EAB03EB8203A1 -:103840000D9391464FEA89030793079A5EAB1344A1 -:10385000B9F1000F53F850AC23DD0DF134084AAF35 -:10386000174490440DAD4FF06E515046FBF7DCFA13 -:10387000FBF7A0FCFBF784FA4FF087418346FBF788 -:10388000D3FA01465046FBF7C5F9FBF793FC5946BE -:1038900045F8040F57F8040DFBF7BEF9454582467D -:1038A000E1D15046069900F025FD4FF078510546CC -:1038B000FBF7BAFA00F0BAFC4FF08241FBF7B4FA1A -:1038C00001462846FBF7A6F90546FBF773FC82463E -:1038D000FBF756FA01462846FBF79CF9069A804604 -:1038E000002A40F3678109F1FF310EA850F821301A -:1038F000C2F1080043FA00F202FA00F01B1A06981F -:103900009244C0F1070743FA07F70EA840F82130A8 -:10391000002F32DDB9F1000F0AF1010A40F3758181 -:103920000EAB079A19461144002507E0C2F58070D6 -:1039300012B143F8040C01258B420BD053F8042B31 -:10394000002DF3D0C2F1FF028B4243F8042C4FF05C -:103950000105F3D1069B002B0DDD012B00F0328118 -:10396000022B08D109F1FF330EA951F8232002F0F0 -:103970003F0241F82320022F70D040460021FBF780 -:10398000E7FB002800F08380089A09F1FF35AA427E -:103990000DDC079A0EAB0D981344002253F8041D5A -:1039A000834242EA0102F9D1002A40F0E481089BF7 -:1039B0000EA85A1E50F82230002B40F0F18100EB87 -:1039C0008202012352F8041D01330029FAD04B442E -:1039D00099450A933DDADDF82CA022AACA44DDF805 -:1039E000308002EB8A02C844C9EB0309131D03921D -:1039F0000593699A079B4FEA89094AAF02EB880849 -:103A0000CDF810901F44002558F8040FFBF7B8F9C3 -:103A1000029B039A002B50514FF0000B13DBDDF893 -:103A200014A04FF00009AA4456F809005AF8041DE2 -:103A3000FBF7FAF901465846FBF7EEF809F10409DD -:103A4000A1458346F0D1049A0435954247F804BF56 -:103A5000DAD1DDF82890F5E6A07D010841464FF067 -:103A60007E50FBF7D7F88046002D86D006994FF0A0 -:103A70007E5000F03FFC01464046FBF7CBF8804605 -:103A800040460021FBF764FB00287FF47DAF069BD6 -:103A900040465942CDF808A000F02CFC4FF0874179 -:103AA0000446FBF773FB002800F07F814FF06E5156 -:103AB0002046FBF7B9F9FBF77DFBFBF761F94FF007 -:103AC00087410546FBF7B0F901462046FBF7A2F80F -:103AD000FBF770FB0EAB43F829002846FBF76AFBA7 -:103AE000069C09F1010508340EA9069441F8250049 -:103AF00006994FF07E5000F0FDFB002D04464FDB91 -:103B00006E1C4FEA8508C6EB867A0DF138094AAB80 -:103B1000C1444FEA8A0A98444FF0000B59F80B0051 -:103B2000FBF72EF92146FBF77FF94FF06E5148F86D -:103B30000B002046FBF778F9ABF1040BD3450446A4 -:103B4000ECD1DFF88C92DDF820A00024B346039579 -:103B50000497BAF1000FB8BF002515DB00263746E1 -:103B6000002501E0A7420FDC58F8061059F80600BE -:103B7000FBF75AF901462846FBF74EF80137BA45DC -:103B8000054606F10406EDDA5EA800EB8403013475 -:103B9000A345A8F1040843F8A05CDAD1039D049F73 -:103BA000689C032C00F29880DFE814F0CB009C00A6 -:103BB0009C00310010D109F1FF330EA951F8237098 -:103BC0003F12A5E609F1FF330EA850F8232002F0BA -:103BD0007F0240F82320CEE64FF07C51FBF7D6FA67 -:103BE00058B90746C9E64FF0000A4AA840F805A0B0 -:103BF000043545457FF401AE1EE6B9F1000F4FF0E4 -:103C000002070AF1010A3FF78BAE0025A2E6002D5C -:103C100040F3DC804FEA850B5EAB36AE05F1FF3A30 -:103C20005B4406EB8A0A53F8A08C54465B4635AADF -:103C3000BB462F4600E0C84654F804594146284682 -:103C400001920093FAF7E8FF814649462846FAF7C1 -:103C5000E1FF4146FAF7E0FF019AC4F8049094426C -:103C6000A060009BE7D13D46012D5F469B4640F397 -:103C7000AD805EAB9B445BF8A04C00E044465AF834 -:103C8000049921464846FAF7C7FF80464146484610 -:103C9000FAF7C0FF2146FAF7BFFF5645CAF804807D -:103CA000CAF80800EAD16C1C06EB84040020083630 -:103CB00054F8041DFAF7B0FFB442F9D1002F7ED0BA -:103CC000369A379B099C00F1004002F1004203F153 -:103CD0000043A06022606360029A02F007005FB0B8 -:103CE000BDE8F08F002DB8BF00200ADB36AE6C1C9B -:103CF000002006EB840454F8041DFAF78DFFB4424B -:103D0000F9D1002F35D000F10043099C0146236012 -:103D10003698FAF77FFF002D08DD36AC04EB8505F9 -:103D200054F8041FFAF778FFAC42F9D10FB100F153 -:103D30000040099A5060029A02F007005FB0BDE8A7 -:103D4000F08F002D39DB6C1C36AE002006EB8404AE -:103D500054F8041DFAF760FFB442F9D10FB100F135 -:103D60000040099A1060029A02F007005FB0BDE8B7 -:103D7000F08F0346C9E7069A0EAC54F82530083A8E -:103D8000CDF808A00692002B7FF4B2AE04EB8503B9 -:103D900053F8041D013D083A0029F9D00692A7E620 -:103DA000012314E60B9B9C0046E52046FBF702FA34 -:103DB0000EAA4D4642F829009AE60020CEE7099C5B -:103DC000369A379BA0602260636085E7002075E724 -:103DD000AC7D01082DE9F84320F00043B3F1485FC2 -:103DE00004460F46904603DAFBF7E4F9002857D063 -:103DF00021462046FBF718F821460546FBF714F844 -:103E0000294906462846FBF70FF82849FAF702FF2A -:103E10002946FBF709F82649FAF7FEFE2946FBF783 -:103E200003F82449FAF7F6FE2946FAF7FDFF22497E -:103E3000FAF7F2FE8146B8F1000F22D038464FF073 -:103E40007C51FAF7F1FF494680463046FAF7ECFF1D -:103E500001464046FAF7DEFE2946FAF7E5FF394605 -:103E6000FAF7D8FE154905463046FAF7DDFF014658 -:103E70002846FAF7D1FE01462046FAF7CBFEBDE808 -:103E8000F88349462846FAF7CFFF0C49FAF7C2FEF5 -:103E90003146FAF7C9FF2146FAF7BEFEBDE8F883BE -:103EA0002046BDE8F88300BFD3C92E2F342FD73268 -:103EB0001BEF3836010D50398988083CABAA2A3EE1 -:103EC0000020704700200149704700BF0000F87FC4 -:103ED0002DE9F043C1F30A5CACF2FF37132F83B036 -:103EE00002460B460D46894680464FEAD17630DCC5 -:103EF000002F4CDB3A49394101EA030010432DD031 -:103F0000490801EA030858EA02080CD04FF480235C -:103F10003B41132F25EA010141EA030914BF4FF089 -:103F200000084FF000482F494B4601EBC606D6E982 -:103F30000045424620462946FAF70CFACDE9000131 -:103F4000DDE9000122462B46FAF702FA03B0BDE88C -:103F5000F083332F07DDB7F5806F3ED0104619464A -:103F600003B0BDE8F083ACF2134C4FF0FF3121FAFF -:103F70000CF10142F2D049080142D4D04FF0804800 -:103F800048FA0CFC20EA010141EA0C08CBE721F0D9 -:103F900000410143E2D0C3F3130101434C420C43FF -:103FA0001048590C240B490404F4002444EA01038A -:103FB00000EBC601D1E9004520462946FAF7CAF9C7 -:103FC000CDE90001DDE900012B462246FAF7C0F9F0 -:103FD00021F0004343EAC671C2E7FAF7BBF9BFE735 -:103FE000FFFF0F00D87D01082DE9F04120F00045CA -:103FF000B5F1A14F0446064608DBB5F1FF4F6FDC73 -:10400000002840F3A0806F48BDE8F0816E4B9D42D0 -:1040100077DCB5F1445F68DB4FF0FF37214620467F -:10402000FAF702FF01468046FAF7FEFE67490546A9 -:10403000FAF7FAFE6649FAF7EFFD2946FAF7F4FEB9 -:104040006449FAF7E9FD2946FAF7EEFE6249FAF704 -:10405000E3FD2946FAF7E8FE6049FAF7DDFD294657 -:10406000FAF7E2FE5E49FAF7D7FD4146FAF7DCFEC1 -:104070005C4980462846FAF7D7FE5B49FAF7CAFD45 -:104080002946FAF7D1FE5949FAF7C4FD2946FAF74D -:10409000CBFE5749FAF7BEFD2946FAF7C5FE55494A -:1040A000FAF7B8FD2946FAF7BFFE7B1C01464046E9 -:1040B0004CD0FAF7B1FD2146FAF7B6FE4E4B4F4D04 -:1040C00053F82710FAF7A6FD2146FAF7A3FD01469B -:1040D00055F82700FAF79EFD002E30DBBDE8F08191 -:1040E0000146FAF799FDBDE8F0814549FAF794FDDC -:1040F0004FF07E51FBF754F800288DD02046BDE8E4 -:10410000F08100F087F83F4B04469D4229DCA3F57F -:10411000D0039D4244DC0146FAF77EFD4FF07E510C -:10412000FAF778FD4FF0804105462046FAF774FD16 -:1041300001462846FAF72CFF002704466EE700F1F7 -:104140000040BDE8F0813048BDE8F081FAF764FD39 -:104150002146FAF769FE01462046FAF75BFDBDE805 -:10416000F0812A4B9D4214DC4FF07F51FAF752FD4B -:104170004FF07F5105462046FAF756FE4FF07E512C -:10418000FAF74AFD01462846FAF702FF02270446DD -:1041900044E701461E48FAF7FBFE032704463DE7C5 -:1041A0004FF07E51FAF736FD4FF07E51054620461E -:1041B000FAF732FD01462846FAF7EAFE01270446DF -:1041C0002CE700BFDB0FC93FFFFFDF3ED769853C0F -:1041D00059DA4B3D356B883D6E2EBA3D2549123E6E -:1041E000ABAAAA3E21A215BD6BF16E3D95879D3D00 -:1041F000388EE33DCDCC4C3EE87D0108F87D0108CA -:10420000CAF24971FFFF973FDB0FC9BFFFFF1B4099 -:10421000000080BF20F00040704700BF20F0004049 -:10422000B0F1FF4FACBF0020012070472DE9F041F5 -:1042300020F00047FD0D7F3D162D064613DC002DB6 -:1042400080461BDB194F2F41074214D01849FAF75B -:10425000E3FC0021FAF7A4FF68B1002E1BDB28EA7B -:104260000700BDE8F081B7F1FF4F04D30146FAF72C -:10427000D3FCBDE8F0813046BDE8F0810C49FAF787 -:10428000CBFC0021FAF78CFF0028F4D0002E08DBCD -:104290000020BDE8F0814FF4000343FA05F5A8447F -:1042A000DDE7002FE7D00348BDE8F081FFFF7F0086 -:1042B000CAF24971000080BF30F0004001D10220F5 -:1042C0007047A0F50003B3F1FE4F01D20420704700 -:1042D000054B421E9A4201D803207047B0F1FF43BC -:1042E00058425841704700BFFEFF7F0000487047AA -:1042F0000000C07F38B530F00044024603460D464A -:1043000014D0B4F1FF4F0DD2B4F5000F0FD3E40D6C -:104310002C44FE2C2EDC002C1DDD23F0FF4343EA51 -:10432000C45038BD0146FAF777FC38BD38BD4FF0B0 -:104330009841FAF779FD194B02469D4207DBC0F31D -:10434000C7540346193CE3E7154800F02DF814491B -:10435000FAF76AFD38BD14F1160F13DA4CF2503338 -:104360009D421146F0DD0F4800F01EF80D49FAF7A6 -:104370005BFD38BD11460B4800F016F80949FAF705 -:1043800053FD38BD04F1190023F0FF4343EAC05048 -:104390004FF04C51FAF748FD38BD00BFB03CFFFF6D -:1043A0006042A20DCAF2497101F0004120F00040C4 -:1043B00008437047014B1868704700BF2C0100206C -:1043C0000800000000200000000C01401000000068 -:1043D0000020000000100140000C01400800100205 -:1043E000000C014010001002000C014004001402F7 -:1043F000000000000000000003010000604A010806 -:1044000004000000204A010804000000E0490108FF -:1044100002010000C0490108000100000000000086 -:10442000060000006049010806000000004901087C -:10443000010100000000000004000000C048010865 -:10444000060000006048010808000000E04701087D -:10445000080000006047010808000000E04601086D -:104460000101000000000000000100000000000049 -:10447000000100000000000004000000A046010848 -:104480000600000040460108000100000000000096 -:1044900002010000204601080101000000000000A8 -:1044A000000000000000000002460108EA45010883 -:1044B000CC450108B4450108F91F0008B51F0008E4 -:1044C000911F0008691F0008591F00084DE20008ED -:1044D000E51F0008091F0008D91F0008CB1F0008AE -:1044E0000000000000C20100B0600108D3600108B4 -:1044F0000100000000E10000E86001080A61010815 -:1045000002000000009600001E61010840610108E1 -:1045100003000000004B00005461010876610108AF -:1045200004000000802500004E7101084E71010852 -:104530000001000200020000091700000100020053 -:1045400002000000010700000000FFFF4A0100FF19 -:104550002C0100FF0E0100FFF00000FFD20000FF61 -:10456000B40000FF960000FF780000FF5A0000FF33 -:104570003C0000FF1E0000FF000000FFCC5F0108B0 -:10458000484501087845010874450108704501084F -:104590006C4501086845010864450108604501084B -:1045A0005C4501085845010854450108504501087B -:1045B0004C4501080001080309030A040B040C041C -:1045C0000D040404050406040704FFFF00020102B1 -:1045D000020203020402050206020702080309039D -:1045E0000A040B040C040D04FFFF00010803090377 -:1045F0000A030B030C030D0304030503060307035F -:10460000FFFF000201020202030204020502060289 -:104610000702080309030A030B030C030D03FFFF42 -:104620000000803F0000000000000000000080BF8C -:104630000000803F00000000000000000000803FFC -:104640000000803F000080BF0000803F000080BF6E -:104650000000803F000080BF000080BF0000803F5E -:104660000000803F0000803F0000803F0000803F4E -:104670000000803F0000803F000080BF000080BF3E -:104680000000803F0000000000000000000000006B -:104690000000803F0000000000000000000000005B -:1046A0000000803F000000000000803F0000803FCD -:1046B0000000803F000080BF000080BF00000000BD -:1046C0000000803F000000000000803F000080BF2D -:1046D0000000803F0000803F000080BF000000809D -:1046E0000000803F0000803F000000BF0000803FCE -:1046F0000000803F000000BF000080BF0000803F3E -:104700000000803F000080BF0000003F0000803FAD -:104710000000803F0000003F0000803F0000803F1D -:104720000000803F0000003F000080BF000080BF0D -:104730000000803F000080BF000000BF000080BF7D -:104740000000803F000000BF0000803F000080BFED -:104750000000803F0000803F0000003F000080BF5D -:104760000000803FF704353FF70435BF0000803F6D -:104770000000803FF70435BFF70435BF0000803FDD -:104780000000803FF70435BFF704353F0000803F4D -:104790000000803FF704353FF704353F0000803FBD -:1047A0000000803F00000000000080BF000080BFCC -:1047B0000000803F000080BF00000000000080BFBC -:1047C0000000803F000000000000803F000080BF2C -:1047D0000000803F0000803F00000000000080BF1C -:1047E0000000803F000080BF0000803F000080BFCD -:1047F0000000803F000080BF000080BF0000803FBD -:104800000000803F0000803F0000803F0000803FAC -:104810000000803F0000803F000080BF000080BF9C -:104820000000803F000080BF0000803F0000803F0C -:104830000000803F000080BF000080BF000080BFFC -:104840000000803F0000803F0000803F000080BFEC -:104850000000803F0000803F000080BF0000803FDC -:104860000000803F000000BFD0B35D3F0000803FEC -:104870000000803F000000BFD0B35DBF0000803F5C -:104880000000803F0000003FD0B35D3F000080BFCC -:104890000000803F0000003FD0B35DBF000080BF3C -:1048A0000000803F000080BF00000000000080BFCB -:1048B0000000803F0000803F000000000000803FBB -:1048C0000000803F000000000000803F000080BF2B -:1048D0000000803F000080BF000080BF000000009B -:1048E0000000803F000000000000803F0000803F8B -:1048F0000000803F0000803F000080BF00000000FB -:104900000000803FD0B35DBF0000003F0000803F4B -:104910000000803FD0B35DBF000000BF000080BF3B -:104920000000803FD0B35D3F0000003F0000803FAB -:104930000000803FD0B35D3F000000BF000080BF9B -:104940000000803F00000000000080BF0000803FAA -:104950000000803F000000000000803F000080BF9A -:104960000000803F00000000A8AAAA3F0000803F8E -:104970000000803F000080BFB0AA2ABF000080BFB7 -:104980000000803F0000803FB0AA2ABF000080BF27 -:104990000000803F00000000A8AAAA3F000080BFDE -:1049A0000000803F000080BFB0AA2ABF0000803F07 -:1049B0000000803F0000803FB0AA2ABF0000803F77 -:1049C0000000803F0000803F000000000000000069 -:1049D0000000803F000080BF0000000000000000D9 -:1049E0000000803F000080BF0000803F000080BFCB -:1049F0000000803F000080BF000080BF0000803FBB -:104A00000000803F0000803F0000803F0000803FAA -:104A10000000803F0000803F000080BF000080BF9A -:104A20000000803F000000000000803F000080BFC9 -:104A30000000803F000080BF000000000000803FB9 -:104A40000000803F0000803F000000000000803F29 -:104A50000000803F00000000000080BF000080BF19 -:104A60000000803F00000000A8AAAA3F000000004C -:104A70000000803F000080BFB0AA2ABF00000000F5 -:104A80000000803F0000803FB0AA2ABF0000000065 -:104A90001000000000200000001001400040000055 -:104AA000001001400001746564666D6A69736C678B -:104AB00001000102000103000104000105000106DC -:104AC00000010700010800010900010A00010B00B4 -:104AD000010C010300000000CF610108000000008C -:104AE00001000000D4610108010000000200000084 -:104AF000DB6101080200000003000000E46101081E -:104B00000300000004000000EA6101080500000045 -:104B100005000000EF61010806000000060000002B -:104B2000F9610108070000000700000002620108A7 -:104B300008000000080000000B62010809000000E6 -:104B400009000000146201080A0000000A000000C9 -:104B50001E6201080B0000000B0000002862010823 -:104B60000C0000000C000000326201080D00000083 -:104B70000D0000003A6201080E0000000E00000067 -:104B8000426201080F0000000F0000004A620108A5 -:104B90001000000010000000536201081100000026 -:104BA000110000005A62010812000000120000000B -:104BB0006462010813000000130000006C62010829 -:104BC00014000000140000007762010815000000C6 -:104BD00015000000816201081600000016000000A8 -:104BE00000000000FF000000B56206010300F005B0 -:104BF00000FF19B56206010300F00300FD15B56260 -:104C000006010300F00100FB11B56206010300F08C -:104C10000000FA0FB56206010300F00200FC13B5B4 -:104C20006206010300F00400FE17B56206010300EE -:104C30000102010E47B562060103000103010F499D -:104C4000B56206010300010601124FB562060103B9 -:104C5000000112011E67B56206080600C8000100C7 -:104C60000100DE6A00B562061608000307030000B3 -:104C700000000031E501B5620616080003070300D5 -:104C8000510800008A4102B56206160800030703B6 -:104C90000004E00400199D03B5620616080003072E -:104CA00003000002020035EF04B562061608000397 -:104CB00007030080010000B2E8009001C800C800AE -:104CC000C800C800C800C800C800C80064000000D0 -:104CD000C800C800C800C8003200010B020D0A035A -:104CE000050B030D0A03070B030D0A03090B020D45 -:104CF0000A030A0B040D0A03080B040D0A03000043 -:104D000064640108696401086D6401088064010835 -:104D100072640108786401087C64010800000000E6 -:104D20004E710108206401082864010830640108FC -:104D3000386401083F6401084A64010852640108AC -:104D40005A6401085F6401080000000048205072A6 -:104D50006F647563743A426C61636B626F7820664E -:104D60006C696768742064617461207265636F7236 -:104D7000646572206279204E6963686F6C6173208C -:104D8000536865726C6F636B0A4820426C61636B99 -:104D9000626F782076657273696F6E3A310A4820C7 -:104DA000446174612076657273696F6E3A310A00EE -:104DB00084640108BE650108096601085766010898 -:104DC000A4660108F266010848204669656C642003 -:104DD00047206E616D653A4750535F6E756D536144 -:104DE000742C4750535F636F6F72645B305D2C4768 -:104DF00050535F636F6F72645B315D2C4750535F3C -:104E0000616C7469747564652C4750535F73706589 -:104E100065640A48204669656C64204720736967A9 -:104E20006E65643A302C312C312C302C300A4820FD -:104E30004669656C64204720707265646963746FAD -:104E4000723A302C372C372C302C300A48204669E7 -:104E5000656C64204720656E636F64696E673A31E4 -:104E60002C302C302C312C310A48204669656C647A -:104E70002048206E616D653A4750535F686F6D65DD -:104E80005B305D2C4750535F686F6D655B315D0A29 -:104E900048204669656C642048207369676E6564C4 -:104EA0003A312C310A48204669656C6420482070EC -:104EB0007265646963746F723A302C300A48204618 -:104EC00069656C64204820656E636F64696E673A3B -:104ED000302C300A000002020308050A0B080A0AF7 -:104EE0000B0C0E0E0F0000001E1E646464646464EC -:104EF000220046022100820120004302100001012D -:104F0000000049020100880102004C0212008401E5 -:104F100011009001110090011100A0011100A001E9 -:104F20007320000891200008AD200008718E000851 -:104F3000D9200008E52000080200000080250000BC -:104F400000C20100000000002000000080250000D9 -:104F500000C20100010000004000000080250000A8 -:104F600000C20100000000000100000080250000D8 -:104F700000C20100000000001000000080250000B9 -:104F800000C20100000300000400000080250000B2 -:104F9000004B0000000000000800000000E10000DD -:104FA00000E10000000400008000000000C20100D9 -:104FB00000C2010000000000000000000000004FDF -:104FC00000000007000700147F147F14242A7F2AA2 -:104FD000122313086462364955225000050300006D -:104FE000001C2241000041221C0014083E08140845 -:104FF000083E080800503000000808080808006053 -:1050000060000020100804023E5149453E00427FE6 -:10501000400042615149462141454B311814127FED -:105020001027454545393C4A494930017109050376 -:105030003649494936064949291E003636000000DE -:1050400056360000081422410014141414140041B0 -:105050002214080201510906324979413E7E11119C -:10506000117E7F494949363E414141227F414122DB -:105070001C7F494949417F090909013E4149497A53 -:105080007F0808087F00417F41002040413F017FA9 -:10509000081422417F404040407F020C027F7F0481 -:1050A00008107F3E4141413E7F090909063E4151BA -:1050B000215E7F09192946464949493101017F018D -:1050C000013F4040403F1F2040201F3F4038403FAD -:1050D00063140814630708700807615149454300C9 -:1050E0007F41410002040810200041417F0004027A -:1050F000010204404040404001020400002054549A -:1051000054787F4844443838444444203844444820 -:105110007F3854545418087E090102064949493F12 -:105120007F0804047800447D40002040443D007F17 -:105130001028440000417F40007C0418047C7C0857 -:1051400004047838444444387C14141408081414B3 -:10515000187C7C080404084854545420043F4440FC -:10516000203C4040207C1C2040201C3C4030403CE7 -:1051700044281028440C5050503C4464544C440083 -:105180000836410000007F0000004136080002019F -:105190000204023E55554122000000000000007943 -:1051A00000001824742E24487E4942405D222222A9 -:1051B0005D15167C161500007700000A5555552818 -:1051C0000001000100000A0D0A0408142A14220438 -:1051D0000404041C00080808000101010101000288 -:1051E00005020044445F444400000402017E202084 -:1051F000103E060F7F007F0018180000004050206E -:1052000000000A0D0A0022142A14081708342A7D07 -:105210001708046A59304845402042004200427E47 -:10522000420042007E7E0042007E7E7E42007E7E04 -:105230007E7E007E7E7E7E7E05040203524F4C4CB5 -:105240003B50495443483B5941573B414C543B50D8 -:105250006F733B506F73523B4E6176523B4C4556D9 -:10526000454C3B4D41473B56454C3B009B63010839 -:10527000C6630108BA630108400080000001000213 -:10528000000449574641540102040810204E45537A -:105290005755442C3A3A0000A987000841200008DD -:1052A0000F200008896C00085D200008856C00084C -:1052B000486D01084C6D0108526D0108586D0108D8 -:1052C0005B6D0108626D0108656D01086A6D01087A -:1052D000766D0108796D01087F6D0108866D010802 -:1052E000906D01089A6D0108A36D0108B16D010868 -:1052F000BD6D0108C46D0108CA6D0108D76D0108B4 -:10530000E26D0108EF6D010800000000966C0108D5 -:105310009D6C0108A26C0108B36C0108BD6C01080A -:10532000C86C0108D36C010878640108DE6C0108C0 -:1053300072640108E76C0108F16C0108FF6C010858 -:10534000026D0108126D0108196D0108226D010836 -:105350002C6D0108346D01083F6D0108000000004C -:10536000316E01083A6E0108E96500085E6E0108B9 -:10537000626E01081D670008786E01087D6E0108E5 -:1053800045AC0008916E0108976E010811B0000845 -:10539000A6700108A86E010889D30008C56E01082F -:1053A000CA6E010885B50008F96E01084E71010842 -:1053B000A5D30008FE6E0108066F0108A99B00082E -:1053C0001A6F01081E6F01085DC70008316F0108E0 -:1053D000406F0108B5B900085A6F01084E71010805 -:1053E00019AC00085F6F0108636F0108B5A90008D8 -:1053F000726F0108766F0108B9B100088B6E010861 -:10540000926F0108D5AE0008A56F0108AB6F0108C7 -:1054100071AF00087F760108C66F010839B5000832 -:10542000D56F0108C66F010871850008E16F01089A -:10543000E66F0108D1D3000898690108F66F0108EA -:10544000BDC700082470010818700108E97700083A -:10545000457401084E710108E9AB00080054004092 -:10546000000C0140400080001F20000000002000D0 -:1054700000580040000C01400004000821220000F8 -:1054800000004000000000008025000000C2010074 -:1054900006000000010000008025000000C201009D -:1054A000070000000300000080250000004B000002 -:1054B000090000000400000080250000004B0000EF -:1054C00009000000000100004F71010844000000C5 -:1054D000F01F002000000000282300005871010880 -:1054E00041000000F21F0020000000000100000049 -:1054F0006671010844000000FE200020B004000096 -:10550000A40600006D710108440000000021002085 -:1055100000000000D007000077710108440000007F -:105520000221002000000000D00700008171010866 -:1055300042000000042100200000000012000000D2 -:105540008E710108420000000521002001000000CA -:10555000FF000000997101084200000006210020B0 -:105560000000000001000000AE71010844000000CE -:10557000B420002000000000D0070000BB7101082B -:1055800044000000B620002000000000D00700000A -:10559000C871010844000000B8200020000000008D -:1055A000D0070000D471010844000000BA20002098 -:1055B00000000000D0070000E47101084400000072 -:1055C000BC20002000000000D0070000F571010899 -:1055D00044000000BE20002000000000D0070000B2 -:1055E0000072010844000000C020002000000000FC -:1055F000D00700001572010844000000C2200020FE -:1056000032000000007D0000247201084400000008 -:10561000C420002032000000F201000033720108B3 -:1056200041000000072100200000000001000000F0 -:105630004072010841000000082100200000000025 -:105640000100000053720108410000000921002000 -:1056500000000000B40000005F720108410000007B -:105660000A21002000000000640000006B720108A5 -:10567000420000000B210020FFFFFFFF010000009F -:10568000817201084100000010210020000000008C -:105690000B00000098720108410000001121002059 -:1056A000000000000B000000AF7201084100000084 -:1056B00012210020000000000B000000C67201084B -:1056C0004100000013210020000000000B0000003A -:1056D000DD7201084100000024210020300000009C -:1056E0007E000000EE72010850000000142100202E -:1056F000B004000000C20100FB720108500000006D -:1057000018210020B004000000C201000873010845 -:10571000500000001C2100200000000000C2010019 -:10572000157301085000000020210020B004000083 -:1057300000C201002E730108410000000C2100206E -:1057400000000000010000003B7301084100000060 -:105750000D21002000000000040000004973010832 -:10576000410000000E2100200000000001000000A8 -:105770005973010881000000002200200000000091 -:10578000C800000063730108810000000A220020A5 -:1057900000000000C80000006D73010881000000D7 -:1057A0001422002000000000C800000077730108E8 -:1057B000810000000122002000000000C80000005D -:1057C00082730108810000000B220020000000000D -:1057D000C80000008D730108810000001522002020 -:1057E00000000000C800000098730108810000005C -:1057F0000222002000000000C8000000A27301087F -:10580000810000000C22002000000000C800000001 -:10581000AC73010881000000162200200000000087 -:10582000C8000000B673010884000000AA2300200D -:1058300000000000D0070000C473010881000000D0 -:10584000AE2300200000000001000000D973010811 -:1058500084000000B02300200A000000D0070000F0 -:10586000E773010884000000B22300200A00000052 -:10587000D0070000F573010881000000AD2300206F -:1058800000000000640000000374010841000000F3 -:10589000FC20002000000000030000001574010837 -:1058A000410000002821002000000000030000004B -:1058B0002874010841000000292100200000000098 -:1058C0000100000039740108410000002A21002075 -:1058D00000000000010000004D740108600000009D -:1058E0002C210020A6FFFFFF5A000000657401086C -:1058F00060000000302100204CFFFFFFB4000000DA -:105900007D740108410000003421002000000000E7 -:1059100001000000967401084100000035210020BC -:105920000000000001000000A17401084400000014 -:10593000F220002000000000204E0000B274010898 -:1059400041000000E820002000000000FF000000EF -:10595000BD74010841000000E92000200A00000099 -:1059600032000000D374010841000000EA2000204A -:105970000A00000032000000E97401084400000041 -:10598000EC2000200100000010270000FD74010839 -:1059900044000000EE20002000000000720600001D -:1059A0001275010841000000F020002000000000F6 -:1059B000010000003075010841000000C6200020F1 -:1059C00000000000080000003B75010841000000D5 -:1059D000C7200020000000000800000045750108F5 -:1059E00041000000C8200020000000000800000066 -:1059F0004F75010848000000CA2000204CFFFFFF3F -:105A0000680100006075010848000000CC200020FB -:105A10004CFFFFFF6801000072750108480000009C -:105A2000CE2000204CFFFFFF6801000082750108B6 -:105A300044000000DA20002064000000840300001D -:105A40009875010844000000D220002000000000EA -:105A500000010000A175010841000000D8200020CD -:105A60000000000080000000B17501084400000043 -:105A7000D420002064000000E8030000C275010883 -:105A800044000000D620002064000000E80300006D -:105A9000D475010881000000572300200100000098 -:105AA000FA000000E675010881000000582300207C -:105AB0000000000001000000DD7501088100000009 -:105AC000552300200000000020000000FB750108A5 -:105AD0008100000056230020000000006400000048 -:105AE00008760108810000005C230020000000000F -:105AF0009600000022760108840000005A2300204E -:105B000001000000840300003C7601084200000010 -:105B1000D0200020FFFFFFFF0100000052760108A7 -:105B200082000000A6230020FFFFFFFF010000000D -:105B30006076010882000000A7230020000000001A -:105B40000100000072760108810000004822002058 -:105B5000000000000200000087760108010100003B -:105B60003A27002000000000FA0000008F760108AC -:105B7000010100003B27002000000000640000003D -:105B800097760108010100003C270020000000007A -:105B9000640000009F760108010100003D270020FD -:105BA0000000000064000000A87601080101000068 -:105BB0003E2700200000000064000000B8760108C5 -:105BC000010100003F2700200000000064000000E9 -:105BD000C1760108010100004027002000000000FC -:105BE00064000000CA76010804010000422700207A -:105BF000E8030000D0070000D9760108810000000A -:105C00009E23002000000000C8000000E876010884 -:105C1000810000009F23002000000000C800000059 -:105C2000FB76010884000000A0230020E8030000A8 -:105C3000D00700000D77010884000000A223002097 -:105C400064000000D00700001F77010884000000F6 -:105C5000A423002064000000B80B00003177010885 -:105C600081000000A823002000000000FF000000C9 -:105C70003E77010841000000D12000200000000014 -:105C8000090000004B77010881000000502200202D -:105C900000000000FA0000005A77010881000000AF -:105CA000582200200000000064000000697701080D -:105CB0008100000059220020000000006400000064 -:105CC00077770108A00000005422002001000000A6 -:105CD0001400000087770108810000006C2200207A -:105CE0000000000001000000967701088800000015 -:105CF0004E220020D4FEFFFF2C010000A5770108F2 -:105D0000880000004C220020D4FEFFFF2C01000080 -:105D1000B3770108810000005C2200200000000031 -:105D200030000000C1770108A000000060220020C0 -:105D30000000000001000000D0770108A000000072 -:105D4000642200200000000001000000DC77010850 -:105D5000A0000000682200200000000001000000F8 -:105D6000E8770108880000004A220020B0B9FFFF50 -:105D700050460000F877010881000000F82100205B -:105D80000000000002000000077801088100000008 -:105D9000FD21002000000000C80000000F7801086D -:105DA000810000000722002000000000C800000061 -:105DB0006A75010881000000112200200000000027 -:105DC000C80000001778010881000000FC210020B5 -:105DD00000000000C80000001E78010881000000DB -:105DE0000622002000000000C800000059750108CC -:105DF000810000001022002000000000C800000008 -:105E00002578010881000000FE210020000000002C -:105E1000C80000002B780108810000000822002043 -:105E200000000000C80000007C750108810000002F -:105E30001222002000000000C80000003178010894 -:105E4000A0000000202200200000000064000000EC -:105E50003A780108A00000002C2200200000000079 -:105E60006400000043780108A000000038220020F0 -:105E700000000000640000004C780108A000000051 -:105E80001C2200200000000064000000547801087B -:105E9000A000000028220020000000006400000094 -:105EA0005C780108A00000003422002000000000FF -:105EB0006400000064780108A00000002422002093 -:105EC00000000000640000006B780108A0000000E2 -:105ED00030220020000000006400000072780108F9 -:105EE000A00000003C220020000000006400000030 -:105EF00079780108A0000000442200200000000082 -:105F00000A00000087780108A0000000402200205D -:105F1000000000000A0000009378010881000000E2 -:105F2000FF21002000000000C8000000997801084F -:105F3000810000000922002000000000C8000000CD -:105F40009F7801088100000013220020000000005B -:105F5000C8000000A578010881000000032200208D -:105F600000000000C8000000AD78010881000000BA -:105F70000D22002000000000C8000000B5780108D4 -:105F8000810000001722002000000000C80000006F -:105F9000BD780108810000000522002000000000FB -:105FA000C8000000C3780108810000000F22002013 -:105FB00000000000C8000000C9780108810000004E -:105FC0001922002000000000C800000000000000AE -:105FD000000000400008014001000000001C0028F3 -:105FE000000000400008014002000000041C0028DE -:105FF000000000400008014004000000081C0028C8 -:106000000000004000080140080000000C1C0028AF -:10601000000400400008014040000000001D00286E -:10602000000400400008014080000000041D00281A -:1060300000040040000C014001000000081D002881 -:1060400000040040000C0140020000000C1D00286C -:10605000002C01400008014000010000001B012845 -:10606000002C014000080140000800000C1B012822 -:1060700000080040000C014040000000001E002805 -:1060800000080040000C014080000000041E0028B1 -:1060900000080040000C014000010000081E00281C -:1060A00000080040000C0140000200000C1E002807 -:1060B00024505542582C34312C312C303030332C74 -:1060C000303030312C3131353230302C302A3145BE -:1060D0000D0A0024504D544B3235312C31313532BC -:1060E00030302A31460D0A0024505542582C3431A4 -:1060F0002C312C303030332C303030312C35373699 -:1061000030302C302A32440D0A0024504D544B328A -:1061100035312C35373630302A32430D0A002450C1 -:106120005542582C34312C312C303030332C303017 -:1061300030312C33383430302C302A32360D0A00CE -:1061400024504D544B3235312C33383430302A32D0 -:10615000370D0A0024505542582C34312C312C3044 -:106160003030332C303030312C31393230302C302B -:106170002A32330D0A0024504D544B3235312C3124 -:10618000393230302A32320D0A0030081002000253 -:106190000001000600080008100140080007100771 -:1061A0002007000410042008000030313233343559 -:1061B000363738394142434445464748494A4B4CB3 -:1061C0004D4E4F505152535455565758595A0041FD -:1061D000524D3B00414E474C453B00484F52495AB7 -:1061E0004F4E3B004241524F3B004D41473B004820 -:1061F000454144465245453B004845414441444A97 -:106200003B0043414D535441423B0043414D5452A6 -:1062100049473B0047505320484F4D453B004750AE -:106220005320484F4C443B0050415353544852551F -:106230003B004245455045523B004C45444D41587A -:106240003B004C45444C4F573B004C4C494748544D -:10625000533B0043414C49423B00474F5645524E49 -:106260004F523B004F53442053573B0054454C453D -:106270004D455452593B004155544F54554E453BA2 -:1062800000534F4E41523B002E0061646A72616EB2 -:106290006765202575202575202575202575202505 -:1062A000752025752025750D0A00617578202575E6 -:1062B0002025752025752025752025750D0A0020BF -:1062C00025642025640053797374656D20557074BE -:1062D000696D653A202564207365636F6E64732C65 -:1062E00020566F6C746167653A202564202A20303F -:1062F0002E315620282564532062617474657279AA -:10630000290D0A004350552025644D487A2C2064FD -:10631000657465637465642073656E736F72733A38 -:1063200020002573200041434348573A202573003D -:106330002E2563004379636C652054696D653A20AE -:1063400025642C20493243204572726F72733A20C3 -:1063500025642C20636F6E6669672073697A653ADD -:106360002025640D0A0048204669726D77617265C8 -:1063700020747970653A436C65616E666C69676814 -:10638000740A0048204669726D77617265207265F3 -:10639000766973696F6E3A25730A0035373934317F -:1063A00030350048204669726D77617265206461FE -:1063B00074653A25732025730A00446563202038EC -:1063C00020323031340032323A30353A34330048FA -:1063D000207263526174653A25640A0048206D6931 -:1063E0006E7468726F74746C653A25640A00482094 -:1063F0006D61787468726F74746C653A25640A0014 -:1064000048206779726F2E7363616C653A30782526 -:10641000780A0048206163635F31473A25750A00B6 -:106420004144584C333435004D50553630353000EA -:106430004D4D413834357800424D41323830004CB2 -:10644000534D333033444C4843004D505536303073 -:1064500030004D5055363530300046414B45004EEA -:106460006F6E65004759524F00414343004241520D -:106470004F00534F4E415200475053004750532B4B -:106480004D41470048204669656C642049206E6193 -:106490006D653A6C6F6F70497465726174696F6E87 -:1064A0002C74696D652C61786973505B305D2C616B -:1064B000786973505B315D2C61786973505B325D34 -:1064C0002C61786973495B305D2C61786973495B35 -:1064D000315D2C61786973495B325D2C6178697339 -:1064E000445B305D2C61786973445B315D2C61786D -:1064F0006973445B325D2C7263436F6D6D616E64D2 -:106500005B305D2C7263436F6D6D616E645B315DFA -:106510002C7263436F6D6D616E645B325D2C7263D0 -:10652000436F6D6D616E645B335D2C6779726F4490 -:106530006174615B305D2C6779726F446174615B7B -:10654000315D2C6779726F446174615B325D2C61DF -:106550006363536D6F6F74685B305D2C616363536D -:106560006D6F6F74685B315D2C616363536D6F6F2A -:1065700074685B325D2C6D6F746F725B305D2C6D77 -:106580006F746F725B315D2C6D6F746F725B325D17 -:106590002C6D6F746F725B335D2C6D6F746F725BFB -:1065A000345D2C6D6F746F725B355D2C6D6F746F25 -:1065B000725B365D2C6D6F746F725B375D004820C7 -:1065C0004669656C642049207369676E65643A307A -:1065D0002C302C312C312C312C312C312C312C31D4 -:1065E0002C312C312C312C312C312C302C312C31C4 -:1065F0002C312C312C312C312C302C302C302C30B7 -:106600002C302C302C302C300048204669656C64CE -:10661000204920707265646963746F723A302C305F -:106620002C302C302C302C302C302C302C302C308A -:106630002C302C302C302C302C342C302C302C3076 -:106640002C302C302C302C342C352C352C352C3552 -:106650002C352C352C350048204669656C64204962 -:1066600020656E636F64696E673A312C312C302C73 -:10667000302C302C302C302C302C302C302C302C3A -:10668000302C302C302C312C302C302C302C302C29 -:10669000302C302C312C302C302C302C302C302C19 -:1066A000302C300048204669656C642050207072A0 -:1066B00065646963746F723A362C322C312C312C3C -:1066C000312C312C312C312C312C312C312C312CE2 -:1066D000312C312C312C332C332C332C332C332CC8 -:1066E000332C332C332C332C332C332C332C332CB2 -:1066F000330048204669656C64205020656E636FE6 -:1067000064696E673A302C302C302C302C302C30B1 -:106710002C302C302C302C302C302C382C382C3881 -:106720002C382C302C302C302C302C302C302C3081 -:106730002C302C302C302C302C302C302C30007263 -:1067400061746570726F66696C652025640D0A005E -:106750004145545231323334005265763A20257324 -:10676000005461726765743A20257300566F6C742B -:10677000733A2025642E2531642043656C6C733A8E -:1067800020256400416D70733A2025642E25326403 -:10679000206D41683A202564002020202020202000 -:1067A000205820202020205920202020205A00413D -:1067B000203D20253564202535642025356400479B -:1067C000203D202535642025356420253564004D85 -:1067D000203D202535642025356420253564005072 -:1067E000726F66696C653A20256400526174652099 -:1067F00070726F66696C653A2025640052432045CB -:1068000078706F3A20256400524320526174653AD3 -:106810002025640052265020526174653A20256478 -:106820000059617720526174653A202564007C2FFD -:106830002D5C00434C45414E464C4947485400416D -:10684000524D454400424154544552590053454E1F -:10685000534F52530052580050524F46494C450036 -:106860004E415A4500456E61626C65642066656103 -:1068700074757265733A2000417661696C61626C6F -:10688000652066656174757265733A2000496E769D -:10689000616C69642066656174757265206E616DF6 -:1068A000650D0A0044697361626C65642000456E81 -:1068B00061626C6564200041464E4100004F20102B -:1068C00004430240010880C325752C25753A2573C1 -:1068D0003A2573006C65642025752025730D0A0028 -:1068E0005061727365206572726F720D0A00496E95 -:1068F00076616C6964206C656420696E6465783AC1 -:10690000206D757374206265203C2025750D0A008A -:10691000436C65616E666C696768742F257320250A -:1069200073202F2025732028257329004176616963 -:106930006C61626C6520636F6D6D616E64733A0D9E -:106940000A0025730925730D0A004E4709004F4BB5 -:106950000900437573746F6D206D697865723A2014 -:106960000D0A4D6F746F720954687209526F6C6C26 -:10697000095069746368095961770D0A0023256419 -:106980003A09002573090053616E697479206368C0 -:1069900065636B3A09007265736574006C6F6164BE -:1069A00000496E76616C6964206D69786572207447 -:1069B0007970650D0A004C6F616465642025732051 -:1069C0006D69780D0A0057726F6E67206E756D6283 -:1069D0006572206F6620617267756D656E74732CC9 -:1069E000206E656564732069647820746872207213 -:1069F0006F6C6C207069746368207961770D0A0090 -:106A00004D6F746F72206E756D626572206D757357 -:106A100074206265206265747765656E203120613F -:106A20006E642025640D0A0043757272656E7420D1 -:106A30006D697865723A2025730D0A0041766169A7 -:106A40006C61626C65206D69786572733A20004DE7 -:106A5000697865722073657420746F2025730D0A40 -:106A60000055736167653A0D0A6D6F746F72206926 -:106A70006E646578205B76616C75655D202D207392 -:106A8000686F77205B6F72207365745D206D6F7423 -:106A90006F722076616C75650D0A004E6F207375FC -:106AA0006368206D6F746F722C2075736520612090 -:106AB0006E756D626572205B302C2025645D0D0A59 -:106AC000004D6F746F7220256420697320736574A4 -:106AD0002061742025640D0A00496E76616C69643A -:106AE000206D6F746F722076616C75652C2031306B -:106AF00030302E2E323030300D0A005365747469F8 -:106B00006E67206D6F746F7220256420746F20256E -:106B1000640D0A00636F6C6F722025752025642C4C -:106B200025752C25750D0A00496E76616C69642007 -:106B3000636F6C6F7220696E6465783A206D75734F -:106B400074206265203C2025750D0A004D75737414 -:106B500020626520616E79206F72646572206F66B5 -:106B60002041455452313233340D0A00437572725C -:106B7000656E742061737369676E6D656E743A201B -:106B8000006D6173746572007261746573000D0A43 -:106B9000232076657273696F6E0D0A000D0A23203B -:106BA00064756D70206D61737465720D0A000D0A55 -:106BB00023206D697865720D0A006D697865722011 -:106BC00025730D0A00636D697820256400636D6983 -:106BD0007820256420302030203020300D0A000D30 -:106BE0000A0D0A2320666561747572650D0A0066D8 -:106BF000656174757265202D25730D0A00666561E7 -:106C0000747572652025730D0A000D0A0D0A232084 -:106C10006D61700D0A006D61702025730D0A000D05 -:106C20000A0D0A23206C65640D0A000D0A0D0A2363 -:106C300020636F6C6F720D0A000D0A232064756D5E -:106C4000702070726F66696C650D0A000D0A232052 -:106C500070726F66696C650D0A000D0A23206175FC -:106C6000780D0A000D0A232061646A72616E6765FF -:106C70000D0A000D0A232064756D70207261746521 -:106C8000730D0A000D0A23207261746570726F66BD -:106C9000696C650D0A0052585F50504D00564241D4 -:106CA0005400494E464C494748545F4143435F4373 -:106CB000414C0052585F53455249414C004D4F548E -:106CC0004F525F53544F5000534552564F5F5449F3 -:106CD0004C5400534F465453455249414C00464191 -:106CE000494C534146450054454C454D4554525935 -:106CF0000043555252454E545F4D45544552003362 -:106D0000440052585F504152414C4C454C5F5057E3 -:106D10004D0052585F4D535000525353495F414408 -:106D200043004C45445F535452495000444953502A -:106D30004C4159004F4E4553484F54313235004273 -:106D40004C41434B424F5800545249005155414425 -:106D5000500051554144580042490047494D424175 -:106D60004C005936004845583600464C59494E4764 -:106D70005F57494E47005934004845583658004F30 -:106D800043544F5838004F43544F464C41545000E1 -:106D90004F43544F464C41545800414952504C4186 -:106DA0004E450048454C495F3132305F4343504DBA -:106DB0000048454C495F39305F44454700565441CF -:106DC000494C340048455836480050504D5F544FA8 -:106DD0005F534552564F004455414C434F50544524 -:106DE000520053494E474C45434F5054455200437F -:106DF0005553544F4D00414552543132333435369A -:106E000037386162636465666768004572726F72E5 -:106E10003A20456E61626C6520616E6420706C750D -:106E20006720696E204750532066697273740D0A9B -:106E30000061646A72616E67650073686F772F73B3 -:106E400065742061646A7573746D656E7420726117 -:106E50006E6765732073657474696E67730061751E -:106E6000780073686F772F7365742061757820736D -:106E7000657474696E677300636D69780064657327 -:106E800069676E20637573746F6D206D69786572C4 -:106E900000636F6C6F7200636F6E66696775726511 -:106EA00020636F6C6F727300726573657420746F0A -:106EB0002064656661756C747320616E6420726510 -:106EC000626F6F740064756D70007072696E74200B -:106ED000636F6E666967757261626C652073657455 -:106EE00074696E677320696E2061207061737461CC -:106EF000626C6520666F726D006578697400666506 -:106F00006174757265006C697374206F72202D76E0 -:106F1000616C206F722076616C0067657400676534 -:106F200074207661726961626C652076616C75654A -:106F300000677073706173737468726F756768004F -:106F4000706173737468726F7567682067707320FF -:106F5000746F2073657269616C0068656C70006C99 -:106F6000656400636F6E666967757265206C656441 -:106F700073006D6170006D617070696E67206F667F -:106F8000207263206368616E6E656C206F72646549 -:106F900072006D69786572206E616D65206F722078 -:106FA0006C697374006D6F746F72006765742F7312 -:106FB0006574206D6F746F72206F757470757420B6 -:106FC00076616C756500696E646578202830207480 -:106FD0006F203229007261746570726F66696C652A -:106FE0000073617665007361766520616E6420725E -:106FF00065626F6F74006E616D653D76616C75657D -:10700000206F7220626C616E6B206F72202A206686 -:107010006F72206C6973740073686F772073797373 -:1070200074656D2073746174757300556E6B6E6F4B -:10703000776E207661726961626C65206E616D6544 -:107040000D0A0043757272656E74207365747469FD -:107050006E67733A200D0A002573207365742074DF -:107060006F200056616C75652061737369676E6D82 -:10707000656E74206F7574206F662072616E67652F -:107080000D0A00736574202573203D20000D0A52FF -:1070900065626F6F74696E670052657365747469B9 -:1070A0006E6720746F2064656661756C7473000D83 -:1070B0000A4C656176696E6720434C49206D6F64A8 -:1070C000652C20756E7361766564206368616E67F8 -:1070D0006573206C6F73742E0D0A00536176696EB0 -:1070E00067000D0A456E746572696E6720434C49EE -:1070F000204D6F64652C2074797065202765786950 -:10710000742720746F2072657475726E2C206F72F4 -:10711000202768656C70270D0A000D0A2320000DDA -:107120001B5B4B001B5B324A1B5B313B31480055FC -:107130006E6B6E6F776E20636F6D6D616E642C2069 -:10714000747279202768656C702700082008006C2D -:107150006F6F7074696D6500656D665F61766F69EC -:1071600064616E6365006D69645F7263006D696E72 -:107170005F636865636B006D61785F636865636B0F -:1071800000727373695F6368616E6E656C00727321 -:1071900073695F7363616C6500696E7075745F66B7 -:1071A000696C746572696E675F6D6F6465006D69A7 -:1071B0006E5F7468726F74746C65006D61785F7473 -:1071C00068726F74746C65006D696E5F636F6D6D6E -:1071D000616E640033645F6465616462616E645F04 -:1071E0006C6F770033645F6465616462616E645FD5 -:1071F000686967680033645F6E65757472616C00FE -:1072000033645F6465616462616E645F7468726F49 -:1072100074746C65006D6F746F725F70776D5F7200 -:1072200061746500736572766F5F70776D5F726110 -:1072300074650072657461726465645F61726D008B -:1072400064697361726D5F6B696C6C5F737769748D -:10725000636800736D616C6C5F616E676C6500667E -:107260006C6170735F7370656564006669786564EE -:1072700077696E675F616C74686F6C645F64697274 -:107280000073657269616C5F706F72745F315F73F8 -:1072900063656E6172696F0073657269616C5F70BE -:1072A0006F72745F325F7363656E6172696F0073D2 -:1072B000657269616C5F706F72745F335F73636571 -:1072C0006E6172696F0073657269616C5F706F7275 -:1072D000745F345F7363656E6172696F00726562BB -:1072E0006F6F745F636861726163746572006D7360 -:1072F000705F626175647261746500636C695F627E -:1073000061756472617465006770735F6261756452 -:1073100072617465006770735F7061737374687213 -:107320006F7567685F62617564726174650067702C -:10733000735F70726F7669646572006770735F73F4 -:107340006261735F6D6F6465006770735F61757410 -:107350006F5F636F6E666967006770735F706F73EE -:107360005F70006770735F706F735F690067707341 -:107370005F706F735F64006770735F706F73725FCD -:1073800070006770735F706F73725F69006770730E -:107390005F706F73725F64006770735F6E61765FBA -:1073A00070006770735F6E61765F69006770735F0E -:1073B0006E61765F64006770735F77705F7261649F -:1073C000697573006E61765F636F6E74726F6C7354 -:1073D0005F68656164696E67006E61765F73706592 -:1073E00065645F6D696E006E61765F73706565647C -:1073F0005F6D6178006E61765F736C65775F726157 -:1074000074650073657269616C72785F70726F7613 -:10741000696465720074656C656D657472795F701E -:10742000726F76696465720074656C656D657472FF -:10743000795F7377697463680074656C656D6574F2 -:1074400072795F696E76657273696F6E00667273CA -:107450006B795F64656661756C745F6C6174746987 -:1074600074756465006672736B795F6465666175D7 -:107470006C745F6C6F6E67697475646500667273B7 -:107480006B795F636F6F7264696E617465735F6659 -:107490006F726D6174006672736B795F756E69747B -:1074A00000626174746572795F63617061636974AD -:1074B0007900766261745F7363616C650076626106 -:1074C000745F6D61785F63656C6C5F766F6C74611F -:1074D000676500766261745F6D696E5F63656C6C91 -:1074E0005F766F6C746167650063757272656E7448 -:1074F0005F6D657465725F7363616C65006375725F -:1075000072656E745F6D657465725F6F66667365D4 -:1075100074006D756C74697769695F637572726503 -:107520006E745F6D657465725F6F757470757400ED -:10753000616C69676E5F6779726F00616C69676E15 -:107540005F61636300616C69676E5F6D61670061B5 -:107550006C69676E5F626F6172645F726F6C6C0002 -:10756000616C69676E5F626F6172645F706974639A -:107570006800616C69676E5F626F6172645F7961F8 -:1075800077006D61785F616E676C655F696E636CD3 -:10759000696E6174696F6E006779726F5F6C706697 -:1075A000006D6F726F6E5F7468726573686F6C6484 -:1075B000006779726F5F636D70665F666163746F99 -:1075C00072006779726F5F636D70666D5F6661638D -:1075D000746F7200616C745F686F6C645F64656186 -:1075E0006462616E6400616C745F686F6C645F6696 -:1075F0006173745F6368616E6765007961775F646A -:1076000065616462616E64007468726F74746C6545 -:107610005F636F7272656374696F6E5F76616C75BC -:1076200065007468726F74746C655F636F72726505 -:107630006374696F6E5F616E676C65007961775F17 -:10764000636F6E74726F6C5F646972656374696F87 -:107650006E007961775F646972656374696F6E004B -:107660007472695F756E61726D65645F7365727661 -:107670006F0064656661756C745F726174655F70DC -:10768000726F66696C650072635F72617465007227 -:10769000635F6578706F007468725F6D6964007411 -:1076A00068725F6578706F00726F6C6C5F70697480 -:1076B00063685F72617465007961775F7261746598 -:1076C000007470615F72617465007470615F6272F2 -:1076D00065616B706F696E74006661696C73616679 -:1076E000655F64656C6179006661696C736166658C -:1076F0005F6F66665F64656C6179006661696C7373 -:107700006166655F7468726F74746C650066616948 -:107710006C736166655F6D696E5F75736563006646 -:1077200061696C736166655F6D61785F75736563D0 -:107730000067696D62616C5F666C616773006163AD -:10774000635F6861726477617265006163635F6C37 -:1077500070665F666163746F720061636378795FFE -:107760006465616462616E64006163637A5F64652D -:10777000616462616E64006163637A5F6C70665F0E -:107780006375746F6666006163635F756E61726DC9 -:10779000656463616C006163635F7472696D5F70DF -:1077A00069746368006163635F7472696D5F726FAF -:1077B0006C6C006261726F5F7461625F73697A659D -:1077C000006261726F5F6E6F6973655F6C706600F7 -:1077D0006261726F5F63665F76656C006261726F93 -:1077E0005F63665F616C74006D61675F6465636CA5 -:1077F000696E6174696F6E007069645F636F6E7447 -:10780000726F6C6C657200705F7069746368006998 -:107810005F706974636800705F726F6C6C00695FA1 -:10782000726F6C6C00705F79617700695F79617766 -:1078300000705F70697463686600695F7069746383 -:10784000686600645F70697463686600705F726F79 -:107850006C6C6600695F726F6C6C6600645F726F5F -:107860006C6C6600705F7961776600695F7961773B -:107870006600645F79617766006C6576656C5F6849 -:107880006F72697A6F6E006C6576656C5F616E67AA -:107890006C6500705F616C7400695F616C7400649A -:1078A0005F616C7400705F6C6576656C00695F6C1D -:1078B0006576656C00645F6C6576656C00705F76FC -:1078C000656C00695F76656C00645F76656C0000CE -:1078D0002020202020202020202828282828202080 -:1078E0002020202020202020202020202020202098 -:1078F0008810101010101010101010101010101010 -:1079000004040404040404040404101010101010EF -:1079100010414141414141010101010101010101C8 -:1079200001010101010101010101011010101010FC -:107930001042424242424202020202020202020299 -:1079400002020202020202020202021010101020C1 -:107950000000000000000000000000000000000027 -:107960000000000000000000000000000000000017 -:107970000000000000000000000000000000000007 -:1079800000000000000000000000000000000000F7 -:1079900000000000000000000000000000000000E7 -:1079A00000000000000000000000000000000000D7 -:1079B00000000000000000000000000000000000C7 -:1079C00000000000000000000000000000000000B7 -:1079D0000000004B000000CB61636F736600000085 -:1079E000706F7766000000007371727466000000AB -:1079F0000000000000C0153F00000000DCCFD135C2 -:107A00000000803F0000C03F000FC93F000F494009 -:107A100000CB9640000FC9400053FB4000CB1641FD -:107A200000ED2F41000F49410031624100537B417D -:107A3000003A8A4100CB9641005CA34100EDAF4182 -:107A4000007EBC41000FC94100A0D5410031E24198 -:107A500000C2EE410053FB4100F20342003A0A42E9 -:107A60000083104200CB164200141D42005C2342EA -:107A700000A5294200ED2F4200363642007E3C42EE -:107A800000C74242000F4942A2000000F900000076 -:107A9000830000006E0000004E0000004400000063 -:107AA0001500000029000000FC0000002700000075 -:107AB00057000000D1000000F50000003400000075 -:107AC000DD000000C0000000DB00000062000000DC -:107AD00095000000990000003C00000043000000F9 -:107AE0009000000041000000FE0000005100000076 -:107AF00063000000AB000000DE000000BB000000DF -:107B0000C500000061000000B70000002400000074 -:107B10006E0000003A000000420000004D0000002E -:107B2000D2000000E0000000060000004900000054 -:107B30002E000000EA00000009000000D100000053 -:107B4000920000001C000000FE0000001D0000006C -:107B5000EB0000001C000000B10000002900000044 -:107B6000A70000003E000000E800000082000000C6 -:107B700035000000F50000002E000000BB000000F2 -:107B80004400000084000000E90000009C000000A8 -:107B90007000000026000000B40000005F0000003C -:107BA0007E0000004100000039000000910000004C -:107BB000D6000000390000008300000053000000E0 -:107BC00039000000F40000009C0000008400000068 -:107BD0005F0000008B000000BD000000F900000005 -:107BE000280000003B0000001F000000F80000001B -:107BF00097000000FF000000DE000000050000000C -:107C0000980000000F000000EF0000002F000000AF -:107C1000110000008B0000005A0000000A00000064 -:107C20006D0000001F0000006D0000003600000025 -:107C30007E000000CF00000027000000CB00000005 -:107C400009000000B70000004F00000046000000DF -:107C50003F000000660000009E0000005F00000082 -:107C6000EA0000002D000000750000002700000061 -:107C7000BA000000C7000000EB000000E5000000B3 -:107C8000F10000007B0000003D0000000700000044 -:107C900039000000F70000008A00000052000000D8 -:107CA00092000000EA0000006B000000FB000000F2 -:107CB0005F000000B10000001F0000008D00000008 -:107CC0005D000000080000005600000003000000F6 -:107CD0003000000046000000FC0000007B000000B7 -:107CE0006B000000AB000000F0000000CF000000BF -:107CF000BC000000200000009A000000F40000001A -:107D0000360000001D000000A9000000E300000094 -:107D100091000000610000005E000000E60000002D -:107D20001B00000008000000650000009900000032 -:107D3000850000005F00000014000000A0000000AB -:107D400068000000400000008D000000FF000000FF -:107D5000D8000000800000004D000000730000000B -:107D600027000000310000000600000006000000AF -:107D70001500000056000000CA000000730000005B -:107D8000A8000000C900000060000000E200000040 -:107D90007B000000C00000008C0000006B000000B1 -:107DA0000400000007000000090000000000C93FB7 -:107DB0000000F0390000DA370000A2330000842E02 -:107DC0000000502B0000C2270000D0220000C41F7A -:107DD0000000C61B000044170000000000003043F4 -:107DE00000000000000030C36937AC316821223345 -:107DF000B40F14336821A2333863ED3EDA0F493FE4 -:087E00005E987B3FDA0FC93FD9 -:087E0800D474FF7F01000000AB -:107E100000127A00000000000000000001020304CC -:107E200006070809010303000000803F0000803FAF -:107E30000000803F000100000000803F00000000C3 -:107E4000000000000100DC05DC05DC05DC05DC05CC -:107E5000DC05DC05DC050100010100000000803FBD -:107E600000000000010203040102030406070809E0 -:107E700002040608000000000000000000000000EE -:107E800001000000000000000000000003000000EE -:107E900000000000000000000400000000000000DE -:107EA0000000000000A24A040300000091D5000871 -:107EB0000F270000FFFFFFFF336801083F6801083C -:107EC000456801084D6801085568010858680108AF -:107ED00060680108B7680108CF7801080000000059 -:107EE0000000000000000000000000000000000092 -:107EF0000000000000000000000000006B640108AA -:107F00000000000000000000000000000000000071 -:107F10000000000000000000000000000000000061 -:107F20000000000000000000000000000000000051 -:107F3000000000000000000000000000CC00002055 -:047F4000010000003C +:10000000AD68814629464046FEF712FE074648463F +:10001000FEF7BAFD294680464FF07E50FEF7FEFC03 +:1000200001464046FEF704FE01463846FEF7F8FC5E +:10003000C4F8640202F02EF905218046FAF788FA26 +:10004000B4F8702240F23E6302F21F3292B29A423A +:10005000C4F89002D4F894720AD87D4AB2F87202B9 +:1000600000F21F3080B298428CBF0020012000E0D7 +:10007000002000286AD094F89832754D13BBD5F84B +:100080002021D5F824317548D31AB3F5FA7FA8BFDB +:100090004FF4FA738342A8BF18460A21FAF758FAB8 +:1000A000D5F89C328022DB78584390FBF2F3B3F50D +:1000B000967FA8BF4FF49673A2F5D6729342B8BF4D +:1000C000134601E0664B1B68D4F89C22C8EB03037F +:1000D000517A20205943D57C91FBF0F1D4F83401BA +:1000E000B1F5967FA8BF4FF4967103FB05005D4BF9 +:1000F000B0F5C81FA8BF4FF4C8109842B8BF184643 +:100100004FF40055C4F8340190FBF5F0564DA94268 +:10011000ACBF45184519507FFEF736FD394680467D +:100120000498FEF77DFC01464046FEF781FD4FF046 +:100130006C51FEF77DFDFEF741FF6FF095039628A9 +:10014000A8BF96209842B8BF1846281A049BC4F846 +:100150003801C4F8943226E0B3681D0623D5F3F7BE +:10016000EFFA20E0D4F81421394BD0061BD53F4AD2 +:10017000D3F8A01212683C318A4214D3C3F8A022EB +:10018000D3F8A8723A4A3B4DC3F8A4223B880B200F +:100190002B61F4F7EDFD3B886B6104E0B3689903D4 +:1001A00001D5FDF705F9D4F83C31052B03DD284BCB +:1001B0000022C3F83C21F4F7DBFC2F4B1860B38915 +:1001C0002BB1D4F8AC22821A002AC0F25887184406 +:1001D0001F4D7379C4F8AC02059305F53170D4F85E +:1001E000B832D4F8B072984705F53170014694F8EA +:1001F000CA22F4F7F9FA214B1B88002B00F0B880D3 +:10020000D5F8CC324FF000091B7805F5347504930E +:10021000C8461A4BB3F800A0194BBAF57A7F03D140 +:10022000002243F809202A61164A32F9080053F8DF +:100230000920024443F80920FEF7A6FC2A6901328E +:10024000012A2A6120D1002368602860AB6046E063 +:10025000380100200024744924FAFFFF0CFEFFFF40 +:10026000CC2700200000E7FFD4FEFFFF282000205D +:10027000A0000020000C0140BC270020C82700205F +:1002800044040020FC030020D5F800C0039261461E +:10029000CDF808C00190FEF7C1FB039A83461046D3 +:1002A000FEF772FC01465846FEF776FDDDF808C001 +:1002B00001466046FEF7B4FB019B024611466860AA +:1002C00018460392FEF7AAFB01465846FEF7B0FC1B +:1002D000A968FEF7A5FB039AE8602A60A860684A4F +:1002E000002302F1540BBAF1010F28F8023028F86C +:1002F0000B30DFF89CA12CD12869012807DD0138DB +:10030000FEF742FC0146E868FEF746FD00E00020EB +:1003100002F016FA0346049858B10193FEF734FC34 +:10032000019B01461846FEF73FFE10B14FF47A7369 +:100330001CE0544B4FF47A7259F803300A2003F54D +:10034000FA7393FBF2F32BF808300F210122F4F734 +:100350002BFD08F10208B8F1060F09F1040905F1B7 +:1003600014057FF456AFBAF80030013BAAF800300C +:100370000023454D05F5317205F54671985A595AD5 +:10038000411A99520233062BF3D1D5F8143113F0E8 +:10039000020300F00583D5F8243305F54B70984728 +:1003A00005F54B70014695F83223F4F71DFAB5F8C0 +:1003B000343305F54B78002B45D00022D5F83803AF +:1003C0001346314D38F902C0B5F8341305F54F7EA8 +:1003D000B1F5C87F04BF00214EF803105EF803108A +:1003E000294D61444EF80310043300210C2B28F8EA +:1003F0000210815202F10202E3D1B5F83433012B2D +:100400001CD1D5F83C334FF4C872C83393FBF2F3D8 +:100410000380D5F84033C83393FBF2F34380D5F81B +:100420004433C83393FBF2F2184B1B88D21A8280F4 +:10043000A7F85410A7F85610FCF74CFCB4F8343366 +:10044000013BA4F83433B3685A0740F18480B4F810 +:1004500048230D4B322A1DD1D3F838231188A3F835 +:100460004A1351889288A3F84C13A3F84E23B7F887 +:100470005420A3F85023B7F85620A3F852230BE0DA +:10048000FC0300204404002038010020000000206C +:10049000C8270020002A3CD00021D4F838530A464F +:1004A000914E38F901E0B6F8483306F55576322B0F +:1004B00004BF0023B350B0588B4B7044B05004328B +:1004C00000200C2A28F80100685201F10201E7D14E +:1004D000B3F84823012A17D183F86123052283F852 +:1004E0006223B3F84A2383F860032A80B3F84C23CD +:1004F0006A80B3F84E23AA80B3F85023B3F852337E +:10050000A7F85420A7F85630B4F84833013BA4F8B4 +:10051000483394F86323744BEAB1D3F85453D3F8B7 +:1005200038133220002295FBF0F583F863230D8009 +:10053000D3F8585395FBF0F54D80D3F85C3393FB1B +:10054000F0F06A4B1B88C01A8880A7F85420A7F8DF +:100550005620FCF7BFFBD4F83833B4F82C131A88B4 +:1005600000268A1AA4F82C23B4F82E135A88B14610 +:100570008A1AA4F82E239B88B4F83023D31AA4F83F +:100580003033F4F7F5FAD4F864330546C31A184645 +:100590000493FEF7F5FAD4F868130690FEF748FBCB +:1005A000D4F86C83C4F8645398F800A007903546DB +:1005B0004F4F785FFEF7E8FA0799FEF739FB09A974 +:1005C0008851BAF1000F2DD05046FEF7DDFA0146F2 +:1005D0004FF07E50FEF7E0FB0246114607F1AC0BF0 +:1005E0004FF07E500392FEF719FA56F80B10FEF703 +:1005F0001FFB07F168018446485FCDF808C0FEF78D +:10060000C3FA039AB8371146FEF712FBDDF808C0AB +:1006100001466046FEF704FA4BF80600FEF7CEFCF2 +:10062000785304E007F1B8026837E95BA952314F0B +:100630000436EA5F0235062D02FB0299B8D12B4D34 +:100640004FF0640A2A880AFB09F3524393FBF2FA3B +:10065000AAF1490A07F1080009A91FFA8AFAF4F772 +:1006600099FDBAF13B0FD8F8046011D9B4F99003A1 +:10067000FEF78AFAD4F88C6301463046FEF794FC04 +:10068000194F94F84A31002838D043F0080337E076 +:100690004FF07E513046FEF7C3F901464FF07E50D1 +:1006A000FEF77AFB4FF0000B8246134B304653F8AF +:1006B0001B100193FEF7BCFA024637F90B000392B8 +:1006C000FEF762FA039A01461046FEF7A9F9514671 +:1006D000FEF7AEFA019B43F81B000BF1020BBBF1D6 +:1006E000060FE2D1C2E700BF380100200000002061 +:1006F000FC030020B4040020BC04002023F0080305 +:100700003146D4F8880387F84A3101F08FFE074656 +:10071000C4F89403D4F88403D4F88CB300F10046F1 +:10072000D4F888030146FEF783FA594682465846B4 +:10073000FEF77EFA01465046FEF772F902F000F825 +:100740000146304601F072FEA6490646C4F89803F9 +:100750003846FEF76DFA01F09DFDA249A4F870023B +:100760003046FEF765FA01F095FDD4F81431A4F88F +:1007700072021B0739D59C4809A9F4F70BFDD8F87C +:1007800008904FF07E514846FEF74AF901464FF077 +:100790007E50FEF701FB4FF0000B8246934D48461A +:1007A00005F5677353F81B100193FEF741FA05F541 +:1007B000A271024631F90B000392FEF7E5F9039AA4 +:1007C00001461046FEF72CF95146FEF731FA019B1F +:1007D00043F81B000BF1020BBBF1060FDED11846EC +:1007E000F4F790FDA5F8A80341E0DFF814A209A9E9 +:1007F0000AF10400F4F7CEFC6868D5F808B00146A9 +:10080000FEF716FAD5F80C90594605465846FEF7FD +:100810000FFA01462846FEF703F9494605464846C1 +:10082000FEF706FA01462846FEF7FAF801F088FFBF +:1008300000210546FEF790FBA0B9DAF8040029462E +:10084000FEF7AAFA2946CAF80400DAF80800FEF70B +:10085000A3FA2946CAF80800DAF80C00FEF79CFA59 +:10086000CAF80C006248F4F74DFDA4F8A8036149EA +:100870000698FEF7DDF907F10047814606F10046CC +:10088000B4F9A8030C970D96FEF77EF95A4900F1CA +:100890000040FEF7CDF90E90B4F97C03FEF774F931 +:1008A0000F90B4F97E03FEF76FF91090B4F980034E +:1008B000FEF76AF90CA911900FA8F4F76BFC98F8F1 +:1008C00001304A4D012B19D14C4B1B785E070ED4D9 +:1008D000D5F8AC33402093FBF0F0181AFEF754F92A +:1008E0001199FEF79DF8FEF769FBC5F8AC033F4B85 +:1008F000D3F8AC03402390FBF3F001E0404B1888A1 +:10090000FEF742F901461198FEF788F8D4F8B413BF +:1009100011904846FEF784F801464846FEF73CFA37 +:10092000D4F8B053064629461198FEF777F80146E9 +:100930003046FEF77DF901462846FEF771F8064677 +:10094000C4F8B0030F98D4F8787201F0A3FCD4F87F +:10095000B8532978F9F7FCFD3844C4F878021098A8 +:10096000D4F87C7201F096FC2978F9F7F1FD38444F +:10097000C4F87C023046D4F8807201F08BFC6978B0 +:10098000F9F7E6FD1F4B049D1A6838442A441A60A3 +:10099000D4F88432C4F880020133C4F8843205E00C +:1009A000A5F82C33A5F82E33A5F830330F4F059E4C +:1009B000B7F8C432012EA7F8BC33B7F8C632A7F88F +:1009C000BE3321D1B7F9C223B7F9C83203EB4203D2 +:1009D000032293FBF2F39BB2A7F8C033A7F8C2330C +:1009E00016E000BF4C3D0F44D40400203801002025 +:1009F00004000020BD37863535FA8E3CD62700200E +:100A000000000020C4270020B7F8C832A7F8C03380 +:100A1000F4F7AEF8C14B01261860D7F8C833C7F811 +:100A2000C803C31AA7F8C433F1F784FFD7F8183105 +:100A3000BB4D13F4801387F8106100F08D80B5F87A +:100A40001C31180600F1D480B64B1B78590770D5BD +:100A500095F8CC23B44B12B195F8CD233AB10022CE +:100A6000C7F8D02301221A74002287F8CD231B7CFB +:100A7000D7F8B052032B95F80080A94E05F1040970 +:100A800087F8CC3306D1484606F575714C2201F043 +:100A900093F944E0012B07D106F5757049464C22C5 +:100AA00001F08AF9002302E0022B02D1012386F82B +:100AB0002034012384F8213484F822340023C4F83C +:100AC0002434C4F82834994A94F82034C4F82C9477 +:100AD00013441B7C964A1D4484F83134C4F8D02357 +:100AE000287984F83084FEF74FF89249FEF754F9DC +:100AF000C4F83404A87BFEF747F88F49FEF74CF999 +:100B0000C4F83804287EFEF73FF88C49FEF790F8C9 +:100B1000C4F83C04FEF778FA00232876AB73B7F8E4 +:100B20001C3143F08003A7F81C31012387F84034BF +:100B30005EE04FF00009D5F8D0034946FEF70CFA05 +:100B40008046002854D1FCF7C5F8774BC5F8D09300 +:100B500085F8CC831E744BE0B5F81C9119F0800F1A +:100B60003BD095F8CC23DFF8C0A1511E012924D831 +:100B70007149D5F83804FEF75BF8FEF745FAD5F869 +:100B80002C6495F831846E49B04488F80A00D5F891 +:100B90003C04FEF74DF8FEF737FA88F81400307879 +:100BA000FDF7F2FF0146FDF73BFFFEF72DFAB37AA2 +:100BB000B0703373337DB37506E0032A04D185F832 +:100BC000CC338AF8106004E09AF8103001338AF8C8 +:100BD000103029F08009A7F81C91524B1B785A0756 +:100BE00006D497F840341BB14D4B012283F8CD2336 +:100BF000D7F814914A4A19F0080F524D38D0B2F87C +:100C00002E1101F145039BB28A2B2DD8B2F81C316D +:100C10005B0729D5B2F8A803B2F8423497F84A61C5 +:100C2000C21A92B293B218B2B330BCBF02F5B47319 +:100C30009BB21AB2B32AC4BFA3F5B4739BB23607F2 +:100C400095F8EC00364A13D540B240424343D2F8FF +:100C5000B0021BB2007B43436FF01D0093FBF0F327 +:100C60001944A2F82E1103E0B7F8A833A7F84234CC +:100C700019F0140F00F09880B7F81C21284B02F4EB +:100C80000272002A00F0908093F84A2102F01002CC +:100C900002F0FF0052B1B3F82C1195F92701D3F8F7 +:100CA000382100FB0212A3F82C217DE0D3F8442464 +:100CB000D1789278002947D0B3F830E1B3F9281100 +:100CC0000FFA8EF6C1EB0608B8F1000FB8BFC8F1F5 +:100CD000000890450FDD8E42C8BF52421FFA8EFEBB +:100CE000C8BF92B2C3F834017244012083F84804AB +:100CF000A7F8302158E093F848242AB1D3F82421EA +:100D000083F84804C3F82021D7F83831D7F84C24A9 +:100D100019441388528899423FE000BFBC27002045 +:100D200038010020D62700200000002038440108A8 +:100D30000000A0410000204100007A445555553F75 +:100D40009A99993F2C200020B3F92801B3F930611A +:100D5000361A86EAE67EAEEBE67E96450ADD02228C +:100D600096FBF2F6A84A1660012283F8982283F8CF +:100D700048240AE093F848243AB1D3F8242183F8B0 +:100D80009812C3F8202183F84814D7F84C14D7F8E8 +:100D900038210B88024449889A4203DB8A42B4BF57 +:100DA00013460B46A7F83031D7F8B032974E93F878 +:100DB00064810493B8F1000F55D0B6F81C319B073D +:100DC00051D0D6F88403D6F888230146D6F88CB3E0 +:100DD000B6F830A10392FDF72BFF039A03461146A4 +:100DE00010460193FDF724FF019B01461846FDF7CD +:100DF00017FE5946034658460193FDF719FF019B1C +:100E000001461846FDF70CFE01F09AFC01465846D3 +:100E1000FDF7C2FF7E498346FEF7B2F8F8B958469F +:100E200001F0B4FAD6F85014FDF702FF01F032FADF +:100E3000B0F5617FA8BF4FF46170FDF7A5FE75495D +:100E4000FDF7AAFF01F064FA06464046FDF79CFE56 +:100E50003146FDF7EDFE01F01DFA80B200E0002002 +:100E60008244A7F830A119F0200F00F08B80B7F86A +:100E70001C31DFF898A103F03003002B00F08280D2 +:100E80009AF84A31D8077DD5BAF9A803FDF77CFE58 +:100E90006149FDF7CDFE064601F03AFA804630463C +:100EA00001F0C2F9DAF85434814693F803B0BAF984 +:100EB0005E045A4EBBF1000F34D0BAF85A24CBF17D +:100EC000000A93B212B2801A0193F9F7D9FC504587 +:100ED000019B03DB5845A8BF584600E05046B7F8D1 +:100EE00058140344B7F95C048AB209B29BB2401AA1 +:100EF000A7F85A3403920193F9F7C2FC5045039ABC +:100F0000019B03DB5845B4BF8246DA4692441FFA80 +:100F10008AFAA4F858A418B2FDF736FE83460FFAF1 +:100F20008AF004E0FDF730FE8346BAF95C04FDF771 +:100F30002BFE494682465846FDF77AFE4146034657 +:100F400050460193FDF774FE019B01461846FDF7DC +:100F500065FD3349FDF720FFFEF730F8414630804C +:100F60005846FDF765FE494680465046FDF760FE4F +:100F700001464046FDF754FD2949FDF70DFFFEF7F8 +:100F80001DF87080049E274B301DD3F800C0D7F8A1 +:100F9000601406F15403B5F8F620E047F5F7E2F8DF +:100FA000D7F86434002B60D0184B93F86834013BB9 +:100FB000142B55D8DFE803F00B54543C5754541FFE +:100FC00054545454544454545454543C4400D7F846 +:100FD0006C345B782BB1144B0020998BF9F7E7FC4C +:100FE00043E0124B1B7803F0040303F0FF00002BD7 +:100FF000F1D10146F2E70C4E0020318BF9F7D7FC16 +:101000000120718BEAE700BFCC27002038010020C7 +:101010008FC2753CEFB6B04435FA8E3CD227002023 +:10102000000020419800002000000020D62700206A +:10103000A44E0020718BF9F7BAFC0120B18BCDE7EB +:10104000A04E0020318BF9F7B2FC0120718BF9F72B +:10105000AEFC0220B18BF9F7AAFC0320F18BBDE7AF +:10106000AB68990601D5F4F787F8FCF7BBFC964B03 +:101070001B7823B9AB681A0301D5F5F795FB924BA2 +:101080001B78002B40F0C983DFF85092D9F8083064 +:101090005B0540F1C2838D4D95F87034002B00F054 +:1010A000BC83F9F76DFA002800F0B78395F8713426 +:1010B000002B00F0B283D5F874341B78002B40F07D +:1010C0001C82D5F87804F3F7CBFE002840F0158297 +:1010D000DFF80C82D5F87C24D8F800309A1A7C2AE4 +:1010E00040F20B82C5F87C3495F880340746013312 +:1010F00085F8803407F12400744EC0B2F3F7DAFFAC +:1011000006F55F7333F91700FDF73EFD6D4B824620 +:101110001888FDF739FD01465046FDF73DFE6C4944 +:10112000FDF786FDFDF74AFF013700B2F3F7EEFF4A +:10113000032FDFD13020F3F7BDFFB6F99002F3F7AC +:10114000E5FFF3F7C5FF96F880349F072FD1D6F857 +:101150007C3441F2883293421AD91020F3F7AAFF67 +:10116000D6F86C02642790FBF7F000B2F3F7CEFFDD +:101170002120F3F79FFFD6F86C3293FBF7F007FBC3 +:10118000103787EAE770A0EBE77000B2F3F7BEFF15 +:101190001420F3F78FFFB5F9A803F3F7B7FF1C206E +:1011A000F3F788FF0020F3F7B1FFF3F791FF95F80D +:1011B0008034464E580740F07A810220F3F77AFFD8 +:1011C000D6F884316422323393FBF2F000B2F3F7A5 +:1011D0009DFF0320F3F76EFF3E4B1B7813F0040FC7 +:1011E0004FF0050304D0B6F9300190FBF3F005E0B1 +:1011F000D6F884245289B2FBF3F000B2F3F786FFED +:10120000D9F80830990775D5334E94F88824337887 +:1012100040F63401B2FBF3F24A432A21B2FBF1F269 +:10122000B4F88A14062091FBF3F703FB17173F016C +:10123000BFB247EA0227BFB2C2F303221743F3F754 +:1012400039FF38B2F3F762FFB4F88A2433780132F9 +:1012500092B292FBF3F103FB1123A4F88A3494F8C1 +:1012600088346E265E43152396FBF3F63A204FF042 +:101270006409F3F71FFFB6FBF9F73846F3F746FFAB +:101280003B20F3F717FF09FB176080B20A270530F0 +:1012900090FBF7F000B2F3F739FF2820F3F70AFFCD +:1012A000D4F88C0490FBF7F000B2F3F72FFF042082 +:1012B000F3F700FFD4F884345B899BB1FAF7E8FBBD +:1012C00015E000BF00000020D027002038010020DA +:1012D00000007A44D6270020940000202C20002013 +:1012E00028200020A84BD3F8900480F3100000B20F +:1012F000F3F70CFFD5F81431A34E9A066BD596F888 +:101300004A319B071AD51120F3F7D4FEB6F894049E +:10131000FDF770F898A3D3E90023FDF7D1F8002278 +:101320009A4BFCF71BFFFDF7DDFA00B2F3F7EEFE78 +:101330001920F3F7BFFE0020F3F7E8FE95F84A31D5 +:10134000B5F8966413F0020F08BF00260120F3F7EA +:10135000B1FE30B2F3F7DAFE0920F3F7ABFE00205E +:10136000F3F7D4FE8A4B95F898641B88B3F5967F03 +:101370000BD9854A92F8802402F00F02072A04D87C +:1013800042F20F76B342B8BF1E460520F3F792FE35 +:10139000D5F89C345B7B0BB930B21AE0A6F1200083 +:1013A000FDF728F876A3D3E90023FDF7B3F9FDF79D +:1013B000E1FA00210646FDF7D9FD10B14FF03F419B +:1013C00001E04FF07C513046FDF72AFBFDF7F6FDBA +:1013D00000B2F3F79BFED5F814319F060ED46A4B8A +:1013E0000021D3F89C647068FDF7B6FD00285CD13D +:1013F000B0680021FDF7B0FD002856D195F84A21CC +:10140000614B960703D493F8A024012A07D1012346 +:10141000D5F8A474D5F8A86485F8A0340FE0D3F803 +:101420009C645C497068FDF703FCFDF7C7FD5949F2 +:101430000746B068FDF7FCFBFDF7C0FD06460FA9A7 +:101440003846F9F7C5F81320F3F734FEBDF93C0030 +:10145000F3F75CFE1B20F3F72DFEBDF93E00F3F71A +:1014600055FE2320F3F726FE002FACBF4E2053205D +:10147000F3F74CFE0FA93046F9F7AAF81220F3F75C +:1014800019FEBDF93C00F3F741FE1A20F3F712FEF6 +:10149000BDF93E00F3F73AFE2220F3F70BFE002ED3 +:1014A000ACBF45205720F3F731FEF3F711FE95F856 +:1014B0008034282B21D1344B0022D8F8006083F8E7 +:1014C00080244FF47A73B6FBF3F817203C26F3F729 +:1014D000F1FDB8FBF6F7B7FBF6F006FB1070000263 +:1014E00000B2F3F713FE1820F3F7E4FD06FB1780B4 +:1014F00000B2F3F70BFEF3F7EBFDD5F87434224E90 +:101500001B78012B40F02481F3F732FBD6F8AC3482 +:10151000214AC31A9342074640F2BC8096F88824B9 +:10152000002386F8CE2486F8C424D6F88C2486F8C6 +:10153000B23486F8B43486F8CF3486F8C5340A233A +:1015400092FBF3F286F8CC24121286F8CD24D6F85A +:10155000902492FBF3F386F8D03496F84A211B12BC +:1015600086F8D13496F89834950786F8F63415D471 +:101570002D2386F8F7348AE07B14AE47E17A843F66 +:10158000CDCCCCCCCCCCFC3F380100200000E03FDF +:101590009C0000208096184B3F0D0300042BD4F8CC +:1015A000A454C9488CBF33233223DFF840C386F8E4 +:1015B000F73495FBF0F60CFB06584FF0060E0EFBC9 +:1015C00008F8C24B06EB860698FBF3F903FB198873 +:1015D00006EB86064FFA89F9D4F8A81409EB8606BB +:1015E000B6B291FBF0F084F8E664360A84F8E7645A +:1015F0000CFB00160EFB06F6ED0F84F8E55496FB87 +:10160000F3F503FB1563642293FBF2F384F8ED34E6 +:101610001B12C90F84F8EE34B4F8943484F8EA1439 +:1016200024214B4398FBF2F893FBF2F2B4F808350F +:1016300084F8E324C2F3072284F8E42484F8EF3426 +:10164000B4F896241B0A84F8F0340A23B2FBF3F3AF +:1016500000EB800003F5FA739BB26DB200EB8000E3 +:1016600005EB800084F8F1341B0A80B284F8F23470 +:10167000B4F80A3584F8E88484F8EB044FEA2828A3 +:10168000000A84F8E98484F8EC0484F8F834904B78 +:10169000C3F8AC748E4D95F80C355BB9D5F81005D0 +:1016A000F3F7DEFB95F81D36002B40F04F83012841 +:1016B00000F25483D5F81825854C002A48D094F8B8 +:1016C0000C653EB1D4F81C3540F6B731FB1A8B429D +:1016D0000BD83DE00123D4F81005022184F80C3525 +:1016E000F3F7AAFB84F8206530E094F821355BB964 +:1016F000D4F810050121C4F8183584F80C35F3F737 +:101700009BFBF3F7B2FB21E0013BDBB284F8213510 +:1017100094F8201594F8220543B901304B1C84F845 +:10172000220584F82035D4F810050DE0134613F88F +:10173000012B0130114484F82205D4F8100584F8F7 +:101740002015C4F818351146F3F79CFBC5F81C7535 +:101750005F4CD4F8743425461B78022B1BD1D4F887 +:101760002435C3B1C4F828351B685A4AC4F82C354F +:10177000D4F830351344987CF7F78AFDD4F828352F +:101780009879F3F784FBD4F830350133092B88BFFF +:101790000023C4F83035F8F745FF00283DD094F811 +:1017A0003435013B012B38D8D5F83805F3F758FB11 +:1017B000474C494ED8B1D4F83805F3F74CFB94F8B0 +:1017C0003C2533687E2A0FD102221B2884F8342559 +:1017D000C4F8403505D00D2803D0342801D067283F +:1017E00002D1012385F8443585F83C05DCE73368F0 +:1017F000D4F8402541F658319A1A8A4203D9032376 +:1018000084F8343509E0D4F848259B1A042B04D910 +:1018100094F844350BB1F9F729FFDFF8D4B0DBF8C1 +:101820000830DC037DF5DDAF294C94F84C352546B6 +:10183000002B3DF4D6AF294B1B78002B7DF4D1AFA4 +:10184000F3F796F9D4F850350746C31ADB43DB0F9C +:101850000493D4F85435C31A6FEA030AD4F8583500 +:101860004FEADA7AC31A6FEA03084FEAD878B8F178 +:10187000000F06D1BAF1000F03D1049B002B3DF4F9 +:10188000B0AF4FF0000995F8E0355FFA89F69E4257 +:10189000DFF83CC05ED21249DCF85C35B200096862 +:1018A00013446244C2F860155988C80522D48B05D8 +:1018B0004DD50C4B1B785E0754BF064B0A4B1B687B +:1018C000C2F8603543E000BF8096980040420F00A8 +:1018D000380100203844010828200020CA270020B1 +:1018E0005C600108D627002044440108806967FF36 +:1018F0002C2000201946A54A30460193CDF808C097 +:10190000F7F795FADDF808C0019BBCF81C2112F02E +:10191000400F03D0304619469D4A16E0500703D5C4 +:10192000304619469B4A10E0110703D53046194648 +:10193000994A0AE0900703D530461946974A04E0D1 +:10194000D10704D5964A30461946F7F770FA09F1DF +:10195000010998E79E000023B3421FD0D5F85C250B +:1019600090491A445288520516D501F5AC62D058F8 +:101970000890B1F9E8057821A0F57A7048434FF452 +:101980007A7190FBF1F000F22B1040F2671190FB9E +:10199000F1FE01FB1E0199520433DDE7B8F1000F9F +:1019A0002CD007F5C333A033C4F8583594F8063665 +:1019B0007C4E1BBB86F80736DBF80830980705D548 +:1019C000F2F7CAFF10B1012386F80736D4F80836BB +:1019D000744E1B689B68984728B196F8073643F009 +:1019E000020386F80736704B1B7813F0050F05D1FC +:1019F00094F8073643F0040384F8073694F8072672 +:101A000022B9684B93F80636002B4ED094F8061690 +:101A100011F0010FA1F10C001AD1032906D8634B74 +:101A2000634E12F0040F18BF334600E05F4B0439D9 +:101A3000072904D85F4912F0010F18BF0B46C0B246 +:101A4000032810D85C4912F0020F18BF0B460AE0B9 +:101A5000C0B2032806D8554B584912F0020F18BFE0 +:101A60000B4600E0514B002095F8E015C6B2B1429C +:101A7000DFF830E10CD9DEF85C15B6003144498856 +:101A8000090603D519687644C6F860150130EBE7FE +:101A9000B8F1000F13D05AB194F80626414B013229 +:101AA000D2B2142A09D1002207E0B8F1000F06D003 +:101AB00094F80636002BEFD101E083F80626BAF140 +:101AC000000F23D0B4F92C31B4F92A213221002A95 +:101AD000B8BF5242002BB8BF5B4293FBF1F392FBBD +:101AE000F1F1DBB2C9B28B4238BF0B46344A0BB1BD +:101AF00092FBF3F23A44C4F8542594F80C26294B8F +:101B00000AB9012200E0002283F80C2694F80C2682 +:101B1000244B22B92B4AC3F81026002009E0234A9F +:101B2000F9E7D3F85C1594000E197688760607D489 +:101B3000013095F8E015C2B291421A4BF1D8B8E0E5 +:101B4000B3F92A61192E3FDD11F822E093F814C68B +:101B50000EF00F08E045D3F8106608DC93F815C6C0 +:101B6000BCEB1E1F03DC23443468C3F8604511F846 +:101B7000224095F816E604F00F0CF445094B4BDBB8 +:101B800093F815E6BEEB141F46DC40E05444010810 +:101B90005A44010860440108664401086C44010885 +:101BA0007244010838010020D62700205C6001083B +:101BB000384401083C4401084044010844440108F9 +:101BC000400D030078440108193625DA11F822E0A7 +:101BD00093F814C60EF00F08E045D3F8106608DC41 +:101BE00093F817C6BCEB1E1F03DB23443468C3F80D +:101BF000604511F8224095F816E604F00F0CF44504 +:101C00006A4B09DB93F817E6BEEB141F04DB34685C +:101C100003EB8203C3F86045B5F92C41634B192CE3 +:101C20001BDD11F822E093F814660EF00F0CB4459A +:101C3000D3F810460ADC93F815C6BCEB1E1F05DC72 +:101C4000D4F800E003EB8203C3F860E511F822301A +:101C500003F00F01B1421FDD6AE71934BFF668AF28 +:101C600011F822E093F816660EF00F0CB445D3F885 +:101C700010460ADB93F815C6BCEB1E1F05DCD4F832 +:101C800000E003EB8203C3F860E511F8223003F0B3 +:101C90000F01B142FFF64CAF95F81716B1EB131FC9 +:101CA000FFF646AF414B03EB82022368C2F8603572 +:101CB0003EE7049DE5B193F8192693F8181607F549 +:101CC00043478818013890FBF2F402FB140083F8B4 +:101CD0001B16013183F81A0691FBF2F002FB101279 +:101CE0005037D2B2C3F8507583F81C2683F81826F3 +:101CF000F3F7CEFEFDF775BDCB067EF55CAAD4F8F2 +:101D000018212A4B910207D4B3F81C2122F4007247 +:101D1000A3F81C21FEF74FBAB3F81C1101F40072AE +:101D200092B2002A7EF447AA41F40071A3F81C1174 +:101D3000D3F82411C3F83421C3F82011B3F83011BB +:101D4000C3F83821A3F82811FEF735BA00283FF46C +:101D5000B1ACD5F81005F3F77EF824E00228144C56 +:101D600003D0F3F782F8012304E094F8222022B193 +:101D7000C5F8147584F822309CE4D5F81435FB1AA4 +:101D8000B3F57A6FFFF496AC0123D5F8100584F80B +:101D90002230F3F760F80446D5F81005F3F75BF846 +:101DA000802C7FF487ACF9F747FA83E438010020F0 +:101DB00000000020AFF3008010B50023934203D051 +:101DC000CC5CC4540133F9E710BD0244034693428E +:101DD00002D003F8011BFAE7704700000D4B70B505 +:101DE0001D680022845C2B195B7803F00303012B30 +:101DF0008B5C08BF2034EE18767806F00306012EBF +:101E000008BF2033E41A02D10132002BEAD1204668 +:101E100070BD00BFC800002010B5044622461378EC +:101E20000134002BFAD1CC5CD4540133002CFAD10C +:101E300010BDC9B2024610F8013B1BB18B42F9D16B +:101E4000104670470029FBD018467047034613F828 +:101E5000012B002AFBD1181A013870470F4BF0B53F +:101E60001E680023934215D0C55C7419647804F091 +:101E70000304012CCC5C08BF203537197F7807F0AC +:101E80000307012F08BF20342D1B04D10133002C80 +:101E9000E8D100E000252846F0BD00BFC8000020C2 +:101EA00010B5034632B111F8014B013A03F8014B6A +:101EB000002CF7D11A44934203D0002103F8011BF0 +:101EC000F9E710BD30B503780BB1044604E00B7898 +:101ED000002B18BF002030BD22461078013438B1E5 +:101EE0000023C85C28B1D55C8542F5D10133F8E701 +:101EF00030BD104630BD00210A2200F001B92DE9A5 +:101F0000F04E82468B461F46144612B90020BDE8AB +:101F1000F08E002BFAD00026A642F7D2A5196D0844 +:101F200007FB05B950464946089B9847002802DB45 +:101F300003D06E1C25462C46EEE74846BDE8F08EE1 +:101F4000174B2DE9F0411D680646AC6D0F46FCB9F4 +:101F5000502000F0E3F8A8658460AB6D0460446035 +:101F60001C61DC60AB6D9C615C61AB6DDC629C6292 +:101F7000AB6D5C631C63AB6DDC639C63AB6D5C64DD +:101F80001C64AB6DDC649C64AB6D1C77AB6D5C62F8 +:101F900030463946AA6D0123BDE8F04100F002B891 +:101FA0002C010020F0B508B9106828B3044614F8D5 +:101FB000015B0F4617F8016B3EB1B542FAD10BB188 +:101FC0002046F3E714600370F0BD4DB91560284654 +:101FD000F0BD17F8016BAE4207D0002EF9D11C46B8 +:101FE000234613F8015B0F46F3E715B1002121707A +:101FF00000E02B461360F0BDF0BD000084463F4872 +:102000002DE9F04FD0F800800E46344614F8015BFD +:1020100008EB0500407800F0080000F0FF0708B169 +:102020002646F2E72D2D03D1B41C7578012703E075 +:102030002B2D04BF7578B41C33F010000DD1302D5A +:1020400008D1207800F0DF00582851D1657810239E +:10205000023402E0002B08BF0A23002F0CBF6FF0F0 +:10206000004A4FF0004ABAFBF3F903FB19AA002615 +:10207000304608EB050B9BF801B01BF0040F01D0B4 +:10208000303D0BE01BF0030B1BD0BBF1010F14BF65 +:102090004FF0570B4FF0370BCBEB05059D4210DA95 +:1020A000B6F1FF3F0AD0484506D801D1554503DCBB +:1020B00003FB0050012601E04FF0FF3614F8015BEE +:1020C000D7E7731C0CD1002F4FF022030CBF6FF029 +:1020D00000404FF00040CCF800302AB9BDE8F08F46 +:1020E00007B1404242B106B1611E1160BDE8F08FF8 +:1020F000002B08BF0823B0E7BDE8F08FC800002020 +:1021000030B51346044A05460C4610682946224657 +:10211000BDE83040FFF772BF2C010020024B0146A2 +:10212000186800F003B800BF2C01002070B5CD1C6A +:1021300025F0030508350C2D38BF0C25002D06466B +:102140003FDB8D423DD3214B1C6818462146A1B18F +:102150000B685B1B0ED40B2B03D90B60CC18CD5036 +:102160001FE08C4202D1626802601AE04B68636033 +:102170000C4616E00C464968E9E7154C23681BB984 +:10218000304600F027F820602946304600F022F85B +:10219000431C014615D0C41C24F0030484420AD118 +:1021A000256004F10B00231D20F00700C31A0BD09B +:1021B0005A42E25070BD3046611A00F00BF801300F +:1021C000EED10C233360002070BD00BFE827002053 +:1021D000E427002038B5064C002305460846236056 +:1021E00000F008F8431C02D1236803B12B6038BD0E +:1021F000F0270020094A136863B1184469468842F1 +:1022000002D8106018467047054B0C221A604FF038 +:10221000FF307047034B1360EFE700BFEC2700204F +:10222000F0270020F427002000B5194A20F00043D1 +:10223000934283B0014617DDB3F1FF4F04DBFCF797 +:10224000EDFB03B05DF804FB694601F03BF800F0DC +:102250000302012A0098019911D0022A0AD09AB1EA +:10226000012201F0F3FDECE7002101F0F3F903B0E6 +:102270005DF804FB01F0EEF900F10040E1E701F048 +:10228000E5FD00F10040DCE701F0E4F9D9E700BF2B +:10229000D80F493F30B5C0F3C754A4F17F031E2BBC +:1022A00083B0014620DC581C1BDB162B4FEAD1758E +:1022B00009DDC1F3160040F40000963CA04005B1D2 +:1022C000404203B030BD114B53F825402046FCF787 +:1022D000A7FB019001982146FCF7A0FB20F00043EA +:1022E00033B9002003B030BDFCF768FE03B030BD49 +:1022F000C0F31604C0F3C75044F40004C0F19600C4 +:1023000024FA00F0002DDCD0DAE700BF6C7A010877 +:1023100000B51D4A20F00043934283B0014618DD0A +:10232000B3F1FF4F04DBFCF779FB03B05DF804FB6E +:10233000694600F0C7FF00F00300012818D002280A +:102340000ED0D0B10098019901F084F900F100405D +:10235000EBE70021002201F079FD03B05DF804FBFA +:1023600000980199012201F071FD00F10040DCE7C5 +:102370000098019901F06EF9D7E7009801990122C0 +:1023800001F064FDD1E700BFD80F493F70B58AB0B6 +:10239000054600F023FA224C064694F9003001333A +:1023A00003D0284601F0C4FF10B930460AB070BD12 +:1023B000284601F06BFF4FF07E51FCF7F5FD002839 +:1023C000F3D0184901220023284600920893019176 +:1023D000FCF722F802460B461348CDE90423CDE969 +:1023E000022301F0ABFD94F90030CDE90601022B88 +:1023F0000BD0684601F0A0FD38B1089B53B9DDE968 +:102400000601FCF7B7FA0AB070BD02F00FF82123FD +:102410000360F2E702F00AF8089B0360EFE700BFF1 +:1024200030010020747A0108807A010800F03EBB78 +:102430002DE9F0418AB007460C4600F0C7FB9B4EE1 +:10244000054696F90030013303D0204601F070FFB5 +:1024500018B928460AB0BDE8F081384601F068FF97 +:102460008046002832D120460021FCF775FD002867 +:10247000EFD08F4A0123384601920093CDF8208097 +:10248000FBF7CAFFCDE902012046FBF7C5FF894BE8 +:1024900096F900400022CDE90623631CCDE9040132 +:1024A0000DD0022C0BD0684601F046FD002800F04C +:1024B0009A80089B1BB101F0B9FF089B0360DDE91E +:1024C0000601FCF757FA0AB0BDE8F0813846002152 +:1024D000FCF742FD18B320460021FCF73DFD804685 +:1024E000002855D0724901220023384600920893F3 +:1024F0000191FBF791FFCDE902012046FBF78CFF2C +:1025000096F9004000220023CDE90401CDE906231D +:10251000002CC8D0674B0022CDE90623CFE7284620 +:1025200001F0B8FE8046002862D028460021FCF762 +:1025300013FD00288DD0384601F0ACFE002888D06D +:10254000204601F0A7FE002883D059490422002329 +:102550003846009208930191FBF75EFFCDE9020136 +:102560002046FBF759FF96F9004000220023022C79 +:10257000CDE90401CDE9062300F08880684601F02A +:10258000DBFC002800F08280089B002B97D092E7AC +:10259000204601F07FFE00283FF45BAF204600217B +:1025A000FCF7E4FC00283FF454AF414A01233846CD +:1025B00001920093CDF82080FBF72EFFCDE90201B8 +:1025C0002046FBF729FF3478CDE904010022002CD6 +:1025D00030D0394B022CCDE906232ED101F026FF55 +:1025E00021230360D0E701F021FF2123036060E78E +:1025F000384601F04FFE002897D0204601F04AFEF1 +:10260000002892D0284601F093FE0346D8B9284905 +:1026100001223846089300920191FBF7FDFECDE9B7 +:1026200002012046FBF7F8FE3478CDE90401002CC6 +:1026300031D100220023CDE90623684601F07CFC5D +:102640000028A1D1CAE71A4A032338460093019211 +:10265000CDF82080FBF7E0FECDE902012046FBF734 +:10266000DBFE96F90030CDE90401384643BB134B3D +:102670004FF060420021CDE90623FCF777FC0028EB +:102680003FD196F90030022B7FF478AF01F0CEFEF7 +:102690002223036078E70020002102460B46FCF766 +:1026A00039F8022CCDE9060198D0C6E730010020A8 +:1026B0007C7A01080000F03F0000F0FFFFFFEF47C9 +:1026C0001C4B00220021CDE90623FCF74FFC00281B +:1026D000D7D020464FF07C51FCF7AAFAFBF79CFEBE +:1026E00004460D4601F030FC02460B4620462946C2 +:1026F000FCF7E6FF0028C4D10F4B0022CDE90623EA +:10270000BFE720464FF07C51FCF792FAFBF784FEBE +:1027100004460D4601F018FC02460B4620462946A9 +:10272000FCF7CEFF0028ACD1044B4FF06042CDE95E +:102730000623A6E70000F07F0000F0FFFFFFEFC7D1 +:1027400070B58AB0054600F031FF224C064694F978 +:102750000030013308D0284601F0EAFD20B12846B8 +:102760000021FCF703FC10B930460AB070BD1A49CD +:10277000012200232846019100920893FBF74CFEAA +:102780002478CDE90401CDE902017CB900220023BF +:10279000CDE90623684601F0CFFB88B1089BA3B9B9 +:1027A000DDE90601FCF7E6F80AB070BD0020002163 +:1027B00002460B46FBF7AEFF022CCDE90601E9D13C +:1027C00001F034FE21230360E8E701F02FFE089BAF +:1027D0000360E5E730010020847A0108F8B520F0B5 +:1027E0000043B3F17E5F044610D008DCB3F17C5F98 +:1027F00011DAB3F10C5F00F384809D48F8BD014607 +:10280000FCF70CF90146FCF7C7FAF8BD002840F3C5 +:10281000CD800020F8BD0028C0F2CA8001464FF0EC +:102820007E50FCF7FBF84FF07C51FCF701FA0446B0 +:1028300000F0BCFE8F4906462046FCF7F9F98E49A8 +:10284000FCF7EEF82146FCF7F3F98C49FCF7E6F8C3 +:102850002146FCF7EDF98A49FCF7E2F82146FCF73E +:10286000E7F98849FCF7DAF82146FCF7E1F98649EF +:10287000FCF7D6F82146FCF7DBF9844905462046EB +:10288000FCF7D6F98249FCF7C9F82146FCF7D0F9E4 +:102890008049FCF7C5F82146FCF7CAF97E49FCF7E8 +:1028A000BDF82146FCF7C4F94FF07E51FCF7B8F8AB +:1028B00001462846FCF770FA3146FCF7B9F926F4D0 +:1028C0007F6525F00F05074629462846FCF7B0F935 +:1028D00001462046FCF7A2F8294604463046FCF79C +:1028E0009FF801462046FCF757FA01463846FCF7A8 +:1028F00097F801462846FCF793F80146FCF790F854 +:10290000F8BD0146FCF794F95A490546FCF790F9E1 +:102910005949FCF785F82946FCF78AF95749FCF72D +:102920007DF82946FCF784F95549FCF779F82946E2 +:10293000FCF77EF95349FCF771F82946FCF778F962 +:102940005149FCF76DF82946FCF772F94F490646E4 +:102950002846FCF76DF94E49FCF760F82946FCF76C +:1029600067F94C49FCF75CF82946FCF761F94A49DC +:10297000FCF754F82946FCF75BF94FF07E51FCF761 +:102980004FF801463046FCF707FA01462046FCF7AF +:102990004FF901464148FCF741F801462046FCF753 +:1029A0003DF801463E48FCF739F8F8BD3D48F8BD12 +:1029B0004FF07E51FCF734F84FF07C51FCF738F9BA +:1029C0002C490446FCF734F92B49FCF729F8214639 +:1029D000FCF72EF92949FCF721F82146FCF728F9E4 +:1029E0002749FCF71DF82146FCF722F92549FCF799 +:1029F00015F82146FCF71CF92349FCF711F821468C +:102A0000FCF716F90646204600F0D0FD1F490546A2 +:102A10002046FCF70DF91E49FCF700F82146FCF7AB +:102A200007F91C49FBF7FCFF2146FCF701F91A499D +:102A3000FBF7F4FF2146FCF7FBF84FF07E51FBF764 +:102A4000EFFF01463046FCF7A7F92946FCF7F0F8FE +:102A50001249FBF7E3FF01462846FBF7E1FF014679 +:102A6000FBF7DEFF01461048FBF7D8FFF8BD00BFBB +:102A7000DB0FC93F08EF1138047F4F3A4611243D60 +:102A8000A80A4E3E90B0A63EABAA2A3E2EC69D3D59 +:102A90006133303F2D57014039D119406821A233AD +:102AA000DA0FC93FDB0F4940DA0F494021F00042FD +:102AB000B2F1FF4FF8B5044614DC20F00045B5F143 +:102AC000FF4F06460EDCB1F17E5F3AD08F1707F05C +:102AD000020747EAD07755B9022F2FD0032F2FD105 +:102AE0003148F8BD08462146FBF79AFFF8BDFAB118 +:102AF000B2F1FF4F29D0B5F1FF4F19D0AA1AD21564 +:102B00003C2A19DC002938DB2046FCF745F901F0A6 +:102B1000BDFB01F0A5FA012F2CD0022F22D0002FEF +:102B20002FD02249FBF77CFF2149FBF777FFF8BD47 +:102B3000002E15DB1F48F8BD1E48ECE71C48F8BD09 +:102B4000F8BDBDE8F84001F08BBAB5F1FF4F19D0E0 +:102B5000022FF3D0032FC3D0012F1BD00020F8BDCC +:102B60001548F8BD1149FBF75BFF01461048FBF71C +:102B700055FFF8BD00F10040F8BD3C32C4DA00203A +:102B8000C9E7F8BD022F0CD0032F08D0012F04D0C5 +:102B90000A48F8BD4FF00040F8BD0948F8BD0948A3 +:102BA000F8BD0948F8BD00BFDB0F49C02EBDBB33DF +:102BB000DB0F4940DB0FC93FDB0FC9BFDB0F493FCC +:102BC000DB0F49BFE4CB16C0E4CB16402DE9F04F34 +:102BD00031F0004987B00D460C46074611D020F071 +:102BE000004ABAF1FF4F804605DD514807B0BDE805 +:102BF000F04F01F0B7BBB9F1FF4F07DDBAF17E5FCF +:102C0000F3D14FF07E5007B0BDE8F08F002840DBD5 +:102C10000026B9F1FF4F34D0B9F17E5F4CD0B4F14A +:102C2000804F384655D0B4F17C5F1BD001F02EFBAD +:102C30000146BAF1000F1DD028F04043B3F17E5F8A +:102C400018D04FEAD87808F1FF3856EA080166D064 +:102C5000B9F19A4F74DD374B9A4533DC002C37DBE2 +:102C60000020D0E7B8F1000FE0DB07B0BDE8F04F7F +:102C700000F09CBC002C41DBB8F1000F32DB0846B1 +:102C8000C1E7BAF17E5FBCD027DD002CE8DB284627 +:102C9000B9E7B9F1974F13DAB9F17E5F0ADB4FEA72 +:102CA000E953C3F1960349FA03F202FA03F34B45E1 +:102CB00000F044820026AFE7002C25DB3846A2E76F +:102CC0000226A6E71C4B9A4540F39D82002CC7DDE7 +:102CD0001A480146FBF7ACFF95E7002CC0DA05F176 +:102CE000004090E7AAF17E5A56EA0A0A12D1084635 +:102CF000FBF794FE0146FCF74FF884E74FF07E5057 +:102D0000FCF74AF80146B7E739464FF07E50FCF72A +:102D100043F878E7012EB2D101F1004073E739465C +:102D20003846FBF77BFE0146FCF736F86BE700BF41 +:102D3000807A0108F7FF7F3F0700803FCAF24971A0 +:102D4000BAF5000F80F202824FF09741FBF770FF57 +:102D50006FF017028246B34B4FEAEA51CAF3160AE4 +:102D60007F399A4501EB020C4AF07E5740F3EB8124 +:102D7000AD4B9A4540F3428200220CF1010CA7F5BD +:102D8000000705920599A94B384653F82130CDF834 +:102D900004C0194603920493FBF740FE0499814650 +:102DA0003846FBF73DFE01464FF07E50FBF7F4FF3F +:102DB0000346194648460293FBF73AFF7910039AF7 +:102DC00041F00051BB4601F5802120F47F6727F0D8 +:102DD0000F070A448246114638460392FBF728FF44 +:102DE00001464846FBF71AFE039A814604991046AD +:102DF000FBF714FE01465846FBF710FE0146384625 +:102E0000FBF716FF01464846FBF708FE029B1946F2 +:102E1000FBF70EFF514683465046FBF709FF01467C +:102E20008146FBF705FF8249034648460293FBF7BC +:102E3000FFFE8049FBF7F4FD4946FBF7F9FE7E49AA +:102E4000FBF7EEFD4946FBF7F3FE7C49FBF7E8FD97 +:102E50004946FBF7EDFE7A49FBF7E2FD4946FBF7F1 +:102E6000E7FE7849FBF7DCFD029B01461846FBF7BD +:102E7000DFFE394681465046FBF7D2FD5946FBF747 +:102E8000D7FE4946FBF7CCFD394604903846FBF7A0 +:102E9000CFFE6D490390FBF7C3FD0499FBF7C0FD1E +:102EA00020F47F6929F00F0949463846FBF7C0FE38 +:102EB000494607465846FBF7BBFE634983464846EA +:102EC000FBF7ACFD039A1146FBF7A8FD01460498F9 +:102ED000FBF7A4FD5146FBF7ABFE01465846FBF756 +:102EE0009FFD834659463846FBF79AFD20F47F6ADA +:102EF0002AF00F0A50465549FBF79AFE544981467D +:102F00005046FBF795FE3946034650460293FBF7C1 +:102F100085FD01465846FBF781FD4E49FBF788FECB +:102F2000029B01461846FBF77BFD4B4B059A53F875 +:102F30002210FBF775FDDDF804C007466046FBF77D +:102F400023FE464B059A049053F822B03946484672 +:102F5000FBF766FD5946FBF763FD0499FBF760FD3F +:102F600020F47F6A2AF00F0A04995046FBF756FDB9 +:102F70005946FBF753FD4946FBF750FD01463846DD +:102F8000FBF74CFD24F47F6424F00F04013E56EA65 +:102F900008068146214628460CBF314F4FF07E5728 +:102FA000FBF73CFD5146FBF743FE494606462846E3 +:102FB000FBF73EFE01463046FBF732FD2146064652 +:102FC0005046FBF735FE054601463046FBF728FD27 +:102FD00000288146044620F00048AA4640F3F880C5 +:102FE000B8F1864F00F3C28000F0B280B8F17C5F88 +:102FF00000F3C4804FF00009C84624F47F6424F035 +:103000000F0420461749FBF713FE5146054620469C +:10301000FBF704FD01463046FBF700FD1249FBF7C4 +:1030200007FE23E071C41C00D6B35D009C7A010842 +:1030300042F1533E55326C3E05A38B3EABAAAA3EED +:10304000B76DDB3E9A99193F000040400038763F4B +:10305000A0C39D364F38763F947A01088C7A0108D8 +:10306000000080BF0072313F1872313F864906462A +:103070002046FBF7DDFD01463046FBF7D1FC064656 +:1030800031462846FBF7CCFC29460446FBF7C6FC34 +:1030900001463046FBF7C2FC214606462046FBF7B8 +:1030A000C7FD7A490546FBF7C3FD7949FBF7B6FC36 +:1030B0002946FBF7BDFD7749FBF7B2FC2946FBF734 +:1030C000B7FD7549FBF7AAFC2946FBF7B1FD73492B +:1030D000FBF7A6FC2946FBF7ABFD01462046FBF7B4 +:1030E0009DFC054629462046FBF7A2FD4FF0804196 +:1030F00082462846FBF792FC01465046FBF74CFE01 +:10310000314605462046FBF793FD3146FBF788FC28 +:1031100001462846FBF782FC2146FBF77FFC01466F +:103120004FF07E50FBF77AFC8144B9F5000FC0F2F6 +:10313000A58049463846FBF77BFD64E502F00102B5 +:10314000C2F1020668E5002205921BE6002202E6B3 +:1031500053493046FBF764FC294682464846FBF754 +:103160005DFC01465046FBF71FFF38B138464D491C +:10317000FBF75EFD4B49FBF75BFD44E54FEAE85882 +:10318000A8F17E084FF4000343FA08F32344C3F385 +:10319000C7524548C3F31608A2F17F0140FA01F176 +:1031A000C2F1960248F4000848FA02F8002C23EA1B +:1031B00001012846B8BFC8F10008FBF72FFC824682 +:1031C00051463046FBF72CFC4FEAC859044614E739 +:1031D000364B98450ADC7FF409AF2946FBF71EFC05 +:1031E00001463046FBF7CCFE0028C7D038463049B0 +:1031F000FBF71EFD2E49FBF71BFD04E501234FF4F1 +:1032000000120593BEE54FF07E51FBF707FC2949FC +:103210000746FBF70DFD284981463846FBF708FDB8 +:10322000394682463846FBF703FD4FF07A51834614 +:103230003846FBF7FDFC01462048FBF7EFFB39461B +:10324000FBF7F6FC01464FF07C50FBF7E7FB01462D +:103250005846FBF7EDFC1A49FBF7EAFC01465046DD +:10326000FBF7DCFB074639464846FBF7D9FB20F461 +:103270007F6A2AF00F0A494650467DE6414601F032 +:1032800075F8014656E700BF8CBEBF354CBB3133E5 +:103290000EEADD3555B38A38610B363BABAA2A3EC0 +:1032A0003CAA3833CAF24971FFFF7F000000164381 +:1032B0006042A20D00AAB83F70A5EC36ABAAAA3EA8 +:1032C0003BAAB83F2DE9F04FAB4A20F000449442AE +:1032D00089B006460D4664DDA84A94421CDC0028ED +:1032E000A74940F3EC80FBF799FBA64B24F00F04B1 +:1032F0009C42064664D0A449FBF790FB0146286037 +:103300003046FBF78BFBA049FBF788FB0123686085 +:10331000184609B0BDE8F08F9C4A944262DDB4F1D2 +:10332000FF4F46DAE715863FA4EBC7542046FBF76C +:1033300045FEFBF729FC0346014620460593FBF7B3 +:103340006DFB4FF08741FBF773FC8046FBF736FEC1 +:10335000FBF71AFC0146044640460694FBF75EFB69 +:103360004FF08741FBF764FC00210790FBF7F4FD69 +:10337000002800F0C58020460021FBF7EDFD002865 +:1033800014BF0123022382480221019000913A4692 +:1033900005A8294600F022FA002EC0F2A7800346B5 +:1033A00003E00022286000234A60184609B0BDE807 +:1033B000F08F0146FBF732FB002368602860F4E7DA +:1033C0007449FBF72BFB74490446FBF727FB0146C6 +:1033D00028602046FBF722FB6F49FBF71FFB012308 +:1033E0006860E2E700F052FF6C490746FBF720FCFB +:1033F0004FF07C51FBF714FBFBF7E0FD8246FBF737 +:10340000C3FB5F498346FBF713FC01463846FBF7D5 +:1034100005FB5D4980465846FBF70AFCBAF11F0FD1 +:1034200081464946404618DC5D4B0AF1FF3253F8AD +:10343000223024F0FF029A420FD0FBF7EFFA074642 +:103440002F6039464046FBF7E9FA4946FBF7E6FAB2 +:10345000002E686056DB5346A7E7FBF7DFFAE3155B +:10346000C0F3C7529A1A082A0746E9DD4949584667 +:103470000393FBF7DDFB074639464046FBF7CEFAE0 +:10348000044621464046FBF7C9FA3946FBF7C6FA1F +:10349000414907465846FBF7CBFB3946FBF7BEFAD6 +:1034A000814649462046FBF7B9FA039BC0F3C75251 +:1034B0009B1A192B074641DC2860A046C1E7FBF7A1 +:1034C000AFFA304B24F00F049C42064623D02E491D +:1034D000FBF7A6FA014628603046FBF79FFA2A4917 +:1034E000FBF79EFA4FF0FF3368605EE795E80C004B +:1034F00003F1004102F1004243422A60696054E74F +:10350000032340E707F1004700F100402F606860A7 +:10351000CAF1000349E71F49FBF782FA1E49044636 +:10352000FBF77EFA014628602046FBF777FA1A4936 +:10353000FBF776FA4FF0FF33686036E719495846D3 +:10354000FBF776FB074639462046FBF767FA8046CD +:1035500041462046FBF762FA3946FBF75FFA12490B +:1035600004465846FBF764FB2146FBF757FA8146B1 +:103570004946404661E700BFD80F493FE3CB1640BC +:10358000800FC93FD00FC93F43443537800F4943AF +:10359000247B01080044353708A3852E84F9223F97 +:1035A000A47A010800A3852E32318D2420F0004238 +:1035B000B2F1FF4FF8B5044603462DD25AB30028A6 +:1035C0003DDBB2F5000F4FEAE0502CD37F38C3F358 +:1035D0001603C20743F4000348BF5B0000274010F6 +:1035E0005B003E4619244FF08072B5189D4202DC04 +:1035F0005B1BAE181744013C4FEA43034FEA5202EB +:10360000F3D113B107F001031F447F1007F17C577A +:1036100007EBC050F8BDF8BD0146FBF709FB21469A +:10362000FBF7FEF9F8BD14F400020FD15B0019029C +:1036300002F10102FAD5C2F101021044C6E70146C7 +:10364000FBF7ECF90146FBF7A7FBF8BD012210449C +:10365000BCE700BF2DE9F84320F00046B6F1485F13 +:1036600005460F4649DAFBF7A9FC002800F09D80CB +:1036700029462846FBF7DCFA4E490446FBF7D8FA00 +:103680004D49FBF7CDF92146FBF7D2FA4B49FBF741 +:10369000C5F92146FBF7CCFA4949FBF7C1F92146A8 +:1036A000FBF7C6FA4749FBF7B9F92146FBF7C0FA21 +:1036B0004549FBF7B5F92146FBF7BAFA80462046A3 +:1036C0004FF07C51FBF7B4FA414606462046FBF723 +:1036D000AFFA394604462846FBF7AAFA01462046C7 +:1036E000FBF79CF901463046FBF798F901464FF08D +:1036F0007E50FBF793F9BDE8F8830146FBF798FA93 +:103700002C490446FBF794FA2B49FBF789F921462B +:10371000FBF78EFA2949FBF781F92146FBF788FA76 +:103720002749FBF77DF92146FBF782FA2549FBF78C +:1037300075F92146FBF77CFA2349FBF771F921461D +:10374000FBF776FA214B80469E42B8DD204B9E4225 +:1037500027DC06F17F4631464FF07E50FBF75EF9DD +:10376000814620464FF07C51FBF762FA3146FBF769 +:1037700055F9414606462046FBF75AFA39460446B3 +:103780002846FBF755FA01462046FBF747F9014664 +:103790003046FBF743F901464846FBF73FF9BDE8E1 +:1037A000F883DFF834900B4EDBE74FF07E50BDE836 +:1037B000F88300BF4ED747ADF6740F317CF29334D7 +:1037C000010DD037610BB63AABAA2A3D9999993EC3 +:1037D0000000483F0000903E0000383F2DE9F04FC8 +:1037E000DFB00B93013B0293D31E48BF131DB84CAF +:1037F00006466898DB1054F8204023EAE3730C93E4 +:10380000DB4302EBC30308940693089C029B0C9ACB +:103810001D190991C3EB02071DD4699C3D4404EBBB +:10382000870901354FF0000822AC0AE059F808007A +:10383000FBF7AAF90137AF4244F8080008F1040881 +:1038400009D0002FF2DA01370020AF4244F8080017 +:1038500008F10408F5D1089A002AC0F2DF82089A1C +:103860000B9B02F101089C0022AF4FEA8808274415 +:103870000025029A002AC0F2F28105EB070B4FF0F7 +:1038800000094FF0000A56F809005BF8041DFBF729 +:10389000CFF901465046FBF7C3F809F10409A145E9 +:1038A0008246F0D14AA840F805A004354545E0D14C +:1038B000089A0EAB03EB82030D9391464FEA8903FE +:1038C0000793079A5EAB1344B9F1000F53F850AC5D +:1038D00023DD0DF134084AAF174490440DAD4FF08D +:1038E0006E515046FBF7A4F9FBF768FBFBF74CF968 +:1038F0004FF087418346FBF79BF901465046FBF7A3 +:103900008DF8FBF75BFB594645F8040F57F8040D9B +:10391000FBF786F845458246E1D15046069900F00E +:1039200025FD4FF078510546FBF782F900F0BAFC0F +:103930004FF08241FBF77CF901462846FBF76EF811 +:103940000546FBF73BFB8246FBF71EF9014628467E +:10395000FBF764F8069A8046002A40F3678109F174 +:10396000FF310EA850F82130C2F1080043FA00F2EE +:1039700002FA00F01B1A06989244C0F1070743FAB6 +:1039800007F70EA840F82130002F32DDB9F1000F03 +:103990000AF1010A40F375810EAB079A19461144EA +:1039A000002507E0C2F5807012B143F8040C012530 +:1039B0008B420BD053F8042B002DF3D0C2F1FF0241 +:1039C0008B4243F8042C4FF00105F3D1069B002BEA +:1039D0000DDD012B00F03281022B08D109F1FF33FC +:1039E0000EA951F8232002F03F0241F82320022FB4 +:1039F00070D040460021FBF7AFFA002800F083802A +:103A0000089A09F1FF35AA420DDC079A0EAB0D9812 +:103A10001344002253F8041D834242EA0102F9D103 +:103A2000002A40F0E481089B0EA85A1E50F822306C +:103A3000002B40F0F18100EB8202012352F8041DBB +:103A400001330029FAD04B4499450A933DDADDF859 +:103A50002CA022AACA44DDF8308002EB8A02C844B6 +:103A6000C9EB0309131D03920593699A079B4FEA5B +:103A700089094AAF02EB8808CDF810901F44002551 +:103A800058F8040FFBF780F8029B039A002B505163 +:103A90004FF0000B13DBDDF814A04FF00009AA442F +:103AA00056F809005AF8041DFBF7C2F801465846BB +:103AB000FAF7B6FF09F10409A1458346F0D1049A4B +:103AC0000435954247F804BFDAD1DDF82890F5E6D1 +:103AD0003C7E010841464FF07E50FAF79FFF80463A +:103AE000002D86D006994FF07E5000F03FFC014635 +:103AF0004046FAF793FF804640460021FBF72CFA38 +:103B000000287FF47DAF069B40465942CDF808A0BF +:103B100000F02CFC4FF087410446FBF73BFA0028ED +:103B200000F07F814FF06E512046FBF781F8FBF7E4 +:103B300045FAFBF729F84FF087410546FBF778F87F +:103B400001462046FAF76AFFFBF738FA0EAB43F856 +:103B500029002846FBF732FA069C09F101050834D2 +:103B60000EA9069441F8250006994FF07E5000F00A +:103B7000FDFB002D04464FDB6E1C4FEA8508C6EBAB +:103B8000867A0DF138094AABC1444FEA8A0A984453 +:103B90004FF0000B59F80B00FAF7F6FF2146FBF740 +:103BA00047F84FF06E5148F80B002046FBF740F8FD +:103BB000ABF1040BD3450446ECD1DFF88C92DDF871 +:103BC00020A00024B34603950497BAF1000FB8BFB4 +:103BD000002515DB00263746002501E0A7420FDC53 +:103BE00058F8061059F80600FBF722F80146284657 +:103BF000FAF716FF0137BA45054606F10406EDDA75 +:103C00005EA800EB84030134A345A8F1040843F83F +:103C1000A05CDAD1039D049F689C032C00F298807D +:103C2000DFE814F0CB009C009C00310010D109F1BA +:103C3000FF330EA951F823703F12A5E609F1FF33B7 +:103C40000EA850F8232002F07F0240F82320CEE691 +:103C50004FF07C51FBF79EF958B90746C9E64FF083 +:103C6000000A4AA840F805A0043545457FF401AE96 +:103C70001EE6B9F1000F4FF002070AF1010A3FF703 +:103C80008BAE0025A2E6002D40F3DC804FEA850BC9 +:103C90005EAB36AE05F1FF3A5B4406EB8A0A53F899 +:103CA000A08C54465B4635AABB462F4600E0C8466A +:103CB00054F804594146284601920093FAF7B0FEA1 +:103CC000814649462846FAF7A9FE4146FAF7A8FE7A +:103CD000019AC4F804909442A060009BE7D13D464D +:103CE000012D5F469B4640F3AD805EAB9B445BF885 +:103CF000A04C00E044465AF8049921464846FAF799 +:103D00008FFE804641464846FAF788FE2146FAF77C +:103D100087FE5645CAF80480CAF80800EAD16C1C30 +:103D200006EB84040020083654F8041DFAF778FEE8 +:103D3000B442F9D1002F7ED0369A379B099C00F10E +:103D4000004002F1004203F10043A0602260636082 +:103D5000029A02F007005FB0BDE8F08F002DB8BFF7 +:103D600000200ADB36AE6C1C002006EB840454F8FD +:103D7000041DFAF755FEB442F9D1002F35D000F1F9 +:103D80000043099C014623603698FAF747FE002D50 +:103D900008DD36AC04EB850554F8041FFAF740FE45 +:103DA000AC42F9D10FB100F10040099A5060029A7B +:103DB00002F007005FB0BDE8F08F002D39DB6C1C0E +:103DC00036AE002006EB840454F8041DFAF728FEF2 +:103DD000B442F9D10FB100F10040099A1060029A83 +:103DE00002F007005FB0BDE8F08F0346C9E7069A0E +:103DF0000EAC54F82530083ACDF808A00692002BF6 +:103E00007FF4B2AE04EB850353F8041D013D083A7C +:103E10000029F9D00692A7E6012314E60B9B9C002B +:103E200046E52046FBF7CAF80EAA4D4642F829009F +:103E30009AE60020CEE7099C369A379BA060226064 +:103E4000636085E7002075E7487E01082DE9F843A7 +:103E500020F00043B3F1485F04460F46904603DA72 +:103E6000FBF7ACF8002857D021462046FAF7E0FED1 +:103E700021460546FAF7DCFE294906462846FAF7A8 +:103E8000D7FE2849FAF7CAFD2946FAF7D1FE264996 +:103E9000FAF7C6FD2946FAF7CBFE2449FAF7BEFD2C +:103EA0002946FAF7C5FE2249FAF7BAFD8146B8F16C +:103EB000000F22D038464FF07C51FAF7B9FE494640 +:103EC00080463046FAF7B4FE01464046FAF7A6FDB2 +:103ED0002946FAF7ADFE3946FAF7A0FD1549054621 +:103EE0003046FAF7A5FE01462846FAF799FD014645 +:103EF0002046FAF793FDBDE8F88349462846FAF7CD +:103F000097FE0C49FAF78AFD3146FAF791FE2146F1 +:103F1000FAF786FDBDE8F8832046BDE8F88300BFC8 +:103F2000D3C92E2F342FD7321BEF3836010D50391D +:103F30008988083CABAA2A3E00207047002001492E +:103F4000704700BF0000F87F2DE9F043C1F30A5C21 +:103F5000ACF2FF37132F83B002460B460D4689465D +:103F600080464FEAD17630DC002F4CDB3A493941AC +:103F700001EA030010432DD0490801EA030858EA7A +:103F800002080CD04FF480233B41132F25EA010196 +:103F900041EA030914BF4FF000084FF000482F49D1 +:103FA0004B4601EBC606D6E9004542462046294667 +:103FB000FAF7D4F8CDE90001DDE9000122462B46ED +:103FC000FAF7CAF803B0BDE8F083332F07DDB7F581 +:103FD000806F3ED01046194603B0BDE8F083ACF2C6 +:103FE000134C4FF0FF3121FA0CF10142F2D0490895 +:103FF0000142D4D04FF0804848FA0CFC20EA01017D +:1040000041EA0C08CBE721F000410143E2D0C3F3C1 +:10401000130101434C420C431048590C240B490432 +:1040200004F4002444EA010300EBC601D1E9004591 +:1040300020462946FAF792F8CDE90001DDE90001B2 +:104040002B462246FAF788F821F0004343EAC6716E +:10405000C2E7FAF783F8BFE7FFFF0F00787E010899 +:104060002DE9F04120F00045B5F1A14F0446064688 +:1040700008DBB5F1FF4F6FDC002840F3A0806F48EC +:10408000BDE8F0816E4B9D4277DCB5F1445F68DBA3 +:104090004FF0FF3721462046FAF7CAFD0146804619 +:1040A000FAF7C6FD67490546FAF7C2FD6649FAF711 +:1040B000B7FC2946FAF7BCFD6449FAF7B1FC29467A +:1040C000FAF7B6FD6249FAF7ABFC2946FAF7B0FDFC +:1040D0006049FAF7A5FC2946FAF7AAFD5E49FAF706 +:1040E0009FFC4146FAF7A4FD5C4980462846FAF752 +:1040F0009FFD5B49FAF792FC2946FAF799FD594969 +:10410000FAF78CFC2946FAF793FD5749FAF786FC33 +:104110002946FAF78DFD5549FAF780FC2946FAF74A +:1041200087FD7B1C014640464CD0FAF779FC2146BE +:10413000FAF77EFD4E4B4F4D53F82710FAF76EFC01 +:104140002146FAF76BFC014655F82700FAF766FCA2 +:10415000002E30DBBDE8F0810146FAF761FCBDE8D6 +:10416000F0814549FAF75CFC4FF07E51FAF71CFFED +:1041700000288DD02046BDE8F08100F087F83F4B45 +:1041800004469D4229DCA3F5D0039D4244DC014650 +:10419000FAF746FC4FF07E51FAF740FC4FF08041B1 +:1041A00005462046FAF73CFC01462846FAF7F4FD9E +:1041B000002704466EE700F10040BDE8F08130487A +:1041C000BDE8F081FAF72CFC2146FAF731FD0146F3 +:1041D0002046FAF723FCBDE8F0812A4B9D4214DC0F +:1041E0004FF07F51FAF71AFC4FF07F5105462046F9 +:1041F000FAF71EFD4FF07E51FAF712FC01462846F1 +:10420000FAF7CAFD0227044644E701461E48FAF7BA +:10421000C3FD032704463DE74FF07E51FAF7FEFB4E +:104220004FF07E5105462046FAF7FAFB0146284634 +:10423000FAF7B2FD012704462CE700BFDB0FC93FA8 +:10424000FFFFDF3ED769853C59DA4B3D356B883D32 +:104250006E2EBA3D2549123EABAAAA3E21A215BD3B +:104260006BF16E3D95879D3D388EE33DCDCC4C3E48 +:10427000887E0108987E0108CAF24971FFFF973FC6 +:10428000DB0FC9BFFFFF1B40000080BF20F00040D4 +:10429000704700BF20F00040B0F1FF4FACBF0020DE +:1042A000012070472DE9F04120F00047FD0D7F3DD2 +:1042B000162D064613DC002D80461BDB194F2F41BF +:1042C000074214D01849FAF7ABFB0021FAF76CFE4D +:1042D00068B1002E1BDB28EA0700BDE8F081B7F1CA +:1042E000FF4F04D30146FAF79BFBBDE8F08130464F +:1042F000BDE8F0810C49FAF793FB0021FAF754FE70 +:104300000028F4D0002E08DB0020BDE8F0814FF437 +:10431000000343FA05F5A844DDE7002FE7D0034882 +:10432000BDE8F081FFFF7F00CAF24971000080BF45 +:1043300030F0004001D102207047A0F50003B3F136 +:10434000FE4F01D204207047054B421E9A4201D80D +:1043500003207047B0F1FF4358425841704700BFF7 +:10436000FEFF7F00004870470000C07F38B530F086 +:104370000044024603460D4614D0B4F1FF4F0DD25F +:10438000B4F5000F0FD3E40D2C44FE2C2EDC002CD2 +:104390001DDD23F0FF4343EAC45038BD0146FAF760 +:1043A0003FFB38BD38BD4FF09841FAF741FC194B3F +:1043B00002469D4207DBC0F3C7540346193CE3E7BE +:1043C000154800F02DF81449FAF732FC38BD14F105 +:1043D000160F13DA4CF250339D421146F0DD0F48B0 +:1043E00000F01EF80D49FAF723FC38BD11460B48C2 +:1043F00000F016F80949FAF71BFC38BD04F1190062 +:1044000023F0FF4343EAC0504FF04C51FAF710FC41 +:1044100038BD00BFB03CFFFF6042A20DCAF2497137 +:1044200001F0004120F0004008437047014B18683C +:10443000704700BF2C010020780000FF000000FF43 +:104440003C0000FFF00000FF0001746564666D6AC7 +:1044500069736C67010B020D0A03050B030D0A0358 +:10446000070B030D0A03090B020D0A030A0B040DC7 +:104470000A03080B040D0A031E0000FF4A0100FF97 +:104480002C0100FF0E0100FFD20000FFB40000FF6E +:10449000960000FF5A0000FF0000FFFF5C6001086B +:1044A000984401083C44010878440108404401084C +:1044B0009444010838440108904401088C440108E0 +:1044C00088440108444401088444010880440108E8 +:1044D0007C4401080800000000200000000C01409E +:1044E000100000000020000000100140000C0140FE +:1044F00008001002000C014010001002000C0140E6 +:10450000040014020000000000000000030100008D +:10451000084B010804000000C84A0108040000001C +:10452000884A010802010000684A010800010000F1 +:104530000000000006000000084A01080600000014 +:10454000A84901080101000000000000040000006B +:104550006849010806000000084901080800000039 +:104560008848010808000000084801080800000009 +:104570008847010801010000000000000001000060 +:104580000000000000010000000000000400000026 +:104590004847010806000000E84601080001000045 +:1045A0000000000002010000C846010801010000EF +:1045B000000000000000000000000000AA46010802 +:1045C00092460108744601085C460108A59E000851 +:1045D000619E00083D9E0008159E0008059E00088B +:1045E00055E00008919E0008B59D0008859E0008D2 +:1045F000779E00080000000000C201004061010831 +:10460000636101080100000000E100007861010819 +:104610009A6101080200000000960000AE610108E6 +:10462000D061010803000000004B0000E4610108B4 +:104630000662010804000000802500000D690108E1 +:104640000D690108000100020002000009170000C6 +:104650000100020002000000010700000001080341 +:1046600009030A040B040C040D04040405040604E5 +:104670000704FFFF00020102020203020402050216 +:1046800006020702080309030A040B040C040D04C4 +:10469000FFFF0001080309030A030B030C030D03CA +:1046A0000403050306030703FFFF000201020202E1 +:1046B00003020402050206020702080309030A03B3 +:1046C0000B030C030D03FFFF0000803F0000000000 +:1046D00000000000000080BF0000803F00000000DC +:1046E000000000000000803F0000803F000080BF0D +:1046F0000000803F000080BF0000803F000080BFBE +:10470000000080BF0000803F0000803F0000803F2D +:104710000000803F0000803F0000803F0000803F9D +:10472000000080BF000080BF0000803F000000004C +:1047300000000000000000000000803F00000000BA +:1047400000000000000000000000803F00000000AA +:104750000000803F0000803F0000803F000080BFDD +:10476000000080BF000000000000803F000000004B +:104770000000803F000080BF0000803F0000803FBD +:10478000000080BF000000800000803F0000803FEC +:10479000000000BF0000803F0000803F000000BF1D +:1047A000000080BF0000803F0000803F000080BF0D +:1047B0000000003F0000803F0000803F0000003FFD +:1047C0000000803F0000803F0000803F0000003F6D +:1047D000000080BF000080BF0000803F000080BF5D +:1047E000000000BF000080BF0000803F000000BF4D +:1047F0000000803F000080BF0000803F0000803F3D +:104800000000003F000080BF0000803FF704353FFC +:10481000F70435BF0000803F0000803FF70435BF3C +:10482000F70435BF0000803F0000803FF70435BF2C +:10483000F704353F0000803F0000803FF704353F1C +:10484000F704353F0000803F0000803F000000007B +:10485000000080BF000080BF0000803F000080BFDC +:1048600000000000000080BF0000803F000000004A +:104870000000803F000080BF0000803F0000803FBC +:1048800000000000000080BF0000803F000080BFEB +:104890000000803F000080BF0000803F000080BF1C +:1048A000000080BF0000803F0000803F0000803F8C +:1048B0000000803F0000803F0000803F0000803FFC +:1048C000000080BF000080BF0000803F000080BF6C +:1048D0000000803F0000803F0000803F000080BF5C +:1048E000000080BF000080BF0000803F0000803FCC +:1048F0000000803F000080BF0000803F0000803F3C +:10490000000080BF0000803F0000803F000000BF2B +:10491000D0B35D3F0000803F0000803F000000BF3B +:10492000D0B35DBF0000803F0000803F0000003F2B +:10493000D0B35D3F000080BF0000803F0000003F1B +:10494000D0B35DBF000080BF0000803F000080BF8B +:1049500000000000000080BF0000803F0000803F9A +:10496000000000000000803F0000803F00000000C9 +:104970000000803F000080BF0000803F000080BF3B +:10498000000080BF000000000000803F0000000029 +:104990000000803F0000803F0000803F0000803F1B +:1049A000000080BF000000000000803FD0B35DBF6A +:1049B0000000003F0000803F0000803FD0B35DBF9B +:1049C000000000BF000080BF0000803FD0B35D3F0B +:1049D0000000003F0000803F0000803FD0B35D3FFB +:1049E000000000BF000080BF0000803F000000000A +:1049F000000080BF0000803F0000803F00000000FA +:104A00000000803F000080BF0000803F00000000E9 +:104A1000A8AAAA3F0000803F0000803F000080BF9E +:104A2000B0AA2ABF000080BF0000803F0000803F86 +:104A3000B0AA2ABF000080BF0000803F0000000035 +:104A4000A8AAAA3F000080BF0000803F000080BFEE +:104A5000B0AA2ABF0000803F0000803F0000803FD6 +:104A6000B0AA2ABF0000803F0000803F0000803FC6 +:104A700000000000000000000000803F000080BF38 +:104A800000000000000000000000803F000080BF28 +:104A90000000803F000080BF0000803F000080BF1A +:104AA000000080BF0000803F0000803F0000803F8A +:104AB0000000803F0000803F0000803F0000803FFA +:104AC000000080BF000080BF0000803F00000000A9 +:104AD0000000803F000080BF0000803F000080BFDA +:104AE000000000000000803F0000803F0000803F89 +:104AF000000000000000803F0000803F0000000038 +:104B0000000080BF000080BF0000803F0000000068 +:104B1000A8AAAA3F000000000000803F000080BF5C +:104B2000B0AA2ABF000000000000803F0000803FC4 +:104B3000B0AA2ABF00000000100000000020000002 +:104B4000001001400040000000100140010001027F +:104B50000001030001040001050001060001070037 +:104B6000010800010900010A00010B00010C01030A +:104B7000000000001A6201080000000001000000AF +:104B80001F62010801000000020000002662010807 +:104B900002000000030000002F6201080300000073 +:104BA0000400000035620108050000000500000057 +:104BB0003A62010806000000060000004462010895 +:104BC00007000000070000004D6201080800000017 +:104BD00008000000566201080900000009000000FA +:104BE0005F6201080A0000000A0000006962010813 +:104BF0000B0000000B000000736201080C000000B5 +:104C00000C0000007D6201080D0000000D00000096 +:104C1000856201080E0000000E0000008D62010890 +:104C20000F0000000F000000956201081000000056 +:104C3000100000009E620108110000001100000039 +:104C4000A56201081200000012000000AF62010816 +:104C50001300000013000000B762010814000000F8 +:104C600014000000C26201081500000015000000D9 +:104C7000CC620108160000001600000000000000D1 +:104C8000FF000000B56206010300F00500FF19B542 +:104C90006206010300F00300FD15B5620601030082 +:104CA000F00100FB11B56206010300F00000FA0FED +:104CB000B56206010300F00200FC13B562060103B1 +:104CC00000F00400FE17B562060103000102010EA8 +:104CD00047B562060103000103010F49B5620601F1 +:104CE0000300010601124FB5620601030001120123 +:104CF0001E67B56206080600C80001000100DE6AF2 +:104D000000B562061608000307030000000000312A +:104D1000E501B5620616080003070300510800000C +:104D20008A4102B562061608000307030004E00486 +:104D300000199D03B5620616080003070300000270 +:104D4000020035EF04B56206160800030703008071 +:104D5000010000B2E80040008000000100020004F1 +:104D600049574641540102040810204E45535755F7 +:104D7000442C3A3A00000000482050726F6475637A +:104D8000743A426C61636B626F7820666C69676825 +:104D9000742064617461207265636F72646572204F +:104DA0006279204E6963686F6C6173205368657225 +:104DB0006C6F636B0A4820426C61636B626F782092 +:104DC00076657273696F6E3A310A48204461746186 +:104DD0002076657273696F6E3A310A009665010834 +:104DE000D06601081B67010869670108B6670108FA +:104DF000046801088B6501084F6801080263010817 +:104E00004F680108946501084F6801084820466909 +:104E1000656C642047206E616D653A4750535F6E44 +:104E2000756D5361742C4750535F636F6F72645B91 +:104E3000305D2C4750535F636F6F72645B315D2C44 +:104E40004750535F616C7469747564652C475053A7 +:104E50005F73706565640A48204669656C64204725 +:104E6000207369676E65643A302C312C312C302CFC +:104E7000300A48204669656C64204720707265647A +:104E80006963746F723A302C372C372C302C300A0F +:104E900048204669656C64204720656E636F6469CD +:104EA0006E673A312C302C302C312C310A48204698 +:104EB00069656C642048206E616D653A4750535FA8 +:104EC000686F6D655B305D2C4750535F686F6D6533 +:104ED0005B315D0A48204669656C6420482073692F +:104EE000676E65643A312C310A48204669656C6406 +:104EF000204820707265646963746F723A302C3098 +:104F00000A48204669656C64204820656E636F64BA +:104F1000696E673A302C300A000002020308050A65 +:104F20000B080A0A0B0C0E0E0F0000000054004084 +:104F3000000C0140400080001F2000000000200005 +:104F400000580040000C014000040008212200002D +:104F500000004000000000000000004F00000007BB +:104F6000000700147F147F14242A7F2A12231308B9 +:104F7000646236495522500005030000001C22419E +:104F8000000041221C0014083E081408083E0808CE +:104F90000050300000080808080800606000002089 +:104FA000100804023E5149453E00427F40004261E4 +:104FB0005149462141454B311814127F1027454570 +:104FC00045393C4A49493001710905033649494987 +:104FD00036064949291E00363600000056360000C4 +:104FE000081422410014141414140041221408025D +:104FF00001510906324979413E7E1111117E7F49E6 +:105000004949363E414141227F4141221C7F494965 +:1050100049417F090909013E4149497A7F08080849 +:105020007F00417F41002040413F017F0814224121 +:105030007F404040407F020C027F7F0408107F3E8B +:105040004141413E7F090909063E4151215E7F09E8 +:10505000192946464949493101017F01013F404034 +:10506000403F1F2040201F3F4038403F631408143A +:105070006307087008076151494543007F414100BB +:1050800002040810200041417F0004020102044094 +:1050900040404040010204000020545454787F48AE +:1050A0004444383844444420384444487F385454B5 +:1050B0005418087E090102064949493F7F08040443 +:1050C0007800447D40002040443D007F102844008B +:1050D00000417F40007C0418047C7C08040478387C +:1050E000444444387C14141408081414187C7C08B4 +:1050F0000404084854545420043F4440203C404099 +:10510000207C1C2040201C3C4030403C442810287F +:10511000440C5050503C4464544C44000836410008 +:1051200000007F0000004136080002010204023E38 +:1051300055554122000000000000007900001824AD +:10514000742E24487E4942405D2222225D15167C41 +:10515000161500007700000A55555528000100017A +:1051600000000A0D0A0408142A1422040404041C72 +:1051700000080808000101010101000205020044C5 +:10518000445F444400000402017E2020103E060FCC +:105190007F007F00181800000040502000000A0D1A +:1051A0000A0022142A14081708342A7D1708046AF2 +:1051B00059304845402042004200427E42004200B1 +:1051C0007E7E0042007E7E7E42007E7E7E7E007E6F +:1051D0007E7E7E7E00011E1E646464646464220020 +:1051E000460221008201200043021000010100005C +:1051F00049020100880102004C02120084011100E2 +:105200009001110090011100A0011100A001000007 +:10521000524F4C4C3B50495443483B5941573B41FA +:105220004C543B506F733B506F73523B4E61765200 +:105230003B4C4556454C3B4D41473B56454C3B004E +:1052400004630108FB620108EF6201081F9F000868 +:105250003D9F0008599F00082DAF0008859F00085A +:10526000919F0008020000008025000000C201009C +:1052700000000000200000008025000000C20100A6 +:1052800001000000400000008025000000C2010075 +:1052900000000000010000008025000000C20100A5 +:1052A00000000000100000008025000000C2010086 +:1052B000000300000400000080250000004B0000F7 +:1052C000000000000800000000E1000000E1000014 +:1052D000000400008000000000C2010000C20100C4 +:1052E00000000000E36A0108E86A0108EC6A0108AE +:1052F000FF6A0108F16A0108F76A0108FB6A010800 +:10530000000000000D6901089F6A0108A76A0108F2 +:10531000AF6A0108B76A0108BE6A0108C96A0108D4 +:10532000D16A0108D96A0108DE6A0108000000009C +:105330009001C800C800C800C800C800C800C80064 +:10534000C80064000000C800C800C800C8003200DF +:1053500019AC0008ED9E0008BB9E0008518D0008A6 +:10536000099F00084D8D0008FC6D0108006E0108C2 +:10537000066E01080C6E01080F6E0108166E01081A +:10538000196E01081E6E01082A6E01082D6E0108B3 +:10539000336E01083A6E0108446E01084E6E010832 +:1053A000576E0108656E0108716E0108786E01087C +:1053B0007E6E01088B6E0108966E0108A36E0108CF +:1053C000000000004A6D0108516D0108566D01088A +:1053D000676D0108716D01087C6D0108876D01081A +:1053E000F76A0108926D0108F16A01089B6D0108D6 +:1053F000A56D0108B36D0108B66D0108C66D010801 +:10540000CD6D0108D66D0108E06D0108E86D010859 +:10541000F36D010800000000E56E0108EE6E010862 +:10542000D9B30008126F0108166F01080DB5000806 +:105430002C6F0108316F01081D570008456F0108E6 +:105440004B6F0108FDBE0008246901085C6F01086C +:105450009D890008796F01087E6F0108BDC80008AA +:10546000AD6F01080D690108A97C0008B26F010841 +:10547000BA6F01089D910008CE6F0108D26F010834 +:1054800025550008E56F0108F46F0108EDCC000810 +:105490000E7001080D6901082D54000813700108F1 +:1054A00017700108315F0008267001082A70010892 +:1054B000AD5900083F6F010846700108C1BD0008E2 +:1054C000597001085F7001085DBE00081B77010874 +:1054D0007A70010871C80008897001087A700108A3 +:1054E00081830008957001089A700108D57C000836 +:1054F000D7630108AA70010885550008D870010813 +:10550000CC70010881B20008E17401080D6901083E +:10551000FD53000805040203000000008025000080 +:1055200000C201000600000001000000802500000C +:1055300000C20100070000000300000080250000F9 +:10554000004B00000900000004000000802500005E +:10555000004B000009000000EB710108440000004E +:10556000382000200000000028230000F47101080A +:10557000410000003A20002000000000010000006F +:10558000027201084400000046210020B00400001F +:10559000A406000009720108440000004821002010 +:1055A00000000000D0070000137201084400000052 +:1055B0004A21002000000000D00700001D720108F1 +:1055C000420000004C2100200000000012000000FA +:1055D0002A720108420000004D2100200100000055 +:1055E000FF00000035720108420000004E2100203B +:1055F00000000000010000004A72010844000000A1 +:10560000FC20002000000000D007000057720108B5 +:1056100044000000FE20002000000000D007000031 +:105620006472010844000000002100200000000016 +:10563000D007000070720108440000000221002021 +:1056400000000000D0070000807201084400000044 +:105650000421002000000000D00700009172010822 +:10566000440000000621002000000000D0070000D8 +:105670009C72010844000000082100200000000086 +:10568000D0070000B1720108440000000A21002088 +:1056900032000000007D0000C072010844000000DC +:1056A0000C21002032000000F2010000CF7201083E +:1056B000410000004F210020000000000100000018 +:1056C000DC720108410000005021002000000000B1 +:1056D00001000000EF72010841000000512100208C +:1056E00000000000B4000000FB720108410000004F +:1056F0005221002000000000640000000773010830 +:105700004200000053210020FFFFFFFF01000000C6 +:105710001D73010841000000582100200000000016 +:105720000B000000347301084100000059210020E3 +:10573000000000000B0000004B7301084100000056 +:105740005A210020000000000B00000062730108D5 +:10575000410000005B210020000000000B00000061 +:1057600079730108410000006C2100203000000026 +:105770007E0000008A730108500000005C210020B8 +:10578000B004000000C2010097730108500000003F +:1057900060210020B004000000C20100A4730108D1 +:1057A00050000000642100200000000000C2010041 +:1057B000B17301085000000068210020B00400000F +:1057C00000C20100CA7301084100000054210020FA +:1057D0000000000001000000D77301084100000034 +:1057E000552100200000000004000000E5730108BE +:1057F00041000000562100200000000001000000D0 +:10580000F57301088100000048220020000000001C +:10581000C8000000FF730108810000005222002030 +:1058200000000000C80000000974010881000000A9 +:105830005C22002000000000C80000001374010872 +:10584000810000004922002000000000C800000084 +:105850001E74010881000000532200200000000097 +:10586000C800000029740108810000005D220020AA +:1058700000000000C800000034740108810000002E +:105880004A22002000000000C80000003E74010809 +:10589000810000005422002000000000C800000029 +:1058A00048740108810000005E2200200000000012 +:1058B000C80000005274010884000000F223002098 +:1058C00000000000D00700006074010881000000A3 +:1058D000F62300200000000001000000757401089C +:1058E00084000000F82300200A000000D007000018 +:1058F0008374010884000000FA2300200A000000DD +:10590000D00700009174010881000000F5230020F9 +:1059100000000000640000009F74010841000000C6 +:10592000442100200000000003000000B1740108C1 +:105930004100000070210020000000000300000072 +:10594000C474010841000000712100200000000023 +:1059500001000000D5740108410000007221002000 +:105960000000000001000000E97401086000000070 +:1059700074210020A6FFFFFF5A00000001750108F6 +:1059800060000000782100204CFFFFFFB400000001 +:1059900019750108410000007C2100200000000072 +:1059A0000100000032750108410000007D21002047 +:1059B00000000000010000003D75010844000000E7 +:1059C0003A21002000000000204E00004E75010822 +:1059D000410000003021002000000000FF00000016 +:1059E0005975010841000000312100200A00000023 +:1059F000320000006F7501084100000032210020D4 +:105A00000A00000032000000857501084400000013 +:105A100034210020010000001027000099750108C2 +:105A20004400000036210020000000007206000043 +:105A3000AE75010841000000382100200000000080 +:105A400001000000CC750108410000000E2100207B +:105A50000000000008000000D775010841000000A8 +:105A60000F2100200000000008000000E17501087F +:105A7000410000001021002000000000080000008C +:105A8000EB75010848000000122100204CFFFFFFC9 +:105A900068010000FC750108480000001421002086 +:105AA0004CFFFFFF680100000E760108480000006F +:105AB000162100204CFFFFFF680100001E76010840 +:105AC0004400000022210020640000008403000044 +:105AD00034760108440000001A2100200000000074 +:105AE000000100003D760108410000002021002057 +:105AF00000000000800000004D7601084400000016 +:105B00001C21002064000000E80300005E7601080C +:105B1000440000001E21002064000000E803000093 +:105B200070760108810000009F2300200100000022 +:105B3000FA0000008276010881000000A023002006 +:105B400000000000010000007976010881000000DB +:105B50009D2300200000000020000000977601082F +:105B6000810000009E23002000000000640000006F +:105B7000A476010881000000A4230020000000009A +:105B800096000000BE76010884000000A2230020D9 +:105B90000100000084030000D876010842000000E4 +:105BA00018210020FFFFFFFF01000000EE76010832 +:105BB00082000000EE230020FFFFFFFF0100000035 +:105BC000FC76010882000000EF23002000000000A6 +:105BD000010000000E7701088100000090220020E3 +:105BE000000000000200000023770108010100000E +:105BF0008227002000000000FA0000002B77010837 +:105C00000101000083270020000000006400000064 +:105C10003377010801010000842700200000000004 +:105C2000640000003B770108010100008527002087 +:105C3000000000006400000044770108010100003A +:105C4000862700200000000064000000547701084F +:105C50000101000087270020000000006400000010 +:105C60005D77010801010000882700200000000086 +:105C70006400000066770108040100008A27002004 +:105C8000E8030000D00700007577010881000000DC +:105C9000E623002000000000C8000000847701080F +:105CA00081000000E723002000000000C800000081 +:105CB0009777010884000000E8230020E803000033 +:105CC000D0070000A977010884000000EA23002023 +:105CD00064000000D0070000BB77010884000000CA +:105CE000EC23002064000000B80B0000CD77010811 +:105CF00081000000F023002000000000FF000000F1 +:105D0000DA7701084100000019210020000000009E +:105D100009000000E77701088100000098220020B8 +:105D200000000000FA000000F67701088100000082 +:105D3000A022002000000000640000000578010897 +:105D400081000000A122002000000000640000008B +:105D500013780108A00000009C2200200100000030 +:105D6000140000002378010881000000B422002004 +:105D700000000000010000003278010888000000E7 +:105D800096220020D4FEFFFF2C010000417801087C +:105D90008800000094220020D4FEFFFF2C010000A8 +:105DA0004F78010881000000A422002000000000BC +:105DB000300000005D780108A0000000A82200204B +:105DC00000000000010000006C780108A000000045 +:105DD000AC220020000000000100000078780108DB +:105DE000A0000000B0220020000000000100000020 +:105DF000847801088800000092220020B0B9FFFFDB +:105E000050460000947801088100000040220020E4 +:105E10000000000002000000A378010881000000DB +:105E20004522002000000000C8000000AB780108F7 +:105E3000810000004F22002000000000C800000088 +:105E400006760108810000005922002000000000B1 +:105E5000C8000000B378010881000000442200203F +:105E600000000000C8000000BA78010881000000AE +:105E70004E22002000000000C8000000F575010857 +:105E8000810000005822002000000000C80000002F +:105E9000C1780108810000004622002000000000B7 +:105EA000C8000000C77801088100000050220020CF +:105EB00000000000C8000000187601088100000002 +:105EC0005A22002000000000C8000000CD78010820 +:105ED000A000000068220020000000006400000014 +:105EE000D6780108A0000000742200200000000005 +:105EF00064000000DF780108A0000000802200207C +:105F00000000000064000000E8780108A000000024 +:105F1000642200200000000064000000F078010806 +:105F2000A0000000702200200000000064000000BB +:105F3000F8780108A00000007C220020000000008A +:105F40006400000000790108A00000006C2200201D +:105F5000000000006400000007790108A0000000B4 +:105F60007822002000000000640000000E79010883 +:105F7000A000000084220020000000006400000057 +:105F800015790108A00000008C220020000000000C +:105F90000A00000023790108A000000088220020E8 +:105FA000000000000A0000002F79010881000000B5 +:105FB0004722002000000000C800000035790108D9 +:105FC000810000005122002000000000C8000000F5 +:105FD0003B790108810000005B22002000000000E6 +:105FE000C800000041790108810000004B22002018 +:105FF00000000000C800000049790108810000008D +:106000005522002000000000C8000000517901085E +:10601000810000005F22002000000000C800000096 +:1060200059790108810000004D2200200000000085 +:10603000C80000005F79010881000000572200209D +:1060400000000000C8000000657901088100000020 +:106050006122002000000000C800000000000000D5 +:10606000000000400008014001000000001C002862 +:10607000000000400008014002000000041C00284D +:10608000000000400008014004000000081C002837 +:106090000000004000080140080000000C1C00281F +:1060A000000400400008014040000000001D0028DE +:1060B000000400400008014080000000041D00288A +:1060C00000040040000C014001000000081D0028F1 +:1060D00000040040000C0140020000000C1D0028DC +:1060E000002C01400008014000010000001B0128B5 +:1060F000002C014000080140000800000C1B012892 +:1061000000080040000C014040000000001E002874 +:1061100000080040000C014080000000041E002820 +:1061200000080040000C014000010000081E00288B +:1061300000080040000C0140000200000C1E002876 +:1061400024505542582C34312C312C303030332CE3 +:10615000303030312C3131353230302C302A31452D +:106160000D0A0024504D544B3235312C313135322B +:1061700030302A31460D0A0024505542582C343113 +:106180002C312C303030332C303030312C35373608 +:1061900030302C302A32440D0A0024504D544B32FA +:1061A00035312C35373630302A32430D0A00245031 +:1061B0005542582C34312C312C303030332C303087 +:1061C00030312C33383430302C302A32360D0A003E +:1061D00024504D544B3235312C33383430302A3240 +:1061E000370D0A0024505542582C34312C312C30B4 +:1061F0003030332C303030312C31393230302C309B +:106200002A32330D0A0024504D544B3235312C3193 +:10621000393230302A32320D0A0041524D3B0041B2 +:106220004E474C453B00484F52495A4F4E3B004267 +:1062300041524F3B004D41473B0048454144465287 +:1062400045453B004845414441444A3B0043414D9C +:10625000535441423B0043414D545249473B004750 +:10626000505320484F4D453B0047505320484F4C1A +:10627000443B0050415353544852553B004245451E +:106280005045523B004C45444D41583B004C454421 +:106290004C4F573B004C4C49474854533B004341FB +:1062A0004C49423B00474F5645524E4F523B004FE0 +:1062B00053442053573B0054454C454D4554525987 +:1062C0003B004155544F54554E453B00534F4E41B2 +:1062D000523B00436C65616E666C696768742F257C +:1062E00073202573202F202573202825732900442F +:1062F000656320203920323031340031373A32356D +:106300003A353800386334313737320041766169C5 +:106310006C61626C6520636F6D6D616E64733A0DC4 +:106320000A0025730925730D0A00202564202564C1 +:1063300000556E6B6E6F776E207661726961626C6C +:1063400065206E616D650D0A0043757272656E742D +:106350002073657474696E67733A200D0A002573A3 +:106360002073657420746F200056616C7565206120 +:10637000737369676E6D656E74206F7574206F66D8 +:106380002072616E67650D0A004E4709004F4B0988 +:1063900000437573746F6D206D697865723A200DD6 +:1063A0000A4D6F746F720954687209526F6C6C09F0 +:1063B0005069746368095961770D0A002325643AAE +:1063C00009002573090053616E697479206368655B +:1063D000636B3A09007265736574006C6F616400E9 +:1063E000496E76616C6964206D6978657220747994 +:1063F00070650D0A004C6F61646564202573206D23 +:1064000069780D0A0057726F6E67206E756D626550 +:1064100072206F6620617267756D656E74732C20D3 +:106420006E65656473206964782074687220726F89 +:106430006C6C207069746368207961770D0A004D77 +:106440006F746F72206E756D626572206D757374F6 +:10645000206265206265747765656E203120616E0B +:10646000642025640D0A004D7573742062652061F7 +:106470006E79206F72646572206F662041455452B8 +:10648000313233340D0A0043757272656E742061C7 +:10649000737369676E6D656E743A2000736574205E +:1064A0002573203D200025752C25753A25733A2546 +:1064B00073006C65642025752025730D0A005061FA +:1064C000727365206572726F720D0A00496E766193 +:1064D0006C6964206C656420696E6465783A206D2F +:1064E000757374206265203C2025750D0A004820D4 +:1064F0004669726D7761726520747970653A436C94 +:1065000065616E666C696768740A00482046697246 +:106510006D77617265207265766973696F6E3A2571 +:10652000730A0048204669726D7761726520646164 +:1065300074653A25732025730A00482072635261FE +:1065400074653A25640A0048206D696E7468726F3C +:1065500074746C653A25640A0048206D617874682B +:10656000726F74746C653A25640A0048206779720A +:106570006F2E7363616C653A307825780A00482085 +:106580006163635F31473A25750A00736572766F00 +:106590005B355D00310048204669656C6420492008 +:1065A0006E616D653A6C6F6F704974657261746984 +:1065B0006F6E2C74696D652C61786973505B305D0A +:1065C0002C61786973505B315D2C61786973505B25 +:1065D000325D2C61786973495B305D2C6178697339 +:1065E000495B315D2C61786973495B325D2C617860 +:1065F0006973445B305D2C61786973445B315D2C59 +:1066000061786973445B325D2C7263436F6D6D61B9 +:106610006E645B305D2C7263436F6D6D616E645BA5 +:10662000315D2C7263436F6D6D616E645B325D2C06 +:106630007263436F6D6D616E645B335D2C6779725D +:106640006F446174615B305D2C6779726F44617473 +:10665000615B315D2C6779726F446174615B325D9F +:106660002C616363536D6F6F74685B305D2C616385 +:1066700063536D6F6F74685B315D2C616363536D41 +:106680006F6F74685B325D2C6D6F746F725B305D21 +:106690002C6D6F746F725B315D2C6D6F746F725BFC +:1066A000325D2C6D6F746F725B335D2C6D6F746F28 +:1066B000725B345D2C6D6F746F725B355D2C6D6F2A +:1066C000746F725B365D2C6D6F746F725B375D003B +:1066D00048204669656C642049207369676E65646B +:1066E0003A302C302C312C312C312C312C312C31B6 +:1066F0002C312C312C312C312C312C312C302C31B3 +:106700002C312C312C312C312C312C302C302C30A4 +:106710002C302C302C302C302C3000482046696531 +:106720006C64204920707265646963746F723A30DA +:106730002C302C302C302C302C302C302C302C3079 +:106740002C302C302C302C302C302C342C302C3065 +:106750002C302C302C302C302C342C352C352C3546 +:106760002C352C352C352C350048204669656C6459 +:10677000204920656E636F64696E673A312C312C55 +:10678000302C302C302C302C302C302C302C302C29 +:10679000302C302C302C302C312C302C302C302C18 +:1067A000302C302C302C312C302C302C302C302C08 +:1067B000302C302C300048204669656C6420502015 +:1067C000707265646963746F723A362C322C312CA6 +:1067D000312C312C312C312C312C312C312C312CD1 +:1067E000312C312C312C312C332C332C332C332CB9 +:1067F000332C332C332C332C332C332C332C332CA1 +:10680000332C330048204669656C64205020656E47 +:10681000636F64696E673A302C302C302C302C302A +:106820002C302C302C302C302C302C302C382C3878 +:106830002C382C382C302C302C302C302C302C3068 +:106840002C302C302C302C302C302C302C302C3068 +:10685000000D0A5265626F6F74696E67000D0A4C15 +:10686000656176696E6720434C49206D6F64652CC5 +:1068700020756E7361766564206368616E67657309 +:10688000206C6F73742E0D0A00536176696E670079 +:106890007261746570726F66696C652025640D0A9B +:1068A000000D0A456E746572696E6720434C49207D +:1068B0004D6F64652C207479706520276578697444 +:1068C0002720746F2072657475726E2C206F722091 +:1068D0002768656C70270D0A000D0A2320000D1B28 +:1068E0005B4B001B5B324A1B5B313B314800556EF2 +:1068F0006B6E6F776E20636F6D6D616E642C2074AC +:106900007279202768656C702700082008004145CF +:1069100054523132333400526573657474696E6752 +:1069200020746F2064656661756C747300456E61D8 +:10693000626C65642066656174757265733A2000E7 +:1069400025732000417661696C61626C6520666523 +:106950006174757265733A2000496E76616C696482 +:106960002066656174757265206E616D650D0A0043 +:1069700044697361626C65642000456E61626C6598 +:1069800064200041464E41003031323334353637D1 +:1069900038394142434445464748494A4B4C4D4E9D +:1069A0004F505152535455565758595A00003008B9 +:1069B0001002000200010006000800081001400853 +:1069C0000007100720070004100420080000537976 +:1069D0007374656D20557074696D653A2025642067 +:1069E0007365636F6E64732C20566F6C746167659A +:1069F0003A202564202A20302E3156202825645341 +:106A00002062617474657279290D0A004350552023 +:106A100025644D487A2C2064657465637465642030 +:106A200073656E736F72733A200041434348573A5F +:106A3000202573002E2563004379636C652054691B +:106A40006D653A2025642C20493243204572726FCF +:106A500072733A2025642C20636F6E666967207319 +:106A6000697A653A2025640D0A0061646A72616E74 +:106A7000676520257520257520257520257520251D +:106A8000752025752025750D0A00617578202575FE +:106A90002025752025752025752025750D0A0041B6 +:106AA00044584C333435004D505536303530004D58 +:106AB0004D413834357800424D41323830004C5326 +:106AC0004D333033444C4843004D50553630303010 +:106AD000004D5055363530300046414B45004E6F25 +:106AE0006E65004759524F00414343004241524FA7 +:106AF00000534F4E415200475053004750532B4DC7 +:106B0000414700004F201004430240010880C34366 +:106B1000757272656E74206D697865723A2025739E +:106B20000D0A00417661696C61626C65206D69785F +:106B30006572733A20004D69786572207365742020 +:106B4000746F2025730D0A0055736167653A0D0A4D +:106B50006D6F746F7220696E646578205B76616C0E +:106B600075655D202D2073686F77205B6F722073D1 +:106B700065745D206D6F746F722076616C75650D44 +:106B80000A004E6F2073756368206D6F746F722CEE +:106B9000207573652061206E756D626572205B30B3 +:106BA0002C2025645D0D0A004D6F746F72202564E2 +:106BB000206973207365742061742025640D0A00B8 +:106BC000496E76616C6964206D6F746F72207661B6 +:106BD0006C75652C20313030302E2E323030300D37 +:106BE0000A0053657474696E67206D6F746F72204C +:106BF000256420746F2025640D0A00636F6C6F722A +:106C00002025752025642C25752C25750D0A004935 +:106C10006E76616C696420636F6C6F7220696E645C +:106C200065783A206D757374206265203C20257567 +:106C30000D0A002E006D61737465720072617465D7 +:106C400073000D0A232076657273696F6E0D0A005A +:106C50000D0A232064756D70206D61737465720D6B +:106C60000A000D0A23206D697865720D0A006D69AE +:106C70007865722025730D0A00636D69782025649C +:106C800000636D697820256420302030203020306A +:106C90000D0A000D0A0D0A23206665617475726580 +:106CA0000D0A0066656174757265202D25730D0AE5 +:106CB00000666561747572652025730D0A000D0A02 +:106CC0000D0A23206D61700D0A006D61702025731F +:106CD0000D0A000D0A0D0A23206C65640D0A000DD3 +:106CE0000A0D0A2320636F6C6F720D0A000D0A23D0 +:106CF0002064756D702070726F66696C650D0A0096 +:106D00000D0A232070726F66696C650D0A000D0A0A +:106D100023206175780D0A000D0A232061646A72D0 +:106D2000616E67650D0A000D0A232064756D702081 +:106D300072617465730D0A000D0A23207261746517 +:106D400070726F66696C650D0A0052585F50504D45 +:106D5000005642415400494E464C494748545F4111 +:106D600043435F43414C0052585F53455249414CA5 +:106D7000004D4F544F525F53544F5000534552569D +:106D80004F5F54494C5400534F4654534552494168 +:106D90004C004641494C534146450054454C454DF5 +:106DA000455452590043555252454E545F4D455437 +:106DB00045520033440052585F504152414C4C45BB +:106DC0004C5F50574D0052585F4D53500052535333 +:106DD000495F414443004C45445F5354524950007D +:106DE000444953504C4159004F4E4553484F54313C +:106DF000323500424C41434B424F580054524900F7 +:106E000051554144500051554144580042490047B2 +:106E1000494D42414C005936004845583600464CD1 +:106E200059494E475F57494E470059340048455825 +:106E30003658004F43544F5838004F43544F464C38 +:106E4000415450004F43544F464C4154580041491F +:106E500052504C414E450048454C495F3132305FFD +:106E60004343504D0048454C495F39305F444547E6 +:106E700000565441494C340048455836480050505B +:106E80004D5F544F5F534552564F004455414C435C +:106E90004F505445520053494E474C45434F505470 +:106EA000455200435553544F4D00414552543132E1 +:106EB0003334353637386162636465666768004528 +:106EC00072726F723A20456E61626C6520616E6409 +:106ED00020706C756720696E204750532066697278 +:106EE00073740D0A0061646A72616E67650073688D +:106EF0006F772F7365742061646A7573746D656E46 +:106F0000742072616E6765732073657474696E674F +:106F100073006175780073686F772F7365742061F3 +:106F200075782073657474696E677300636D697832 +:106F30000064657369676E20637573746F6D206D8F +:106F40006978657200636F6C6F7200636F6E66695B +:106F50006775726520636F6C6F727300726573651D +:106F60007420746F2064656661756C747320616E43 +:106F700064207265626F6F740064756D700070726A +:106F8000696E7420636F6E666967757261626C65A5 +:106F90002073657474696E677320696E2061207058 +:106FA00061737461626C6520666F726D00657869EB +:106FB000740066656174757265006C697374206F26 +:106FC00072202D76616C206F722076616C0067658F +:106FD0007400676574207661726961626C65207601 +:106FE000616C756500677073706173737468726F3C +:106FF00075676800706173737468726F7567682075 +:1070000067707320746F2073657269616C006865C6 +:107010006C70006C656400636F6E6669677572659D +:10702000206C656473006D6170006D617070696ED5 +:1070300067206F66207263206368616E6E656C20E6 +:107040006F72646572006D69786572206E616D653E +:10705000206F72206C697374006D6F746F720067BB +:1070600065742F736574206D6F746F72206F757403 +:107070007075742076616C756500696E6465782042 +:10708000283020746F203229007261746570726F2D +:1070900066696C6500736176650073617665206171 +:1070A0006E64207265626F6F74006E616D653D760F +:1070B000616C7565206F7220626C616E6B206F72FF +:1070C000202A20666F72206C6973740073686F7772 +:1070D0002073797374656D207374617475730052D5 +:1070E00065763A202573005461726765743A2025ED +:1070F0007300566F6C74733A2025642E253164201A +:1071000043656C6C733A20256400416D70733A20BE +:1071100025642E253264206D41683A2025640020C4 +:1071200020202020202020582020202020592020EE +:107130002020205A0041203D20253564202535643B +:10714000202535640047203D202535642025356401 +:1071500020253564004D203D2025356420253564EB +:10716000202535640050726F66696C653A2025648D +:1071700000526174652070726F66696C653A2025F3 +:1071800064005243204578706F3A202564005243D2 +:1071900020526174653A20256400522650205261C5 +:1071A00074653A2025640059617720526174653A0C +:1071B000202564007C2F2D5C00434C45414E464CFD +:1071C000494748540041524D4544004241545445BA +:1071D00052590053454E534F52530052580050528B +:1071E0004F46494C45004E415A45006C6F6F7074D4 +:1071F000696D6500656D665F61766F6964616E6378 +:1072000065006D69645F7263006D696E5F636865D8 +:10721000636B006D61785F636865636B00727373A5 +:10722000695F6368616E6E656C00727373695F732A +:1072300063616C6500696E7075745F66696C746516 +:1072400072696E675F6D6F6465006D696E5F74680B +:10725000726F74746C65006D61785F7468726F74BE +:10726000746C65006D696E5F636F6D6D616E640057 +:1072700033645F6465616462616E645F6C6F770044 +:1072800033645F6465616462616E645F68696768E6 +:107290000033645F6E65757472616C0033645F64A3 +:1072A00065616462616E645F7468726F74746C654A +:1072B000006D6F746F725F70776D5F7261746500DF +:1072C000736572766F5F70776D5F7261746500725F +:1072D000657461726465645F61726D006469736195 +:1072E000726D5F6B696C6C5F737769746368007350 +:1072F0006D616C6C5F616E676C6500666C6170736C +:107300005F737065656400666978656477696E6748 +:107310005F616C74686F6C645F646972007365723E +:1073200069616C5F706F72745F315F7363656E610A +:1073300072696F0073657269616C5F706F72745F00 +:10734000325F7363656E6172696F00736572696144 +:107350006C5F706F72745F335F7363656E617269C7 +:107360006F0073657269616C5F706F72745F345F18 +:107370007363656E6172696F007265626F6F745FCF +:10738000636861726163746572006D73705F6261DE +:1073900075647261746500636C695F6261756472C3 +:1073A000617465006770735F6261756472617465B2 +:1073B000006770735F706173737468726F7567686C +:1073C0005F6261756472617465006770735F70728B +:1073D0006F7669646572006770735F736261735F73 +:1073E0006D6F6465006770735F6175746F5F636F65 +:1073F0006E666967006770735F706F735F700067B8 +:1074000070735F706F735F69006770735F706F7325 +:107410005F64006770735F706F73725F7000677096 +:10742000735F706F73725F69006770735F706F7303 +:10743000725F64006770735F6E61765F7000677083 +:10744000735F6E61765F69006770735F6E61765F10 +:1074500064006770735F77705F7261646975730051 +:107460006E61765F636F6E74726F6C735F68656177 +:1074700064696E67006E61765F73706565645F6DE9 +:10748000696E006E61765F73706565645F6D6178CB +:10749000006E61765F736C65775F7261746500730F +:1074A000657269616C72785F70726F76696465721B +:1074B0000074656C656D657472795F70726F766962 +:1074C0006465720074656C656D657472795F73775D +:1074D000697463680074656C656D657472795F6961 +:1074E0006E76657273696F6E006672736B795F6436 +:1074F000656661756C745F6C6174746974756465DC +:10750000006672736B795F64656661756C745F6C3D +:107510006F6E676974756465006672736B795F631B +:107520006F6F7264696E617465735F666F726D61AF +:1075300074006672736B795F756E69740062617452 +:10754000746572795F6361706163697479007662F2 +:1075500061745F7363616C6500766261745F6D6115 +:10756000785F63656C6C5F766F6C746167650076DD +:107570006261745F6D696E5F63656C6C5F766F6C82 +:10758000746167650063757272656E745F6D6574B2 +:1075900065725F7363616C650063757272656E74AA +:1075A0005F6D657465725F6F6666736574006D7597 +:1075B0006C74697769695F63757272656E745F6D0B +:1075C000657465725F6F757470757400616C69675E +:1075D0006E5F6779726F00616C69676E5F6163638C +:1075E00000616C69676E5F6D616700616C69676EF1 +:1075F0005F626F6172645F726F6C6C00616C69676F +:107600006E5F626F6172645F706974636800616C61 +:1076100069676E5F626F6172645F796177006D6147 +:10762000785F616E676C655F696E636C696E6174CB +:10763000696F6E006779726F5F6C7066006D6F7254 +:107640006F6E5F7468726573686F6C6400677972DF +:107650006F5F636D70665F666163746F72006779F8 +:10766000726F5F636D70666D5F666163746F7200E9 +:10767000616C745F686F6C645F6465616462616EA5 +:107680006400616C745F686F6C645F666173745FE3 +:107690006368616E6765007961775F6465616462E4 +:1076A000616E64007468726F74746C655F636F728E +:1076B00072656374696F6E5F76616C75650074687E +:1076C000726F74746C655F636F7272656374696FF7 +:1076D0006E5F616E676C65007961775F636F6E7472 +:1076E000726F6C5F646972656374696F6E00796153 +:1076F000775F646972656374696F6E007472695F45 +:10770000756E61726D65645F736572766F00646536 +:107710006661756C745F726174655F70726F6669C3 +:107720006C650072635F726174650072635F657897 +:10773000706F007468725F6D6964007468725F6571 +:1077400078706F00726F6C6C5F70697463685F72E1 +:10775000617465007961775F72617465007470614E +:107760005F72617465007470615F627265616B70F5 +:107770006F696E74006661696C736166655F6465EC +:107780006C6179006661696C736166655F6F6666DE +:107790005F64656C6179006661696C736166655FE1 +:1077A0007468726F74746C65006661696C7361668D +:1077B000655F6D696E5F75736563006661696C73A3 +:1077C0006166655F6D61785F757365630067696D9C +:1077D00062616C5F666C616773006163635F6861BF +:1077E000726477617265006163635F6C70665F6687 +:1077F0006163746F720061636378795F646561646B +:1078000062616E64006163637A5F64656164626192 +:107810006E64006163637A5F6C70665F6375746F3A +:107820006666006163635F756E61726D6564636156 +:107830006C006163635F7472696D5F706974636823 +:10784000006163635F7472696D5F726F6C6C00627C +:1078500061726F5F7461625F73697A650062617201 +:107860006F5F6E6F6973655F6C7066006261726FE7 +:107870005F63665F76656C006261726F5F63665F0F +:10788000616C74006D61675F6465636C696E6174DF +:10789000696F6E007069645F636F6E74726F6C6C99 +:1078A000657200705F706974636800695F70697405 +:1078B000636800705F726F6C6C00695F726F6C6CF4 +:1078C00000705F79617700695F79617700705F7040 +:1078D000697463686600695F7069746368660064F0 +:1078E0005F70697463686600705F726F6C6C6600CD +:1078F000695F726F6C6C6600645F726F6C6C6600BF +:10790000705F7961776600695F7961776600645FAF +:1079100079617766006C6576656C5F686F72697A0D +:107920006F6E006C6576656C5F616E676C6500708C +:107930005F616C7400695F616C7400645F616C749A +:1079400000705F6C6576656C00695F6C6576656C70 +:1079500000645F6C6576656C00705F76656C0069CD +:107960005F76656C00645F76656C000020202020E7 +:1079700020202020202828282828202020202020DF +:1079800020202020202020202020202088101010BF +:107990001010101010101010101010100404040417 +:1079A000040404040404101010101010104141418C +:1079B00041414101010101010101010101010101F7 +:1079C000010101010101011010101010104242428A +:1079D00042424202020202020202020202020202C7 +:1079E0000202020202020210101010200000000029 +:1079F0000000000000000000000000000000000087 +:107A00000000000000000000000000000000000076 +:107A10000000000000000000000000000000000066 +:107A20000000000000000000000000000000000056 +:107A30000000000000000000000000000000000046 +:107A40000000000000000000000000000000000036 +:107A50000000000000000000000000000000000026 +:107A60000000000000000000000000000000004BCB +:107A7000000000CB61636F7366000000706F776673 +:107A800000000000737172746600000000000000C6 +:107A900000C0153F00000000DCCFD1350000803F62 +:107AA0000000C03F000FC93F000F494000CB964087 +:107AB000000FC9400053FB4000CB164100ED2F41A1 +:107AC000000F49410031624100537B41003A8A4135 +:107AD00000CB9641005CA34100EDAF41007EBC416C +:107AE000000FC94100A0D5410031E24100C2EE4182 +:107AF0000053FB4100F20342003A0A420083104265 +:107B000000CB164200141D42005C234200A529420E +:107B100000ED2F4200363642007E3C4200C7424212 +:107B2000000F4942A2000000F9000000830000009D +:107B30006E0000004E000000440000001500000030 +:107B400029000000FC000000270000005700000092 +:107B5000D1000000F500000034000000DD0000004E +:107B6000C0000000DB000000620000009500000083 +:107B7000990000003C00000043000000900000005D +:107B800041000000FE000000510000006300000002 +:107B9000AB000000DE000000BB000000C5000000DC +:107BA00061000000B7000000240000006E0000002B +:107BB0003A000000420000004D000000D20000002A +:107BC000E000000006000000490000002E00000058 +:107BD000EA00000009000000D1000000920000004F +:107BE0001C000000FE0000001D000000EB00000073 +:107BF0001C000000B100000029000000A7000000E8 +:107C00003E000000E8000000820000003500000097 +:107C1000F50000002E000000BB0000004400000042 +:107C200084000000E90000009C00000070000000DB +:107C300026000000B40000005F0000007E0000008D +:107C4000410000003900000091000000D600000053 +:107C500039000000830000005300000039000000DC +:107C6000F40000009C000000840000005F000000A1 +:107C70008B000000BD000000F9000000280000009B +:107C80003B0000001F000000F8000000970000000B +:107C9000FF000000DE00000005000000980000006A +:107CA0000F000000EF0000002F0000001100000096 +:107CB0008B0000005A0000000A0000006D00000068 +:107CC0001F0000006D000000360000007E00000074 +:107CD000CF00000027000000CB00000009000000DA +:107CE000B70000004F000000460000003F00000009 +:107CF000660000009E0000005F000000EA00000037 +:107D00002D0000007500000027000000BA000000F0 +:107D1000C7000000EB000000E5000000F1000000DB +:107D20007B0000003D00000007000000390000005B +:107D3000F70000008A0000005200000092000000DE +:107D4000EA0000006B000000FB0000005F00000084 +:107D5000B10000001F0000008D0000005D00000069 +:107D60000800000056000000030000003000000082 +:107D700046000000FC0000007B0000006B000000DB +:107D8000AB000000F0000000CF000000BC000000CD +:107D9000200000009A000000F400000036000000FF +:107DA0001D000000A9000000E30000009100000099 +:107DB000610000005E000000E60000001B00000003 +:107DC0000800000065000000990000008500000028 +:107DD0005F00000014000000A00000006800000028 +:107DE000400000008D000000FF000000D8000000EF +:107DF000800000004D00000073000000270000001C +:107E00003100000006000000060000001500000020 +:107E100056000000CA00000073000000A800000027 +:107E2000C900000060000000E20000007B000000CC +:107E3000C00000008C0000006B0000000400000087 +:107E400007000000090000000000C93F0000F039F1 +:107E50000000DA370000A2330000842E0000502B0F +:107E60000000C2270000D0220000C41F0000C61B73 +:107E70000000441700000000000000000000304334 +:107E800000000000000030C36937AC3168212233A4 +:107E9000B40F14336821A2333863ED3EDA0F493F43 +:087EA0005E987B3FDA0FC93F39 +:087EA8003C72FF7F01000000A5 +:107EB000000100000000803F000000000000000002 +:107EC0000100DC05DC05DC05DC05DC05DC05DC058A +:107ED000DC05010000127A00000000000000000034 +:107EE0000102030406070809010303000000803FA4 +:107EF0000000803F0000803F010100000000803F43 +:107F0000000000000102030401020304060708093F +:107F1000020406080000000000000000000000004D +:107F2000010000000000000000000000030000004D +:107F3000000000000000000004000000000000003D +:107F40000000000003000000957E00080F270000DD +:107F5000FFFFFFFF00A24A0483690108B97101080D +:107F6000C5710108CB710108D3710108DB710108EB +:107F7000DE710108E67101086B790108000000005C +:107F800000000000000000000000000000000000F1 +:107F9000000000000000000000000000EA6A010884 +:107FA00000000000000000000000000000000000D1 +:107FB00000000000000000000000000000000000C1 +:107FC00000000000000000000000000000000000B1 +:107FD000000000000000000000000000CC000020B5 +:047FE000010000009C :0400000508000000EF :00000001FF diff --git a/src/main/blackbox/blackbox.c b/src/main/blackbox/blackbox.c index 836205e4a7..a6b059cd56 100644 --- a/src/main/blackbox/blackbox.c +++ b/src/main/blackbox/blackbox.c @@ -212,6 +212,29 @@ static const char * const blackboxHeaderFields[] = { ENCODING(SIGNED_VB) }; +/** + * Additional fields to tack on to those above for tricopters (to record tail servo position) + */ +static const char * const blackboxAdditionalFieldsTricopter[] = { + //Field I name + "servo[5]", + + //Field I signed + "0", + + //Field I predictor + PREDICT(1500), + + //Field I encoding: + ENCODING(SIGNED_VB), + + //Field P predictor: + PREDICT(PREVIOUS), + + //Field P encoding: + ENCODING(SIGNED_VB) +}; + static const char blackboxGpsHeader[] = "H Field G name:" "GPS_numSat,GPS_coord[0],GPS_coord[1],GPS_altitude,GPS_speed\n" @@ -270,6 +293,10 @@ static blackbox_values_t blackboxHistoryRing[3]; // These point into blackboxHistoryRing, use them to know where to store history of a given age (0, 1 or 2 generations old) static blackbox_values_t* blackboxHistory[3]; +static int isTricopter() +{ + return masterConfig.mixerConfiguration == MULTITYPE_TRI; +} static void blackboxWrite(uint8_t value) { @@ -425,6 +452,9 @@ static void writeIntraframe(void) for (x = 1; x < motorCount; x++) writeSignedVB(blackboxCurrent->motor[x] - blackboxCurrent->motor[0]); + if (isTricopter()) + writeSignedVB(blackboxHistory[0]->servo[5] - 1500); + //Rotate our history buffers: //The current state becomes the new "before" state @@ -481,6 +511,9 @@ static void writeInterframe(void) for (x = 0; x < motorCount; x++) writeSignedVB(blackboxHistory[0]->motor[x] - (blackboxHistory[1]->motor[x] + blackboxHistory[2]->motor[x]) / 2); + if (isTricopter()) + writeSignedVB(blackboxCurrent->servo[5] - blackboxLast->servo[5]); + //Rotate our history buffers blackboxHistory[2] = blackboxHistory[1]; blackboxHistory[1] = blackboxHistory[0]; @@ -576,10 +609,43 @@ static void writeGPSFrame() gpsHistory.GPS_coord[1] = GPS_coord[1]; } +/** + * Fill the current state of the blackbox using values read from the flight controller + */ +static void loadBlackboxState(void) +{ + blackbox_values_t *blackboxCurrent = blackboxHistory[0]; + int i; + + blackboxCurrent->time = currentTime; + + for (i = 0; i < 3; i++) + blackboxCurrent->axisP[i] = axisP[i]; + for (i = 0; i < 3; i++) + blackboxCurrent->axisI[i] = axisI[i]; + for (i = 0; i < 3; i++) + blackboxCurrent->axisD[i] = axisD[i]; + + for (i = 0; i < 4; i++) + blackboxCurrent->rcCommand[i] = rcCommand[i]; + + for (i = 0; i < 3; i++) + blackboxCurrent->gyroData[i] = gyroData[i]; + + for (i = 0; i < 3; i++) + blackboxCurrent->accSmooth[i] = accSmooth[i]; + + for (i = 0; i < motorCount; i++) + blackboxCurrent->motor[i] = motor[i]; + + //Tail servo for tricopters + blackboxCurrent->servo[5] = servo[5]; +} + void handleBlackbox(void) { int i; - blackbox_values_t *blackboxCurrent; + const char *additionalHeader; const int SERIAL_CHUNK_SIZE = 16; static int charXmitIndex = 0; int motorsToRemove, endIndex; @@ -607,8 +673,10 @@ void handleBlackbox(void) break; case BLACKBOX_STATE_SEND_FIELDINFO: /* - * Once again, chunking up the data so we don't exceed our datarate. This time we're removing the excess field defs - * for motors we don't have. + * Send information about the fields we're recording to the log. + * + * Once again, we're chunking up the data so we don't exceed our datarate. This time we're trimming the + * excess field defs off the end of the header for motors we don't have. */ motorsToRemove = 8 - motorCount; @@ -618,7 +686,16 @@ void handleBlackbox(void) for (i = charXmitIndex; i < charXmitIndex + SERIAL_CHUNK_SIZE && i < endIndex; i++) blackboxWrite(blackboxHeaderFields[headerXmitIndex][i]); + // Did we complete this line? if (i == endIndex) { + if (isTricopter()) { + //Add fields to the end for the tail servo + blackboxWrite(','); + + for (additionalHeader = blackboxAdditionalFieldsTricopter[headerXmitIndex]; *additionalHeader; additionalHeader++) + blackboxWrite(*additionalHeader); + } + blackboxWrite('\n'); headerXmitIndex++; charXmitIndex = 0; @@ -626,6 +703,8 @@ void handleBlackbox(void) charXmitIndex = i; } } else { + //Completed sending field information + if (feature(FEATURE_GPS)) { blackboxState = BLACKBOX_STATE_SEND_GPS_HEADERS; } else { @@ -678,29 +757,8 @@ void handleBlackbox(void) headerXmitIndex++; break; case BLACKBOX_STATE_RUNNING: - // Copy current system values into the blackbox to be written out - blackboxCurrent = blackboxHistory[0]; - - blackboxCurrent->time = currentTime; - - for (i = 0; i < motorCount; i++) - blackboxCurrent->motor[i] = motor[i]; - - for (i = 0; i < 3; i++) - blackboxCurrent->axisP[i] = axisP[i]; - for (i = 0; i < 3; i++) - blackboxCurrent->axisI[i] = axisI[i]; - for (i = 0; i < 3; i++) - blackboxCurrent->axisD[i] = axisD[i]; - - for (i = 0; i < 4; i++) - blackboxCurrent->rcCommand[i] = rcCommand[i]; - - for (i = 0; i < 3; i++) - blackboxCurrent->gyroData[i] = gyroData[i]; - - for (i = 0; i < 3; i++) - blackboxCurrent->accSmooth[i] = accSmooth[i]; + // Copy current system values into the blackbox + loadBlackboxState(); // Write a keyframe every 32 frames so we can resynchronise upon missing frames int blackboxIntercycleIndex = blackboxIteration % 32; diff --git a/src/main/blackbox/blackbox.h b/src/main/blackbox/blackbox.h index 19aeabbdc6..cd8f326c34 100644 --- a/src/main/blackbox/blackbox.h +++ b/src/main/blackbox/blackbox.h @@ -27,7 +27,8 @@ typedef struct blackbox_values_t { int16_t rcCommand[4]; int16_t gyroData[3]; int16_t accSmooth[3]; - int16_t motor[8]; + int16_t motor[MAX_SUPPORTED_MOTORS]; + int16_t servo[MAX_SUPPORTED_SERVOS]; } blackbox_values_t; void initBlackbox(void); diff --git a/src/main/blackbox/blackbox_fielddefs.h b/src/main/blackbox/blackbox_fielddefs.h index e89b152d1e..a38495b42e 100644 --- a/src/main/blackbox/blackbox_fielddefs.h +++ b/src/main/blackbox/blackbox_fielddefs.h @@ -41,6 +41,9 @@ //Predict this GPS co-ordinate is the GPS home co-ordinate (or no prediction if that coordinate is not set) #define FLIGHT_LOG_FIELD_PREDICTOR_HOME_COORD 7 +//Predict 1500 +#define FLIGHT_LOG_FIELD_PREDICTOR_1500 8 + #define FLIGHT_LOG_FIELD_ENCODING_SIGNED_VB 0 #define FLIGHT_LOG_FIELD_ENCODING_UNSIGNED_VB 1 From 5cc3ad3da78f8f644b2d761eefffa47387ccb38b Mon Sep 17 00:00:00 2001 From: Nicholas Sherlock Date: Wed, 10 Dec 2014 15:35:36 +1300 Subject: [PATCH 03/24] New encoding for PID I terms which saves 2 bytes per frame --- src/main/blackbox/blackbox.c | 169 ++++++++++++++++++++++--- src/main/blackbox/blackbox_fielddefs.h | 7 +- 2 files changed, 154 insertions(+), 22 deletions(-) diff --git a/src/main/blackbox/blackbox.c b/src/main/blackbox/blackbox.c index a6b059cd56..b5cd03eaf5 100644 --- a/src/main/blackbox/blackbox.c +++ b/src/main/blackbox/blackbox.c @@ -195,7 +195,7 @@ static const char * const blackboxHeaderFields[] = { ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," /* PIDs: */ ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," - ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," + ENCODING(TAG2_3S32) "," ENCODING(TAG2_3S32) "," ENCODING(TAG2_3S32) "," ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," /* rcCommand[0..3] */ ENCODING(TAG8_4S16) "," ENCODING(TAG8_4S16) "," ENCODING(TAG8_4S16) "," @@ -340,15 +340,134 @@ static void writeSignedVB(int32_t value) writeUnsignedVB((uint32_t)((value << 1) ^ (value >> 31))); } -#define FIELD_ZERO 0 -#define FIELD_4BIT 1 -#define FIELD_8BIT 2 -#define FIELD_16BIT 3 +/** + * Write a 2 bit tag followed by 3 signed fields of 2, 4, 6 or 32 bits + */ +static void writeTag2_3S32(int32_t *values) { + static const int NUM_FIELDS = 3; + + //Need to be enums rather than const ints if we want to switch on them (due to being C) + enum { BITS_2 = 0}; + enum { BITS_4 = 1}; + enum { BITS_6 = 2}; + enum { BITS_32 = 3}; + + enum { BYTES_1 = 0}; + enum { BYTES_2 = 1}; + enum { BYTES_3 = 2}; + enum { BYTES_4 = 3}; + + int x; + int selector = BITS_2, selector2; + + /* + * Find out how many bits the largest value requires to encode, and use it to choose one of the packing schemes + * below: + * + * Selector possibilities + * + * 2 bits per field ss11 2233, + * 4 bits per field ss00 1111 2222 3333 + * 6 bits per field ss11 1111 0022 2222 0033 3333 + * 32 bits per field sstt tttt followed by fields of various byte counts + */ + for (x = 0; x < NUM_FIELDS; x++) { + //Require more than 6 bits? + if (values[x] >= 32 || values[x] < -32) { + selector = BITS_32; + break; + } + + //Require more than 4 bits? + if (values[x] >= 8 || values[x] < -8) { + if (selector < BITS_6) + selector = BITS_6; + } else if (values[x] >= 2 || values[x] < -2) { //Require more than 2 bits? + if (selector < BITS_4) + selector = BITS_4; + } + } + + switch (selector) { + case BITS_2: + blackboxWrite((selector << 6) | ((values[0] & 0x03) << 4) | ((values[1] & 0x03) << 2) | (values[2] & 0x03)); + break; + case BITS_4: + blackboxWrite((selector << 6) | (values[0] & 0x0F)); + blackboxWrite((values[1] << 4) | (values[2] & 0x0F)); + break; + case BITS_6: + blackboxWrite((selector << 6) | (values[0] & 0x3F)); + blackboxWrite((uint8_t)values[1]); + blackboxWrite((uint8_t)values[2]); + break; + case BITS_32: + /* + * Do another round to compute a selector for each field, assuming that they are at least 8 bits each + * + * Selector2 field possibilities + * 0 - 8 bits + * 1 - 16 bits + * 2 - 24 bits + * 3 - 32 bits + */ + selector2 = 0; + + //Encode in reverse order so the first field is in the low bits: + for (x = NUM_FIELDS - 1; x >= 0; x--) { + selector2 <<= 2; + + if (values[x] < 128 && values[x] >= -128) + selector2 |= BYTES_1; + else if (values[x] < 32768 && values[x] >= -32768) + selector2 |= BYTES_2; + else if (values[x] < 8388608 && values[x] >= -8388608) + selector2 |= BYTES_3; + else + selector2 |= BYTES_4; + } + + //Write the selectors + blackboxWrite((selector << 6) | selector2); + + //And now the values according to the selectors we picked for them + for (x = 0; x < NUM_FIELDS; x++, selector2 >>= 2) { + switch (selector2 & 0x03) { + case BYTES_1: + blackboxWrite(values[x]); + break; + case BYTES_2: + blackboxWrite(values[x]); + blackboxWrite(values[x] >> 8); + break; + case BYTES_3: + blackboxWrite(values[x]); + blackboxWrite(values[x] >> 8); + blackboxWrite(values[x] >> 16); + break; + case BYTES_4: + blackboxWrite(values[x]); + blackboxWrite(values[x] >> 8); + blackboxWrite(values[x] >> 16); + blackboxWrite(values[x] >> 24); + break; + } + } + break; + } +} /** * Write an 8-bit selector followed by four signed fields of size 0, 4, 8 or 16 bits. */ static void writeTag8_4S16(int32_t *values) { + + //Need to be enums rather than const ints if we want to switch on them (due to being C) + enum { FIELD_ZERO = 0}; + enum { FIELD_4BIT = 1}; + enum { FIELD_8BIT = 2}; + enum { FIELD_16BIT = 3}; + uint8_t selector; int x; @@ -468,7 +587,7 @@ static void writeIntraframe(void) static void writeInterframe(void) { int x; - int32_t rcDeltas[4]; + int32_t deltas[4]; blackbox_values_t *blackboxCurrent = blackboxHistory[0]; blackbox_values_t *blackboxLast = blackboxHistory[1]; @@ -487,19 +606,25 @@ static void writeInterframe(void) writeSignedVB(blackboxCurrent->axisP[x] - blackboxLast->axisP[x]); for (x = 0; x < 3; x++) - writeSignedVB(blackboxCurrent->axisI[x] - blackboxLast->axisI[x]); + deltas[x] = blackboxCurrent->axisI[x] - blackboxLast->axisI[x]; + /* + * The PID I field changes very slowly, most of the time +-2, so use an encoding + * that can pack all three fields into one byte in that situation. + */ + writeTag2_3S32(deltas); + for (x = 0; x < 3; x++) writeSignedVB(blackboxCurrent->axisD[x] - blackboxLast->axisD[x]); for (x = 0; x < 4; x++) - rcDeltas[x] = blackboxCurrent->rcCommand[x] - blackboxLast->rcCommand[x]; + deltas[x] = blackboxCurrent->rcCommand[x] - blackboxLast->rcCommand[x]; /* - * RC tends to stay the same or very small for many frames at a time, so use an encoding that + * RC tends to stay the same or fairly small for many frames at a time, so use an encoding that * can pack multiple values per byte: */ - writeTag8_4S16(rcDeltas); + writeTag8_4S16(deltas); //Since gyros, accs and motors are noisy, base the prediction on the average of the history: for (x = 0; x < 3; x++) @@ -729,27 +854,39 @@ void handleBlackbox(void) blackboxPrintf("H Firmware type:Cleanflight\n"); break; case 1: - blackboxPrintf("H Firmware revision:%s\n", shortGitRevision); + // Pause to allow more time for previous to transmit (it exceeds our chunk size) break; case 2: - blackboxPrintf("H Firmware date:%s %s\n", buildDate, buildTime); + blackboxPrintf("H Firmware revision:%s\n", shortGitRevision); break; case 3: - blackboxPrintf("H rcRate:%d\n", masterConfig.controlRateProfiles[masterConfig.current_profile_index].rcRate8); + // Pause to allow more time for previous to transmit break; case 4: - blackboxPrintf("H minthrottle:%d\n", masterConfig.escAndServoConfig.minthrottle); + blackboxPrintf("H Firmware date:%s %s\n", buildDate, buildTime); break; case 5: - blackboxPrintf("H maxthrottle:%d\n", masterConfig.escAndServoConfig.maxthrottle); + // Pause to allow more time for previous to transmit break; case 6: + blackboxPrintf("H rcRate:%d\n", masterConfig.controlRateProfiles[masterConfig.current_profile_index].rcRate8); + break; + case 7: + blackboxPrintf("H minthrottle:%d\n", masterConfig.escAndServoConfig.minthrottle); + break; + case 8: + blackboxPrintf("H maxthrottle:%d\n", masterConfig.escAndServoConfig.maxthrottle); + break; + case 9: floatConvert.f = gyro.scale; blackboxPrintf("H gyro.scale:0x%x\n", floatConvert.u); break; - case 7: + case 10: blackboxPrintf("H acc_1G:%u\n", acc_1G); break; + case 11: + // One more pause for good luck + break; default: blackboxState = BLACKBOX_STATE_RUNNING; } diff --git a/src/main/blackbox/blackbox_fielddefs.h b/src/main/blackbox/blackbox_fielddefs.h index a38495b42e..1e0dbce1e7 100644 --- a/src/main/blackbox/blackbox_fielddefs.h +++ b/src/main/blackbox/blackbox_fielddefs.h @@ -47,11 +47,6 @@ #define FLIGHT_LOG_FIELD_ENCODING_SIGNED_VB 0 #define FLIGHT_LOG_FIELD_ENCODING_UNSIGNED_VB 1 -#define FLIGHT_LOG_FIELD_ENCODING_U8 2 -#define FLIGHT_LOG_FIELD_ENCODING_U16 3 -#define FLIGHT_LOG_FIELD_ENCODING_U32 4 -#define FLIGHT_LOG_FIELD_ENCODING_S8 5 -#define FLIGHT_LOG_FIELD_ENCODING_S16 6 -#define FLIGHT_LOG_FIELD_ENCODING_S32 7 +#define FLIGHT_LOG_FIELD_ENCODING_TAG2_3S32 7 #define FLIGHT_LOG_FIELD_ENCODING_TAG8_4S16 8 #define FLIGHT_LOG_FIELD_ENCODING_NULL 9 From e47a82add8710d588848306b43a3bfc210af5853 Mon Sep 17 00:00:00 2001 From: Nicholas Sherlock Date: Wed, 10 Dec 2014 15:35:49 +1300 Subject: [PATCH 04/24] Version 0.1.2 --- obj/cleanflight_NAZE.hex | 11585 +++++++++++++++++++------------------ 1 file changed, 5801 insertions(+), 5784 deletions(-) diff --git a/obj/cleanflight_NAZE.hex b/obj/cleanflight_NAZE.hex index ac1771b1cb..21712cb525 100644 --- a/obj/cleanflight_NAZE.hex +++ b/obj/cleanflight_NAZE.hex @@ -1,24 +1,24 @@ :020000040800F2 -:100000000050002025F70008D1F7000821E1000882 -:10001000D1F70008D1F70008D1F700080000000070 -:10002000000000000000000000000000D1F7000800 -:10003000D1F7000800000000D1F7000811E1000826 -:10004000D1F70008D1F70008D1F70008D1F7000870 -:10005000D1F70008D1F70008D1F7000865DF0008E4 -:10006000D1F70008D1F70008D1F70008D1F7000850 -:10007000D1F70008D1F7000825DF0008D1F7000804 -:1000800069DF0008D1F70008D1F70008D1F70008B0 -:10009000D1F70008D1F70008D1F7000861DF0008A8 -:1000A000D1F7000839DE0008D1F7000849DE000862 -:1000B00029DE000819DE000809DE0008A5DF0008B7 -:1000C0009DDF0008A1DF000899DF0008D1F70008D4 -:1000D000D1F70008E1DE000859DE0008D1F700087A -:1000E000A9DF0008D1F70008D1F7000800000000E0 +:1000000000500020ADF9000859FA0008A9E30008E3 +:1000100059FA000859FA000859FA000800000000CF +:1000200000000000000000000000000059FA000875 +:1000300059FA00080000000059FA000899E3000886 +:1000400059FA000859FA000859FA000859FA000844 +:1000500059FA000859FA000859FA0008EDE10008B9 +:1000600059FA000859FA000859FA000859FA000824 +:1000700059FA000859FA0008ADE1000859FA0008D9 +:10008000F1E1000859FA000859FA000859FA000885 +:1000900059FA000859FA000859FA0008E9E100087D +:1000A00059FA0008C1E0000859FA0008D1E0000838 +:1000B000B1E00008A1E0000891E000082DE200088E +:1000C00025E2000829E2000821E2000859FA0008A8 +:1000D00059FA000869E10008E1E0000859FA00084F +:1000E00031E2000859FA000859FA0008000000003F :1000F0000000000000000000000000000000000000 :0C01000000000000000000005FF808F1A3 :100110002DE9F04F734B744D9FB02B6000236B6043 -:100120000AF0C8FF18B908F05FFA0AF0E5FF0DF011 -:10013000A9FC002308936D4C09930A934FF4E01334 +:100120000BF0C3FB18B907F0EBF90BF0E1FB0DF096 +:10013000EDFD002308936D4C09930A934FF4E013EF :100140000B9323686A4943F480338A7B2360A36955 :10015000894643F01003A361236803F40033099335 :10016000089B01330893099B1BB9089BB3F5A06F4B @@ -45,34 +45,34 @@ :1002B00005E0526812F4003F3A6818BF52085143F3 :1002C00019606268C2F303123A4492F804B01A68E3 :1002D00022FA0BFB0A4AC3F800B03B68934217D1DD -:1002E000012219E0D54F00085807002000100240F5 -:1002F0002C20002000200240240000200410014097 -:1003000000127A00001BB700A400002000093D0085 +:1002E000012219E0955A0008D406002000100240AF +:1002F0003020002000200240240000200410014093 +:1003000000127A00001BB700A800002000093D0081 :10031000B24A934202D10222B14B1A70DFF800A315 :10032000B04B1EAECAF80C30A3694FF0000843F082 :100330000103A361636AAC4843F080736362A369FD :1003400043F01C03A3614FF6FF7326F82C3D3146A2 -:100350008DF84E800AF036FBA44831460AF032FB95 -:100360003146A3480AF02EFBA24B30465A6842F0B1 -:1003700000725A600CF05CF8139B9F4A6420B3FB38 +:100350008DF84E8009F0DEFAA448314609F0DAFA49 +:100360003146A34809F0D6FAA24B30465A6842F00B +:1003700000725A6006F08AFA139B9F4A6420B3FB0E :10038000F2F34FF47A72AB60BBFBF2FB9B4B0BF1C9 :10039000FF325A60F0228AF823200722C3F808802F -:1003A0001A6004F0F0FC96484146A02211F00DFDC1 +:1003A0001A6005F050FA96484146A02211F099FDD6 :1003B000E36943F00703E361A36943F4006343F097 :1003C0000C03A3618F4B002103F10C0208F802100B :1003D00008F10108B8F10E0FF4D1FF229A76DA760F :1003E0001A775A77884B0FCB86E80F00A36908224B :1003F00043F00803A361A369139843F00803A361C2 -:100400007A4B14A91A6110221A610AF0DBFA1598C6 -:1004100016A90AF0D7FA724B73481A789846012A3F +:100400007A4B14A91A6110221A6109F083FA15981F +:1004100016A909F07FFA724B73481A789846012A98 :100420008CBF102314238DF84E304FF002038DF84B :100430004F30A3694FF4805243F00403ADF84C20D1 -:100440008CBF4FF0010A4FF0000AA36131460AF059 -:10045000B9FA6E4BBAF1000F01D06D4A00E06D4A57 -:1004600000201A6004F099FC6B4B93E80300A36929 -:1004700086E8030043F0080314A9A36113980AF067 -:10048000A1FA0CF0D1FB9F238DF8383032200023E5 -:100490008DF839308DF83A308DF83B3004F073FC2C +:100440008CBF4FF0010A4FF0000AA361314609F05A +:1004500061FA6E4BBAF1000F01D06D4A00E06D4AAF +:1004600000201A6005F0F9F96B4B93E80300A369CB +:1004700086E8030043F0080314A9A361139809F068 +:1004800049FA0BF041F99F238DF8383032200023D0 +:100490008DF839308DF83A308DF83B3005F0D3F9CE :1004A000524B4FF480525A61A3F554430EAA9B89D4 :1004B00005204FF47A7331469246013823D01AB1A1 :1004C00092F800E0013208E04FF0FF0E05E003F182 @@ -82,34 +82,34 @@ :1005000001339BB2EB83DFF8E4B04FF48053CBF8B8 :1005100010309DF84E109DF84D20090241EA02412D :100520009DF84F2011433D4A914214D0CBF814302E -:10053000F52002930BF0E1F9FF200BF0DEF9029BAE +:10053000F52002930CF042FFFF200CF03FFF029BDE :100540007028CBF8103006D198F80030022B02D179 :10055000234B03221A7098F800B0BBF1030F02D0AE -:10056000012006F0EBFCD9F80820DFF8988002F4AF +:10056000012007F0D1F9D9F80820DFF8988002F4CB :1005700000434FF0100C02F4006204920021624626 -:1005800008F120000293CDF80CC011F01EFC0022EF +:1005800008F120000293CDF80CC011F0AAFC002263 :100590008DF83B200422DDF80CC0072085F82020D0 :1005A0000122022185F8230093458DF83A10ADF819 :1005B00038C085F82220029B36D94FF0300EADF8B6 :1005C00038E04FF0050E88F828E088F8292088F8F0 :1005D0002A2088F82B00884627E000BF001BB700C0 -:1005E000D72700200005FA0500080140000C014053 +:1005E000D62700200005FA0500080140000C014054 :1005F000001001400000014040420F0010E000E008 -:10060000CC1E002058070020EC440108DC27002005 -:100610005146000865460008FC44010815202000EA +:10060000D01E0020D406002004460108D827002070 +:10061000E1500008F550000814460108152020009C :1006200000ED00E00038004090469BB1BDF8383046 :1006300085F8258043F00203ADF83830012308EB3C :10064000030285F8243085F82630072385F8273003 -:100650005FFA82F8854851460BF03CFF049BABB132 -:10066000022383485146ADF838300BF033FF09239D +:100650005FFA82F88548514604F063FD049BABB114 +:10066000022383485146ADF8383004F05AFD09237F :10067000012285F82C3085F82E2008F1010307228D :1006800085F82D8085F82F205FFA83F86369794813 :1006900043F001036361A369764D43F40073A361E2 -:1006A00004F02AF8744B00241393744BB8F1010F33 +:1006A00004F0BCFD744B00241393744BB8F1010F9C :1006B00014930CBF2346802318934FF4807319932F :1006C0004FF480631A93202331461B9328464FF43E -:1006D00000531C931594CDF8588017941D9403F083 -:1006E000EDFF2B68B8F1010F43F001032B60644B61 +:1006D00000531C931594CDF8588017941D9404F082 +:1006E0007FFD2B68B8F1010F43F001032B60644BD1 :1006F00098BF00215A6888BF012122F4702222F499 :10070000807242EA01225A6099685E4A20460A4095 :1007100042F4602242F002029A60D96A08F1FF3284 @@ -134,40 +134,40 @@ :1008400013F00403FAD19168B9F8E60041F4A0016D :1008500091600E4AE8B9B2F9E830CBB9B2F9EA30A2 :10086000D3F1010338BF002313E000BF00080140AB -:10087000000C0140080002404C2401408807002081 -:1008800000240140FDF7F1FF780700202C20002014 +:10087000000C0140080002404C2401400407002005 +:1008800000240140FDF7F1FFF40600203020002095 :10089000034613F0010340F081803B7500B20EF077 -:1008A00073F9AB490EF0C4F9AA4C0646B4F9E80056 -:1008B0000EF06AF9A6490EF0BBF90546B4F9EA0054 -:1008C0000EF062F9A2490EF0B3F90446304611F079 -:1008D000ABFC0746304611F01BFD8046284611F060 -:1008E000A3FC0646284611F013FD0546204611F0EC -:1008F0009BFC8246204611F00BFD3946814650464E -:100900000EF096F93946834648460EF091F9514665 -:10091000049040460EF08CF94946059040460EF092 -:1009200087F93146079050460EF082F98A4C4946C5 -:10093000A06306F100400EF07BF92946E0632564D0 -:1009400005980EF075F9014604980EF069F82946ED -:10095000606407980EF06CF9014658460EF05EF898 -:100960003146A06408F100400EF062F92946E064C7 -:1009700058460EF05DF9014607980EF04FF82946EB -:10098000206504980EF054F9014605980EF048F8D9 -:100990003946606530460EF04BF9A0656D4B6E4DE3 -:1009A0009A6812F4003F18D0C8206A4C04F0EBF9A2 -:1009B00006F020FCC82004F0E6F904F58873002155 -:1009C0000C2205F16000EB6511F0FFF90CF0F0FC72 -:1009D00004F0CEF8614B0344AB66614B00211A680A +:1008A000B7FAAB490EF008FBAA4C0646B4F9E800CB +:1008B0000EF0AEFAA6490EF0FFFA0546B4F9EA00CA +:1008C0000EF0A6FAA2490EF0F7FA0446304611F0EF +:1008D00037FD0746304611F0A7FD8046284611F047 +:1008E0002FFD0646284611F09FFD0546204611F0D3 +:1008F00027FD8246204611F097FD39468146504635 +:100900000EF0DAFA3946834648460EF0D5FA5146DB +:10091000049040460EF0D0FA4946059040460EF04D +:10092000CBFA3146079050460EF0C6FA8A4C49463B +:10093000A06306F100400EF0BFFA2946E06325648B +:1009400005980EF0B9FA014604980EF0ADF9294663 +:10095000606407980EF0B0FA014658460EF0A2F90E +:100960003146A06408F100400EF0A6FA2946E06482 +:1009700058460EF0A1FA014607980EF093F9294661 +:10098000206504980EF098FA014605980EF08CF94F +:100990003946606530460EF08FFAA0656D4B6E4D9E +:1009A0009A6812F4003F18D0C8206A4C04F04BFF3C +:1009B0000BF0E3F8C82004F046FF04F5887300212B +:1009C0000C2205F16000EB6511F08BFA0BF047F992 +:1009D00004F060FE614B0344AB66614B00211A6872 :1009E000994642F00E021A605E4A5F4B12685948FF :1009F000B2F85220B0F8EE6005925C4A90F8ED70C3 :100A000011705B4903F10C0291F800A0594CBAF146 -:100A1000010F88BF1346EB6606F08CFEDFF8848179 +:100A1000010F88BF1346EB6607F0E8FADFF8848120 :100A20008346DFF884C108B3534BBB2EC8F80030AF :100A3000524BC8F80CC0C8F8043001D901230EE0AD :100A4000612E01D902230AE0292E01D9032306E0F1 :100A5000132E01D9042302E0092E05D90523434AA8 :100A60006375012313702CE00623F8E71920CDF8F5 -:100A70000CC004F088F9682015215A4606F058FB8E -:100A8000DDF80CC0002801F011823D4A622EC8F842 +:100A70000CC004F0E8FE682015215A4607F03EF845 +:100A8000DDF80CC0002801F010823D4A622EC8F843 :100A900000203C4AC8F80CC0C8F804203A4AC8F8FC :100AA000082000F0ED8240F2E482BC2E00F0E682E5 :100AB000B6F5807F40F0E78284F816B02B4801231A @@ -176,41 +176,41 @@ :100AE000110011003200B900DA00F200F200F20049 :100AF000F2000A00D9F8003023F00203C9F80030F0 :100B0000E0E0BAF1010F20D84FF000081EAB03F867 -:100B10002C2D53204146012206F0EEFC90B19DF8A9 +:100B10002C2D53204146012207F04AF990B19DF84F :100B20004C30E52B0ED11A4B1A4A85F870801A60AA :100B3000194A5A60042301223370184B97421A70E5 :100B400000F0C080BAF1010F30D9154B2FE000BF83 -:100B500035FA8E3C2C20002058070020404B4C00DA -:100B60004C020020E8030020D444010802040020C5 -:100B7000D72700202400002035730008F7760008EE -:100B80009D730008917700085F7700086A040020D1 -:100B900058040020A17400086B780008D8270020B2 -:100BA000E0440108EC03002090C1793D8B4BDFF855 -:100BB0005882EB6606F0BEFD00284AD0062113AB32 -:100BC00068200A4606F098FC9DF84F309DF851B019 +:100B500035FA8E3C30200020D4060020404B4C005B +:100B60004C020020E8030020EC45010802040020AC +:100B7000D627002024000020ED7B0008AF7F00086E +:100B8000557C000849800008178000086A0400208E +:100B900058040020597D000823810008D727002031 +:100BA000F8450108EC03002090C1793D8B4BDFF83C +:100BB0005882EB6607F01AFA00284AD0062113ABD8 +:100BC00068200A4607F0F4F89DF84F309DF851B0C0 :100BD00003F001035B000BF0010B43EA8B0B9DF864 :100BE0004D3003F001035BEA030B08D0BBF1010FAA :100BF00001D1002317E0BBF1020F0BD112E00EABC5 -:100C000068200C21012206F077FC9DF8383013F0A3 -:100C10000F0302D1052001F04AB9042B02D188F854 +:100C000068200C21012207F0D3F89DF8383013F04A +:100C10000F0302D1052001F049B9042B02D188F855 :100C200071B002E0012388F871306D4B6D4A1A6093 :100C30006D4A5A6095F87120002A14BF6E226F2207 :100C40001A726A4B02221A7097424FF001033370F6 :100C500038D0BAF1010F1DD800221EAB03F82C2D9D -:100C60001C200D21012206F047FC98B19DF84C3064 +:100C60001C200D21012207F0A3F898B19DF84C300B :100C70002A2B01D01A2B0DD1594A5D4985F87230C3 :100C800011605C490223516033700322574B974235 :100C90001A7017D000211EAB03F82C1D182001225A -:100CA00006F02AFC70B19DF84C30FB2B0AD14C4B5E +:100CA00007F086F870B19DF84C30FB2B0AD14C4B05 :100CB000514A1A60514A5A604C4B04221A70504BE8 :100CC00001221A70494B1B7843B90FB11F46FEE64B :100CD000D9F8003023F00203C9F80030BAF1010F4F -:100CE00005D10AF095FE474B4FF400525A610A2095 -:100CF00004F049F87720A02101220EAB06F0FCFB9E +:100CE00005D107F0C9FA474B4FF400525A610A2068 +:100CF00004F0A9FD7720A02101220EAB07F058F8DF :100D000038B995F884A0404EBAF1000F00F08A80FF -:100D100055E11E210122772006F00AFA4FF42F60D8 -:100D200004F026F80026A6F160010027C9B20222CD -:100D300013AB77208DF84C708DF84D7006F0DCFB0E +:100D100055E11E210122772006F0F0FE4FF42F60EE +:100D200004F086FD0026A6F160010027C9B2022268 +:100D300013AB77208DF84C708DF84D7007F038F8B4 :100D40009DF84D309DF84C1043EA01212E4B03F1E4 :100D50007402B1520236102EE5D1B3F882E00121BF :100D60000EF00F060EF47F4EA3F882E03A463B46A3 @@ -220,23 +220,23 @@ :100DA000F7D10132102AE3D146EA0E0EA5F882E00F :100DB0000029A6D1C3F303339E42A2D1134B42F2C2 :100DC00010721A805A80124A5A60124A9A60124A65 -:100DD000DA60124A1A61124A5BE100BFD44401088A -:100DE00058040020B95C0008B9760008D827002014 -:100DF000ED730008CF7700087D740008277800089D -:100E00006A0400200010014058070020A0020020C2 -:100E1000F772000811760008EF72000821760008CA -:100E2000E1A000089C4F0AF0F3FD4FF480450EA9A5 +:100DD000DA60124A1A61124A5BE100BFEC45010871 +:100DE00058040020D1780008717F0008D727002020 +:100DF000A57C000887800008357D0008DF8000089A +:100E00006A04002000100140D4060020A002002047 +:100E1000AD7B0008C97E0008A57B0008D97E0008CC +:100E2000398F00089C4F07F027FA4FF480450EA930 :100E300004233846ADF838508DF83A304FF4005856 -:100E400009F0C0FD954BC7F810805A6913A822F429 +:100E400008F068FD954BC7F810805A6913A822F482 :100E500070625A615A694FF0030942F400725A6194 :100E60000823139501258DF851308DF850A08DF889 -:100E7000525004F03DFF28230DA88DF834308DF832 -:100E800035908DF836A08DF8375004F0D7FE142039 -:100E900003F079FF0EAB7720D0212A4606F02CFB19 +:100E7000525009F0C5FE28230DA88DF834308DF8A6 +:100E800035908DF836A08DF8375009F099FE142072 +:100E900004F0D9FC0EAB7720D0212A4606F088FF5B :100EA0009DF83830A6F8A890552B86F89F307FD152 -:100EB000D1212A460EAB772006F01EFB9DF8383074 +:100EB000D1212A460EAB772006F07AFF9DF8383014 :100EC000772003F00F021B0986F8A02086F8A130D6 -:100ED000162213ABAA2106F00FFB9DF84C209DF8BB +:100ED000162213ABAA2106F06BFF9DF84C209DF85B :100EE0004D3043EA0223A6F888309DF84E209DF845 :100EF0004F3043EA0223A6F88A309DF850209DF82F :100F0000513043EA0223A6F88C309DF852209DF818 @@ -252,35 +252,35 @@ :100FA000414A9A60414ADA60414A1A61414A70E016 :100FB000414BC7F814801A6822F004021A601EAA76 :100FC000002302F82C3D04921E200A210122049BDA -:100FD00006F092FA384F38B19DF84C30482B03D1C7 +:100FD00006F0EEFE384F38B19DF84C30482B03D167 :100FE000364B03221A7003E03B6823F008033B6092 :100FF000334D95F8E2300BB1324A137095F8E33077 :101000000BB1314A137095F8E4300BB12B4A1370D1 :101010003B68990702D52D4B1B689847DFF8BC80C9 :101020002B4ED8F8003098473B6813F0080F1CD0BF :10103000059B4FF0640A0FFA83F898FBFAF94846CB -:101040000DF0A2FD83460AFB198000B20DF09CFD55 -:1010500020490DF0EDFD014658460DF0E1FC1E491A -:101060000DF0E6FDC6F8AC003AE00023C6F8AC305F +:101040000DF0E6FE83460AFB198000B20DF0E0FECB +:1010500020490DF031FF014658460DF025FE1E498E +:101060000DF02AFFC6F8AC003AE00023C6F8AC3019 :1010700036E00A2E0BD0142E07D004E0012300E046 :101080000223A3751AE50323FBE70423F9E70523ED :10109000F7E75A6193E700BF0010014000000140EC -:1010A000A00200202173000881760008FF7200086A -:1010B0003176000839A200084C020020CB2700201E -:1010C0002C200020020400206A0400205804002084 -:1010D000580700208988883C00002041EC0300204C +:1010A000A0020020D97B0008397F0008B57B00082A +:1010B000E97E0008919000084C020020CF27002014 +:1010C00030200020020400206A0400205804002080 +:1010D000D40600208988883C00002041EC030020D1 :1010E000844B10225A6108221A614FF00A0ADFF875 :1010F00004921920D9F80C300AF1FF3A83F010035A :10110000C9F80C30D9F80C3083F00803C9F80C305A -:1011100003F039FE012003F040FE192003F033FEF6 -:10112000002003F03AFE1AF0FF0AE0D10823C9F8C4 +:1011100004F099FB012004F0A0FB192004F093FBDC +:10112000002004F09AFB1AF0FF0AE0D10823C9F866 :1011300010301023C9F810306F4BDFF8FC911B689A -:1011400093F90C000DF020FD6C490DF071FD11F0CC -:101150006BF88246B9F800000DF016FD51460DF00F -:1011600067FD11F097F8664B1880B9F800000DF094 -:101170000BFD014663480DF00FFE63490DF00CFEB8 -:10118000624B63491860C8685C490DF051FD6149C4 -:101190000DF04EFD604B6A791860604B60491A7023 +:1011400093F90C000DF064FE6C490DF0B5FE11F042 +:10115000F7F88246B9F800000DF05AFE51460DF03E +:10116000ABFE11F023F9664B1880B9F800000DF0C2 +:101170004FFE014663480DF053FF63490DF050FFE9 +:10118000624B63491860C8685C490DF095FE61497F +:101190000DF092FE604B6A791860604B60491A70DE :1011A000604B01EBC20292F83120C6F8B0305E4BC2 :1011B0001A60AA68920644BF01221A603B681B07A6 :1011C00040F1FF804B4B10225A61584A4FF0000803 @@ -288,34 +288,34 @@ :1011E0004FF0080E90698CBF4FF480414FF480514E :1011F0004EEA000090614F484FF0020298BF184637 :10120000ADF838108DF83B200EA904228DF83A2055 -:1012100009F0D8FB322003F0B6FD002111221E2078 -:1012200005F086FF012160221E2005F081FF642069 -:1012300003F0A9FD049806F09DF9C146C3460221BA -:1012400001221E2005F074FF322003F09CFD04985B -:1012500006F090F9BDF94C20BDF94E10BDF95030A3 +:1012100008F080FB322004F016FB002111221E2072 +:1012200006F06CFC012160221E2006F067FC6420A1 +:1012300004F009FB049806F0F9FDC146C3460221FB +:1012400001221E2006F05AFC322004F0FCFA049819 +:1012500006F0ECFDBDF94C20BDF94E10BDF9503043 :1012600093449142B8BF0A4698449A42B8BF134685 :1012700013F5805F89440ADD1E4BBAF1010ADA6872 :1012800082F01002DA60DAD14FF0010A01E04FF08B -:10129000000A1E200021122205F04AFF0A23022123 -:1012A00001221E20029305F043FF322003F06BFD64 -:1012B000049806F05FF9BDF94C10BDF94E00BDF978 +:10129000000A1E200021122206F030FC0A2302213F +:1012A00001221E20029306F029FC322004F0CBFA22 +:1012B000049806F0BBFDBDF94C10BDF94E00BDF918 :1012C0005020C1EB0B0B8842B8BF0146C2EB0808A7 :1012D0009142B8BF0A4612F5805FC0EB0909029B34 :1012E0002CDD044A013BD16881F01001D160D6D1D8 :1012F00026E000BF000C0140A404002035FA8E3C1B :10130000C80400200AE81C4100401C46C00300201D -:10131000EC030020BD378635A0040020A005002086 -:10132000D44401083C2000209C050020D727002041 +:10131000EC030020BD378635A00400209405002092 +:10132000EC4501084020002090050020D627002031 :101330000010024000100140000000204FF0000AA1 -:10134000AF4B584602930DF01FFC0146AD480DF01F -:1013500023FD20F00040A06148460DF015FC014639 -:10136000A8480DF019FD20F00040E06140460DF066 -:101370000BFC0146A4480DF00FFD20F00040206258 -:10138000002170221E2005F0D3FE012120221E2004 -:1013900005F0CEFE022100221E2005F0C9FE6420C9 -:1013A00003F0F1FC029BBAF1000F04D14FF07E5222 +:10134000AF4B584602930DF063FD0146AD480DF0DA +:1013500067FE20F00040A06148460DF059FD0146AF +:10136000A8480DF05DFE20F00040E06140460DF021 +:101370004FFD0146A4480DF053FE20F000402062CE +:10138000002170221E2006F0B9FB012120221E2020 +:1013900006F0B4FB022100221E2006F0AFFB642001 +:1013A00004F051FA029BBAF1000F04D14FF07E52C3 :1013B0009A61DA611A62954B10221A61944B0122EC -:1013C0001A700BF025FD0EA80021142210F0FDFC70 +:1013C0001A700AF0F1FE0EA80021142210F089FD17 :1013D0006B790E2B01D0082B02D101238DF84330FD :1013E0008C4A8C4C9368B4F8E000C3F380418DF8CC :1013F0003E108949C3F3400209688DF83D20C3F3CC @@ -347,50 +347,50 @@ :10159000606886F80091C6F80C41ADF84C308DF8C3 :1015A0004E10022304998DF84F3086F8B890C6F893 :1015B000BC90C6F8C090C6F8C490C6F8F89086F8FB -:1015C000FE9086F8FF90039209F0FCF9039A217BC4 -:1015D00052F80B004A460AF0E1FE204649464246D0 -:1015E0000AF070F9134B1449C6F81031134BC6F8C2 -:1015F0001891C6F8143120460A1D07F0ABFBBFE076 +:1015C000FE9086F8FF90039208F0A4F9039A217B1D +:1015D00052F80B004A4605F00FF9204649464246AC +:1015E0000AF0B0FA134B1449C6F81031134BC6F881 +:1015F0001891C6F8143120460A1D09F0ADF9BFE074 :101600002400002000406F4601C05E46000C0140EF -:10161000940200202C2000209C050020E8030020DC -:1016200058070020D4440108A0050020606001088C -:1016300000040040C19F0008680800209DA0000829 +:10161000940200203020002090050020E8030020E4 +:10162000D4060020EC4501089405002094610108CF +:1016300000040040198E0008E4070020F58E000821 :10164000B8F1020F43D10599B448CBB21C215943DC :101650004FF0000300EB010989F8023089F80A30E5 :10166000059B94F80FE089F8013001234354A168E9 :101670006068C9F80C40ADF84C1004998DF84EE044 -:10168000029303928DF84F8009F09CF9039A217B15 -:1016900052F80B0000220AF081FE029B20461A46F7 -:1016A00000210AF00FF99E4B0020C9F810309D4B25 +:10168000029303928DF84F8008F044F9039A217B6E +:1016900052F80B00002205F0AFF8029B20461A46D4 +:1016A00000210AF04FFA9E4B0020C9F810309D4BE4 :1016B000C9F81800C9F81430204609F1100109F1E1 -:1016C000140207F047FB059C0134059458E0B8F17B +:1016C000140209F049F9059C0134059458E0B8F179 :1016D000030F39D19DF83E30DFF85C8233B198F8C2 :1016E000B690204608214FF6FF721CE0BDF844304A :1016F00098F8B690B3F5FA7F0FD98B4A2046B2FB23 -:10170000F3F20821BDF8483092B207F0FBFB08EB7A +:10170000F3F20821BDF8483092B20BF00BFD08EB64 :101710008903C3F8E001854B0EE0854A2046B2FB01 -:10172000F3F2012192B2BDF8483007F0EBFB08EB71 +:10172000F3F2012192B2BDF848300BF0FBFC08EB5C :101730008903C3F8E0017F4BC3607F4B93F8B62069 :10174000013283F8B6201BE0B8F1040F18D1BDF8C0 :101750004630774ADFF8E08192FBF3F22046BDF88D -:101760004A30012192B298F8B59007F0CBFB08EB14 +:101760004A30012192B298F8B5900BF0DBFC08EBFF :101770008903C3F8100298F8B530013388F8B53002 :101780000AF1020ABAF11C0F7FF494AE9BE66B4B90 :1017900006EB030E98E80F008EE80F00684B10363A :1017A0001A78C02E02F101021A7009D0D4F8B030B4 -:1017B0000021985903EB06080DF0CEFB0028E6D077 +:1017B0000021985903EB06080DF012FD0028E6D031 :1017C000AB68DB0420D419E05E4B5D4A03EBC90330 :1017D00093F830C0D3F8348082F800C0B8F1000F1D :1017E000EED000266645EBDA544A330103EB020ED5 :1017F00043440FCB01368EE80F00F3E7B9F1080F31 :10180000DFF86C8128D12AE04D4B93F800A0BAF1A3 :10181000010FF3D94C4E4FF00008D04506F11006E9 -:10182000ECDA56F8100C4FF07C510DF001FA4FF045 -:101830007C5146F8100C56F8140C0DF0F9F94FF0E5 -:101840007C5146F8140C56F80C0C0DF0F1F908F127 +:10182000ECDA56F8100C4FF07C510DF045FB4FF000 +:101830007C5146F8100C56F8140C0DF03DFB4FF09F +:101840007C5146F8140C56F80C0C0DF035FB08F1E1 :10185000010846F80C0CE0E7B9F10E0F04D198F836 :10186000003043F0100303E098F8003023F0100339 -:1018700088F800300CF09AF83449354B3548364A30 +:1018700088F800300BF0BCFE3449354B3548364A09 :10188000C4F8F43201600023B5F81A01C4F8F0126C :10189000A4F8FA3284F8FC32C4F80023C4F8042314 :1018A0002E4958520233242BFAD12D4B1A60AB68C3 @@ -399,23 +399,23 @@ :1018D0004FF0030208D184F80823072284F80A3362 :1018E00084F809230C2308E0022384F8083300233A :1018F00084F80A3384F80923072384F80B33002380 -:1019000000931020012318494FF4E1320BF022F923 -:10191000164BC4F81003C4F8143370E058080020C4 -:10192000D9C30008959F000800127A00BDA00008E6 -:1019300040420F00ADA00008580700208809002091 -:10194000E1270020D4440108900900203C21002018 -:10195000CC4501083C0100204C0A00201A07002059 -:10196000400200202C200020054C000859450008AA +:1019000000931020012318494FF4E13209F092FEB0 +:10191000164BC4F81003C4F8143370E0D407002049 +:1019200035680008ED8D000800127A00158F000858 +:1019300040420F00058F0008D40600200409002053 +:10194000E1270020EC4501080C090020402100207F +:10195000E44601083C010020C8090020960600204A +:101960004002002030200020C9560008E94F00083E :10197000820200200123574A574900931020052373 -:101980000BF0E8F8C4F818030646B5F81A010DF094 -:10199000FBF852490DF04CF951490DF03FF80DF0AC -:1019A00033FB00234F4A98500433402BFAD14E4B5F +:1019800009F058FEC4F818030646B5F81A010DF020 +:101990003FFA52490DF090FA51490DF083F90DF0DC +:1019A00077FC00234F4A98500433402BFAD14E4B1A :1019B000301CC4F814334FF0100384F80B331FE0CD -:1019C00000920123102049494FF4E1320BF0C2F894 +:1019C00000920123102049494FF4E13209F032FE20 :1019D000474BC4F81C03C4F8143310230DE00092E5 -:1019E0000123102043494FF4E1320BF0B3F8424B8E +:1019E0000123102043494FF4E13209F023FE424B1A :1019F000C4F82003C4F81433082384F80B330030F0 -:101A000018BF012028B9082008F0B1FD0023C4F850 +:101A000018BF012028B9082007F059FD0023C4F8A9 :101A10001433AB68580405D5082284F80B23374AE1 :101A2000C4F8142342F201021A4003F0010103F446 :101A300000505AB1324AC4F8142318B1314A082070 @@ -424,27 +424,27 @@ :101A6000D5F83811C3F824230023284A02EB0310C9 :101A7000D0F824011646884204D00133DBB2042B8F :101A8000F3D9002384F82933214B0020C4F84433D0 -:101A90000AF0A4F81F4B94F829231B680021C4F80E +:101A900003F090F91F4B94F829231B680021C4F828 :101AA000303395F8283106EB02128B42C4F82C1320 :101AB0004FF020000091D2F824210CBF0123032312 -:101AC0000BF048F8C4F8480330BB802008F04FFD05 -:101AD00025E000BFA0860100114D0008CDCCCC3F11 -:101AE0000000B0445C0100200D4600089D4C000839 -:101AF000FD450008514C0008E9450008394600083A -:101B0000454600085807002058210020D444010809 -:101B1000542100202820002001200AF05FF88C4B7F -:101B200018688C4B00F5D97204301A6008F058FE22 -:101B3000AB689A050CD59E044CBF8748874809F0CE -:101B400001FF3B68002243F010033B60844B1A60A6 -:101B5000844B8549D4F800230B608033C4F84C33A0 -:101B6000824B834E1A60AB680027D803377040F170 -:101B7000B380DFF828B2DFF828A208F06DFD08F086 -:101B8000A7FD08F081FD40F22A334FF001091A4603 -:101B90005846394686F80090029310F016F9DAF8A4 -:101BA0001820744842F00402CAF818204022ADF808 +:101AC00009F0B8FDC4F8480330BB802007F0F7FCEC +:101AD00025E000BFA0860100D5570008CDCCCC3F43 +:101AE0000000B0445C0100209D50000861570008D0 +:101AF0008D5000081557000879500008C95000089B +:101B0000D5500008D40600205C210020EC450108D7 +:101B1000582100202C200020012003F04BF98C4B91 +:101B2000186800F5D9730430C4F84C3307F000FE90 +:101B3000AB689A050CD59E044CBF8648864809F0D0 +:101B40009BFF3B68002243F010033B60834B1A600D +:101B5000834B8449D4F800230B608033C4F850339E +:101B6000814B824E1A60AB680027D803377040F172 +:101B7000B380DFF824B2DFF824A207F015FD07F0E8 +:101B80004FFD07F029FD40F22A334FF001091A46B4 +:101B90005846394686F80090029310F0A2F9DAF818 +:101BA0001820734842F00402CAF818204022ADF809 :101BB000302018228DF833200CA903228DF8322012 -:101BC0000AF088FCDAF81C206B4E42F00202CAF8D8 -:101BD0001C206A4AAAF6947A1168694AB1FBF2F1AC +:101BC00003F0AFFADAF81C206A4E42F00202CAF8BB +:101BD0001C20694AAAF6947A1168684AB1FBF2F1AE :101BE0003288013922F45C721204120C328089B2FC :101BF0001D22B2853185A6F81490328C22F00102A4 :101C00001204120C3284328CB088318B22F0020222 @@ -452,99 +452,99 @@ :101C200080B242EA0902B0803183B7863284328BB7 :101C300022F008021204120C42F008023283B6F8B5 :101C400044206FEA42426FEA524292B2A6F8442020 -:101C5000DAF8A82F42EA0902CAF8A82F504602F083 -:101C60004BFD484A029B1392802218924FF48072D7 +:101C5000DAF8A82F42EA0902CAF8A82F504603F082 +:101C6000DDFA474A029B1392802218924FF4807249 :101C7000CDF850B019924FF0100B4FF4005250466F :101C800004991C92CDF854B0169317971A971B9786 -:101C90001D9702F013FDB2890DA892B242F40072B2 +:101C90001D9703F0A5FAB2890DA892B242F4007222 :101CA000B281DAF8002042F00202CAF800208DF872 -:101CB00034B08DF835908DF836708DF8379003F08C -:101CC000BDFF314B1A68314BFA500437802FF8D1E1 -:101CD00003F0DEFE03F0DCFEAB68590540F19280B4 -:101CE00008F0A0FC08B1082000E00420012109F060 -:101CF000B4F9AB6884F87A0613F4806F244E01D1EE +:101CB00034B08DF835908DF836708DF8379008F087 +:101CC0007FFF304B1A68304BFA500437802FF8D121 +:101CD00002F0E4FE02F0E2FEAB68590540F19180AB +:101CE00007F048FC08B1082000E00420012106F0BC +:101CF00060FFAB6884F87E0613F4806F234E01D139 :101D000000201DE033681B78032B05D133681B7856 -:101D1000032B0BD0012013E0042009F00EF901463B -:101D2000042008F0D9FF0028F0D1E9E7082009F0E5 -:101D300004F90146082008F0CFFF003018BF012049 -:101D4000144B36681870337863BB134B1E604DE03C -:101D5000E80300208C050020444601085046010895 -:101D6000A0000020802100209406002040070020D1 -:101D7000840600200008014000040040A400002068 -:101D800000366E0134040040984401089806002093 -:101D9000AC050020A8050020D4050020A80A0020DA -:101DA00000100240012B21D1434F002138462C2244 -:101DB000C4F87C6610F009F88E237B704FF07C0A23 -:101DC000E0234FF07D09FB7087F800A087F82B9087 -:101DD0003A4F002138462C220FF0F7FF8A237B7000 -:101DE000A02387F800A0FB7087F82B903378022B94 -:101DF00008BFC4F8806608F015FC08B1C4F8846612 -:101E00000BF0B8F8AB6813F4002300D0012384F87A -:101E10008A3602F0ADFE2A4B18606B79052B03D190 -:101E2000284B4FF4C8721A80274B4FF47A721A80ED -:101E3000264BC8221A8098F8003043F0080388F82F -:101E40000030234B1A7822F002021A70AB689A070E -:101E50001ED5204B204A1D461A6002F093FD282013 -:101E600002F091FF069901390691F6D129681B4BC2 -:101E700048781E7802460123964203D30133082B8B -:101E80000244F9D1164A13708A785343A4F888366D -:101E9000144B9B689B030CD594F8633043F001030B -:101EA00084F86330032384F8643002E0032002F0F6 -:101EB000A1FF1FB0BDE8F08FE80500201406002048 -:101EC000000500206C040020C8270020C027002047 -:101ED000D6270020BC05002030210020C0050020AE -:101EE000940000202C200020A14A2DE9F04F136817 +:101D1000032B0BD0012013E0042006F0BAFE01468D +:101D2000042006F085FD0028F0D1E9E7082006F040 +:101D3000B0FE0146082006F07BFD003018BF0120F0 +:101D4000134B36681870337853BB124B1E604CE04F +:101D5000E80300205C47010868470108A400002050 +:101D60008421002010060020BC060020020600206E +:101D70000008014000040040A800002000366E0169 +:101D800034040040B045010814060020A0050020DE +:101D90009C050020C8050020280A002000100240F1 +:101DA000012B22D100212C224348C4F8806610F078 +:101DB00098F88E234FF07C0984F885367D27E02340 +:101DC0003E4800212C2284F8873684F8849684F8D3 +:101DD000AF7610F086F88A2384F8B136A02384F811 +:101DE000B09684F8B33684F8DB763378022B08BFDC +:101DF000C4F8DC6607F0BEFB08B1C4F8E0660AF080 +:101E000085FAAB6813F4002300D0012384F8E6368A +:101E100003F040FC2A4B18606B79052B03D1294B4A +:101E20004FF4C8721A80284B4FF47A721A80274BED +:101E3000C8221A8098F8003043F0080388F8003070 +:101E4000234B1A7822F002021A70AB689A071ED54B +:101E5000204B214A1D461A6003F026FB282003F080 +:101E6000F2FC069901390691F6D129681B4B487896 +:101E70001E7802460123964203D30133082B024405 +:101E8000F9D1174A13708A785343A4F8E436154BF6 +:101E90009B689B030CD594F8633043F0010384F8EE +:101EA0006330032384F8643002E0032003F002FD72 +:101EB0001FB0BDE8F08F00BF580D0020840D00203A +:101EC000000500206C040020CC270020C42700203F +:101ED000D5270020B005002034210020B4050020C3 +:101EE0009800002030200020A14A2DE9F04F13680F :101EF000A04903F59C43A04D20330B60AB6885B02F :101F000013F4807F174604D09C4B1B681B681B6929 :101F10009847AB6842F201041C405CB9984E337894 -:101F200073B1964B1B681B681B6898470BF050FCFD -:101F3000347005E0934B1A7801321A700BF048FCAC +:101F200073B1964B1B681B681B6898470BF06AFAE5 +:101F3000347005E0934B1A7801321A700BF062FA94 :101F4000AB68DA0405D5904B1B68DB0701D40CF0B5 -:101F50003FF88E4B3C681868037CCBB18C4A013B40 +:101F500083F98E4B3C681868037CCBB18C4A013BFB :101F600032F91300A0F57A70B0F57A7FA8BF4FF46C -:101F70007A7020EAE0700CF007FE86490CF00CFF46 -:101F800085490CF055FE0DF03FF87E4B588039E046 +:101F70007A7020EAE0700CF04BFF86490DF050F8C3 +:101F800085490CF099FF0DF083F97E4B588039E0BC :101F9000AA68160436D57B4A5168611A002931DBDC :101FA00004F59C41203151607C494E797C4931F8DF :101FB0001660417CB6B296FBF1F0117A013101F066 :101FC0000F0111720A44507218466E4E06F1090252 :101FD0009A5C01331044102B80B2F6D100B290FB12 :101FE000F3F000B26428A8BF642020EAE0700CF08F -:101FF000CBFD6C490CF0D0FE67490CF019FE0DF0DA -:1020000003F87080AB68D80510D5674B9C42674CCD +:101FF0000FFF6C490DF014F867490CF05DFF0DF010 +:1020000047F97080AB68D80510D5674B9C42674C88 :1020100008D923681B681B6A984718B923681B688E :102020005B6A984723681B685B699847AA68DFF872 :1020300060A112F4805F504BB5F8DC10BAF90620AD :1020400007D0B3F81A31581A824207DD19448A4280 -:1020500002E0B3F81C319A42C0F2548401220021FC +:1020500002E0B3F81C319A42C0F2528401220021FE :1020600095F8238195F82401B5F81C61B5F81E7127 :102070000B463AF901409B08B442C4BF63F07F03AA :10208000DBB20231BC42B8BF43F040030829F0D1B3 :102090003C4C617E994204D1A17EF92903D80131DB :1020A00000E00021A1766376414B374F1978A1B942 :1020B0003B68D90707D582B93E4B1B78DB070CD5A7 -:1020C0000BF0E6F809E03B4B1B785E0705D510B135 -:1020D0000BF07EFF01E0002AFAD0A37E294A142BE0 +:1020C0000AF0A4FA09E03B4B1B785E0705D510B176 +:1020D0000CF0C2F801E0002AFAD0A37E294A142BA2 :1020E000354E40F09980334B18F100081B7818BF2B :1020F0004FF0010803F0040303F0FF0093B12C49F3 -:102100000B78002B00F08880537E5F2B01D10BF001 -:102110005FFFB8F1000F7FD0637E7D2B7CD10BF089 -:1021200057FF79E0537E572B0BD1244B4FF47A7233 +:102100000B78002B00F08880537E5F2B01D10CF000 +:10211000A3F8B8F1000F7FD0637E7D2B7CD10CF04B +:102120009BF879E0537E572B0BD1244B4FF47A72F6 :102130001A80234B1B6813F008036DD1214A1380CA :102140006AE0A968490745D55A2B43D11E4B197837 :1021500019B1187001221D4B4DE0D17E1C4B81F04E :102160000101D17609B1042245E0062243E000BF17 -:10217000BC270020440200202C2000204002002028 -:1021800038010020E40D0020500200203C01002016 -:102190001A07002000007A4400C07F44780700201E -:1021A000880700200000C842404B4C00580A00201D -:1021B00048000020D6270020E8030020C827002080 +:10217000C027002044020020302000204002002020 +:1021800038010020BC0D0020500200203C0100203E +:102190009606002000007A4400C07F44F406002028 +:1021A000040700200000C842404B4C00D409002026 +:1021B00048000020D5270020E8030020CC2700207D :1021C0004C020020E0040020990400209B04002021 -:1021D0009A0400205D2B00F01D835B2B00F01C8314 -:1021E0005E2B0AD1032218E3A72B40F05F83AA4B92 -:1021F0001A7842F004021A700EE0562B01D10AF050 -:1022000069FDA64A1378002B00F01D83637E6F2BB7 -:1022100040F013830BF03CF8AB685B0731D5E37EED +:1021D0009A0400205D2B00F01E835B2B00F01D8312 +:1021E0005E2B0AD1032219E3A72B40F05D83AA4B93 +:1021F0001A7842F004021A700EE0562B01D109F051 +:10220000D9FAA64A1378002B00F01E83637E6F2B49 +:1022100040F014830AF0FAF9AB685B0731D5E37E2E :102220009BB19F4B1B7858070FD59E4BBAF90620E0 :10223000B3F81C319A4208DD3B6813F0010304D166 :10224000994A32211180994AD3763B68D9030AD53D @@ -553,13 +553,13 @@ :1022700002F0040202F0FF011AB919708E4B01221C :102280001A70D6F80090002309F1750B3B6009F134 :10229000770698460BF1020303EB080113F80820B8 -:1022A0004B7816F8010C9A420AD2314609F0CCFB61 +:1022A0004B7816F8010C9A420AD2314602F0BAFD78 :1022B00030B116F8023C01229A403B6813433B6060 :1022C00008F10408B8F1A00F06F10406E2D17B4B37 :1022D0001B7843B13B68DFF8FC8113F0020F784EA6 :1022E00040F09A818FE109F21512019209F58B767F :1022F0009846019A16F8010C531C03EB080113F8D9 -:1023000008204B789A4228D2314609F09DFB20B331 +:1023000008204B789A4228D2314602F08BFD20B348 :10231000B0786C4B013800EB400096F804B01844DC :102320004FF00C0CF3780CFB0BFC00935F4B03F1AC :102330001C0909EB0C014A6882420ED0009A09F888 @@ -580,15 +580,15 @@ :10242000DFE801F0060F1B28315C6E80929CA6004D :1024300032781344FA2BA8BFFA2323EAE3733370EC :1024400007E072781344642BA8BF642323EAE37384 -:102450007370304602F064FBC4E0F27830461344F7 -:10246000642BA8BF642323EAE373F370216D02F0A9 -:1024700013FBB7E032791344642BA8BF642323EA2B +:102450007370304603F0F6F8C4E0F2783046134467 +:10246000642BA8BF642323EAE373F370216D03F0A8 +:10247000A5F8B7E032791344642BA8BF642323EA9C :10248000E3733371AEE072791344642BA8BF642305 :1024900023EAE3737371A5E0820200204800002064 -:1024A000D62700202C20002080040020E40D0020EE -:1024B00098040020990400209B040020D0270020CD -:1024C000540200204C4B01089805002028200020D1 -:1024D0009A0400204C020020040E0020616D4A780E +:1024A000D52700203020002080040020BC0D002013 +:1024B00098040020990400209B040020D4270020C9 +:1024C00054020020644C01088C0500202C200020C0 +:1024D0009A0400204C020020DC0D0020616D4A7837 :1024E0001A44C82AA8BFC82222EAE2724A700A78AF :1024F0001344C82BA8BFC82323EAE3730B7071E011 :10250000616DCA7A1A44C82AA8BFC82222EAE272B8 @@ -602,5547 +602,5564 @@ :1025800093752FE0012A2DD13AF910009B784FF472 :102590009662B0F5617F92FBF3F305DB40F6330200 :1025A0009042B8BF024601E04FF46172A2F5617239 -:1025B00092FBF3F3DBB2A84A581C0C29107011D11E -:1025C00094F858209A420DD0A44A042B28BF022325 -:1025D0000A2184F8583001FB0323A14A0633136013 -:1025E00002F0B8FA012303FA09F394F84C201343DC +:1025B00092FBF3F3DBB2A94A581C0C29107011D11D +:1025C00094F858209A420DD0A54A042B28BF022324 +:1025D0000A2184F8583001FB0323A24A0633136012 +:1025E00003F04AF8012303FA09F394F84C2013434B :1025F00084F84C3009F10109B9F1040F08F10C0815 -:102600007FF4BBAE66E6AB68D80514D5954B1B6866 +:102600007FF4BBAE66E6AB68D80514D5964B1B6865 :102610001B689B68984770B1D8F800309B070AD5B3 -:10262000338813F001020CD18F4943F00103E265B6 +:10262000338813F001020CD1904943F00103E265B5 :1026300022660B8006E03388012223F001033380F9 :1026400000E000223B68590710D57AB1328822F0A9 :10265000010102F0020289B292B2318052B9E26500 -:102660002266814A41F00201118003E0328822F0A3 -:102670000202328032887D4912F0030F4FF01000C1 +:102660002266824A41F00201118003E0328822F0A2 +:102670000202328032887E4912F0030F4FF01000C0 :1026800014BF48610861D8F8001011F00A0F21D07A -:10269000D80609D550070AD442F004023280744AA1 -:1026A0001088744A108002E022F0040232809806FA -:1026B000328806D5500607D46B4842F040020280AB -:1026C00002E022F040023280580603D5684A1288A0 -:1026D000A4F86420890640F18880674A127892073E -:1026E0007CD5664A1278042A78D913F4007C3288A3 -:1026F00012D002F010039BB2002B76D15A4922F07F -:10270000200242F010025E480A805E4A011D5370AA -:1027100008F09DFA022366E022F0100189B2580504 -:1027200031802ED5584B1B685889584BB3F900801F +:10269000D80609D550070AD442F004023280754AA0 +:1026A0001088754A108002E022F0040232809806F9 +:1026B000328806D5500607D46C4842F040020280AA +:1026C00002E022F040023280580603D5694A12889F +:1026D000A4F86420890640F18980684A127892073C +:1026E0007DD5674A1278042A79D913F4007C3288A0 +:1026F00012D002F010039BB2002B77D15B4922F07D +:10270000200242F010025F480A805F4A011D5370A8 +:1027100006F048F8022367E022F0100189B258055C +:1027200031802ED5594B1B685889594BB3F900801D :10273000B8F1000FB8BFC8F10008804509DAB3F955 :102740000230002BB8BF5B428342ACBF00230123A1 :1027500000E06346DB0714D502F0200292B2002AA3 -:1027600043D1484B4A485A704A4B41F020011A68FD -:102770005B683180011DA367626708F068FA012376 -:1027800031E022F0300232803E4A53786BBB0121A7 -:1027900051701A464049002050524049404C505216 -:1027A000404904EB030C5052002119510232CCF87D -:1027B0000400CCF8081004F1280C503443F80C1035 -:1027C00019519C441C44042ACCF80400CCF808108D -:1027D0006060A16003F11403DCD106E0338823F0CC -:1027E00030033380002384F870303B6813F4006FAB -:1027F000338814BF43F4807323F4807333806B7980 -:10280000082B02D00E2B40F09080338823F0400339 -:1028100033808AE0012200E002225FFA82F808F1A8 -:10282000FF3385F8543708F067FC0BF02BF90220D2 -:102830002821424602F0B8FAEEE4B8F1000F02D0C7 -:102840007E2B3FF4E7AC637E972B7FF4CDAC164B29 -:102850004FF4C8721A80DFE49A0400207C2700201D -:1028600098050020580A002054020020000C014066 -:10287000E00400207A05002082020020D00500201C -:102880004C0E0020480000208C0500206202002031 -:10289000580E0020DC050020D227002090050020E3 -:1028A000600E0020940500206C0400200022BB2B49 -:1028B000039201D1022303E0B72B04D14FF6FE733C -:1028C000ADF80E300AE0BE2B01D1022304E0BD2B8F -:1028D0007FF4A2AC4FF6FE73ADF80C303368BDF850 -:1028E0000C10B3F854200A44A3F85420BDF80E107D -:1028F000B3F856200A44A3F856200AF0EBF9002357 -:10290000A37689E40A4B00220021DA651A66C3F82F -:10291000F420C3F8F820C3F8FC20C3F80011C3F872 -:102920000411C3F80811FFF79ABB05B0BDE8F08F9A -:10293000E40D0020664B2DE9F04FB3F90600654B1E -:1029400087B01D682B8998420EDBB0F5FA6FAF791E -:1029500007DAC21A5743A3F5FA6397FBF3F7643714 -:1029600003E0C7F1640700E064275B4B5B4AB3F800 -:102970001A1193F9EC3016685B4204919BB2002166 -:10298000059334460A46524BDDF810C0CB5E40F248 -:10299000E63E0393CCEB030303F2F31CF44503D8A8 -:1029A000002BB8BF5B4201E04FF4FA73022ADFF854 -:1029B000388131D096F85DE1BEF1000F04D0734547 -:1029C000CCBFCEEB030300234FF0640EDFF814A15D -:1029D00093FBFEFC6FF0630B3AF81C900BFB0C3B77 -:1029E0000CF1010C3AF91CA00FFA89FCCCEB0A0C93 -:1029F0000CFB0BFC9CFBFEFCCC4428F801C095F8BA -:102A000004C003FB0CFC364B9CFBF3F373449BB2FA -:102A10007B4393FBFEFE1BE096F85EE1BEF1000FE8 -:102A200004D07345CCBFCEEB03030023DDF814C004 -:102A300003FB0CFEA8F804E095F805E0002BB8BFF6 -:102A40005B4203FB0EFE264B9EFBF3FE0EF1640E73 -:102A5000B31893F80480DFF894C00EFB08F86423E1 -:102A600098FBF3F802F80C8094F80E900CF1030830 -:102A70000EFB09F999FBF3F902F8089094F8188015 -:102A80000CF1060C0EFB08FE9EFBF3F302F80C3073 -:102A9000DDF80CE0049B9E45DFF84CE004DA3EF8DC -:102AA00001305B422EF801300132032A01F10201AC -:102AB00004F101047FF467AF074EB6F81C31984269 -:102AC00016DBB0F5FA6FA8BF4FF4FA6011E000BF53 -:102AD0001A070020980500202C200020E803002081 -:102AE0000CFEFFFFF00E002062020020FE0E002010 -:102AF0001846C01A4FF47A725043C3F5FA63B0FB1C -:102B0000F3F36427A34C93FBF7F204EB42016FF05D -:102B1000630000FB0233098B04EB4202B2F91A0096 -:102B20000AB2821A534393FBF7F739449A4F9B4DED -:102B30003B88AEF806105A063DD5994B1888994B3C -:102B40001B88C01A00B20CF01FF897490CF070F8FF -:102B500080460FF069FB814640460FF0D9FB804666 -:102B6000B5F902000CF010F88246B5F900000CF03F -:102B70000BF8494683460CF05BF841460346504645 -:102B800002930CF055F8029B014618460BF046FFE5 -:102B90000CF014FA4946288050460CF049F841469A -:102BA000814658460CF044F8014648460BF038FF81 -:102BB0000CF004FA6880B26840F602031340002B60 -:102BC00053D07A4B06211D88236B1D4494F8343072 -:102BD00025630133DBB2B3FBF1F084F8343001FB41 -:102BE000103313F0FF0F40D1930706D501F0CAFE52 -:102BF00001F0B2FE674B83F83500B368180532D593 -:102C00006B4BA16B5A7B6B4B33F81200082391FB83 -:102C1000F3F280B28A1A0244A26392FBF3F292B2F8 -:102C200040F6E4435A43644B40F6FF71B2FBF1F2C5 -:102C300019684FF47A73C8888988121A5A4392FB2C -:102C4000F1F255435D4995FBF3F30A60D4E91001B5 -:102C5000C01841EBE371C4E910010023584A0CF09D -:102C6000F3F9584B1860002323635749494A0B680E -:102C700094F8358013F4805318BF012382F848304C -:102C8000B3688A4613F4807F504D2CD0DFF8509102 -:102C90002878D9F80030C0F380001B685B6898473B -:102CA00060B1012384F84930D9F800301B68DB6833 -:102CB000984718B1374B022283F84920D9F80030E1 -:102CC0001B689B68984728B12B7859075CBF022383 -:102CD00084F84930D9F800301B689B69984710B1D7 -:102CE000002384F849303A4B1A6892060DD5DAF879 -:102CF000003013F4C06F05D0364B1B789B0701D40E -:102D0000012300E0002384F84A3094F84920214B45 -:102D1000022A02D14C204E211EE0012A06D1532066 -:102D20004D214C220B4608F009FF2BE093F84A2076 -:102D3000012A03D1532001464E2206E093F8482091 -:102D4000012A04D15320014602464D23EBE7B8F196 -:102D5000000F04D053204D210A464423E3E73A886C -:102D6000170603D553204D210246DBE71A4A127895 -:102D70001AB1192008F0B6FE04E0404683F84B80F3 -:102D800002F00BF82B7858072CD5144B08225A6107 -:102D900083E000BFF00E00205402002062020020F9 -:102DA000E0040020480E002035FA8E3CFC04002090 -:102DB0007807002088070020BC050020C4050020FB -:102DC000407E0500C805002050020020D6270020C4 -:102DD0004C020020820200209A040020000C0140D6 -:102DE0005C0A0020DAF80020D10703D4B74943F089 -:102DF00001030B70B6490B6813F0020302D0B5490A -:102E00000988A1B9B449098801B12BB9B34B1B8812 -:102E1000003318BF012300E0012343B1B04BD96850 -:102E200081F00801D9602B7823F001032B70AD4BA2 -:102E30001B781F0703D42B7823F001032B70D002DB -:102E400003D52B7823F001032B702B78A64A13F0BF -:102E5000010F05D00023E364A14B082119610BE0A9 -:102E6000E16C136841B9A14903F5F42303F59073AC -:102E7000CB649B4B08215961E36C12686BB1D21A89 -:102E8000002A0ADB964A03F5F423D16803F5907310 -:102E900081F00801D160954AD3640AF06BF8944B35 -:102EA0001B7813B105F098FAF9E3012008F0E6F871 -:102EB000002800F0F483DFF8589299F84A30012B8B -:102EC00040F0E7838B4A8C4BD9F80010C2F8009091 -:102ED00019609246884A106801F0C2FF002800F08D -:102EE000D283854B186801F0B6FFDAF8003093F80A -:102EF0004820DAB9B0F124014A424A4183F8482017 -:102F0000002AE7D12B785B07E4D4232802D105F00F -:102F100063FADFE7D4F8E8301B7D8342DAD1774AE1 -:102F2000774B1A60774A784BDA60D3E7012A04D1ED -:102F30004D2814BF00220222A2E3022A04D13C2819 -:102F400014BF002203229BE3032A0AD140284FF03A -:102F5000000200F295831A71DA7158719871042297 -:102F60008EE3042A06D19A7983F84900504098717B -:102F7000052285E3052AADD159791A7991429979CB -:102F800006D941409971511C197113441872A1E777 -:102F9000814240F0728393F8490006F079F90028E5 -:102FA00040F06683DAF8003093F84930C82B00F01F -:102FB000DD8043D82D2B00F0F08224D8252B00F0A3 -:102FC000CD8206D8212B00F02382232B00F06881CC -:102FD00086E3292B00F0CD822B2B00F0D682272B05 -:102FE00040F07E83002001F081FF01F019FD474F82 -:102FF000A7F8E60001F014FDA7F8E80001F010FDC5 -:10300000A7F8EA0031E3332B00F0DB820CD82F2B3A -:1030100000F0ED82312B40F063833C4FC02001F083 -:1030200065FF07F18008F8E2412B00F0D282442BC3 -:1030300000F01583352B40F0538353E1D02B00F083 -:10304000F58169D8CC2B00F07B8106D8C92B00F024 -:103050002782CA2B00F0A28042E3CE2B00F012821E -:1030600040F2EF8101F0DCFC01F0DAFC274FDFF8E1 -:10307000A480A7F8D00001F0D3FCA7F8D20001F09B -:10308000CFFCD8F800B0A7F8D40001F0C9FCABF829 -:10309000A80101F0C5FC01F0CDFCD8F8008001F0DA -:1030A000BFFC00EB80004000A8F8520001F0AEFC2D -:1030B00087F8040101F0AAFC87F8060101F0A6FCDC -:1030C00087F8050101F0A2FCCFE200BFD62700205F -:1030D0004C020020C02700206C040020C8270020DC -:1030E000000C014082020020BC270020F00E0020CE -:1030F000D02700206006002064060020EFBEADDE71 -:10310000F04F00200400FA0500ED00E02C20002024 -:10311000400F0020E8030020D42B00F0438108D8A2 -:10312000D22B10D040F2E18101F07AFCC94B18801B -:103130009BE2EF2B25D0FA2B00F0AE81D62B40F08E -:10314000CF82002726E12B7803F0040303F0FF076A -:10315000002B40F08A8201F059FCBF4B022883F813 -:10316000540740F2698183F8547765E1002701F044 -:1031700057FCBA4BD8530237102FF8D10122B84B65 -:1031800088E1B84FD7F8008001F04AFCA8F8560053 -:103190003F6801F045FCA7F8540066E2B14B0027F8 -:1031A0001A6898461278022A61D1D8F800B001F066 -:1031B0002DFC07F108020BEB820B0BF0E1FCAA4996 -:1031C0000BF0EAFDCBF80400D8F800B001F01EFCCB -:1031D00007F10A020BEB820B0BF0D2FCA3490BF0B8 -:1031E000DBFDCBF80800D8F800B001F00FFC07F1C8 -:1031F0000E020BEB820B0BF0C3FC9D490BF0CCFDD8 -:103200000137032FCBF80400CFD1072FD8F800B037 -:1032100016D101F0FBFB0BF0B3FC93490BF0BCFDA6 -:10322000CBF84800D8F800B001F0F0FB0BF0A8FC98 -:103230008D490BF0B1FDCBF84C0001F0E7FB12E03B -:1032400001F0E4FB0BEB07031871D8F800B001F0B4 -:10325000DDFB0BEB07039873D8F800B001F0D6FB49 -:103260000BEB0703187601370A2FCED1FDE1D8F812 -:1032700000B001F0CBFB0BEB07031871D8F800B0DE -:1032800001F0C4FB0BEB07039873D8F800B001F012 -:10329000BDFB0BEB070301370A2F1876E7D1E4E1FA -:1032A00001F0B4FB272821D86E4B00F11C081B68E5 -:1032B00003EB880801F0AAFB6E4B08F1050703F544 -:1032C0008A72197A814203D00C339342F9D10DE00E -:1032D0001B7888F8053001F099FB787001F096FBB7 -:1032E000B87053E001F092FB0B2804D901200021B3 -:1032F00001F0DEFDB9E14FF0060808FB00F0594B84 -:1033000000F588701B6803EB000801F07FFB0328C1 -:10331000ECD888F80A0001F079FB88F8050001F084 -:1033200075FB88F8060001F071FB88F8070001F0D2 -:103330006DFB88F8080001F069FB88F8090094E14A -:103340004D4FD7F8008001F061FB88F80000D7F8F6 -:10335000008001F05BFB88F80100D7F8008001F0E5 -:1033600055FB88F80400D7F8008001F04FFB88F87F -:103370000500D7F8008001F049FB88F80600D7F86F -:10338000008001F043FB88F802003F6801F03EFB3B -:10339000F8706AE101F044FB384BD8530237102F24 -:1033A000F8D162E14FF000082E4F08F12C0B39687C -:1033B000029101F035FB02994FEACB021144C8801B -:1033C00039680192029101F02BFB019A0299114494 -:1033D0000881019201F024FB0728019A02D839687C -:1033E0000A445073A0F57A7292B2B2F57A7F03D88C -:1033F0003A6802EBCB0250813F6801F007FB08F10D -:10340000010807EBCB03B8F1080F1873CCD12CE1FE -:103410000027144BD3F8008001F0F8FA08EBC7033B -:103420000137082F83F86D01F3D11EE12B785F0778 -:1034300000F11B8105F0D8F807F05EFE0AF022FBD0 -:1034400013E12B78580700F110810D4B4FF4C8722F -:103450001A800AE17A0500202C2000201A0700209B -:103460003C020020E8030020000020410000C84288 -:1034700000007A44704B010898050020DC0F002002 -:103480006C0400202B78590700F1EF80984B1A78D4 -:1034900042F004021A70E8E02B785A07CCD51FE1FD -:1034A00001F0B4FA924B1A7810B142F0020201E036 -:1034B00022F002021A7001F0A9FA8E4B8E4F18709A -:1034C00001F0B8FA386001F0B5FA786001F0A8FAB6 -:1034D0008A4B188001F0A4FA894B188094F80431C3 -:1034E00043F0020384F80431BFE001F08FFA019049 -:1034F00001F0A0FA029001F09DFA804601F09AFADC -:10350000074601F08DFA01F08BFA01F07FFA019A7B -:10351000029B92B97B4A82E808017B4B1A8822F011 -:1035200010021A80724B1A7842F001021A70002FB2 -:1035300000F09B80754B1F6097E0102A40F095804B -:10354000734A82E808010FB1704B1F607048714BDD -:103550000222011D1A7007F07AFB86E0002001F0BC -:10356000C5FC0023B36001F065FAB3681843B0608E -:103570007BE0002001F0BAFC01F052FAA6F8080145 -:1035800001F04EFAA6F80A016FE0002001F0AEFC4F -:1035900001F03CFA604B587167E0002001F0A6FC96 -:1035A00001F034FA86F8180101F03AFAA6F81E0183 -:1035B00001F036FAA6F81A0101F032FAA6F81C0159 -:1035C00053E0002001F092FC01F020FA86F820017F -:1035D0004BE0002001F08AFC002701F017FA4E4B67 -:1035E0003B440137082F83F81001F6D13DE000205D -:1035F00001F07CFC484F07F1400801F011FAA7F8F0 -:10360000D40101F003FA87F8D60101F0FFF904377D -:1036100087F8D3014745F0D127E001F001FA00F027 -:103620003F00A7F8560101F0FBF9B7F856218001D9 -:1036300000F4F8631343A7F8563101F0E7F90001ED -:1036400087F8540101F0E2F997F8543100F00F00C7 -:10365000184387F8540104374745DED105E00020C0 -:1036600001F044FC012384F80531002001F03EFC08 -:10367000DAF80030987901F00AFCDAF8003000221C -:1036800083F8482026E494F8053113B1234A244BEB -:10369000DA60244B09F14C0999457FF40EAC2249BC -:1036A0000B689B0616D5214BD4F808211B689A1A83 -:1036B000002A0FDB0F4A1278042A0BD91C4A03F5A3 -:1036C000123303F5F873C2F808311A4BDA6882F046 -:1036D0001002DA60184B9B683BB11848984704E029 -:1036E0000120002101F0E4FBC2E707B0BDE8F08F44 -:1036F00082020020D0050020DC050020CE0500203D -:10370000CC0500204C0E002054020020580200205E -:10371000580E0020540E00202C2000200400FA0532 -:1037200000ED00E0D80F00204C020020BC27002054 -:10373000F00E0020000C0140EC030020FC0F0020E4 -:103740002DE9F04F974B91B01B68BBB9964C23788D -:10375000013B042B00F2F086DFE813F00B060B06AA -:103760000B06DE06C406206801F075FB8F4B04468D -:103770001B681B784BB1012B00F0ED80894C206851 -:1037800001F06EFB0028EED1E0E72428884D0CD034 -:1037900006D80A2800F08E800D2800F08B80C6E045 -:1037A0002A2806D02C2804D0C1E02B706B70AB7097 -:1037B000CEE06A782E782A4400217D4BD170EEB994 -:1037C000DA789E74472A19D11A79502A16D15A7973 -:1037D000472A07D19A79472A04D1DA79412A01D1B7 -:1037E00001229A746A79724B522A07D19A794D2A2A -:1037F00004D1DA79432A04BF02229A74AB7C6C4F5D -:10380000012B02D0022B36D049E0B31E072B46D83D -:10381000DFE803F0040810141C27452C02F0E6FA38 -:1038200068613CE0EA78624B532A38D15A695242C7 -:103830005A6134E002F0DAFAA86130E0EA785C4BD1 -:10384000572A2CD19A6952429A6128E0EB78302BA2 -:10385000584B1A788CBF42F0020222F002021A7012 -:103860001DE0002002F01CFB287718E0002002F089 -:1038700017FBE88313E0072E06D0082E0FD1012096 -:1038800002F00EFB78840AE0012002F009FB41F20D -:10389000184358434FF47A72B0FBF2F33B8401367D -:1038A00000232A2C424A2E706B704CD1012182F8E1 -:1038B00024104DE095F82430002B34D03C4BDB78BD -:1038C000402B04D9A3F137021201D2B202E01B014E -:1038D00003F0F0022B79A978402B8CBF373B303BAB -:1038E000DBB21344DBB29942314A1BD1937C012BEA -:1038F00008D0022B16D1118C2F4B528C19802F4BD4 -:103900001A800FE02B4909788E070CD52C49506995 -:10391000086090694860107F2A490870D18B2A4A54 -:10392000118000E00023002285F8242010E06B784D -:103930001F4A0E2B03D8591C13445170DC7095F8A4 -:1039400024301B4A1BB991784C40947000E000234E -:1039500003F0010361E1164B002193F82520082AAA -:1039600000F25A81DFE802F00B0514324353718DE7 -:103970009A00622801D1022207E083F82510B52CB5 -:1039800040F04A8193F82520013283F8252043E155 -:10399000032283F8252083F8260083F8270083F884 -:1039A000280039E1A00A0020800A00209C0A00209B -:1039B0000010002082020020CC0500202A140020E4 -:1039C000DC050020D0050020CE050020042283F86D -:1039D000252093F8272093F828100244D2B283F8C8 -:1039E00027200A4483F8282083F8290014E10522BF -:1039F00083F8252093F8272093F828100244D2B2A8 -:103A000083F827200A4483F82820588504E10621FA -:103A100083F8251093F8271093F828002144C9B2A1 -:103A200083F82710014483F82810598D6C4A01EB64 -:103A30000424A4B2B4F5007F89BF002154855185C8 -:103A400082F8251000229A85E6E093F8272093F863 -:103A500028100244D2B283F827200A4483F8282091 -:103A60009A8DC72A03D85E49114481F8300001328B -:103A700092B29A855B8D934240F0CE800722584BDC -:103A800083E7082283F8252093F82730834200F04B -:103A9000C380534A002382F82530BEE083F8251006 -:103AA00093F828104E4A814240F0B68092F82910CF -:103AB000062947D004D8022912D003292CD0ABE024 -:103AC00012295CD0302940F0A78092F83410454A82 -:103AD000102988BF102111701078434900225CE042 -:103AE0004249506B4860906B0860116C4FF47A70DB -:103AF00091FBF0F13E48018092F8F8103D4A19B16F -:103B0000117841F0020102E0117821F002011170F8 -:103B1000012283F8F92055E092F8351011F00101E7 -:103B200005D092F83420D41E6242624100E00A4679 -:103B300083F8F820002A45D12E4A117821F002019D -:103B400011703FE092F83B1011F0010105D092F89E -:103B50003A20D01E4242424100E00A4683F8F82053 -:103B600022B9244A117821F00201117093F85F10F4 -:103B7000214A1170B3F85C10204A118022E0516C88 -:103B80001F480180916C42F2107091FBF0F11D48CA -:103B90000180012182F8FA1014E0824201F10C0147 -:103BA00010DA11F8045C184C155511F8035C174C29 -:103BB000155511F8015C164C15550D78154C155519 -:103BC0000132EAE793F8F930054A2BB392F8FA305C -:103BD00013B3002382F8F93082F8FA3001231CE095 -:103BE000001000202C14002030100020DC050020E4 -:103BF000CE05002082020020D00500209C0000207D -:103C0000CC0500202A1400202D1400203D14002093 -:103C10004D1400205D1400200023002B3FF4AEADB6 -:103C2000A54BA64E9A68DA6032689A60A44B1A686F -:103C300042F020021A60A34B1A78012A0CBF00221E -:103C400001221A70A04B1A7891077FF597AD9F4912 -:103C5000097804297FF692AD9D49097801F00401A5 -:103C600001F0FF0011B922F001021A701B78964F83 -:103C700013F0010F974C984D11D180B19B070ED5D1 -:103C8000964B28686A6818605A6006F08BFD944B62 -:103C90001B88A4F8FC303B7843F001033B7094F898 -:103CA000FE304FF00509013393FBF9F909EB89095F -:103CB000C9EB03098B4B8C481B7884F8FE90059365 -:103CC000831D03EB890907900023DFF80CE2874A84 -:103CD00053F80E00864F985090FBF7FC02F108074E -:103CE00043F807C0834F03EB0E0107FB0C0742F2BA -:103CF000107097FBF0F00691079980B221F8020F3F -:103D000002F1100A03EB830B0490079153F80A00A9 -:103D100059F80B1049F80B70C1EB000808EB0700CD -:103D2000734F4FF0050843F80A0090FBF8F007FBCB -:103D30000C000599183201299850774608D1DDF812 -:103D400010E0AEF10202B2F5797F9CBF06990860DF -:103D50000433082BB9D1DFF87C813068D8F84C31B6 -:103D6000C01A0AF00DFF64490BF016F833684FF0E3 -:103D70007E51C8F84C3181460BF0F8F810B94FF07D -:103D80007E5000E048460CAAC4F85001534B009204 -:103D90000DAA019297E803000CCB06F0C1FC0C9B26 -:103DA00056496422B3FBF2F30D980B80544B90FB01 -:103DB000F2F21A80444A474E127812F0010208BF0C -:103DC0001A8098F8543108BF0A80002B3AD0D6F8F0 -:103DD00050114FF07E500AF0DFFFD6F8583181467F -:103DE0002868C01A0AF0D0FE49460AF021FF0BF0FD -:103DF000E5F8D6F85C211FFA80FA68680FFA8AFAAB -:103E0000801A0AF0C1FE3F4B19680AF011FF4946BB -:103E10000AF00EFF0BF0D2F8B6F9623100B2C21808 -:103E2000B6F960310221534492FBF1F293FBF1F3B6 -:103E300092B29BB2A6F86621A6F86431A6F8622178 -:103E4000A6F86031012388F854312F4B79681B881C -:103E5000386803F030031F4E1F4DC8F85C11C8F8D6 -:103E60005801002B3FF48AAC06F5B873009306F5B1 -:103E7000BA730193D6F86821D6F86C3106F050FC7D -:103E80006B68D6F86C01C01A0AF07EFE1D4B1968EB -:103E90000AF0CEFE0BF092F8D6F868312A68C6F820 -:103EA0007C019B1AC6F878310E4B1B78012B2DD064 -:103EB000022B00F0F58061E4800A00202820002019 -:103EC0004C020020F40F002082020020D0050020C8 -:103ED000D627002000100020DC0500204C0E00201A -:103EE000E0040020540E0020FE1000202C110020C1 -:103EF00080969800806967FF00007A4440060020A1 -:103F0000420600204C00002054020020D6F89C41BC -:103F1000D6F89031D6F88021D6F8947104F100409B -:103F20000593049207970BF049F8074620460BF0DB -:103F300045F88C4BD6F850511B68D6F898618A4CDE -:103F40000890069609934FF0000ADFF83C9259F862 -:103F50001A60A9F1140230463AF802800AF014FE01 -:103F600004990AF065FE0BF029F8C8EB000080B256 -:103F700009F128092AF809000FFA80F948460AF0E1 -:103F800003FE05990AF054FE0BF018F81FFA80FBA7 -:103F900009EB06000AF0F8FD07990AF049FE2946E8 -:103FA0000AF046FE21680AF03BFD0BF007F8B84224 -:103FB00004DB089A9042A8BF104600E038460AF099 -:103FC000E3FD20600AF0FAFF58441FFA80FB6068A6 -:103FD00008F13108301A0AF0D7FD29460AF0DCFE54 -:103FE000099B206102469878D4F8089003920AF061 -:103FF000C7FD5E490AF01CFE01464FF07E500AF0F4 -:10400000CBFE29460AF00CFD014628460AF0C4FE04 -:10401000039A844649461046CDF80CC00AF0FEFCCF -:10402000DDF80CC0014660460AF002FE0146484633 -:104030000AF0F6FC1FFA88F8B8F1620F0146206119 -:104040006660A0600ED906980AF0F2FD0AF0B6FF8D -:10405000474AB0F5FA6FA8BF4FF4FA609042B8BF74 -:10406000104600E00020834440F6B8320FFA8BFB84 -:104070009345A8BF93463F4A0A219345B8BF93464C -:1040800001FB0AF13C4A54F8140B2AF802B03B4AEF -:104090000AF1020ABAF1040F88503FF46FAB54E7FB -:1040A000304BD6F870911F68B6F8A451B7F808A045 -:1040B0004FEA59039A4528BF9A462BB29A4502DC2B -:1040C0001FFA8AFA0BE02E49D6F850010AF0B0FD2B -:1040D0000AF074FF28441FFA80FAA6F8A4A1D8F8C1 -:1040E0007451D8F8A861AE1B304606F0C9FB002811 -:1040F000D8BF404241F293139842CCBF0020012028 -:10410000002843D030460AF03FFD1E490AF090FDDA -:104110000EF0FEF8064648460AF032FD01463046EB -:104120000AF086FD0AF04AFF80B240F6B83203B2C8 -:104130009342A8BF13460F4AA8F8AC019342ACBF04 -:10414000EB18AB1848F6A042934203DDA3F50C43ED -:10415000A03B04E0002BBCBF03F50C43A033C8F820 -:10416000B03115E08C050020880E0020DB0FC9401F -:1041700030F8FFFF48F4FFFF94050020B00E002048 -:104180000000C842D302373978110020C8F8B05176 -:10419000D4F8B021C2F50C50283004920AF0F4FC97 -:1041A000AA490AF045FD05460EF03EF80F90284654 -:1041B0000EF0AEF8D4F8C051D4F8B431D4F8B82128 -:1041C0000E9005F1004007930A920AF0F7FE059061 -:1041D00028460AF0F3FED4F85081D4F8BC410B9085 -:1041E00009949B4C002550460AF0CEFC0EAB53F8C8 -:1041F00015100AF01DFDDFF894B206463BF90500E4 -:104200000AF0C2FC014630460AF008FC0AF0D6FE6D -:10421000904B06B2B6F57A7FA8BF4FF47A769E42ED -:10422000B8BF1E46B0B20BF13C0B25F80B0000B234 -:104230000AF0AAFC079983460AF0FAFC0AF0BEFECF -:1042400080B208900A9958460AF0F2FC41460AF0FA -:10425000EFFC21680AF0E4FB0AF0B0FE059B9842EF -:1042600004DB0B9A9042A8BF104600E005980AF0C4 -:104270008BFC8346206060681434301A0AF084FC9A -:1042800041460AF089FD54F80C3C44F8040C0246FF -:10429000B878069303920AF073FC6F490AF0C8FCE1 -:1042A00001464FF07E500AF077FD41460AF0B8FB18 -:1042B000014640460AF070FD039A8446069910466E -:1042C000CDF80CC00AF0AAFBDDF80CC00146604630 -:1042D0000AF0AEFC014606980AF0A2FB44F8106C06 -:1042E000014644F8040C44F80C0C09980AF0A0FCB0 -:1042F0000AF064FE089E064458460AF05FFE304409 -:1043000040F6B83200B29042A8BF1046534A0A2184 -:104310009042B8BF10466943514AA852514A0235EB -:10432000042D41F802B07FF45EAF3B792BB1049BC2 -:10433000642293FBF2F24C4B1A803B884B4C99451C -:104340000ED9D4F8A831D4F87401C01A06F098FA3E -:1043500042F210730028B8BF404298427FF70EAA7D -:10436000434B01221A70B4F8FC203F4B1A80FFF730 -:1043700005BA404A116890460F7817B1012F0DD049 -:10438000ADE0012B00F2AB8062783B4B03EB0213F4 -:104390003A4A5968106800F059FD9DE0374E306880 -:1043A00000F04FFDB146002800F099802378344D8D -:1043B000022B29D0032B31D0012B40F09080314BC0 -:1043C0001F686B69FB1A632B40F289802B69042BF1 -:1043D00018D8DFF8A480306808EB0313596800F0A0 -:1043E00035FD6B78366808EB03139D6815F8011BE3 -:1043F00019B1304600F046FDF8E7236967610133E3 -:1044000023616CE0022068E06A781B4B306803EBA4 -:104410000213596800F01AFD03205EE02B7E03B9F9 -:104420002F76227E164B012A36D11A697B2A2FD885 -:10443000D8F800309B782BB9134BD9F80000995C61 -:1044400000F020FD23690133236125E0D3023739D1 -:10445000B00E002018FCFFFFDB0FC94048F4FFFF3F -:1044600094050020880E00207A050020001000200E -:10447000540E00209C0A0020F4450108A00A0020E8 -:10448000800A002028200020844C010864110020AC -:1044900000221A6102221A76227E294B022A18D1A2 -:1044A0001A690F2A13D8D8F80030997859B95B786F -:1044B000244903EB03130B441A44D9F8000092F883 -:1044C0007D1000F0DFFC23690133236101E003224A -:1044D0001A76237E022B02D9042007F07FFB0023EB -:1044E000636029E06368052201336360637801201B -:1044F0000133DBB2B3FBF2F202EB82029B1A637070 -:10450000114B00221B68A360104B1A70104B1A78D5 -:1045100022F002021A700DE00B4B1A68A368D21A3F -:1045200040F6C4139A4207D90A4B05201A6822F0B4 -:1045300020021A6007F052FB11B0BDE8F08F00BFF7 -:10454000800A0020844C010828200020D00500208B -:10455000820200204C0200201E4B2DE9F0431A7805 -:104560001D460AB31C4B07781E781C4B93F800C0FD -:1045700002231B4A03F10108D45C344104F00F0408 -:10458000BC420CD20B2C0AD812F8039012F8088007 -:1045900002EB840209EA0C0408EB042414610233E0 -:1045A000102BE6D100232B7003788B420FD90C4BD4 -:1045B00093F8400060B10B4A890012780B441869E7 -:1045C00002B1400800F5777080B2BDE8F0830020AA -:1045D000BDE8F08340010020600A0020610A00204D -:1045E000C4110020620A002007299ABF024B33F849 -:1045F00021000020704700BF1C020020024B53F82E -:104600002100C0F3CF007047C401002008B5074B5C -:1046100053F821000AF0B4FA05490AF009FB0549EC -:104620000AF0FEF90AF0F0FC80B208BD5C0100203F -:104630000000203F00005C44014B33F8110070473C -:104640001A070020014B33F8110070474C19002065 -:10465000034B4FF4805208B11A6170475A6170479A -:1046600000080140034B4FF4805208B15A61704773 -:104670001A6170470008014038B50C6805462046AD -:104680000DF0E4FB214602462868BDE838400DF0F5 -:10469000E5BB094BDA68D10709D4DA68520708D4B8 -:1046A000DB6813F0100F0CBF0420032070470120BB -:1046B00070470220704700BF002002408A6810B592 -:1046C0000C6A036814430A6923F4FF4314434A69DC -:1046D00023F0700314438A691443CA6914434A6A75 -:1046E00014438A6A224313430360CB6843600B6818 -:1046F00083604B68C36010BD02684FF6FE731340C1 -:1047000003600023036043608360C3602A4B9842C8 -:1047100022D02A4B984229D0294B984230D0294B9D -:10472000984237D0284B98423ED0284B984206D129 -:1047300053F8682C42F4700243F8682C7047244BFD -:10474000984206D153F87C2C42F0706243F87C2CDE -:104750007047204B984206D153F8042C42F00F02C8 -:1047600043F8042C70471C4B984206D153F8182C80 -:1047700042F0F00243F8182C7047184B984206D1CB -:1047800053F82C2C42F4706243F82C2C7047144BD5 -:10479000984206D153F8402C42F4704243F8402C22 -:1047A0007047104B984205D153F8542C42F47022B4 -:1047B00043F8542C704700BF080002401C00024020 -:1047C0003000024044000240580002406C000240A9 -:1047D00080000240080402401C04024030040240F1 -:1047E00044040240580402402DE9F843574B0C465C -:1047F0000168013AC3F842108188A3F84610072ADD -:1048000042D8DFE802F0040A101822292F35B3F845 -:1048100042202280B3F8442013E0B3F844202280E1 -:10482000B3F8422005E0B3F8422052422280B3F8A8 -:104830004420524205E0B3F8442052422280B3F8AB -:1048400042206280B3F846301DE0B3F84220524265 -:104850002280B3F8442012E0B3F844202280B3F859 -:1048600042200CE0B3F842202280B3F8442005E057 -:10487000B3F8442052422280B3F842205242628070 -:10488000B3F846305B42A380314B1B78002B5AD1E2 -:10489000B4F900000AF078F98046B4F902000AF091 -:1048A00073F90746B4F904000AF06EF9294D06467B -:1048B000296840460AF0BCF9E968814638460AF0A2 -:1048C000B7F9014648460AF0ABF8A9698146304677 -:1048D0000AF0AEF9014648460AF0A2F80DF0DAFCFB -:1048E0006968208040460AF0A3F929698146384664 -:1048F0000AF09EF9014648460AF092F8E9698146B5 -:1049000030460AF095F9014648460AF089F80DF05C -:10491000C1FCA968608040460AF08AF9696980464E -:1049200038460AF085F9014640460AF079F8296AC6 -:10493000074630460AF07CF9014638460AF070F81E -:104940000DF0A8FCA080BDE8F88300BFC4110020D2 -:104950003800002090070020074B084A1B78128877 -:104960009A4207D3064A1268907898428CBF00207A -:104970000120704700207047C0050020E00D002096 -:10498000BC05002010B5194B93F84820511C83F842 -:104990004810174902F007024878164903EB420312 -:1049A00031F81010A3F84A1000231846124A9A5AF8 -:1049B00002331044102B80B2F8D1C0080AF0E4F89A -:1049C0000E490AF035F90E490AF0E6F90D4B044696 -:1049D0001B6818780AF0D8F8014620460AF028F932 -:1049E0000AF012FB084B187010BD00BFC411002064 -:1049F00078070020880700200E1200203333534030 -:104A000000F07F45BC050020C0050020034B1B685B -:104A1000DA79511CD9711344187A70476006002066 -:104A200010B5FFF7F3FF0446FFF7F0FF04EB00209B -:104A300080B210BD10B5FFF7F3FF0446FFF7F0FF9B -:104A400004EB004010BD0B4AA2F13003197A8142F9 -:104A50000BD00C339342F9D1074B197A014004D1A2 -:104A60000C339342F9D1084603E018460BB158685D -:104A7000704770479400002064000020002305491F -:104A8000DAB2595C814203D001330C2BF7D11A46BC -:104A900010467047036B01082DE9F0478278C6780D -:104AA0001E4BC2F1640802EB820C54425FFA88F894 -:104AB0004FEA4C0CC6F16409A4B203F11807A5B281 -:104AC00028B2002804DC002D14BF1546012500E0A3 -:104AD000454600FB00FA6D430AFB06FA9AFBF5F522 -:104AE0004D4468434FF00A0A90FBFAF0604480B2EC -:104AF00058800D88B1F802A000B2C5EB0A0A00FB8D -:104B00000AF04FF47A7A90FBFAF0054423F8025F3A -:104B10000A34BB42A4B2D2D1BDE8F087060F002010 -:104B200010B544780078002303FB03F11939614381 -:104B300001F6C4115943414340F6C41291FBF2F10E -:104B4000034A22F813100133072BEDD110BD00BF2B -:104B5000F00E002010B5044C2068FFF7E1FF20683C -:104B60000249BDE8104097E798050020FC2000208E -:104B700010B5094A094913688C6812689342F8D144 -:104B8000074A106811684FF47A725043001BB0FB5B -:104B9000F1F002FB030010BD2820002010E000E02F -:104BA0006007002038B5124B124C9968124B1A68F6 -:104BB0001D465288114203D0FFF7DAFFE06511E08D -:104BC000FFF7D6FFE36D98420CD9C01A0B4B3B227E -:104BD000B0FBF2F01B68B0F5967FC8BF4FF0FF3016 -:104BE00003B118602B685A68054B5A6138BD00BF85 -:104BF000000C0140C4110020E0030020DC03002071 -:104C00000004014038B5104C0123054684F84030BB -:104C1000FFF7AEFF236E41F28832C31A93426366F8 -:104C200084BF002384F8683094F86830EDB20F2B0D -:104C30002066E55403D1054B01221A7038BD024AA3 -:104C4000013382F8683038BDC411002040010020D3 -:104C500010B50446FFF78CFF0D4B41F28831DA6E38 -:104C6000D866821A8A421A6784BF002283F87420A9 -:104C700093F87430074A142BD45403D1064B012205 -:104C80001A7010BD024A013382F8743010BD00BFA3 -:104C9000C4110020050200200402002010B50446C3 -:104CA000FFF766FF164A936F9067C31AB3F57A6FE2 -:104CB00084BF002382F87C3092F87C3023B9A82C82 -:104CC0001CD110490B7006E0022B02D10E490C706A -:104CD00001E0242B01D80D49CC540133DBB282F81A -:104CE0007C30094A127852000532934206D1044BB7 -:104CF000002283F87C20034B01221A7010BD00BFF4 -:104D0000C41100209C010020C20100209D01002050 -:104D100038B50446FFF72CFF124B40F6C411D3F808 -:104D20008020C3F88000821A8A4284BF002283F860 -:104D3000842093F884200AB90F2C11D10A4800214D -:104D4000017052B1094D182A154405F8014C04D1DF -:104D5000012283F88410027038BD013283F8842068 -:104D600038BD00BFC41100204101002042010020D5 -:104D700038B50446FFF7FCFE0546FFF7F9FE401B79 -:104D8000A042FAD338BD10B504462CB14FF47A7066 -:104D9000FFF7EEFF013CF8E710BD08B5014B1B68BB -:104DA000984708BDDC2700202DE9F04106460F4654 -:104DB00090460025EBB2434518D20024E3B2B3423B -:104DC0000FD20B4B0120DA68013482F00802DA605E -:104DD000FFF7E3FF3846FFF7D6FF0020FFF7DDFFC0 -:104DE000ECE73C20FFF7CFFF0135E3E7BDE8F081BA -:104DF000000C014040F2DB14604308B50D4B10225B -:104E00005A6108221A61841E0A4B2046DA6882F031 -:104E10001002DA60DA6882F00802DA60FFF7B3FFA6 -:104E20000120FFF7BAFF1920FFF7ADFF0020FFF7C1 -:104E3000B4FFE9E7000C014008B503685B699847D7 -:104E400008BD08B503681B69984708BD08B5036825 -:104E5000DB68984708BD08B503689B68984708BD9C -:104E600008B503685B68984708BD10B5044C206816 -:104E7000FFF7F6FF18B12068FFF7EDFFF6E710BD6A -:104E80004806002008B503681B68984708BD064B14 -:104E900010B5044621461868FFF7F4FF034B1B6862 -:104EA0009A7954409C7110BD640600206006002071 -:104EB00038B5044624200D46FFF7E9FF4D20FFF7E3 -:104EC000E6FF002C084C0CBF3E202120FFF7DFFF3F -:104ED0002368002228469A71FFF7D9FF236893F8C8 -:104EE0004900BDE83840D2E76006002001460020B6 -:104EF000DEE7F8B50E4E0F4C0F4DC1B207463068D5 -:104F000084F88510FFF7BEFF2B6894F885109A7916 -:104F100030684A409A71C7F3072184F88510FFF77B -:104F2000B1FF2B6894F885109A794A409A71F8BDC0 -:104F300064060020C411002060060020F8B51B4D57 -:104F40001B4C1C4F0646C1B2286884F88610FFF738 -:104F500099FF3B6894F886109A7928684A409A71BC -:104F6000C6F3072184F88610FFF78CFF3B6894F89E -:104F700086109A7928684A409A71C6F3074184F8E6 -:104F80008610FFF77FFF3B6894F886109A792868AF -:104F90004A409A71310E84F88610FFF773FF3B6820 -:104FA00094F886109A794A409A71F8BD64060020F8 -:104FB000C41100206006002010B5441E14F8011F23 -:104FC00021B1034B1868FFF75DFFF7E710BD00BF85 -:104FD0008C1C0020014B186854E700BF60130020B0 -:104FE000014B014618684DE71820002010B5044613 -:104FF0007F2C06D964F07F00C0B2FFF7F1FFE4090F -:10500000F6E7E0B2BDE81040EAE7430083EAE0706B -:10501000ECE770B5104E114C114D4720FFF7E0FF43 -:105020003078FFF7E3FF23682868C01AFFF7EDFF29 -:1050300063686868C01AFFF7E8FF0A4B1888FFF733 -:10504000D5FF094B1888FFF7D1FF337823742B68FD -:10505000A3606B68E36070BDD0050020C01C002019 -:10506000DC050020CE050020CC050020014B18688F -:1050700008E700BF18200020A0F17D03012B70B5C8 -:1050800004460D460A4E05D830687D21FFF7FAFE2A -:1050900084F0200430682146FFF7F4FE35B12B88F8 -:1050A0001C4404EB142404F0FF042C8070BD00BFEA -:1050B0007006002038B5054C05465E212068FFF7D4 -:1050C000E1FE20682946BDE83840DBE6B005002057 -:1050D000014B5E211868D5E6B005002010B50A4CDA -:1050E0005E280146206805D15D21FFF7CBFE2068D0 -:1050F0003E2105E05D2903D1FFF7C4FE20683D2174 -:10510000BDE81040BEE600BFB005002010B5044663 -:10511000C0B2FFF7E3FFC4F30720BDE81040FFF77C -:10512000DDBF064B1B6803EBC00090F90630194247 -:105130000CBF01204FF0FF30704700BFA41E0020BD -:105140000A4B1A6802EBC002D379FF2B07D008493B -:105150000978994203D9074A32F8130004E0072876 -:10516000D4BF908840F2DC5000B27047A41E0020EB -:10517000630A00201A07002010B5054C0020218882 -:1051800005F015FC61880120BDE8104005F00FBC5A -:10519000120000202DE9F04F0C68836889B0D0F828 -:1051A00000A0D0F804800646204603938B460DF0FD -:1051B0003BF8074620460DF0ABF8DBF8044081468B -:1051C00020460DF031F8054620460DF0A1F8DBF839 -:1051D00008200446104601920DF026F8019A8346F5 -:1051E00010460DF095F839460290584609F020FD1A -:1051F00039460490029809F01BFD5946059048462F -:1052000009F016FD02990690484609F011FD29465D -:105210000790584609F00CFD0146504609F008FD7C -:1052200021468346069809F003FD0146059809F0DA -:10523000F7FB0146404609F0FBFC0146584609F0E1 -:10524000EFFB21468346049809F0F2FC01460798DB -:1052500009F0E4FB0146039809F0EAFC01465846D0 -:1052600009F0DEFB3060029905F1004009F0E0FC36 -:105270000146504609F0DCFC21468346079809F0B8 -:10528000D7FC0146049809F0C9FB0146404609F0E5 -:10529000CFFC0146584609F0C3FB214683460598DA -:1052A00009F0C6FC0146069809F0BAFB01460398CE -:1052B00009F0BEFC0146584609F0B2FB2146706079 -:1052C000504609F0B5FC2946044609F1004009F0B2 -:1052D000AFFC0146404609F0ABFC0146204609F010 -:1052E0009FFB39460446284609F0A2FC0146039874 -:1052F00009F09EFC0146204609F092FBB06009B01F -:10530000BDE8F08F2DE9F84F2E4E04463768384639 -:105310000CF08AFF054638460CF0FAFF76688046A6 -:1053200030460CF081FF834630460CF0F1FFD4F894 -:10533000049006462946484609F07AFCA76882464A -:105340004146384609F074FC0146504609F066FBB8 -:1053500021688246584609F06BFC4146044648469F -:1053600009F066FC314609F063FC0146204609F06D -:1053700057FB31460446384609F05AFC294609F0E5 -:1053800057FC0146204609F04BFB014650460DF004 -:105390004DF80D4909F04CFC0C4909F0FDFC0C4B93 -:1053A000196809F03DFB0B4909F0F6FC0CF072FF9F -:1053B00083B21A0444BF00F5B4739BB218B2BDE8BF -:1053C000F88F00BFCC0400200000E144DB0F49400F -:1053D0000408002000002041064B1B7803F0040362 -:1053E00003F0FF001BB1044B1888C0F3C01000F09D -:1053F00001007047D62700205402002007B5064B55 -:1054000006480093064B074A1968074B06F0BAFC9A -:1054100003B05DF804FB00BF04630108D362010818 -:10542000C4000020EF620108FB62010810B50748C4 -:10543000FFF7C2FD0024064B0648E218E158526807 -:105440000C3406F09FFCFC2CF5D110BD0C63010858 -:10545000185401082263010837B58288044683681E -:1054600010060D4606D529494FF4E07091F85417FF -:1054700000FB0133D10504D525490A20097800FB3A -:10548000013302F03F02042A12D006D8012A0DD0BF -:10549000022A2FD193F900102DE0102A0AD0202AD9 -:1054A0000AD0082A26D1B3F9001024E0197822E0A6 -:1054B000198820E019681EE06946186806F0F2FDB8 -:1054C0000146144806F05EFCF5B1E06809F05CFBAB -:1054D000694606F0E7FD01460F4806F053FC2069D7 -:1054E00009F052FB694606F0DDFD01460A4806F068 -:1054F00049FC09E00021094806F044FC25B10848B0 -:10550000E168226906F03EFC03B030BD2C2000208B -:105510003C0E0020316A0108306A01086E710108F2 -:105520002A6301082DE9F041002407462546114B66 -:105530003946E65804EB030830460CF0C3FC58B17A -:105540000D48314606F01EFC40460021FFF784FF5F -:105550000A4806F017FC0135143440F604339C4227 -:10556000E5D125B90648BDE8F041FFF725BDBDE806 -:10557000F08100BF58550108A06401085B63010871 -:10558000316301082DE9F74F04460CF05FFC054636 -:1055900020B1012819D123782A2B16D15648FFF7BC -:1055A0000BFD0024554B5648E618E15806F0EAFB7F -:1055B00030462946FFF750FF5248FFF7FDFC1434F0 -:1055C00040F604339C42EDD192E020463D210CF0A0 -:1055D00030FC002800F08780034613F8012C202AB5 -:1055E00001D1013BF9E7451C2846C4EB030A0CF046 -:1055F00082FC8346284604F08DFE002605461423CF -:105600007343DFF8F89053F8097003EB0908384644 -:105610000CF01CFC03461A462046394601930CF058 -:105620001DFC019B002855D15FFA8AF29A4251D1A4 -:10563000D8F80C0009F0A8FA0146284609F0AAFC9F -:10564000002845D0D8F8100009F09EFA01462846F7 -:1056500009F096FC00283BD0B8F804309B064FF0C8 -:10566000140303FB0696B28858BF5D46140629460C -:10567000B36806D524484FF4E07490F8540704FB4F -:105680000033D00504D521480A24007804FB0033F8 -:1056900002F03F02042A0BD004D8013A012A0CD8A8 -:1056A00019700AE0102A05D0202A05D0082A04D152 -:1056B000198002E0196000E01D603946144806F0C8 -:1056C00061FB3046002103B0BDE8F04FFFF7C4BED8 -:1056D000104803E001368D2E91D10F4803B0BDE88C -:1056E000F04FFFF769BC204603B0BDE8F04F19E763 -:1056F00003B0BDE8F08F00BF4963010858550108A9 -:10570000A06401085B6301082C2000203C0E0020EF -:105710005E63010869630108316301082DE9F04304 -:1057200089B004460CF092FBC6B2002E6CD18B48B7 -:10573000FFF742FC8A4C2069002109F00DFC40BBB8 -:1057400001368848314606F01DFB206904A906F0A1 -:10575000A9FC0146844806F015FB606904A906F01F -:10576000A1FC0146804806F00DFBA06904A906F0E3 -:1057700099FC01467C4806F005FBE06904A906F0A7 -:1057800091FC0146794806F0FDFA0C2E04F1100454 -:10579000D1D10025764C2F462B464FF00008B0455E -:1057A00004F1100415DA184654F8101C09F038F901 -:1057B00054F80C1C8146284609F032F954F8081CAC -:1057C0000546384609F02CF908F101084B46074612 -:1057D000E5E76848019302950397FFF7EDFB002486 -:1057E00001ABE058644920F0004009F0DDFB634B59 -:1057F000634A0434002814BF10461846FFF7DCFB48 -:105800000C2CEDD15F4891E020465F4905220CF059 -:1058100025FB38B9524B002203441030C0281A61CE -:10582000F8D197E02046594904220CF017FB0646B0 -:105830002046002E40D120210CF0FBFA002800F079 -:105840008980451C28460CF001FB34468046504BAD -:1058500053F824600EB94F4868E0284631465FFA95 -:1058600088F20CF0FBFA671C20BB3D4B0021C218EC -:105870001030C02811619C46F7D1474B002403EB40 -:10588000C702D2F804E09846BEF1000F04D14348A5 -:10589000314606F077FA55E018F837309C42F6DAD0 -:1058A00023010CEB0305103573440FCB013485E85D -:1058B0000F00F1E73C46CAE70CF01DFB461E0B2E1D -:1058C000074643DC204620210CF0B3FA054640B1E0 -:1058D000451C284604F01EFD214B3F01D8510124F0 -:1058E00000E00446284620210CF0A3FA054640B10A -:1058F000451C284604F00EFD194B013403EB06133A -:105900005861284620210CF094FA054640B1451C08 -:10591000284604F0FFFC124B013403EB0613986198 -:10592000284620210CF085FA18B91D48FFF744FBE2 -:1059300010E0013004F0EEFC094B032C03EB0616DB -:10594000F061F2D11748FFF7E9FE03E016480C2199 -:1059500006F018FA09B0BDE8F08300BF91630108B2 -:105960002C200020BC630108C263010825630108E4 -:1059700040200020C66301080AD7233C8D6301083C -:10598000896301085B630108D5630108DB630108D3 -:1059900068530108E063010804450108F563010844 -:1059A000056401080D6901083F6401087FB50446DC -:1059B0000CF04CFA082824D100231F49E25C096846 -:1059C0001144497801F00301022908BF203AE2544A -:1059D0000133082BF1D10025665D184831460CF0E3 -:1059E00028FA28B10135601931460CF022FA18B1B5 -:1059F0001348FFF7E1FA1CE0082DEDD1204606F030 -:105A000039FB1048FFF7D8FA00230F4A04A91A44BB -:105A100092F810210A440949595C0133082B02F815 -:105A20000C1CF2D10023094801A98DF80C3006F0B6 -:105A3000A9F904B070BD00BFC8000020AA6E01081B -:105A400067640108876401082C2000202563010891 -:105A500070B5064600240B4BE518AA8816420AD0FA -:105A6000E158094806F08EF928460021FFF7F4FCBA -:105A70000648FFF7A1FA143440F604339C42EAD1F9 -:105A800070BD00BF585501089C6401085B630108A4 -:105A90002DE9F04F624C23686249581C0A78894608 -:105AA00002F0FF0C0AB10346F6E7277A667AA57A78 -:105AB000E1682360E0461FFA88F213B21F2B00F35F -:105AC0009380594901EB8300C278807831F8231024 -:105AD000C0F1FF0080B2002861D0C0F1FF00504348 -:105AE0003C23B1FBF3FA0012BAF1050F5AD8DFE8F4 -:105AF0000AF0030B1A283846161A4E43C5B2B6FBF5 -:105B0000F3F62E44F6B248E0B1FBF3F703FB1717A8 -:105B1000BFB2C5B2C7F13C07101A4743B7FBF3F752 -:105B20002F44164629E0B1FBF3F503FB1515C7B268 -:105B3000ADB2101A4543B5FBF3F53D44EDB2164640 -:105B400030E0B1FBF3F603FB1616B6B2C7B2C6F1EE -:105B50003C06101A4643B6FBF3F63E441546F6B231 -:105B600020E0B1FBF3F703FB1717C6B2BFB2101A60 -:105B70004743B7FBF3F737441546FFB212E0B1FBDA -:105B8000F3F503FB1515ADB2C6B2C5F13C05101A0D -:105B90004543B5FBF3F53544EDB2174602E0154633 -:105BA000164617464FEA072A4AEA064A4AEA050A0B -:105BB0001723012199400CF1170211EA0A0FC3EBD8 -:105BC00002021A490CBF0920112092B213F1FF33CF -:105BD0008854EED20CF1180C08F101081FFA8CFC65 -:105BE0001FFA88F8124966E7012389F80030114B43 -:105BF000E28040F22A3227726672A572E160A4F850 -:105C000004C05A600C4A00219184118889B241F085 -:105C1000010111801A6842F001021A60BDE8F08F9C -:105C20004C120020CA27002098060020A80A002055 -:105C3000541200206C000240000400400D4B02781A -:105C4000D9684378C943C1F30221C1F1040103FAC1 -:105C500001F1094B0901C9B21A4482F80013027814 -:105C60000120510902F01F0200FA02F243F821203C -:105C7000704700BF00ED00E000E100E00C4B07B50D -:105C80001B68196819B10B4A9069014391619A88A0 -:105C90009868ADF8042002228DF8072004220DEB4D -:105CA00002018DF8062004F08DFE03B05DF804FBC0 -:105CB000C40700200010024010B50A4C23681BB135 -:105CC000FFF7DCFF00232360074B1B7813B1012B88 -:105CD00003D010BD4FF4006201E04FF48052034B3B -:105CE0001A8010BDC4070020C90700200000002052 -:105CF000134B026810B51C68D1430C401C605C68F3 -:105D00002140596019680A431A6002689C68D143AF -:105D10000C409C60DC682140D9604179102906D193 -:105D2000996811439960D9680A43DA6010BD01F19E -:105D3000804303F5823319680A431A6010BD00BF1F -:105D400000040140254B10B55343254A254C1268E9 -:105D50000139B2FBF3F20388013AA04289B292B250 -:105D60009BB212D004F50064A0420ED0B0F1804F77 -:105D70000BD0A4F59834A04207D004F58064A0426B -:105D800003D004F58064A04202D123F070039BB2DB -:105D9000154CA04206D004F58064A0421CBF23F439 -:105DA00040739BB203800F4B8185984202850FD0D0 -:105DB00003F5006398420BD003F54063984207D087 -:105DC00003F58063984203D003F58063984201D1C4 -:105DD000002303860123838210BD00BF40420F00D1 -:105DE000A4000020002C014000100040284BF0B51A -:105DF0001D6800222748165C1418AB19597801F069 -:105E0000040101F0FF0371B10132102AF2D1002028 -:105E1000F0BD1BB103EB83035B00DBB210F8012B79 -:105E2000303A1344DBB2221A022AF2DC0021844207 -:105E30000AD919B101EB81014900C9B210F8012B4F -:105E4000303A1144C9B2F2E72E2E14D1601C002260 -:105E50000424067802EB8202AF197F7852007F0794 -:105E600092B203D5303A3244013092B2013C14F080 -:105E7000FF04EED100E000220748062441436420DD -:105E800000FB02120548B2FBF4F200FB0320F0BD58 -:105E9000C80000200310002040420F0080969800A8 -:105EA00030B5002213460D495C5C9CB12E2C04D108 -:105EB000013378B11C1800250D550A246243C95CD2 -:105EC000A1F13004092C9CBF303A52180E2B03D894 -:105ED0000133E8E7104630BD002030BD031000203C -:105EE0000FB407B504AB53F8042B00200449019309 -:105EF00005F082FE03B05DF804EB04B0704700BF0C -:105F00006D5000080EB40FB505AB53F8042B01908B -:105F1000064901A8039305F06FFE019B00221A7049 -:105F200004B05DF804EB03B0704700BFB19E0008F9 -:105F30002DE9F0438DB005460BF088FFC0B2002874 -:105F400058D104467F4B00211E68142207A80BF08D -:105F50003CFFA500002303A905A803930593771927 -:105F60000B7183801A46DFF8F0E1B7F802C03EF803 -:105F7000138018EA0C0F0CD00EF10A0E0DF1300848 -:105F800013F80EE002F1010C424402F824EC5FFA2F -:105F90008CF20133052BE6D100231A46DFF8C0E16D -:105FA000B7F802C013F80E8018EA0C0F0CD00EF1EF -:105FB000060E0DF1300813F80EE002F1010C424418 -:105FC00002F81CEC5FFA8CF20133062BE6D1735D0C -:105FD0008DE803001A0907A85B4903F00F03FFF7D8 -:105FE00091FF2146594807AA013405F0CBFE202C29 -:105FF000A8D1A3E028460BF07EFF1F28044600F33B -:10600000918028462021E4B20BF013FF1F2C01D908 -:106010004F4888E04B4B471C1B68002103EB84046E -:10602000204604220BF0D1FE00254A4B07AE304635 -:1060300000210A2215F803905FFA85F80BF0C5FEDF -:106040000023FA5CF91832B10A2B04D04A4502D079 -:10605000F2540133F5E74A4501F1010767D1B8F180 -:10606000020F0DD0B8F1030F0CD0B8F1010F0BD017 -:1060700030460BF040FF2378C0B243EA00100AE03C -:10608000002219E0002226E030460BF034FF23788E -:1060900000F00F001843207038E00133062B0AD0BF -:1060A0002D4800F115069E5D8E42F6D10344D97B42 -:1060B00063880B43638001320CA9D3B20B4413F8FD -:1060C000141C19B30023EBE7412B1DD0542B08BF40 -:1060D00004230ED00132D3B20DF13008434413F83B -:1060E000143C9BB1492B01D1002302E0572B07D16F -:1060F0000123194931F8131063880B436380E9E7E2 -:10610000462BE1D10223F4E70323F2E70135042D06 -:106110008BD1012404F0A0FA04F0DAFA04F0B4FA06 -:1061200064B975E70D48202105F02CFE06E02046F5 -:10613000002104220BF049FE0024EBE70DB0BDE87E -:10614000F08300BF94060020A6640108B264010831 -:10615000BE640108714D0108564D0108CC64010868 -:10616000654D01082DE9F04FAE4E85B03778032F0D -:1061700014D9AD4BAD48B3F90410B0F9042000298F -:10618000B8BF49426FF063035B1A9A4204DB01F126 -:1061900064039342A8BF134683801FE0012F1DD8DC -:1061A000A34BA44C1B78013B142B00F2E181DFE8E8 -:1061B00013F09100DF01DF0168009F00DF01DF01C4 -:1061C0002F01DF01DF01DF01DF01DF01BD00DF01A2 -:1061D000DF01DF01DF01DF01A101B801924B964928 -:1061E000B3F806A0914B0968B3F80280B3F80090A9 -:1061F000B3F904B0914C02910025BD4204F11004A2 -:10620000CED20FFA8AF008F0BFFC54F8101C08F048 -:106210000FFD03460FFA88F0019308F0B5FC54F81F -:10622000081C08F005FD019B0146184608F0F8FB24 -:1062300003460FFA89F0019308F0A6FC54F80C1CF1 -:1062400008F0F6FC019B0146184608F0E9FB029AAB -:10625000034692F90000019340420BFB00F008F066 -:1062600093FC54F8041C08F0E3FC019B014618461B -:1062700008F0D6FB08F0A2FE714B23F8150001359B -:10628000BBE702210420FEF74CFF684D0121AF88D7 -:1062900078431FFA80F80420FEF743FF6D8800FB67 -:1062A00005801FFA80F80420FEF74AFF4044208151 -:1062B00002210520FEF735FF7843012187B2052032 -:1062C000FEF72FFF00FB057087B20520FEF738FFB1 -:1062D00038440BE005200121FEF723FF534B9D8836 -:1062E000684385B20520FEF72BFF284460813FE11B -:1062F000544B00201D68FEF723FFDFF8648195F9F9 -:106300000630B8F902203227534393FBF7F31844C1 -:1063100020800120FEF714FF95F90E30B8F9002017 -:10632000534393FBF7F73844608021E1464B1B78D9 -:1063300013F0040F454B02D11B689B880BE01968D2 -:10634000394A0B88B2F9062049889A4203DB914208 -:10635000B4BF0B461346E381E289394B394F1A80AB -:106360003B4B1B681D7845B30220FEF7E9FE3A68F7 -:10637000B2F91030518A984203DB0BB29842B8BF91 -:106380000346344909684889C3EB000E324B0FFAC3 -:106390008EFE19880FFA81FCF44501DA0D4401E004 -:1063A00001DD4D1B1D8092F91620B3F900305343D7 -:1063B000642293FBF2F31844A080284B1B88DB0572 -:1063C0000CD5194B1A88D7F80090E28022819A8860 -:1063D000184F62815B880325A38101E0134BF1E72D -:1063E00009EBC50393F90630B7F90680284608FB88 -:1063F00003F8642398FBF3F8A7F80680FEF7A0FEE5 -:1064000001354044072DF88007F10207E8D1AFE0DD -:106410000D4B1B7813F0040F0C4B23D11B689B888A -:106420002CE000BFE127002062020020F0120020D3 -:10643000A005002012000020A405002088090020EB -:10644000A4270020A41E0020D6270020AC1E002078 -:10645000B01E0020B41E00205C1200205402002058 -:10646000A80300201968AD4A0B88B2F906204988B4 -:106470009A4203DB9142B4BF0B461346E381E289A3 -:10648000A74BA84D1A80A84B03201B880121DF05CC -:1064900003D5FEF746FEA14F02E0FEF742FEA34FF2 -:1064A000B7F80280022100FB08F01FFA80F90320F0 -:1064B000FEF737FE3F88012100FB0790E8800420AB -:1064C000FEF72FFE00FB08F002211FFA80F80420DF -:1064D000FEF727FE00FB078028810320FEF730FE31 -:1064E000E3881844E0800420FEF72AFE238918443C -:1064F00020813DE001210420FEF713FE8B4D6F88C3 -:10650000784387B204202781FEF71AFE38442081A1 -:1065100001210520FEF705FE2D88684385B26581BF -:10652000E0E6824B0325B3F8049098462846022102 -:10653000FEF7F7FD00FB09F0012187B22846FEF7C0 -:10654000F0FDC5F106035B0838F8133000FB03705B -:1065500087B224F815702846FEF7F2FD384424F877 -:1065600015000135072DE1D16C4BDA886C4B1A8090 -:106570006F4DDFF8E491AB6813F0200F34D00020AA -:10658000FEF7DEFD208080460120FEF7D9FD694B35 -:10659000644F1B6860801A0626D5674B1B681B7802 -:1065A00013F0020F654B23D0D9F800C0B3F90010E7 -:1065B0009CF90E209CF906C0B3F902304A43CCF195 -:1065C000000C03FB0CF3322192FBF1F26FF0310C63 -:1065D00092B293FBFCFC9444E04493FBF1F1A7F8E6 -:1065E00000800A4410447880D9F80010002319E094 -:1065F000D9F80010B3F902C091F90620B3F90030C0 -:106600000CFB02FC32229CFBF2FCE044A7F8008069 -:1066100091F90E104B4393FBF2F2E3E7E25202339F -:10662000102B0CD0E05E31F9232001EB8307904260 -:106630007F88F3DB3AB28242A8BF0246EEE73E4BC8 -:106640001B681B785B0704D435493478088801231C -:106650001BE03B4B00241F780423043FFFB25FFA8A -:1066600087F84FFA88F2D4420BD4364A03F1010975 -:10667000381932F813105FFA89F9C0B204F097F9AB -:106680004B460134042CECD1DEE7A34208D231F9A9 -:10669000132000B28242A8BF104680B20133F4E753 -:1066A000294B4FEA44081A68AB6803F480550395F8 -:1066B000244D03F01009254BB5F90660244D1B78D5 -:1066C0002F68244D03F00403DBB2D5F800C0029319 -:1066D0000023434562D0B2F802A004B2544505DD60 -:1066E0000F4CC0EB0A0A1D5B55441D53039D0C4C17 -:1066F000002D33D07D8931F903A0AE42CBBFBCF869 -:1067000002509588B2F802B0BCF800B0AA4503DB8D -:10671000DA45B4BF55465D46E55238E062020020D6 -:10672000A42700201200002054020020F0120020B4 -:106730002C20002050020020B81E0020A8030020BA -:106740000F0800201A070020AC1E0020D6270020CA -:10675000B41E0020A81E0020A41E002031F903A0B2 -:106760001588B2F802B0AA4503DBDA45B4BF554636 -:106770005D46E55204EB030ABC89A64207DAB9F18B -:10678000000F01D1148800E09488AAF80040029C10 -:1067900014B9044C1C5BCC5202339AE705B0BDE837 -:1067A000F08F00BFDC0F00202DE9F04F8E4C8BB036 -:1067B0002378023B042B00F25983DFE813F0070033 -:1067C0002C0005009A00D50010267CE0874B1A6843 -:1067D000874B1B6864339A4240F248831026854DEC -:1067E000854B2A689846985C2F4638B1FEF7F8FB2F -:1067F0002A68013E02F101022A60F0D13B6818F8D4 -:106800000330002B40F0328303222270794A136058 -:106810007A4A53602AE3774D794B2E6893F80080CB -:10682000052E3FD8744FC8F1080807EB8603586E51 -:106830000BF00CFB002E14BF022309236F4E08FB44 -:106840001308746873680F33A34202DA444527D1F2 -:106850000AE04445FADA2B6807EB83035B6E185DA8 -:10686000FEF7BEFB0134EDE7664B5B79012B08D0E8 -:106870000A20FEF7B5FB2B6801332B600023736001 -:10688000F4E22C20FEF7ACFB2B6807EB8307FC6FD0 -:10689000013C14F8010F0028EAD0FEF7A1FBF8E74D -:1068A0007460E3E2574B9B681A064CBF0423052330 -:1068B0002370002356E0FEF793FB2A68013E02F1A5 -:1068C00001022A6009D04B4D4B4B2A6898461A4466 -:1068D00092F894002F460028EDD13B68434493F88A -:1068E0009430002B40F0C28205222270414A13608E -:1068F000BCE2404D2B68072B30D8DFE803F00408DA -:106900000B111D22272B4048FFF7EAFA28E03F48E9 -:106910003F490EE03F484049404AFFF7E1FA1FE097 -:10692000384B0A2193F854273D4801FB023393F872 -:106930005617FFF7D5FA13E0324B3A48B3F8D010A8 -:10694000F7E7304B3848B3F8D210F2E7374B384806 -:10695000D968EEE7374B38481988EAE706232370F1 -:106960002B6801332B6081E2344D354B2C681B685A -:106970002360344B1A6862605A689B68A260E360C7 -:10698000314B1A6822615A689B686261A3612F4B80 -:106990001A68E2615A689B68226263622C4B1A880B -:1069A00022855A8862859A88DB88A285E385294BEF -:1069B0001A8822865A889B886286A386264B1A8864 -:1069C000E2865A889B8822870D4A638711780023C4 -:1069D00091468B4244DA214804EB430230F813001D -:1069E00001339087F5E700BFE20D0020282000204A -:1069F000B41C0020B81C0020784D01085C12002057 -:106A0000E12700202C200020EE6401080B6501081E -:106A10000463010823650108EF620108FB620108B5 -:106A20003A6501084765010859650108EC03002033 -:106A30006B650108000000207E650108D41C002061 -:106A4000BC270020F812002004130020101300209F -:106A500062020020F4040020B4040020A4270020D7 -:106A6000D14BD24F5B89D7F80080A4F85E3018F084 -:106A70001F03019340F087804920FEF7B1FA386880 -:106A8000FEF7B4FA2068FEF7B1FA6068FEF7BDFAC7 -:106A9000A068FEF7BAFAE068FEF7B7FA2069FEF7D9 -:106AA000B4FA6069FEF7B1FAA069FEF7AEFAE069E0 -:106AB000FEF7ABFA206AFEF7A8FA606AFEF7A5FABD -:106AC000B4F92800FEF7A1FADFF8F082B4F92A0041 -:106AD000FEF79BFAB4F92C00FEF797FAB8F8D0301D -:106AE000B4F92E000126C01AFEF780FAB4F930007E -:106AF000FEF78BFAB4F93200FEF787FAB4F93400E6 -:106B0000FEF783FAB4F93600FEF77FFAB4F93800DD -:106B1000FEF77BFAB4F93A00FEF777FAB4F93C00D5 -:106B2000B8F8D030C01AFEF761FA99F800309E42EA -:106B30000ADA04EB4603B3F93C00B4F93C30013601 -:106B4000C01AFEF762FAF0E798F80530012B06D17B -:106B50002B68B3F95E00A0F2DC50FEF756FA2B6802 -:106B6000934A94496B60AB609B1A9B104B43032183 -:106B7000013393FBF1F101EB41015B1A642101FB4D -:106B800003222A606FE150206E68FEF729FAAA6896 -:106B90002B6810681B684FF0000B18446B681B686B -:106BA000A0EB4300FEF731FA04EB0B0206EB0B03FC -:106BB00050685B680BF1040BC01AFEF726FABBF1B4 -:106BC0000C0FF1D14FF0000B04EB0B0206EB0B03A3 -:106BD00010691B690BF1040BC01AFEF716FABBF122 -:106BE0000C0FF1D14FF0000B04EB0B0206EB0B0383 -:106BF000D069DB690BF1040BC01AFEF706FABBF192 -:106C00000C0FF1D10023E218B2F92810F218B2F9F2 -:106C100028208A1A02A941F813200233082BF2D146 -:106C2000654B0DF1180E03F1100C18685968724687 -:106C300003C2083363459646F7D105AA01A800238D -:106C400052F804199B00DBB271B101F1080EBEF1DC -:106C50000F0F02D843F0010306E08031FF2994BFF3 -:106C600043F0020343F003038242E9D10AA901EB96 -:106C7000131203F00F030B4412F810BC13F8103C6E -:106C80004FF0000A43EA0B1B5FFA8BFB5846FEF7F6 -:106C9000A7F90BF00302022A16D0032A1AD0012A00 -:106CA00026D10AAB03EB8A0252F8200C52F81C1CC6 -:106CB00000F00F0040EA0110C0B2FEF791F90AF1AE -:106CC000010A4FEA9B0B13E00AA901EB8A0212F8B2 -:106CD000200C0BE00AAB03EB8A0252F8202CD0B256 -:106CE0000092FEF77DF9009AC2F30720FEF778F9CB -:106CF0000AF1010ABAF1030F4FEA9B0BC9DD4FF00D -:106D0000000B2A680BF1180332F913006A680BF1C3 -:106D1000010B32F91310AA6832F9133002220B4426 -:106D200093FBF2F3C01AFEF770F9BBF1030FE8D141 -:106D30004FF0000B2A680BF118035B001A44B2F9FC -:106D400006006A680BF1010B1A44B2F90610AA6832 -:106D50001344B3F9063002220B4493FBF2F3C01A3A -:106D6000FEF753F9BBF1030FE4D14FF0000B99F894 -:106D700000309B4524DA2A680BF11C035B001A449F -:106D8000B2F904006A680BF1010B1A44B2F904105D -:106D9000AA681344B3F9043002220B4493FBF2F3C4 -:106DA000C01AFEF732F9E2E712000020BC1C0020F6 -:106DB000E01C0020295C8FC2194F01082C20002004 -:106DC0002C4B5A799946012A06D1B4F95E00B6F9DE -:106DD0005E30C01AFEF719F96B682A68AB60264B63 -:106DE00026496A60D21A92104A430321013292FB6B -:106DF000F1F101EB4101521A642101FB02332B60D6 -:106E0000D9F808301B062ED51D4C1E4D22682B6864 -:106E10009A4209D162686B689A4205D1019A0F2A99 -:106E200010D118F47E6F0DD14820FEF7D9F82068F4 -:106E3000FEF7EBF86068FEF7E8F823682B606368FC -:106E40006B600EE0104A0F4B11782A7C914208D1FA -:106E50000E4A99681068884203D15268DB689A42EA -:106E600001D0FEF7D6F83B6801333B600BB0BDE8BC -:106E7000F08F00BF2C200020E01C0020295C8FC276 -:106E80004C0E0020C01C0020D0050020DC05002096 -:106E9000642928BF6421F8B501FB00F7642497FB3F -:106EA000F4F40546E4B20026F3B2A34204D29F20D4 -:106EB00000F082F90136F7E7AC420BD2142097FBC1 -:106EC000F0F0C4EB84136638C4EB83031844C0B2FB -:106ED00000F072F90134E4B2AC4238BF9A20F7D323 -:106EE000F8BD0F4B10B50446185C00F065F90D4B6A -:106EF00033F91430B3F57A7F05DBB3F5FA6FA8BF29 -:106F00004FF4FA6301E04FF47A73A3F57A730A221F -:106F100093FBF2F10920C9B2BDE81040B8E700BF09 -:106F2000AA6E01081A07002010B5441E14F8010FBC -:106F300010B100F041F9F9E710BD00BF2DE9F04FA5 -:106F4000012828BF0120142101FB00F389B0DFF8DC -:106F5000BCB101900BEB03025BF803706548019B29 -:106F6000654E0760F469037110691589B2F80A90DB -:106F70002043546849EA0508F0610222C4F81080F1 -:106F800020468DF80E1003A9ADF80C808DF80F2067 -:106F900003F018FD4FF0080AA268154203D10A2039 -:106FA000FDF7E6FEF8E70A206561FDF7E1FE2561E1 -:106FB0000A20FDF7DDFEBAF1010AEDD10A20C4F87E -:106FC0001490FDF7D5FE0A206561FDF7D1FE0A2079 -:106FD0002561FDF7CDFE0222C4F8109020468DF801 -:106FE0000F2003A91C228DF80E20ADF80C8003F0B1 -:106FF000E9FC424A9742326905D142F400123261FB -:107000004FF4001004E042F4800232614FF480003B -:1070100005F058FABA8803A822F440721204120C40 -:10702000BA803A88012592B242F001023A80BC88C7 -:1070300005F0FEF924F03F04059831492404B0FB23 -:10704000F1F1240C0C43A4B2BC803A88142322F042 -:1070500001021204120C3A802A4A0024B0FBF2F218 -:107060004FF49670414392B24FF47A70002A91FB2C -:10707000F0F108BF0122013142F4004289B23984A3 -:10708000BA833A8803A892B242F001023A803A8861 -:1070900022F4816222F002021204120C3A804FF4B0 -:1070A00080423A81019A8DF80D4003FB02B77B7B49 -:1070B0008DF80E408DF80C308DF80F50FEF7BEFDA8 -:1070C0003B7B9DF80F208DF80C308DF80D408DF82E -:1070D0000E401AB103A8FEF7B1FD07E0590903F00D -:1070E0001F039D40084A203142F8215009B0BDE8F5 -:1070F000F08F00BF641200200010024000540040D6 -:1071000040420F00804F120000E100E02C4F0108C8 -:1071100008B5054B1A88013292B21A80034B1879D0 -:10712000FFF70CFF002008BD281400206412002087 -:1071300013B51E4B4000C0B2587102AC186899716B -:1071400004F8012D00210122DA71DC6019721C6142 -:107150001A755A75997538B38288920515D40288C4 -:10716000D4050DD447F230520188890502D5013A81 -:10717000FAD112E08AB1028892B242F4807202809F -:10718000828892B242F44072828047F23052597D36 -:1071900011B1013AFBD100E012B9FFF7B9FF03E0EA -:1071A000024B987D80F0010002B010BD64120020F7 -:1071B000024640213C20BBE770B50A4E00EB800040 -:1071C00006440024331913F8A00C074B01341D7832 -:1071D0006840FFF7EDFF052CF4D12846BDE870406C -:1071E000E6E700BF544F0108E02700200246802157 -:1071F0003C209DE710B5AE20FFF7F8FFD420FFF745 -:10720000F5FF8020FFF7F2FFA820FFF7EFFF3F20F8 -:10721000FFF7ECFFD320FFF7E9FF0020FFF7E6FFC1 -:107220004020FFF7E3FF8D20FFF7E0FF1420FFF77A -:10723000DDFFA120FFF7DAFFC820FFF7D7FFDA2034 -:10724000FFF7D4FF1220FFF7D1FF8120FFF7CEFF19 -:10725000CF20FFF7CBFFD920FFF7C8FFF120FFF7C2 -:10726000C5FFDB20FFF7C2FF4020FFF7BFFFA420D0 -:10727000FFF7BCFFA620FFF7B9FFAF20FFF7B6FF6F -:10728000A620FFF7B3FFAE20FFF7B0FF2020FFF7E7 -:10729000ADFF0020FFF7AAFFB020FFF7A7FF4020B7 -:1072A000FFF7A4FF0020FFF7A1FF1020FFF79EFFCC -:1072B0004FF48064013C0020A4B2FFF779FF002C5A -:1072C000F8D18120FFF792FFC820FFF78FFFBDE8BC -:1072D0001040AF208AE708B55038C0B2FFF786FFEC -:1072E0000020FFF783FFBDE8084010207EE77720ED -:1072F000482101221CE777205821012218E7064B7C -:10730000002193F82020054B920134321970772028 -:10731000F42102F0FC020BE7E0070020142000201B -:10732000034B00221A707720F4212E2200E700BFC1 -:107330001420002010B5174C23681BB1FEF79EFCEB -:10734000002323606B2180226820FFF7F1FE642078 -:10735000FDF719FD192100226820FFF7E9FE6B21D6 -:1073600003226820FFF7E4FE372102226820FFF79E -:10737000DFFE094B1A211A786820FFF7D9FE1B217E -:1073800018226820FFF7D4FEBDE8104068201C21B9 -:107390001022CDE6C40700203900002008B51920CE -:1073A000FDF7F1FC682015210022FFF7C1FE10B99E -:1073B0000320FDF71FFD0C4B16211A78682042F0C0 -:1073C0001802FFF7B5FE172100226820FFF7B0FE74 -:1073D0003D2101226820FFF7ABFEBDE80840682090 -:1073E0003E210122A4E600BF3A00002013B500228E -:1073F0002A211C20FFF79CFE0E2102221C20FFF7F1 -:1074000097FE0F2103221C20FFF792FE2B21122250 -:107410001C20FFF78DFE164B02249A69154842F096 -:1074200004029A612023ADF8043004230DEB03011C -:107430008DF806308DF8074003F0C4FA22462C215F -:107440001C20FFF775FE2D2101221C20FFF770FE86 -:107450002E2100221C20FFF76BFE2A2105221C2072 -:10746000FFF766FE044B4FF480721A8002B010BD25 -:1074700000100240000801400000002008B50F2164 -:1074800008221820FFF754FE0E2218201021FFF7C3 -:107490004FFE024B4FF480521A8008BD00000020BE -:1074A00008B5134B53201B782D2108227BB1FFF721 -:1074B0003FFE31210A225320FFF73AFE2C210C22F5 -:1074C0005320FFF735FE53203821902209E0FFF7C3 -:1074D0002FFE31210A225320FFF72AFE53202C21B0 -:1074E0000A22FFF725FE034B40F209121A8008BD5D -:1074F000C80700200000002010B540001C4CC0B29E -:107500006071A17101200021E17120722275607506 -:1075100020682361E360A17540B383889B0515D47F -:107520000388D9050DD447F230530288920502D55D -:10753000013BFAD112E08BB103889BB243F4807314 -:10754000038083889BB243F44073838047F23053B7 -:10755000627D12B1013BFBD100E01BB9BDE81040D8 -:10756000FFF7D6BD024B987D80F0010010BD00BF33 -:107570006412002037B50622044603216B461E2004 -:10758000FFF7BAFF9DF801309DF80000154D43EA62 -:10759000002000B207F0F8FA296807F049FB07F06D -:1075A0000DFD9DF8033020809DF8020043EA002085 -:1075B00000B207F0E9FAA96807F03AFB07F0FEFC11 -:1075C0009DF80530A0809DF8040043EA002000B239 -:1075D00007F0DAFA696807F02BFB07F0EFFC608030 -:1075E00003B030BD3C00002007B5002101AB0322F1 -:1075F0007720FFF781FF9DF805009DF80430000219 -:1076000040EA03409DF80630184303B05DF804FBE0 -:1076100008B5FFF7E9FF014B986108BD641200202F -:1076200008B5FFF7E1FF014BD86108BD64120020E7 -:10763000104B13B51B78104C13B9238C01332384E2 -:1076400001ABF62103227720FFF756FF9DF80530A6 -:107650009DF804201B0243EA02439DF806201343D1 -:10766000064AB2F92020C2F10802D340636202B098 -:1076700010BD00BF1420002064120020E00700208D -:107680000B4B13B51B780B4C13B9238C013323849C -:1076900001ABF62102227720FFF72EFF9DF8042090 -:1076A0009DF8053043EA0223238502B010BD00BFD8 -:1076B000142000206412002013B5062204466B46F5 -:1076C0003B216820FFF718FF9DF800209DF801304E -:1076D00043EA022323809DF802209DF8033043EA09 -:1076E000022363809DF804209DF8053043EA0223BD -:1076F000A38002B010BD13B5062204466B46432199 -:107700006820FFF7F9FE9DF800209DF8013043EA5C -:10771000022323809DF802209DF8033043EA0223D0 -:1077200063809DF804209DF8053043EA0223A3807E -:1077300002B010BD07B52320FDF725FB6820752199 -:1077400001220DF10703FFF7D7FE28B19DF80700CE -:10775000B0F168035842584103B05DF804FB13B51B -:107760000222044601AB1B216820FFF7C5FE9DF8ED -:1077700004209DF8053043EA022303F54E534FF4ED -:107780008C72103393FBF2F32333238002B010BDCD -:1077900013B5062204466B461D216820FFF7ACFE98 -:1077A0009DF800209DF8013043EA022323809DF8D4 -:1077B00002209DF8033043EA022363809DF80420F1 -:1077C0009DF8053043EA0223A38002B010BD13B533 -:1077D000062204466B4601211C20FFF78DFE9DF812 -:1077E00001309DF800209DF8021043EA022242F386 -:1077F0008D02042392FBF3F222809DF8032042EADB -:10780000012242F38D0292FBF3F262809DF8041094 -:107810009DF8052042EA012242F38D0292FBF3F328 -:10782000A38002B010BD13B5062204466B460221A8 -:107830001820FFF761FE9DF800309DF801209B089D -:1078400003EB022323809DF802309DF803209B0860 -:1078500003EB022363809DF804309DF805209B080C -:1078600003EB0223A38002B010BD2F4B2DE9F3419F -:107870001B780546002B39D0002426462746A04613 -:1078800008226B4653203221FFF736FE9DF8012077 -:107890009DF80030013403EB02231BB29DF8032056 -:1078A00098449DF80230E4B203EB02231BB21F445C -:1078B0009DF805209DF80430202C03EB02231BB219 -:1078C0001E449DF8073003F07F0301D0002BD7D171 -:1078D000164B98FBF4F897FBF4F796FBF4F6A5F833 -:1078E00000806F80AE8083F82A401AE006226B4643 -:1078F00053203221FFF700FE9DF801209DF8003053 -:1079000003EB02232B809DF803209DF8023003EB4C -:1079100002236B809DF805209DF8043003EB0223C1 -:10792000AB8002B0BDE8F081C807002064120020DF -:1079300013B5224C23689A8A92B20192019A12F4EA -:10794000706F1CBF0122A275019A12F4E06F29D05A -:107950001A8B9A8822F480621204120C9A80019A7F -:1079600091051FD41A8892051CD41A88D0050ED50B -:107970001A88D105FCD41A8892B242F400721A8097 -:107980001A889205FCD42079FFF7D8FA0AE01A8801 -:1079900092B242F400721A809A8822F44072120461 -:1079A000120C9A802268938A23F470631B041B0CC8 -:1079B00093820023637502B010BD00BF64120020E3 -:1079C000954B2DE9F74F1B78013B012B00F22081ED -:1079D000924B1E78864240F01B81914B1B78022B04 -:1079E00000F016818F4B904D13F806808F4B83F873 -:1079F00000808F4B1A7801921AB18E4B33F9160022 -:107A000007E08C4A2B6832F9160003F100432B6023 -:107A1000404207F0B9F8884907F0BEF9DFF838A20C -:107A20000446DAF800B00021584607F095FA00271E -:107A3000DFF82C92002859D0D9F800B020465946DA -:107A400007F0B2FA68B17D4B2A687B491A60C9F821 -:107A50000040204607F0ECF807F0B0FA784BD880E9 -:107A6000BDE05846394607F09FFA002800F0B7807D -:107A7000744B1A78002A31D12046296806F0CEFFCF -:107A80004FF07E5107F072FA6F4C28B160686F4971 -:107A900007F0CEF860600FE06D49606807F0C8F845 -:107AA000DFF8CCA18346514607F060FA10B9C4F85C -:107AB00004B001E0C4F804A0624A01231370654BCE -:107AC00000221B68C9F8007043449A72019A82F040 -:107AD0000103574A1370604B1F6080E05F4BCAF888 -:107AE00000401A68554BFA325A6078E020465946F1 -:107AF00007F03CFA48B1584A4F491460204607F055 -:107B000097F807F05BFA4E4BD880534BD9F80090AA -:107B1000D3F800A04846514606F080FF4F4B8346FD -:107B20001968464B5A688A1A002A0BDA4FF07E51C0 -:107B300007F03AFA002852D02046514607F034FAAE -:107B400000284CD03D4A4846116807F02DFA3E4CBB -:107B500038B120683E4907F06BF83C492060A068C6 -:107B600007E058464FF0804107F01EFA28B1A068A0 -:107B7000374907F05DF8A06004E02068334907F05A -:107B800057F82060334B2C492068D3F8009007F059 -:107B90004FF807F039FA09F80800A06807F034FA3E -:107BA000019AC84482F00103214A88F81400137036 -:107BB000294B1F602A4B1F60224B1A780132D2B228 -:107BC000032A01D01A700AE000221A701E4B2549C0 -:107BD000586807F02DF807F017FA88F80A001EB960 -:107BE000174B1A8864321A80114A13780BB11E4B56 -:107BF00000E01E4B2B600F4B33F9160006F0C4FF5C -:107C00000D4907F0C9F80146286806F007FF00E0B3 -:107C1000084603B0BDE8F08F040500205805002099 -:107C20006805002048440108080500206905002077 -:107C300059050020A80300200000204190120020D8 -:107C40006E1400205A0500206C0500200AD7833FDF -:107C5000EC51783F640500205C05002028200020BE -:107C60006005002000007A440000A0410000A0C18F -:107C70006F12833A10B50848FDF79EF9074B1C6850 -:107C80002046FDF7DEF818B90A20FDF77CF8F7E783 -:107C9000034A044BDA6010BD516801088C1C0020B7 -:107CA0000400FA0500ED00E008B50748FDF784F987 -:107CB000064A002313729363054A137005F076FE9B -:107CC000BDE80840FFF7D6BF5D68010890120020AC -:107CD000D027002008B50448FDF76EF903F00CFA30 -:107CE000BDE80840FFF7C6BF896801082DE9F04FDD -:107CF000002487B0074604919246059380462546A6 -:107D0000022DDFF888914FEA450607D104984379A0 -:107D1000B9F904001B3343435B1148E0524B39F976 -:107D2000151033F9153003EB4101CAF100039942F4 -:107D300003DB5145B4BF0B4653464C49059A31F914 -:107D400006B0915FCBEB030303EB010BFDF744FBA4 -:107D500098B1474B58465B5D039306F015FF4549C4 -:107D600007F01AF8039B01461846FFF729FE414920 -:107D700006F05EFF07F022F983463F4B1988C807DB -:107D800011D404988A07037939F9060003F11B031B -:107D900000FB03F34FEA231309D57A7C02FB0BFBAC -:107DA00003EB2B2303E0FB7903FB0BF31B11334A9B -:107DB00098F80AB0905F042290FBF2F0181A7B5DED -:107DC0002F4A4343DB1101932E4B01351988A358E9 -:107DD00001FB00FC4FEAEC2C0BFB0C33DFF8B0C0CE -:107DE000B3F5001FA8BF4FF400136345B8BF634647 -:107DF000A3504FEA633C244B0909E258E050821A31 -:107E00004FF6FF70B0FBF1F14A4303F10C0003F1B0 -:107E1000180B215854F80B90921189442250CDF838 -:107E20000890914498F8142044F80B1002FB09F1D3 -:107E300001980912084403F1240260449053019808 -:107E400003F12C02A050032D03F1380203F1440387 -:107E500044F802C0E15008F1010804F104047FF481 -:107E60004FAF07B0BDE8F08FD2270020A803002055 -:107E7000D45101080000204154020020F4040020E5 -:107E8000D80E0020FC040020CC120020620200204A -:107E90000000E0FF2DE9F04F89B00793994B06925F -:107EA000B3F90220B3F90030002AB8BF5242002BC8 -:107EB000B8BF5B4200249A42B8BF1A4603900592AD -:107EC0002646A04627460494A3462546DFF860923E -:107ED000B9F8003099075AD0022D58D0894BDDF8F7 -:107EE00018C0F25E884BF35E03EB4202CCF1000354 -:107EF0009A4203DB63469A42B8BF1346834ADDF8D1 -:107F00001CC036F902A03CF90620CAEB030303EBC0 -:107F1000020AFDF761FA90B17D4B504615F803B0A7 -:107F200006F032FE7B4906F037FF01465846FFF760 -:107F300047FD784906F07CFE07F040F8824603983A -:107F40006423C2796FF0040102FB0AF292FBF3F2A0 -:107F5000C37E01FB03FB5A4505DB03EB83039A4217 -:107F6000B4BF93469B466C4A42F21071A3585344E7 -:107F70008B42A8BF0B4669498B42B8BF0B46039999 -:107F8000A35091F811A00AFB03F31B130493B9F853 -:107F9000003003F00302012A01D1022D3DD1594ADC -:107FA0005F49B75E895F039A81EAE170A0EBE170F7 -:107FB00012F805C05B4AB0F5206F54F802801DDC52 -:107FC000022D15D05020784390FBFCFC042091FB3F -:107FD000F0F1C1EB0C0CE0445348B8F57A5FA8BF50 -:107FE0004FF47A588045ACBF42F80480105107E046 -:107FF00087EAE770A0EBE7706428E3DD0021115108 -:10800000484AA1587D2291FBF2F8039A2A44927AB9 -:1080100002FB08F8402298FBF2F89A0716D5022DC9 -:1080200014D0059BDDF814C0C3F5FA720CFB08F000 -:108030007B43DDF810C002FB0B3302FB0C024FF454 -:10804000FA7193FBF1F392FBF1F208E0DB0701D543 -:10805000022D02D142463B4601E0049A5B4630497C -:10806000DFF8D0A0715A4FF0040C0FFA81F915F81F -:108070000AA099FBFCF00AFB00F06FF04F0A90FB9E -:10808000FAF01844294B019036F903A0F152CAEBDB -:10809000090999FBFCF903F1140A03F1080C54F8DF -:1080A0000C0054F80A1044F80C90DFF88CC001441E -:1080B00015F80CC0494402910CFB01F14FF0200C63 -:1080C00091FBFCF144F80A000198C1EB0209A3F10D -:1080D0002C0C814426F80C900135A3F1240C44F8B3 -:1080E0000C004942A3F11800032DA3F10C03225008 -:1080F000E15006F1020604F104047FF4E7AE09B092 -:10810000BDE8F08F62020020D2270020A8030020E3 -:10811000D451010800002041400E0020F0D8FFFF9C -:10812000F4040020D80E002080C1FFFF1C130020A3 -:1081300054020020FE0E0020040F00202DE9F04F15 -:1081400089B007937A4B814618880491059206F00E -:1081500017FD784906F06CFD002403904F46254634 -:108160002646022EDFF80CA20BD10499BAF90400BE -:108170004B790A33584306F007FD6F4906F00CFEB1 -:1081800044E06E4B3AF90520EB5E05991A444B42E8 -:108190009A4203DB0B469A42B8BF1346684AAA5E6E -:1081A0009B1A079A505F184406F0EEFC654906F0EA -:1081B000F3FD8046FDF710F928B1634B4146985D09 -:1081C000FFF7FEFB8046614B1A88D10705D5404674 -:1081D000D9F8441006F02CFD18E004993AF905008E -:1081E0000B7901921433584306F0CEFC524906F045 -:1081F000D3FD019A8346930709D5D9F84810404624 -:1082000006F016FD0146584606F00AFC8346504A21 -:10821000505F06F0B9FC4F4AD16806F009FD82466E -:108220005146584606F0FAFB396A804606F000FDD2 -:10823000DFF844B106900399404606F0F9FCF96A6C -:1082400006F0F6FC54F80B1006F0EAFB42498046B3 -:1082500006F08CFE38B94046404906F0A5FE20B134 -:10826000DFF8F88001E0DFF8F0804BF80480DFF8F9 -:108270000CB1504654F80B1006F0D0FB44F80BA09C -:10828000034603994FF07E50029306F085FD029B52 -:108290000146184606F0CCFC0BF10C03E2580BF13A -:1082A000180B54F80B10824610460192029306F008 -:1082B000B7FB514606F0B4FB019A029B44F80B2031 -:1082C00044F803A0264906F067FDB96B06F0B0FC40 -:1082D0002449824606F04AFE38B95046224906F043 -:1082E00063FE20B1DFF880A001E0DFF878A00698F7 -:1082F000414606F095FB514606F090FB09F0CAFF97 -:108300001A4BB0F57A7FA8BF4FF47A709842B8BF85 -:1083100018460136164B032EE85204F1040405F109 -:10832000020507F104077FF41CAF09B0BDE8F08F28 -:10833000FC040020BD37863500004842D2270020CB -:10834000A803002000002041D4510108540200205D -:10835000F4040020EC03002000007AC300007A43FC -:1083600000004040000096C30000964318FCFFFF49 -:10837000F012002062020020E40E00203C130020D6 -:1083800010B50446204609F061FD10F0FF0F06D13C -:108390000C4B0D481978BDE8104003F0F3BC2046A3 -:1083A00009F0A9FD02280CD8064B0A221870074BC9 -:1083B000074C02FB0030074B06301860FCF7CAFB85 -:1083C000E0E710BD3C0E0020906801087C270020EB -:1083D0000D690108980500202DE9F047734A86B021 -:1083E00013789146DFF8D881C3B90122D8F800107C -:1083F00089F800206E4A1A445068884203D00C3332 -:10840000302BF7D10022022353726A4B6A48C3F81B -:10841000D010FCF7D1FD6948FCF7CEFDD8F800007C -:10842000FCF71EFD002800F0BE80654B614C18680B -:10843000FCF711FD0928014601D03F284FD14FF02C -:10844000000AA56B5F4F56462DB15F4839682A4632 -:1084500009F004FD10B9BA4606B93E465B4B0C372D -:108460009F42F1D3CEB13768DAF800E02B46F85CD2 -:108470001EF80310814201D0A3630EE05A1C41B9DB -:108480002D2B06D8A2632344202022441872117297 -:1084900003E04D4958541346E9E7A36B0BB1564529 -:1084A00012D04B48FCF788FD564509D856F80C0BFE -:1084B000FCF782FDD8F800000921FCF7E3FCF3E7A4 -:1084C0003E48FCF779FD0025A36B9D42A6D23E4BAA -:1084D000D8F80000595DFCF7D5FC0135F4E7A36B33 -:1084E00033B904283BD104F10800FFF7DDFB5AE063 -:1084F0000C2801D137488CE70A2901D00D2949D130 -:108500003548FCF759FDA36BE21800231372227A59 -:10851000232A17D00493314B2B4E009303A82949EB -:1085200015220C23039609F0EAFC054638B10068D1 -:1085300009F08CFC0130AB683044984702E02848D1 -:10854000FCF73AFD20480021302209F03EFC0023D0 -:10855000A36399F80030002B7FF45DAF23E00C2873 -:10856000C8D07F2903D159E72F2B3FF657AFA1F190 -:108570002002D2B25E2A3FF651AF13B920293FF450 -:108580004DAF5A1CA263D8F800001C442172FCF7BE -:1085900079FC43E77F29E7D1013BA3630022234411 -:1085A0001A72104838E706B0BDE8F087D0270020DF -:1085B0006400002090120020A1680108D968010819 -:1085C0008C1C002018540108981200201455010832 -:1085D000DE680108E36801085B630108794600086A -:1085E000EE6801080A6901082DE9F04FD84AD94C14 -:1085F00085B01068516802AB03C3DFF89083002197 -:108600004FF4EF62204609F0E0FB04F50573C8F86B -:108610000030D14B0025DFF878A31D7004F25673AB -:10862000CAF80030032363710223A36040F24C4078 -:108630004FF41673A4F8F030A4F81C01FA2340F2AA -:108640006C70A4F8F230A4F81E012A231920A4F8B3 -:10865000EE3084F825014FF4FA7340F27E40A4F81E -:10866000F630A4F8D000202340F23A7084F8F430B9 -:10867000A4F8D2006E234FF47A7084F80431A4F881 -:10868000D4002B2340F27E5084F80531A4F8D600A4 -:10869000212340F2EA500126552240F2DC514FF0EE -:1086A0001E0B4FF0320984F80631A4F8D8004FF4BD -:1086B000C87340F2B4502270A4F80831A4F81A111B -:1086C000A4F8DA00A4F8DE3084F8EC6084F821B174 -:1086D00084F8246184F82761A4F8DC90A4F8E09081 -:1086E0008DE8060003F0A6FC40F6AC53A381D8F851 -:1086F000003028271720A57318761F7183F80EB055 -:108700005F7183F80FB058761D700B20019A1872B4 -:10871000142058721875502098776420D8774FF03D -:10872000080E782083F813E05873DFF868C28B488E -:108730004FF00E0E9A7183F80AE02D224FF05A0E78 -:108740004FF00A0B1A745A7783F80BE01F73DA752F -:1087500083F821609D7683F807905D74DD769D74C3 -:108760001D7783F815B0C3F824C0D86318644FF0A0 -:108770008240D8624FF07C5098637948C3F828C093 -:108780005864784A7848DFF810C200991A635A632F -:108790009864C3F84CC084F856E74FF0410EA4F833 -:1087A0005E1784F857E784F85A5784F85B5784F8C3 -:1087B000589784F8595784F85C579A666B4A042195 -:1087C000DA666B4A83F858101521D86583F8607013 -:1087D00083F861701A6783F87460A3F85450A3F8A3 -:1087E0005650A3F8525083F86410624803F042FCDC -:1087F000D8F800304FF44872A3F86221C82283F8F9 -:10880000A7214FF49662A3F8A82140F2D932A3F829 -:10881000AA2140F6430283F85F7183F86061A3F8F0 -:10882000AC2183F85D5183F85E5183F8645183F87D -:10883000A6B11A46474656464FF47F71A2F8661114 -:108840004FF4FA61A2F8681102A840F2DC51A2F8D4 -:108850006A11415D013582F86C11082D4FF0FF015E -:1088600082F86D1102F10802E6D1012283F8AE21EF -:1088700083F8AF2183F8B021C82183F8B6216422A0 -:10888000A3F8B211A3F8B82114214FF4967283F81B -:10889000B411A3F8BA211E21282283F8B511A3F838 -:1088A000BC210023E21810330021C02B1161F9D143 -:1088B00031480021402209F088FA00232F49E218AC -:1088C000595804330868382BC2F8D401F6D12C4823 -:1088D0000021802209F079FA2A4B294D03F1300E4C -:1088E000186859682A4603C2083373451546F7D1FC -:1088F000254D01F0B1FE01F0EBFE01F0C5FE3F6831 -:10890000284639464FF4E07209F056FA394605F523 -:10891000E0704FF4E07209F04FFA336805F56372C6 -:108920005968186803C2198911801A68C5F8962316 -:108930005A68C5F89A231B89A5F89E33012384F849 -:108940002434022384F8E43505B0BDE8F08F00BF7D -:10895000D65101082C2000203C0E00208FC2753D0E -:10896000CDCC4C3D9A99193F0000A040F6287C3FA1 -:108970003D0A773F0E690108002200209C4401084F -:1089800080210020DE51010800240020E80300209F -:1089900098050020000020400000404008B5054830 -:1089A000FCF70AFBFFF720FE02F0A6FBBDE808403B -:1089B000FFF760B917690108F0B5884C884A236849 -:1089C0009D8AADB2E9B211F0010F32D0198821F4BD -:1089D00000610904090C1980198889B241F4806189 -:1089E0001980002111707F4908787F49A8B150781B -:1089F00018B97E480078FF280FD1012050707C48BC -:108A00000078022804D1188880B240F400601880F1 -:108A1000097841F00101198202E1097801F0FE01B3 -:108A20001982724B1B78FF2B00F0FA80FF23137022 -:108A3000F6E08F073CD5BFF35F8F6D490878C0B271 -:108A4000012814D1674D2D788DB155787DB11988E5 -:108A500021F480610904090C1980BFF35F8F198B21 -:108A60001988907089B241F4007119801BE0188B4D -:108A7000BFF35F8F087802280BD15A48007840B1C5 -:108A8000507830B1198821F480610904090C1980EB -:108A9000C0E00978032906D15249097819B1517803 -:108AA000002940F0B780998889B241F48061B6E02E -:108AB0004E075BD5012191704A49097800293AD0C7 -:108AC0005178002937D04A4910780978494D022950 -:108AD00019881ED921F480610904090C19801F8AA4 -:108AE0002E68C1B2FFB240B23754188880B240F449 -:108AF000007018808B1C1370236828681D8A013150 -:108B000049B2EDB24554998889B241F480619980A7 -:108B100027E089B241F4007119801E8A2D68C1B224 -:108B2000F6B240B22E541B8A481C40B2DBB203316D -:108B30002B54117015E0517811B92F49097841B1C2 -:108B4000198889B241F400711980137801331370C8 -:108B500007E0198889B241F480711980204B012106 -:108B6000597021680B88D805FCD459E001F0400108 -:108B700001F0FF061E48F1B11E49B3F810C00F689E -:108B800011785FFA8CFCCDB26E1C49B2F6B207F8D0 -:108B900001C01670077876B2F11C8F4205D1998812 -:108BA00021F480610904090C99800378B34237D11C -:108BB0000235157034E0290632D511784DB26F1C9C -:108BC0001ED00E4E01313668C9B2755D1170EDB21E -:108BD0001D82007849B2884222D11BE06412002035 -:108BE000641300206C120020691200206A12002019 -:108BF00078120020741200206B12002070120020E6 -:108C0000134916700978C9B219821249097809B94D -:108C1000017829B9998821F480610904090C9980A7 -:108C20000D4B92F9001018780C4B421C91420DD15B -:108C300000225A709B7833B12268938823F44073E2 -:108C40001B041B0C9380064B00221A70F0BD00BF62 -:108C50006A1200206C120020781200206413002099 -:108C60007912002070B5046D4279A38902F00401E5 -:108C700023F400531B041B0C0546866886B0A381B1 -:108C800001F0FF0021B14FF480604FF4005100E08B -:108C9000014612F0010F14BF0423002312F0020F4B -:108CA0001CBF43F008039BB212F0080F228A18BFC2 -:108CB0000C2392B222F4405211432182A28992B233 -:108CC00022F4B05222F00C02104303439BB2A38162 -:108CD000A38A01A823F440731B041B0CA38203F096 -:108CE000A7FB1949049A039B8C4208BF1346A2892B -:108CF0001921594312B2002AB4BF7600B600B1FB65 -:108D0000F6F16423B1FBF3F21201100903FB101119 -:108D1000A08900B2002806DAC9003231B1FBF3F3B2 -:108D200003F0070305E009013231B1FBF3F303F06F -:108D30000F031A4392B22B6D22819A8992B242F4A8 -:108D400000529A8106B070BD00380140417189E738 -:108D5000816087E7F8B50468054620460E46174649 -:108D600001F0E3FD032845D82B7B9B089AB246B956 -:108D70004FF0020C0CFA03F3A18989B221EA030334 -:108D8000A3810A2101FB00211B4B43F82160043120 -:108D900043F8217046B12A7B0225920805FA02F2B7 -:108DA000A1890A4392B2A281282202FB003000F17D -:108DB0002002EFF31286502383F312880023C11898 -:108DC0000D6915B115600A6904320433102BF6D110 -:108DD00000231360F3B283F31188036A23B1A389DC -:108DE0009BB243F0010304E0A38923F001031B04B9 -:108DF0001B0CA381F8BD00BFCC1E0020826A8169D4 -:108E0000436B1144D960416A914203D98A1A5A606E -:108E1000816204E001698A1A5A600022826200229B -:108E200080F844201A6842F001021A6070474B88AB -:108E300010B5DC0607D52D4B14791B6853F8244078 -:108E40002B4B43F820404B889B0607D5274B547982 -:108E50001B6853F82440264B43F820404B881C07DE -:108E60000DD5244B0C781B78B3EB141F07DB1F4B7D -:108E7000D4781B6853F824401D4B43F820404B889E -:108E80009B070DD51C4B0C781B78B3EB141F07DC2C -:108E9000164B54781B6853F82440154B43F8204078 -:108EA0004B88DC070ED5154B0C781B7804F00F04AB -:108EB0009C4207DC0D4B14781B6853F824400C4B84 -:108EC00043F820404B885B070ED50D4B09781B7883 -:108ED00001F00F01994207DB044B92781B6853F8AD -:108EE0002220034B43F8202010BD00BFA40A00201D -:108EF000980600204F0700204D0700204C07002057 -:108F00004E0700202DE9F74FA24F0C46FE7805468C -:108F10001146006891469B462246731CFB70FCF785 -:108F200011FFAB686868ADF8043018238DF806307F -:108F300001A902238DF8073001F044FD2B7B043793 -:108F4000360107EB060A2C680C2B00F2F280DFE8F2 -:108F500013F00D00F000F000F0004D00F000F00004 -:108F6000F0008200F000F000F000B600238C8A4888 -:108F700023F001031B041B0C2384218CA288238B68 -:108F8000844223F073034FEA03434FEA134389B249 -:108F900092B243F0700314D000F50060844210D008 -:108FA00000F5406084420CD000F58060844208D017 -:108FB00000F58060844204D021F0020141F00301F9 -:108FC00007E021F00E0122F4407241F0030142F467 -:108FD0008072A2802383A4F834B02184238B23F0F1 -:108FE00008031B041B0C43F0080332E0238C6A487F -:108FF00023F010031B041B0C2384218CA288238BD9 -:10900000844223F4E6434FEA03434FEA134389B211 -:1090100092B243F4E04308D000F50060844204D0EB -:1090200021F0200141F0300107E021F0E00122F4BD -:10903000406241F0300142F48062A2802383A4F8B0 -:1090400038B02184238B23F400631B041B0C43F4EE -:10905000006323836DE0238C4F4823F480731B044B -:109060001B0C2384218CA288A38B844223F07303DE -:109070004FEA03434FEA134389B292B243F07003BD -:1090800008D000F50060844204D021F4007141F45E -:10909000407107E021F4606122F4405241F44071D4 -:1090A00042F48052A280A383A4F83CB02184A38B15 -:1090B00023F008031B041B0C43F0080338E0B4F84A -:1090C00020C0354A2CF4805C4FEA0C4C4FEA1C4C13 -:1090D000A4F820C0B4F820C0A388B4F81C802CF4F5 -:1090E000005C28F4E6484FEA08484FEA0C4C4FEA87 -:1090F00018484FEA1C4C94429BB248F4E0484CF4A8 -:10910000405C03D002F50062944203D123F4804313 -:1091100043F48043A380A4F81C80A4F840B0A4F8D2 -:1091200020C0A38B23F400631B041B0C43F40063D7 -:10913000A383AB7B43B1B4F844306FEA43436FEA97 -:1091400053439BB2A4F8443023889BB243F00103FD -:1091500023802B7B0C2B14D8DFE803F007131313A9 -:109160000A1313130D131313100004F1340307E053 -:1091700004F1380304E004F13C0301E004F140038E -:10918000BB515046AAF80890CAF8044003B0BDE8A5 -:10919000F08F00BF64130020002C01402DE9F04740 -:1091A000054608F053FE2E4B0446D3F808809A4635 -:1091B00090B92C48FBF700FF2B4B53F8241049B112 -:1091C0000123A34013EA080F02D0284802F0DAFD79 -:1091D0000134F1E7264821E028462649224608F0D6 -:1091E0003DFE58B92448FBF7E7FE244C54F8041F11 -:1091F0000029EFD01D4802F0C5FDF7E72B780026C7 -:109200002D2B03BF013504F1FF344FF001094FF05E -:109210000009154B53F8267027B91948BDE8F047E7 -:10922000FBF7CABE28463946224608F017FEA8B901 -:109230000120B040B9F1000F03D001F098F91148B6 -:1092400004E040EA0800CAF808000F48FBF7B4FE43 -:1092500039460E48BDE8F04702F094BD0136D8E724 -:109260002C2000202D690108C45301084069010821 -:109270005B6301085470010844690108C053010888 -:1092800059690108706901087A69010825630108B4 -:109290002DE9F04F692887B0044600F0A78200F25C -:1092A00096802E2800F03A8562D8242800F00A859E -:1092B0002BD8202800F08282222800F0BE830128CB -:1092C00040F05D852C20FBF711FE0020FBF7DFFD51 -:1092D0002046FBF7DCFD0020FBF7D9FD4320FBF720 -:1092E000D6FD4C20FBF7D3FD4620FBF7D0FD4C20EC -:1092F000FBF7CDFD2046FBF7CAFD0020FBF7C7FDBD -:109300000020FBF7C4FD0024F0E0282800F0E284F0 -:1093100012D8262840F03385924C0320FBF7E6FD57 -:10932000B4F9E600FBF7E5FDB4F9E800FBF7E1FD71 -:10933000B4F9EA0000F034BC2A2800F0D6842C28C6 -:1093400040F01D85874C0720FBF7D0FD94F81801ED -:10935000FBF79DFDB4F91E01FBF7CBFDB4F91A0133 -:10936000FBF7C7FDB4F91C01FBF7C3FD00F0C3BC5C -:10937000642800F0E3801AD8322800F0BC840AD8B0 -:10938000302840F0FC84774C8020FBF7AFFD04F1DF -:10939000800500F0D9BC342800F06F83402840F0ED -:1093A000EE840820FBF7A2FD002400F0ADBC662887 -:1093B00000F09C81C0F0F080672800F0D081682820 -:1093C00040F0DD841020FBF791FD002406E27328B5 -:1093D00000F0BA8355D86D2800F01B8212D86B2894 -:1093E00000F0008440F2BB835F4C0620FBF77EFD5B -:1093F000B4F90000FBF77DFDB4F90200FBF779FD3D -:109400005A4B0EE26F2800F06782C0F00D82702880 -:1094100000F08182722840F0B284524C1620FBF793 -:1094200065FD0020FBF765FDB4F9D000FBF761FD99 -:109430004F4DB4F9D200FBF75CFDB4F9D400FBF753 -:1094400058FD2B68B3F9A801FBF753FD0020FBF78B -:1094500050FD0020FBF772FD2B68B3F952000A2380 -:1094600090FBF3F0FBF745FD94F80401FBF70FFDCB -:1094700094F80601FBF70BFD94F80501FBF707FDD7 -:10948000E6E3782800F0778110D8752800F0C982CB -:10949000C0F01483762800F0B783772840F06F84FB -:1094A000344D00242878FBF721FD42E3A42800F086 -:1094B000D18310D8A02840F062840C20FBF716FD61 -:1094C0002D4B1868FBF73AFD2C4B1868FBF736FD5F -:1094D0002B4B1868FBE3F02800F0E783FE2840F0F0 -:1094E0004E840820FBF702FD0024D6E3254B1B68C1 -:1094F000185D0134FBF7CBFC042CF7D1224B002480 -:109500001878FBF7F6FC214B185D0134FBF7BFFC24 -:109510000B2CF8D100241E4B185D0134FBF7B7FC6F -:10952000082CF8D10720FBF7B2FC0024194B185D7A -:109530000134FBF7ACFC072CF8D189E30720094C78 -:10954000FBF7D4FCE620FBF7A2FC6079FBF79FFC5D -:109550000020FBF79CFC94F82631002B0CBF042064 -:109560000C20B4E32C200020A8030020E0040020FD -:10957000E80300208A1C0020E8F7FF1FECF7FF1F1C -:10958000F0F7FF1FA8000020D7270020EF62010896 -:10959000FB620108046301080B20FBF7A7FCB64B34 -:1095A000B3F90000FBF7A5FCB44B188800B2FBF739 -:1095B000A0FCB34B1B68C3F3C000C3F38002800060 -:1095C00040EA4200C3F340021043C3F3401240EAB2 -:1095D000C20003F010031843FBF78BFCA94B1A8859 -:1095E00012F0010F0CBF0020022012F0020F0CBF7E -:1095F0000021042112F0040F0CBF0023102312F0ED -:10960000400F0CBF00242024019312F0100F9E4B3A -:1096100002940CBF00244FF4007412F0200F1B685A -:1096200003940CBF00244FF4806412F4807F0494F0 -:109630000CBF00244FF4006402F0080B03F4807A9E -:10964000059403F4805903F4005803F4004C03F428 -:10965000803E03F4003703F4802603F4002503F46E -:10966000801403F0C00343EA0B0343EA0A0343EA0E -:10967000090343EA080343EA0C0343EA0E0E834B53 -:109680004EEA07073E431B7835432C43C3F3800360 -:10969000234303430B430199029C0B430399234348 -:1096A000049C0B430599234312F4007F43EA010312 -:1096B0000CBF00224FF400121A43754B00201C7897 -:1096C0000346A3420CD273495D5C012101FA05F502 -:1096D000154218BF994003F1010318BF0843F0E792 -:1096E000FBF72CFC6C4B93F854070AE31220FBF7B2 -:1096F000FDFB6A4B6A4C1B88B3F5806F22D90025AD -:10970000605F082390FBF3F00235FBF7F2FB062DB8 -:10971000F6D1644CB4F90000FBF7EBFBB4F902009E -:10972000FBF7E7FBB4F904005F4CFBF7E2FBB4F98D -:109730000000FBF7DEFBB4F90200FBF7DAFBB4F93B -:1097400004002DE2B4F90000FBF7D3FBB4F90200EA -:10975000FBF7CFFBB4F90400FBF7CBFBD9E71020F4 -:10976000FBF7C4FB0024514B185D0134FBF78FFB62 -:10977000102CF8D116E23820FBF7B8FB00254C4E30 -:1097800005F12C043368E4002344B3F90600FBF729 -:10979000B0FB336801352344B3F90800FBF7A9FB9C -:1097A00033682344B3F90A00FBF7A3FB33681C4476 -:1097B000207BFBF76CFB082DE1D1F3E10820FBF7E0 -:1097C00095FB00243A4B1B6803EBC40393F86D012F -:1097D0000134FBF75CFB082CF4D1E3E1354B185D59 -:1097E0000134FBF754FB102CF8D1DBE1324D00249F -:1097F0002878400000F0FE00FBF778FB2B789C42B5 -:1098000080F0D0812D4B33F91400FBF772FB01344B -:10981000F4E70620FBF76AFB294B1868FBF78EFB81 -:10982000284BB3F90000BBE10720FBF75FFB264B99 -:109830004FF6FF741878FBF72AFB244B1868A042F8 -:10984000A8BF204620EAE07000B2FBF752FB204B95 -:10985000B3F90000FBF74DFB0F4B93F80C211D4BA8 -:1098600018680028B8BF40420AB10A235843A042F2 -:10987000A8BF204600B293E1FC0400202814002079 -:109880004C0200205402002050020020D627002065 -:109890008A1C0020741C00202C20002000000020C6 -:1098A000B4040020F40400207C02002012000020F8 -:1098B000E8030020A4270020630A00201A070020E4 -:1098C0005C020020C8030020C0050020C80500205D -:1098D000E60D0020C4050020B34C0720FBF706FB73 -:1098E00023681878FBF7D3FA23685878FBF7CFFA88 -:1098F00023681879FBF7CBFA23685879FBF7C7FA86 -:1099000023689879FBF7C3FA23689878FBF7BFFAC6 -:109910002368D878F5E1A54D1E20FBF7E7FA2B6800 -:1099200000241B78022B69D12B68A14903EB840327 -:10993000586A05F07DF908F0ADFCFA28A8BFFA20B6 -:1099400020EAE070C0B2FBF7A2FA2B68994903EB5A -:109950008403186B05F06CF908F09CFCFA28A8BF8A -:10996000FA2020EAE070C0B2FBF791FA2B68924926 -:1099700003EB8403D86B05F05BF908F08BFC6428DB -:10998000A8BF642020EAE070C0B20134FBF77FFA80 -:10999000032CC9D1072C2B681ED1986C844905F083 -:1099A00047F908F077FCFA28A8BFFA2020EAE0700F -:1099B000C0B2FBF76CFA2B687D49D86C05F038F91A -:1099C00008F068FCFA28A8BFFA2020EAE070C0B2CC -:1099D000FBF75DFA00200BE023441879FBF757FAF8 -:1099E0002B682344987BFBF752FA2B682344187E9C -:1099F0000134FBF74CFA0A2CCCD1D3E02B6823447A -:109A00001879FBF744FA2B682344987BFBF73FFA5D -:109A10002B682344187E0134FBF739FA0A2CEDD168 -:109A2000C0E02F20FBF762FA644C14F8010F002805 -:109A300000F0B880FBF72BFAF7E7A020FBF756FA07 -:109A400000245A4B04F11C021B680C2103EB820317 -:109A50005D1D5B4A5B79013401FB0323187AFBF738 -:109A600016FA6878FBF713FAA878FBF710FAE8788B -:109A7000FBF70DFA282CE4D194E04820FBF736FAE6 -:109A8000002506266E43494B06F588761B6801358E -:109A90001E44B07AFBF7FBF97079FBF7F8F9B0795F -:109AA000FBF7F5F9F079FBF7F2F9307AFBF7EFF90C -:109AB000707AFBF7ECF90C2DE3D173E00027012459 -:109AC0000025404B1B789D4222DA3F4BE95C002386 -:109AD0003B4A03EB02089A5C8A4204D00C33B3F58C -:109AE0008A7FF5D112E0D8F8040008F0AFF981467A -:109AF0000CB9264601E0074408E04E4506DAD8F8DE -:109B00000430985DFBF7C3F90136F6E70135D8E775 -:109B1000002C47D0F8B2FBF7E9F90024D0E7284A37 -:109B200099189A5C82420BD00C33B3F58A7FF6D138 -:109B300001342B789C4235D2234BE05C0023EEE7C6 -:109B4000087AFBF7A4F9F3E70820FBF7CFF9012423 -:109B5000E0B20134FBF79BF9092CF9D122E0102087 -:109B6000FBF7C4F9194B1A4C187800F00200FBF708 -:109B70008EF9184B1878FBF78AF92068FBF7DEF9A5 -:109B80006068FBF7DBF9144BB3F90000FBF7B1F9A0 -:109B9000124BB3F90000FBF7ACF9114BB3F902001B -:109BA000FBF7A7F90120EBE098050020E80300206F -:109BB000000020410000C84200007A440F52010812 -:109BC000704B01088A1C0020741C002082020020B7 -:109BD000DC050020D0050020CE050020CC050020AB -:109BE000281400200520FBF781F9674BB3F900002A -:109BF000FBF77FF9654BB3F90000FBF77AF9644B8B -:109C0000187800F001007CE0FAF700FF0646122009 -:109C1000FBF76CF90EB95F4B02E0102E03D15E4BDF -:109C20001D685C6801E0002425463046FBF72FF9EB -:109C30002846FBF783F92046FBF780F9574B186855 -:109C4000FBF77CF90020FBF754F90020FBF751F9F2 -:109C5000002056E0524D002428792E468000013025 -:109C6000C0B2FBF743F92879FBF711F933799C422D -:109C700098D24C4D285DFBF70AF905F11003185DE9 -:109C8000FBF705F905F12003185D3035FBF7FFF808 -:109C9000285DFBF7FCF80134E8E7434B185F02341A -:109CA000FBF727F9082CF8D17CE7404C0420FBF7A0 -:109CB0001DF92368B3F95600FBF71BF92368B3F9C4 -:109CC00054006DE70420FBF711F9394B9868FBF756 -:109CD00035F967E7364C0420FBF708F9B4F90801B9 -:109CE000FBF707F9B4F90A015AE70120FBF7FEF880 -:109CF0002F4B587905E00120FBF7F8F82C4B93F82F -:109D00002001FBF7C4F84DE7294B234493F81001D9 -:109D10000134FBF7BCF8082CF6D143E74020FBF7F1 -:109D2000E5F8234C04F14005B4F9D401FBF7E1F860 -:109D300094F8D601FBF7ABF8043494F8D301FBF7A1 -:109D4000A6F8AC42F0D12DE7B4F85601043400F087 -:109D50003F00FBF7CEF8B4F85201C0F38410FBF7D4 -:109D6000C8F894F850010009FBF791F894F85001F5 -:109D700000F00F00FBF78BF8AC42E5D112E70020B2 -:109D800007B0BDE8F08F00BF40060020420600206B -:109D9000F40F00204C0E0020580E00205802002026 -:109DA000281400202D1400206E140020E803002049 -:109DB0002C200020032810B50F4B0DD80F4A126835 -:109DC00094888C4208D2D2888A4205D9012202FAAC -:109DD00000F01A78104318701B780F2B0BD1064B2C -:109DE00000221A70064B998808B2142802DD143933 -:109DF000998010BD9A8010BD761400202420002088 -:109E00004C0A0020024B9A8801329A80704700BFAA -:109E10004C0A0020074B1A68074B1178B3F904006D -:109E200053780B4403EB83039842D4BF00200120F6 -:109E3000704700BF242000204C0A0020064BB3F9D5 -:109E40000400064B1B681B7803EB83039842D4BFC6 -:109E500000200120704700BF4C0A00202420002071 -:109E600010B50446FFF7EAFF002814BF2046002083 -:109E700000F0010010BD024B01221A72704700BFB2 -:109E80004C0A0020014B187A704700BF4C0A002092 -:109E9000034BB3F90400D0F1010038BF0020704734 -:109EA0004C0A0020014B00229A8070474C0A002087 -:109EB00003685A1C026019707047016B0346C26840 -:109EC00010B5406941B1196C541A005D013918BFD1 -:109ED0000A46C0B21A6410BD196A405C0131B1FB78 -:109EE000F2F402FB1412C0B21A6210BD026B0369D5 -:109EF0001AB15168013B026C02E0C169026A013B80 -:109F0000881A1840C0B27047436B13B190F84400F0 -:109F10007047826A436AD31A58425841704743795E -:109F20009B070AD5436A8269D154426A03690132A8 -:109F3000B2FBF3F103FB112343627047437913F043 -:109F4000010307D0C368C169026A013B881A18403F -:109F5000C0B2704718467047437910B513F001033B -:109F600004460DD0FFF7EAFF58B1226A6369985C96 -:109F7000E3680132B2FBF3F103FB1123236210BD4E -:109F8000184610BD426A806A131A584258417047F9 -:109F90004171704710F80A3C0133DBB20A2B00F81C -:109FA0000A3C0AD910F8123C23B910F8131C034AD2 -:109FB00022F81130002300F80A3C70474C190020A9 -:109FC000334A10B5136C90681944081A40F68C2374 -:109FD00098429160D060516013463CD9127893F951 -:109FE00045108A420BD1111F082908D893F8461052 -:109FF000182901D8013103E083F8442002E0002150 -:10A0000083F8461093F944108A421CD1204991F8F4 -:10A010004710C1B1002191421E4806DA03EB8104CA -:10A02000246920F811400131F5E7511E00EB410190 -:10A030001630814203D0002421F8024FF9E7164977 -:10A0400008780130087083F84520002201211A7039 -:10A0500083F8471010BD92F84710B9B1A0F2EF2471 -:10A0600040F2DA518C4208D811780B2905D80B1D23 -:10A070000131117042F8230010BD002283F84720FF -:10A08000991804320020302A0861F9D110BD00BFB0 -:10A09000100800204C190020281E0020024B1A6CCA -:10A0A000013211441964704710080020024B53F824 -:10A0B00020301B681980704738090020074BA1F534 -:10A0C0007A7153F820304FF47A701A681B894B4329 -:10A0D00093FBF0F39BB21380704700BF3809002058 -:10A0E0002DE9F04F504A514E1768738984463089E4 -:10A0F000A7EB032785B0039187FB0001B288CB1142 -:10A100001404C209F08842EA416287FB000114EBA3 -:10A11000020872884FF000054FEAC2344FEA10225D -:10A12000B08945EB030942EA01620B1287FB00018B -:10A1300014EB020A4FEAD05242EA41224FF00005E6 -:10A1400045EB030B12F5FA604FEAE15343F10001CE -:10A15000CDE90001B0F5FA6F71F1000147DAA2FB19 -:10A16000024502FB03F1052605EB4105A4FB0601B0 -:10A1700006FB05114D104FEA3004B8EB040869EBFB -:10A18000050984082A4844EA81748D104FF0FF3194 -:10A19000BAEB040A6BEB050BDDE9004584428D4107 -:10A1A00025DA40F6AC5012184FF0000143EB0103E2 -:10A1B00002FB03F1A2FB02236FF0060003EB410355 -:10A1C000544200FB0344A2FB000118EB00082144A9 -:10A1D0004FF00B0449EB0109A2FB040104FB03113E -:10A1E00049104FEA3000BAEB000A6BEB010B114B40 -:10A1F0001A68A2FB0A0102FB0B11420D42EAC122BE -:10A200004B15B2EB080263EB0903D00B40EA434065 -:10A21000BCF1000F01D0CCF80000039808B1009900 -:10A22000016005B0BDE8F08F7C120020CC07002053 -:10A2300024FAFFFF80120020324B2DE9F0411C88E8 -:10A24000314B0A265A89B3F91250A41A1A89ED0221 -:10A250005443B3F91420E413224495FBF2F2224450 -:10A26000DA615643A2F57A6202FB02F4B3F9048084 -:10A27000B3F902C0B3F90E7002FB0CFC02FB08F24A -:10A28000B3F90C802413674304FB08F4241404EB93 -:10A2900062320232DC88921002F50042B3F920509B -:10A2A0006243B3F900304FEAEC2404EBE72404EBFB -:10A2B0008304AC40154B02341B68D20BA3EBA404FF -:10A2C0004CF250332B41634355BF5B00B3FBF2F3B9 -:10A2D000B3FBF2F35B001A12524340F6DE346243E2 -:10A2E0000B4C08365C43241404EB224202F6CF6286 -:10A2F000361103EB221300B1036001B10E60BDE81B -:10A30000F08100BF8C120020E0070020881200209E -:10A3100043E3FFFF2DE9F04102780346202A00F1D4 -:10A320000100F9D0092AF7D02D2A02D10346414D68 -:10A3300004E02B2A08BF03464FF07E551E4600243A -:10A34000334616F8012BA2F13007F9B209290DD8CE -:10A350003949204604F06CFC0446384604F014FCED -:10A360000146204604F05CFB0446E9E72E2A17D19B -:10A37000314F334616F8010B3038C2B2092A0FD8D4 -:10A3800004F002FC394604F007FD0146204604F0C3 -:10A3900047FB29490446384604F04AFC0746E8E7EB -:10A3A0001A7802F0DF02452A38D15A782D2A02D1D4 -:10A3B0000233012604E02B2A14BF013302330026A6 -:10A3C000013B002713F8012F303AD1B2092903D8F5 -:10A3D0000A2101FB0727F5E7B7F59A7F28BF4FF45D -:10A3E0009A77B8464FF07E51B8F1070F07D9084663 -:10A3F000124904F01DFCA8F108080146F4E707F033 -:10A40000070737B108460C4904F012FC013F01462A -:10A41000F7E72EB1204604F0BFFC04E04FF07E5178 -:10A42000204604F005FC0146284604F001FCBDE886 -:10A43000F08100BF000080BF0000204120BCBE4C66 -:10A44000F0B50124B0FBF4F58D4201D34C43F9E79C -:10A450000026DCB1B0FBF4F504FB1500B4FBF1F40D -:10A460001EB9002D01DC002CF3D1092D03F10107E9 -:10A470005FFA85FC04DD002A0CBF5725372500E074 -:10A48000302565441D7001363B46E2E71C70F0BD87 -:10A49000F0B50124B0FBF4F58D4201D34C43F9E74C -:10A4A0000026DCB1B0FBF4F504FB1500B4FBF1F4BD -:10A4B0001EB9002D01DC002CF3D1092D03F1010799 -:10A4C0005FFA85FC04DD002A0CBF5725372500E024 -:10A4D000302565441D7001363B46E2E71C70F0BD37 -:10A4E00070B50646B6FBF2F40846154614B1204690 -:10A4F000FFF7F6FF05FB1464024B1B5D00F8013B00 -:10A5000070BD00BF886901082DE9F041069C002B51 -:10A5100006460F460CBF4FF020084FF03008234688 -:10A5200013F8011B09B9154603E0002AFBDD013AC7 -:10A53000F6E7002D04DD30464146B847013DF8E717 -:10A5400014F8011B11B13046B847F9E7BDE8F081B6 -:10A5500080EAE073A3EBE0738B4206DB002801DDA9 -:10A56000401A704702D00844704700207047034BE0 -:10A570009A6822EA00009860704700BF2C200020F3 -:10A580000E4B1B78BBB10E4B1B681A78032A06D101 -:10A590000C4B187802288CBF0020012070475B7894 -:10A5A00023B1094B1868C0F3C0407047074B1878B7 -:10A5B000C0F3800070470120704700BFD20D00201B -:10A5C000AC0500206C06002050020020D627002099 -:10A5D000114A30B50028B8BF4042104C90FBF2F34E -:10A5E00004FB03003C2568430D4D90FBF2F22D68FF -:10A5F0002D7B25B903EB830303EB830301E0C3EB5E -:10A60000031302EB830304FB02020B804FF47A7303 -:10A6100092FBF3F24A8030BD80969800806967FF14 -:10A62000D4050020034B1B681878C31E58425841BC -:10A63000704700BFAC05002008B5064807F006FCCF -:10A64000C0B2142805D8034A431C20211154D8B2A3 -:10A65000F7E708BD111E0020094A0A48002310B57B -:10A66000116803701A46CC1864880CB9CC5C24B10C -:10A6700004330132802BD2B2F5D1027010BD00BF7D -:10A68000940600201807002010B50B4B0B481978D2 -:10A690000B4B5A784B085C1E047001F0010109480D -:10A6A0000B44037008495308581E087002F0010259 -:10A6B000064913440B7010BD510700204C070020C1 -:10A6C000761400204E0700204F0700204D07002081 -:10A6D000F0B50F4A0F4816780F4A002317684370E9 -:10A6E0001A4619460546D0B2B0420CD217F82200DD -:10A6F000013204099C4200F00F00A8BF631C88428D -:10A70000A8BF411CEFE76B70044B1970F0BD00BF90 -:10A71000180700207614002094060020510700201E -:10A72000F8B5101A0C461F4604F02EFA0546381BE1 -:10A7300004F02AFA174B079E196804F079FA2946A3 -:10A740000446284604F074FA21460746204604F0E1 -:10A750006FFA0146384604F063F907F0F1FF0E493D -:10A7600004F066FA04F050FC069B2146186005F1DF -:10A77000004007F05BFE094904F05AFA084904F06A -:10A780004FF904F01BFC0028BCBF00F50C40A030C2 -:10A790003060F8BD4C0000202C7D8E3FA00CB345EE -:10A7A00000A00C4610B504F0EFF90021044604F0B7 -:10A7B000FBFB08B1204601E004F10040054904F02C -:10A7C000EBFA054904F034FA07F02EFD034B18604C -:10A7D00010BD00BF8096184B35FA8E3C4C0000200F -:10A7E00070B50446007904F0CBF91E4904F0D4FAA0 -:10A7F0001D4D1E4E2860A07B04F0C2F9194904F0DB -:10A80000CBFAEE606860607904F0BAF9184904F098 -:10A81000C3FA184D2860E07B04F0B2F9114904F046 -:10A82000BBFA6860607E04F0ABF9134904F0B4FA37 -:10A83000EE60A860A07904F0A3F90D4904F0ACFA29 -:10A840000E4D2860207C04F09BF9064904F0A4FA20 -:10A850006860A07E04F094F9074904F09DFAEE6068 -:10A86000A86070BD0000C842801100200000FA44BA -:10A87000000020419011002000007A44B411002013 -:10A8800044F25063984203DDA0F50C40A0387047B5 -:10A89000034B9842BCBF00F50C40A030704700BF8E -:10A8A000B0B9FFFF2DE9F041038A87890446BFB2A2 -:10A8B0000D461F40002F36D0B7FA87F34FF0004205 -:10A8C000DA40D24391B21B3B21821740042BF1D8CE -:10A8D000DFE803F0221F1C1903006B6A33B103F198 -:10A8E000FF3800231FFA88F86B6203E0B4F82C806D -:10A8F0001FFA88F82E6A002EDCD0336830464146B5 -:10A9000098477668F7E72868A18E08E06868218F85 -:10A9100005E0A868A18F02E0E868B4F84010036879 -:10A9200089B29847C6E7BDE8F0810C4B800A98428F -:10A930000CD003D8B0F5801F0ED00BE0084B984226 -:10A9400006D04933984205D1002070470220704755 -:10A9500003207047FE20704701207047010010005F -:10A960000200100090F83B3210B57BB990F83A32F3 -:10A9700090F83922934209D201219940B0F840421F -:10A9800001332143A0F84012DBB2F3E710BD837915 -:10A99000012B03D1D1F1010138BF0021D0F83431AE -:10A9A0005A681B8909B11361704753617047044BA2 -:10A9B00053F820301BB107289CBF1B6819807047D3 -:10A9C000680900202DE9F0410F88002347FA03F2BF -:10A9D000D2072BD58A7803F0070512F0100F18BFA5 -:10A9E00091F803C002F00F0618BF46EA0C06AD004E -:10A9F0004FF00F0C0CFA05FC06FA05F5DC0850F8D0 -:10AA00002480282A28EA0C0C45EA0C0540F824503A -:10AA100005D101229A40C46824EA020205E0482ACE -:10AA200004D101229A40C4682243C2600133102B32 -:10AA3000CCD1BDE8F08100BF1FB50123ADF80830CF -:10AA4000ADF80410002301A9ADF80A30ADF80C30C0 -:10AA5000ADF8062001F090FB05B05DF804FB10B5E1 -:10AA6000A0F5127494F83C22C2B9A36A616A9942B3 -:10AA700029D0591CA069A162C05C2369C0B2994267 -:10AA80004FEA400343F40073A4F83E324FF00A0348 -:10AA900084F83D3228BFA262012312E094F93D32CE -:10AAA0007BB1B4F83E1220464B08A4F83E3201F0C8 -:10AAB0000101FFF76CFF94F83D32013B84F83D3211 -:10AAC00001E084F83C3294F83832002B4FD194F8EE -:10AAD00039320133DBB2092B84F8393204D12046F4 -:10AAE000BDE81040FFF73EBF0A2B40D194F83B323F -:10AAF0002BB9B4F8403243F00103A4F84032637933 -:10AB0000D9071CD5B4F84002820501D4C30705D487 -:10AB1000B4F844320133A4F8443210E0E36AC0F3DD -:10AB200047000BB198470AE0E3696269D054E269D3 -:10AB3000E3680132B2FBF3F103FB1123E36101226D -:10AB400084F8382294F83B220023012A84F8393211 -:10AB50000DD1A27984F83B32236B012A1868197B46 -:10AB600014BF02220022BDE81040FFF765BF10BDF0 -:10AB700010B5A0F513746379DB074CD594F838321F -:10AB800013B3236B1868828DC2F34E02828494F84B -:10AB90003C2222B1B4F842220132A4F84222A27926 -:10ABA000197B012A0CBF02220022FFF745FF012377 -:10ABB00084F83B32002384F8393284F83A3284F83E -:10ABC0003832A4F8403210BD94F83B322046012BB5 -:10ABD00004BF94F8393284F83A32FFF7C3FE94F890 -:10ABE0003B12236BA27949B9012184F83B128A42B6 -:10ABF0001868197B0CBF0222002208E0002184F8AB -:10AC00003B12012A1868197B14BF02220022BDE8FA -:10AC10001040FFF711BF10BD426A10B58469A154FE -:10AC2000416A02690131B1FBF2F402FB1412426283 -:10AC3000426B32B11368DB0708D4BDE81040FEF761 -:10AC4000DDB8036DDA6842F08002DA6010BDF7B556 -:10AC50000368174C174D23600B68174E636000683C -:10AC6000FFF7A0FD95E80300144B0196009394E8CC -:10AC70000C00FFF755FD3668114B60681E606B686D -:10AC8000104FC01A03F080FF0F4B196803F0D0FF7C -:10AC900004F094F922682B687860D31A3B600B4B60 -:10ACA0001E600B4B1B68DA880A4B1A8003B0F0BD9C -:10ACB00068110020DC0500207411002070110020B4 -:10ACC000B0110020781100204C000020A8110020B5 -:10ACD0008C050020A41100202DE9F043142285B03A -:10ACE000814688461B48002107F06FF803261A4B5F -:10ACF0000027B74224DA13F8042C0021C8B201312E -:10AD000012B1501E0240F9E71C7AD1B2013214B1DF -:10AD1000611E0C40F9E7421A002A0EDD01ACA3F1D6 -:10AD20000C0595E8070084E8070093E8070085E82C -:10AD3000070094E8070083E8070001370C33D8E7E1 -:10AD4000013ED4D1034A4846414605B0BDE8F04330 -:10AD500002F0CEBD7C140020700000200022064BC3 -:10AD600013445968814203D00C32302AF7D10023B2 -:10AD700000225A725A6070476400002038B50E4DA8 -:10AD800004462B68834207D10121FFF7E7FF2846DD -:10AD900000214C2207F019F8EB6CA3420AD120469F -:10ADA0000121FFF7DBFFBDE83840044800214C22B9 -:10ADB00007F00BB838BD00BF400F00208C0F0020FB -:10ADC00010B50023054A1A445468844203D00C335A -:10ADD000302BF7D10022517210BD00BF640000205B -:10ADE0002DE9F34706461F464FF414737343474853 -:10ADF0009246C41880460EB9454A02E0012E04D19D -:10AE0000444A22631032C4F83421434A0025C25018 -:10AE1000032363714FF480734FF00109E3602361F2 -:10AE2000D4F8343184F83C5284F8389284F839529A -:10AE300084F84662586804F134029B68626104F544 -:10AE40009C72A261E1622562E561A5626562A4F877 -:10AE50004252A4F84452ADF804300225102301A94F -:10AE6000C4F808A0A7718DF806308DF80750FFF7D9 -:10AE7000A9FD236B01A958689B688DF80750ADF8B0 -:10AE8000043048238DF80630FFF79CFD49462046E4 -:10AE9000FFF77DFD3220F9F776FF204BD4F834918F -:10AEA0001B681D46B5FBFAF1B1F5803F03D3012DB8 -:10AEB000F8D96D08F6E71A4A4846B3FBF2F289B2B0 -:10AEC000D2B200F0FFFC4FF414735E43154B06F54D -:10AED000127608EB060548F8063048462946002257 -:10AEE000FDF738FF266B012F14BF022200223068C5 -:10AEF000317BFFF7A1FD0C4B30466B60291D002212 -:10AF0000FDF728FF204602B0BDE8F087901400202E -:10AF1000A0600108C06001084C520108A400002094 -:10AF200040420F005FAA000871AB000803460A46C2 -:10AF300090F84602D96A9B7952E7F8B50022074695 -:10AF40003749130101F11800185CB84204D00132EE -:10AF5000082AF5D10020F8BD324E0B44183306F212 -:10AF6000B445082F0FCB344685E80F001BD009D815 -:10AF7000022F0ED0042F16D0012F4FD12A4B1B6861 -:10AF80005B6847E0202F42D0402F06D0102F45D1DC -:10AF900022E0254B1B689B6802E0234B1B681B6962 -:10AFA000C6F8B83436E0214B1B681B7853B1013B1F -:10AFB000012B0AD9FFF736FB002814BF4FF4614379 -:10AFC000002304E04FF4165301E04FF49643C4F815 -:10AFD000B834C4F8BC3421E0154B1B681B7A042B31 -:10AFE0001CD8DFE803F00A0A030A0A00114BC6F86E -:10AFF000B834C6F8BC34032306E04FF4E133C6F896 -:10B00000B834C6F8BC34012384F8C13406E0064BDA -:10B010001B68DB68C6F8BC342846F8BD0648F8BD96 -:10B020004C5201087C140020D80F0020AC050020F1 -:10B030003C010020A08601003019002010B5044614 -:10B04000FFF77BFF01462046FFF746FE4368187A6C -:10B0500010F0010018BF586810BD38B505460C4601 -:10B06000FFF76BFF01462846FFF736FE28B143681D -:10B070001B7A1C420CBF0020012038BD38B50B4B99 -:10B0800005469B685A050ED5FFF7CCFA044650B129 -:10B090000820E9B2FFF7E1FF30B1054B1C78231F10 -:10B0A0005C425C4100E00124204638BD2C20002099 -:10B0B0006C0600200E4B1A78552A16D15A88B2F524 -:10B0C000EF6F12D11A79BE2A0FD193F8742700209E -:10B0D000EF2A0CD113F8012B5040064A9342F9D1C4 -:10B0E000D0F1010038BF0020704700207047704742 -:10B0F00000F8010878FF01084A4B55222DE9F34179 -:10B100001A704FF4EF625A80BE221A71EF2283F850 -:10B110007427002283F8752711461E46B35C01325E -:10B12000B2F5EF6F81EA0301F8D13E4B3E4A83F856 -:10B1300075173E4B04275A6002F188325A6000208E -:10B14000013F17F0FF075DD0384B3422384CDA60EE -:10B15000C4F309037BB1331903F17843A3F5FC333E -:10B16000D3F800804FF400500023019301F000FA5F -:10B170000428E5D11BE04FF4302001F0F9F9042850 -:10B18000DED12A4D4FF430202B6943F002032B61AE -:10B190006C612B6943F040032B6101F0E9F92A69E6 -:10B1A00041F6FD73134004282B61D4D0C8E71F4D2E -:10B1B0004FF400502B6943F001032B611FFA88F311 -:10B1C000238001F0D5F9042812D1A31C0193019B1F -:10B1D0004FEA1848A3F800804FF4005001F0C8F976 -:10B1E0002B6941F6FE721A4004282A6106D0A7E7AF -:10B1F0002B6941F6FE721A402A61A1E70D4B043417 -:10B200009C42A5D1094B04281A6942F080021A61B8 -:10B2100002D1FFF74FFF10B90A20F9F7EBFD02B09A -:10B22000BDE8F0812C20002023016745002002406A -:10B2300000F8010878FF01088A2802D08E2809D07A -:10B240007047094B1B689B060DD5084B1B7853B9FB -:10B25000074A03E0054B1B782BB9064A064B1A60D8 -:10B26000064B2D221A7070474C0200204406002025 -:10B2700014060020E8050020500600205906002092 -:10B28000234B70B519684FF47A73B1FBF3F1214B7E -:10B2900021481A78214B224D1B7800F073FD214B79 -:10B2A00021481968214B2E68B1FBF3F100F06AFDCB -:10B2B00000241F4BE2B253F8221049B1012303FAD4 -:10B2C00002F2324202D01B4800F05CFD0134F0E78C -:10B2D0002A6892070DD5184A1848127803EB8203A2 -:10B2E000196A00F04FFD164B197A11B1154800F09C -:10B2F00049FD1548F9F760FEBDE87040134B14484E -:10B300001A88144B92B219884FF4EF6300F03ABDDB -:10B3100028200020C0050020CE69010894000020EC -:10B320004C020020A40000200C6A010840420F00DB -:10B33000E452010840690108D82700202A6A010860 -:10B3400058040020346A01085B63010828140020B7 -:10B35000386A0108FC04002070B50E46202115460D -:10B3600006F067FD0446B8B1441C204606F0C3FD54 -:10B37000B0F5617F05DB40F634039842A8BF18465C -:10B3800001E04FF461701923A0F5617090FBF3F0B8 -:10B3900030702B7801332B702046202106F049FDB8 -:10B3A0000446B8B1441C204606F0A5FDB0F5617F07 -:10B3B00005DB40F634039842A8BF184601E04FF47D -:10B3C00061701923A0F5617090FBF3F070702B7819 -:10B3D00001332B70204670BD70B586B0054606F06F -:10B3E00035FDC0B208BB044606236343444A03F557 -:10B3F0008873126819201344591D4D789A7A454371 -:10B4000005F561755B7900958D78684300F561708D -:10B410000190C878029009793A4803912146013495 -:10B4200000F0B0FC0C2CDFD168E0284606F063FD8C -:10B430000B285FDC06267043314B00F588701E68D0 -:10B44000202106440023681C8DF8173006F0F1FC1B -:10B45000741D054658B1451C284606F04CFD0328CE -:10B4600005D89DF81730607101338DF817302846E4 -:10B47000202106F0DEFC054658B1451C284606F0A2 -:10B480003AFD0D2805D870719DF8173001338DF8FD -:10B4900017302846611C0DF11702FFF75DFF2021D0 -:10B4A00006F0C7FC054658B1451C284606F023FDAA -:10B4B0000C2805D89DF81730E07001338DF817304F -:10B4C0002846202106F0B5FC50B1013006F013FDEE -:10B4D0000D2805D89DF81730207101338DF81730ED -:10B4E0009DF81730062B09D020460021062206F0D1 -:10B4F0006CFC03E004480C2100F044FC06B070BD75 -:10B50000E80300206A6A0108D8640108F0B585B034 -:10B51000074606F09BFCC0B2E0B90446324B04F18A -:10B520001C021B68192003EB8203591D8D785A7980 -:10B53000454305F561759B790095C978484300F549 -:10B540006170019021462948013400F01BFC282C31 -:10B55000E4D146E0384606F0CEFC27283DDC224BFD -:10B5600000F11C061B68781C03EB860620210023D3 -:10B570008DF80F3006F05DFC751D044658B1441C73 -:10B58000204606F0B8FC152805D870719DF80F30DC -:10B5900001338DF80F302046202106F04AFC044686 -:10B5A00058B1441C204606F0A6FC0D2805D89DF88D -:10B5B0000F30687001338DF80F302046A91C0DF153 -:10B5C0000F02FFF7C9FE9DF80F30042B09D0284663 -:10B5D0000021042206F0F9FB03E00548282100F0D1 -:10B5E000D1FB05B0F0BD00BFE80300208A6A010866 -:10B5F000D864010830B585B004AC002524F8025D9C -:10B600000091ADF8060021461020F9F735FD9DF8B0 -:10B6100006002146F9F730FD9DF807002146F9F7AD -:10B620002BFD9DF800002146F9F726FD9DF801004D -:10B630002146F9F721FD9DF802002146F9F71CFD8E -:10B640009DF803002146F9F717FD9DF80E002946E5 -:10B65000C043C0B2F9F710FD024B1A68024B1A60E2 -:10B6600005B030BD282000208006002038B5834B6F -:10B67000834A197832F8110010B918704FF403603A -:10B680001978B0F5C06F01F10101C9B27B4A197098 -:10B690004CD019D8B0F5007F44D006D8B0F5807FE3 -:10B6A00042D0B0F5887F63D038BDB0F5806F72D0DE -:10B6B000B0F5826F00F0AC80B0F5047F40F0DC8024 -:10B6C000704B53211B78D1E0B0F5006F30D00DD80E -:10B6D000B0F5E26F54D0B0F5E46F55D0B0F5E06F3F -:10B6E00040F0CA80684BB3F9001050E0B0F5036F2A -:10B6F00007D0B0F5046F3ED0B0F5026F40F0BC80CB -:10B70000A8E0624B1B689A0640F1B680604B1B783C -:10B710009B0740F1B1805F4B24211B885943642370 -:10B72000123135E05C4B24E05C4B22E05C4B20E0C6 -:10B73000564B1B689D0640F19F80554B1B789C071C -:10B7400040F19A8011F0010F564B08D0596800293A -:10B75000BCBF494241F0804141F0004105E0196819 -:10B760000029BCBF494241F080414FF400607EE0B7 -:10B770004D4B19687BE04D4B6421B3F9003075E007 -:10B78000414BB3F9021002E03F4BB3F904102C23F4 -:10B7900091FBF3F16BE051780131C9B2032988BF05 -:10B7A000012151705B7842F210715943404B1B7874 -:10B7B000D80748BF01319A0748BF02315D073D4BAA -:10B7C00048BF04311B88DC0748BF0A31980748BFCF -:10B7D00014311A0648BF2831DD0548BF28315C07FF -:10B7E00048BF6431180748BFC8319A0548BF01F502 -:10B7F000C8719D0648BF01F57A71DC0648BF01F5A6 -:10B80000FA61580648BF01F57A614FF480602EE076 -:10B810001E4B294C1D6815F0200516D01C4B1B78BB -:10B8200013F0020F0CBF00214FF47A7113F0010FD7 -:10B830000CBF00234FF4FA631944204B1B781944C2 -:10B84000FFF7D8FE0023237038BD2946FFF7D2FE4C -:10B85000257038BD0D4B1B689A060DD50C4B1B7817 -:10B860009B0709D5164B4FF47A711B885943FFF794 -:10B87000C1FE114B00221A7038BD00BF40190020D4 -:10B88000AE690108C0050020B40400204C0200206D -:10B8900082020020CC050020C4050020A403002063 -:10B8A000C8050020DC050020C8030020E0040020BB -:10B8B000D6270020540200207C060020D00500205E -:10B8C000CE05002013B504460068FAF73BFA23685A -:10B8D00001A81A8892B242F001021A80637B00220A -:10B8E0008DF8043001238DF805308DF806208DF891 -:10B8F0000730FAF7A3F902B010BD40F2E9330F4A5E -:10B900001189890709D5908140F2E9330B4A1189E1 -:10B91000C9070DD59089C0B27047013B9BB2002B7F -:10B92000EDD1074BFF201A88013292B21A8070477E -:10B93000013B9BB2002BE9D1F3E700BF0038004088 -:10B94000760700207FB52B4B2B4C9A69206042F084 -:10B9500001029A61294D03881026ADF8043028466B -:10B96000022301A98DF807308DF80660FFF72AF849 -:10B97000236828465B88ADF8043004230DEB0301EF -:10B980008DF80630FFF71EF822680F20137A03F0B7 -:10B9900003018900884003F0FC0303F1804303F5B1 -:10B9A00080339D6825EA0000012505FA01F19860C1 -:10B9B0009868014399605368114A02A85361029341 -:10B9C00000238DF80C308DF80E508DF80D60FAF7CD -:10B9D0008FF923680B4A5B7A59B203F01F039D402D -:10B9E0004909094B42F821501A68084B3C3A1A6041 -:10B9F00004B070BD00100240E0030020000C0140C4 -:10BA00000004014000E100E028200020D8030020CD -:10BA10000B4B07B59A690B4842F010029A614FF43C -:10BA20000053ADF8043002238DF8073001A910232C -:10BA30008DF80630FEF7C6FF03B05DF804FB00BFCB -:10BA40000010024000100140104B043033F9103058 -:10BA5000B3F5617F05DB40F633029342A8BF13467E -:10BA600001E04FF4617308781922504300F28330EB -:10BA7000984208DA4878504300F283309842B4BFC5 -:10BA80000020012070470020704700BF1A070020E7 -:10BA9000114B70B51B685E89104B186880F310005D -:10BAA000301A02F0A7FC00220D4B02F009FD0446FB -:10BAB00030460D4602F09EFC02460B4620462946C3 -:10BAC00002F028FE02F00EFF6428A8BF642020EADE -:10BAD000E070C0B270BD00BFBC050020C8050020EA -:10BAE0000000594038B5114B114D1A78114C296896 -:10BAF0008AB162680244914217D300201870F9F7A6 -:10BB00004CF92B6863600C4B1A780AB1013A1A7031 -:10BB10000123237238BD6268C832914205D30120E7 -:10BB20001870F9F73AF92B68636038BD3B0F0020B5 -:10BB300028200020401900209A04002037B5224D0B -:10BB40008DF807306B7A8DF8062002AA8DF8040074 -:10BB50008DF805101A4412F8042C443AD2B20F2A78 -:10BB60002BD81A49022B01EB4202B2F84C4003D801 -:10BB700014B12046FFF7B6FF6B7A134A022B09D99E -:10BB8000134B19685368091B8B4203D2002353726D -:10BB9000104A13702B7A012B00D09CB96B7A022BC0 -:10BBA00002D8094A013353720B4B002028721870D7 -:10BBB00003B0BDE83040F9F7F0B8022B4FF0C804ED -:10BBC000D7D9D9E703B030BD40190020E4520108AD -:10BBD000282000209A0400203B0F00200449054B38 -:10BBE0000968002218701A6159611A76704700BFFF -:10BBF00028200020800A00202DE9F04F064689B059 -:10BC00000F4615469B462978002900F0B880252963 -:10BC100002D001353046B0E06C78302C03D00235CC -:10BC20004FF0000903E0AC784FF001090335A4F1AF -:10BC30003003092B4FF000081AD8A4F13003DAB210 -:10BC4000092A07D80A2B13DC0A2202FB083815F848 -:10BC5000014BF2E7A4F16103052B02D8A4F15703CD -:10BC6000F0E7A4F14103052B02D8A4F13703E9E77B -:10BC70006C2C03BF2C78012201350022632C66D086 -:10BC800006D8252C77D0582C3FD0002C77D0BAE797 -:10BC9000732C63D002D8642C11D0B4E7752C02D079 -:10BCA000782C32D0AFE70BF1040A05ACDBF80000CA -:10BCB0000A2112B10022234613E0234620E00BF1B3 -:10BCC000040A05ACDBF8000072B1002806DA2D2367 -:10BCD0008DF8143040420DF1150300E023460A218F -:10BCE0000022FEF7D5FB0DE0002806DA2D238DF8A3 -:10BCF000143040420DF1150300E023460A210022D2 -:10BD0000FEF79EFBD34600941AE00BF10403039365 -:10BD10000DF1140ADBF80000102132B1583C6242E8 -:10BD200062415346FEF7B4FB06E0B4F158035A42B1 -:10BD30005A415346FEF784FBDDF80CB0CDF800A065 -:10BD40003046394642464B46FEF7DEFB5BE730465F -:10BD50009BF800100BF10404B8470AE0DBF8003050 -:10BD6000304600933946424600230BF10404FEF7A7 -:10BD7000CBFBA34647E730462146B84743E709B027 -:10BD8000BDE8F08F0FB407B50A4904AB08680A494B -:10BD900053F8042B09680193FFF72EFF074B18682F -:10BDA000F9F74FF80028F9D003B05DF804EB04B0C0 -:10BDB000704700BF5C070020580700206013002078 -:10BDC000F8B5074606F042F8044638B9194B1A4848 -:10BDD0005A791A4B013A53F8221028E0384618498C -:10BDE000224606F03BF860B91648F9F7E5F8164C1C -:10BDF00054F8041F19B11548FFF7C4FFF8E71448B9 -:10BE000005E000250D4B53F8256026B91148BDE823 -:10BE1000F840F9F7D1B838463146224606F01EF808 -:10BE200001350028EED1034B0B485D713146BDE86A -:10BE3000F840A7E72C2000200F6B01086853010889 -:10BE400054700108236B010864530108406901081C -:10BE50005B630108E0630108366B010870B50446B6 -:10BE600005F0F4FF08B91E482EE020461D4906F0F3 -:10BE700067F800242646254678B12CB1012C06D15E -:10BE800006F039F8064602E006F035F80546154991 -:10BE90000020013406F054F8EEE70B2D04D9BDE87C -:10BEA000704011480C216DE7012C07DC0F4B29462F -:10BEB00033F915200E48BDE8704063E7A6F57A73A4 -:10BEC000B3F57A7F03D90B48BDE870405AE70A48BA -:10BED00029463246FFF756FF044B23F8156070BD24 -:10BEE000486B0108DC680108826B0108DC0F002048 -:10BEF000A86B0108C06B0108E26B01082DE9F7434C -:10BF0000044605F0A3FFC0B290B9304C054694F842 -:10BF1000D711B4F8D42194F8D6312D480091294690 -:10BF20000135FFF72FFF102D04F10404EFD14AE093 -:10BF3000204605F0E0FF0F28054636DC204620218C -:10BF400005F077FF234FEDB2D7F80090441CAD0009 -:10BF50000026204605F0CFFF5FFA86F8B8F1010F02 -:10BF600083B208D0B8F1020F0BD0B3F5B47F1ED264 -:10BF70003A6853530AE0FF2B19D83B682B4498705A -:10BF800004E0FF2B13D83B682B44D87020462C21AB -:10BF900005F04FFF044608B1441C02E0B8F1020F5F -:10BFA00005D10136032ED4D10DE00B4806E009EB94 -:10BFB00005000021042205F008FF0848102103B005 -:10BFC000BDE8F043DEE603B0BDE8F0832C2000209E -:10BFD000FB6B0108A40A00200F6C0108BE64010875 -:10BFE000F0B500231946CEB200220C2505FB02F75E -:10BFF0000D48D4B23F5CB74203D00132042AF4D1D9 -:10C000000BE0FF2C09D0094A05FB04001A4492F802 -:10C010002C21074C0133A25C02720131052901D0A9 -:10C02000032BE0D9F0BD00BF640000202C200020CD -:10C03000036B010810B54F20F8F720FD0C4C84F875 -:10C040002C010020F8F71AFD4FF4E133C4F8303129 -:10C05000C4F83431C4F83831C4F83C31522384F880 -:10C060002D0184F82E0184F82F0184F8403110BD91 -:10C070002C20002070B50546441E14F8011F61B144 -:10C08000064E304605F0D5FE0028F6D0861B044843 -:10C09000631B304480F81031EFE770BDAA6E0108D1 -:10C0A0002C20002030B587B005460C4603A800219F -:10C0B0000C2205F08AFE2846002102F075FF20B10F -:10C0C00028462A4902F0ACFC03E02846274902F042 -:10C0D000A5FC274902F0ACFD02F070FF054685EA99 -:10C0E000E570A0EBE57069460A22FEF7F9F9002336 -:10C0F0009D420370ACBF20232D2368468DF80C3081 -:10C1000005F0A4FE012807D130238DF80D308DF8FD -:10C110000E308DF80F300CE0022805D130238DF859 -:10C120000D308DF80E3004E0032804BF30238DF865 -:10C130000D30694603A805F06FFE03A805F086FEE2 -:10C140000338C5B22A4603A9204605F0A9FE0023FC -:10C1500063552046074905F05FFE03A920462944A0 -:10C1600005F05AFE204607B030BD00BF6F12033AFB -:10C1700000007A44336C01080A88F0B54B888F8838 -:10C180000E89CD88002A3AD1048C834A24F0010418 -:10C190002404240C0484018B048C89B221F0F30163 -:10C1A00041EA0616B6B29042A4B246EA070743F047 -:10C1B000010315D002F50062904211D0B0F1804F1A -:10C1C0000ED0A2F5983290420AD002F580629042D9 -:10C1D00006D002F58062904218BF24F00A0401D113 -:10C1E00024F00204234307830384038B23F00C030E -:10C1F0001B041B0C0383038B9BB21D4344E0042AE6 -:10C2000044D1048C644A24F010042404240C0484D3 -:10C21000018B048C21F440710905090D41EA0631B6 -:10C2200089B241EA07279042A4B2BFB212D002F508 -:10C23000006290420ED0B0F1804F0BD0A2F5983240 -:10C24000904207D002F58062904203D002F58062EE -:10C25000904207D124F0200444EA03139BB243F038 -:10C26000100304E024F0A00443F0100323430783E9 -:10C270000384038B23F440631B041B0C0383038B95 -:10C280009BB243EA0525ADB20583F0BD082A018CB7 -:10C290003ED121F480710904090C0184818B3E4A4E -:10C2A00089B221F0F301048C41EA0616B6B290423D -:10C2B000A4B246EA070712D002F5006290420ED0FF -:10C2C000B0F1804F0BD0A2F59832904207D002F522 -:10C2D0008062904203D002F58062904207D124F43C -:10C2E000007444EA03239BB243F4807304E024F413 -:10C2F000206443F48073234387830384838B23F078 -:10C300000C031B041B0C8383838B9BB21D4341E0F6 -:10C3100021F480510904090C0184828B048C22F4DD -:10C3200040721205120D42EA072242EA06361A4A04 -:10C33000A4B29042B6B212D002F5006290420ED082 -:10C34000B0F1804F0BD0A2F59832904207D002F5A1 -:10C350008062904203D002F58062904207D124F4BB -:10C36000005242EA033292B242F4805205E047F6AC -:10C37000FF52224043F480531A4386830284838B06 -:10C3800023F440631B041B0C8383838B9BB243EA1F -:10C390000525ADB28583F0BD002C01401FB50123FA -:10C3A000ADF808300023ADF80C30ADF80A30094B79 -:10C3B000ADF804101B7801A9012B08BF0323ADF8C9 -:10C3C000062008BFADF80C30FFF7D6FE05B05DF8CB -:10C3D00004FB00BF0C08002038B510F80E2C0446F2 -:10C3E00050F8043C52B9012200F80E2C20F80C1C25 -:10C3F000197B18680222BDE83840CFE730F80C2CD2 -:10C4000020F80A1C891A89B220F8081C074A10F87B -:10C410000F0C002522F8101004F80E5C1868197B28 -:10C420002A46FFF7BBFF04F8065C38BD4C19002014 -:10C430001F4B10B55A6802F00C02042A03D0082AD8 -:10C4400004D01C4A14E01C4A126811E05A6859686A -:10C45000C2F38342C90302F1020201D4174906E084 -:10C46000596811F4003F1449096818BF49084A4344 -:10C4700002605968124AC1F30311545C0168E1403B -:10C4800041605C68C4F30224145D21FA04F4846002 -:10C490005C68C4F3C224145DE140C1605B68C3F30F -:10C4A00081331A44137CB1FBF3F1016110BD00BF6D -:10C4B0000010024000127A002400002000093D0014 -:10C4C00050000020024B1A6922EA000018617047F0 -:10C4D00000100240CB78F0B5DA0648BF8A780988A8 -:10C4E00003F00F0548BF154311F0FF0F1DD004687E -:10C4F00000220127974007EA0106BE4211D19700AA -:10C500004FF00F0C0CFA07FC05FA07F724EA0C04AD -:10C51000282B44EA070401D1466102E0482B08BFFA -:10C5200006610132082AE4D10460FF291FD944685A -:10C53000002202F108060127B74007EA0106BE42C1 -:10C5400011D197004FF00F0C0CFA07FC05FA07F712 -:10C5500024EA0C04282B44EA070401D1466102E0D6 -:10C56000482B08BF06610132082AE2D14460F0BDC1 -:10C5700010B50446F8F78DF8012806D11CB1F8F77C -:10C5800088F8013CF8E7052010BD002C08BF052005 -:10C5900010BD00BF2DE9F0418CB01D469DF848301C -:10C5A0008846012B174608D1A84B984240F0468197 -:10C5B000042203F548431A6165E0A54B98425ED119 -:10C5C000A448A54B87600360A44BA907436103F10E -:10C5D000C00383614FF0C003C36003619C4B0365DC -:10C5E00003F104038364C36403F5484303F1540374 -:10C5F0000363A3F11403D3F8D42F436342F48042BE -:10C60000C3F8D42FD3F8D02F42F00102C3F8D02FB3 -:10C610004FF002038DF803304FF40073ADF8003093 -:10C620004FF018038DF8023003D58D486946FEF7A8 -:10C63000C9F91C232A078DF8023003D588486946BA -:10C64000FEF7C0F94FF48063ADF8003048238DF851 -:10C650000230EB0703D582486946FEF7B3F90E2393 -:10C660008DF804300022012301A88DF805308DF8E3 -:10C6700006208DF80730774CF9F7E0FA55E0734B58 -:10C68000984240F0DF80774B734A9F601A60C02267 -:10C69000DA601A61744AAE075A6102F1C0029A6107 -:10C6A0006A4A1A6502F104029A64DA646F4BDA6925 -:10C6B00042F40032DA615A6942F001025A614FF0E5 -:10C6C00002038DF803304FF00403ADF800304FF053 -:10C6D00018038DF8023003D561486946FEF772F9F8 -:10C6E0001C232C078DF8023003D55D486946FEF700 -:10C6F00069F90823ADF80030E8074FF048038DF8DA -:10C70000023003D556486946FEF75CF926238DF8BA -:10C7100004300022012301A88DF805308DF8062091 -:10C720008DF80730F9F78AFA4E4C0026012384F879 -:10C7300044302662E661A6626662C4F82C806571A8 -:10C74000A760A6712046FCF78DFA15F0090F31D0CD -:10C75000206B002826D0E36C039601934FF480539E -:10C760000A9380230693E368059604932023099394 -:10C7700063690796029308960B96F7F7BDFF01A928 -:10C78000206BF7F79BFF236B1A6842F001021A60D7 -:10C79000226D918A89B241F0400191825B689BB21F -:10C7A000236407E0236D4FF6DF721A80DA6842F0E7 -:10C7B0002002DA6015F00A0F2CD0606B28B3A36C4E -:10C7C000002601934FF480530A9380230693236934 -:10C7D00002960493102303930596079608960996EC -:10C7E0000B96F7F789FF606B01A9F7F767FF636B9B -:10C7F0001A6842F002021A605E605E60236D9A8AD7 -:10C8000092B242F080029A8204E0236DDA6842F02C -:10C810008002DA60236D29079A8992B242F40052AD -:10C820009A819A8A03D592B242F0080203E022F07C -:10C8300008021204120C9A82204604E0044B98422B -:10C840003FF4BEAE00200CB0BDE8F08100440040D3 -:10C8500000380140C01F0020505301086419002017 -:10C86000000801406C1F0020E41A00200010024064 -:10C8700010B50446204605F0E9FA10F0FF0F07D185 -:10C880000B4B0C4893F85417BDE81040FFF77ABAE9 -:10C89000204605F030FB022808D8054B064C83F8EB -:10C8A0005407FEF729FC01F0EDF8E3E710BD00BFE7 -:10C8B0002C200020946801080D6901082DE9F04F33 -:10C8C000844985B0054605F089FA83490028284641 -:10C8D0000CBF0124072405F081FA8049002828466E -:10C8E00008BF022405F07AFA002808BF0424E107F3 -:10C8F00040F1BE807A48FFF745FA0020F8F77EFD48 -:10C90000784F7948FFF73EFA7848FFF73BFA7A7993 -:10C91000774B784803EB82035969FFF733FA38699C -:10C92000002102F019FB00285CD13D460646D5F8EF -:10C9300010800021404602F00FFB00284ED1013646 -:10C940006D483146D5F814B0D5F818A0D5F81C902C -:10C95000FFF718FA4046002102F008FB10B16748C3 -:10C96000FFF710FA69464046FFF79CFB0146644812 -:10C97000FFF708FA5846002102F0F8FA10B15F48B4 -:10C98000FFF700FA69465846FFF78CFB01465C4802 -:10C99000FFF7F8F95046002102F0E8FA10B15748C5 -:10C9A000FFF7F0F969465046FFF77CFB0146544813 -:10C9B000FFF7E8F94846002102F0D8FA10B14F48D5 -:10C9C000FFF7E0F969464846FFF76CFB01464D4822 -:10C9D000FFF7D8F90C2E05F11005A8D14A48711CB3 -:10C9E000FFF7D0F94948FFF7CDF9494DD7F808804E -:10C9F00055F8041F19B14748FFF7C4F9F8E70D4689 -:10CA0000454B53F8256056B10123AB4013EA080F9C -:10CA100003D042483146FFF7B5F90135F0E7404809 -:10CA2000FFF7B0F931467B1893F8103104AA13448C -:10CA30003C4A8A5C0131082903F8102CF3D1002309 -:10CA4000694639488DF80830FFF79CF93748FFF7F9 -:10CA500099F93748F9F76CFA3648FFF793F93448F3 -:10CA6000FFF74CFA3448FFF78DF94020F8F7F0FF54 -:10CA7000A2071AD53148FFF785F93148FFF782F947 -:10CA80002B48FFF7F5FE2F48FFF77CF92848FEF703 -:10CA90003DFD2D48FFF776F92548FEF79DFC264819 -:10CAA000FFF770F98020F8F7D3FF63070FD5274809 -:10CAB000FFF768F92648FFF765F91D48FBF760FCAA -:10CAC0001D48FFF75FF94FF48070F8F7C1FF05B01C -:10CAD000BDE8F08F356C01081B7701083C6C01083C -:10CAE000426C01082C200020506C0108626C010887 -:10CAF000505301086E6C0108796C0108DC6801086C -:10CB0000316A010825630108816C0108936C0108F2 -:10CB1000C0530108A36C0108C4530108B16C01089B -:10CB2000BE6C0108AA6E0108CA6C0108D36C01082A -:10CB30000D690108DF6C01085B630108ED6C0108F9 -:10CB4000006D01080E6D0108186D0108276D0108C0 -:10CB5000386D01082DE9F04F87B0984682460F46A0 -:10CB600016469DF84040FEF7E8F90DF1080E05461F -:10CB7000034600F1100C18685968724603C2083366 -:10CB800063459646F7D12B7B0BB903960496504626 -:10CB900002A9FEF7A1F8054640B14368586830B1D4 -:10CBA000504602A92A4600F0A3FEF4E733E0AB6842 -:10CBB00095F800B093F80090B9F1040F2BD8DFE896 -:10CBC00009F003062A0F11000094144801E01448EC -:10CBD0000094394632464346FFF7DCFC04460BE03E -:10CBE000002000E00120394623463246FEF7F8F8DF -:10CBF00041460446F8F720F964B10A4B84F80490E2 -:10CC000003EB8B03C3F800436B6820465C6051461E -:10CC1000FEF7D6F8204607B0BDE8F08F0038014097 -:10CC20000044004064190020F7B5274C274DE36904 -:10CC3000284643F48043E361236901A943F4804318 -:10CC4000236118238DF806304FF42043ADF80430EB -:10CC500003238DF80730FDF7B5FE04234FF480461B -:10CC60000DEB030128468DF806304FF48057ADF8E0 -:10CC70000460FDF7A7FE1023284601A98DF80630B1 -:10CC8000ADF80470FDF79EFE2F61236930463343F3 -:10CC90002361FFF717FC0E4B1A8802F4415242F44D -:10CCA000457242F003021A809A8B22F40062120449 -:10CCB000120C9A8307221A821A8892B242F040021A -:10CCC0001A8003B0F0BD00BF00100240000C01400C -:10CCD0000038004008B5FEF70FFA00F0D3FEBDE8BB -:10CCE00008400F2014210122F8F75EB82DE9F34126 -:10CCF0002D4B1B78042B50D14020F7F7A4FE04469F -:10CD000070B12046F8F79DF818B90A20F8F73BF8FB -:10CD1000F7E7264B20461B681969F8F797F80BE0F0 -:10CD2000224B21461B6800901A6940200323FFF71D -:10CD300011FF0446002830D01D4D286841798B072B -:10CD400003D441F00201F8F777F81A4B08221A6170 -:10CD500010221A612868F8F783F858B1144B154E61 -:10CD6000082718687761F8F776F801462046F8F743 -:10CD700089F837612046F8F773F80028EAD00D4E9D -:10CD8000102777612046D5F80080F8F764F801464F -:10CD90004046F8F777F83761DCE7074802B0BDE8AE -:10CDA000F041F8F709B900BF800A00207C0A002092 -:10CDB000A00A0020000C0140BF6E01082DE9F743D6 -:10CDC000124C814604F1980894F84A60C6B9D9F823 -:10CDD000042000250095012029460323FFF7BAFE11 -:10CDE000074620B97EB94FF496420126F1E7204666 -:10CDF00029464C2204F0E9FF0123276084F84A30D9 -:10CE00004C344445E0D103B0BDE8F083400F00202E -:10CE1000F7B5524B524C2360FFF7E2F80120FEF7C2 -:10CE20002DF9002800F084804E4BFF211846162271 -:10CE3000256804F0CAFF002202704B4A01211268E3 -:10CE400003469707817504D541700321817502213E -:10CE50008170560704D5997D481C98750320585455 -:10CE600012F00A0F0CD09A7D04219954511CC9B2BA -:10CE700005205854D11C02329975D2B2062199541A -:10CE80003A4FBA68900604D5997D481C98750720DA -:10CE90005854110608D5997D09205854881C013131 -:10CEA0009875C9B20A2058547979082901D00E29F9 -:10CEB00004D1997D481C98750B205854997D4FF0EA -:10CEC0000C0E481CC0B212F0040F264E987503F8E1 -:10CED00001E003D00231B17510213154997D97F8EA -:10CEE0004571481CC0B24FF0120E002F0CBF002736 -:10CEF00002F001071B4E987503F801E01FB10231E3 -:10CF0000B17513213154997D1427481CC0B298750E -:10CF10005F549305134E03D502311523B175335475 -:10CF200013480021982204F050FF2846FFF746FFDF -:10CF30000220FEF7A3F870B10220F7F784FD256800 -:10CF4000084C0146A06130B90090AA680220032372 -:10CF5000FFF700FEA06103B0F0BD00BF5821002024 -:10CF6000D80F0020741C00204C0200202C20002030 -:10CF7000400F0020A94B2DE9F7431B78002B00F050 -:10CF80008181FDF7FDFAA64E05463378834200F015 -:10CF90007981A44C23681B78002800F0F08063BBE3 -:10CFA0000420F7F750FDA04F01463860DFF8848277 -:10CFB00090B143794FF4165188F81C308368C8F853 -:10CFC0002030F7F743FF38680221F7F735FF38685C -:10CFD0000421FDF7F5FE10E0944B04201B684FF48C -:10CFE00016529B7800930223FFF7B4FD4379386013 -:10CFF00088F81C308368C8F8203023681F78012F18 -:10D0000034D10420F7F71FFDDFF844820146C8F849 -:10D010000000DFF82092A0B143794FF4964189F8DF -:10D0200024308368C9F82830F7F710FFD8F80000DB -:10D030003946F7F701FFD8F800000421FDF7C0FEDC -:10D0400014E000903B4604204FF49642FFF782FD27 -:10D050004379C8F8000089F824308368C9F828307B -:10D060000379033B012B9CBF714B1F7023681F7812 -:10D07000022F41D10420F7F7E6FC6E4C0146E06236 -:10D0800088B143794FF4964184F830308368636304 -:10D09000F7F7DCFEE06A3946F7F7CEFEE06A0421D6 -:10D0A000FDF78EFE0CE000903B4604204FF49642C4 -:10D0B000FFF750FD4379E06284F8303083686363A2 -:10D0C000E76A5D4C94F84A30022B09D094F8962018 -:10D0D000022A00F0D5801BB14C34002A18BF00246E -:10D0E000564B1C6044B1204600214C2204F06DFEDA -:10D0F0000223276084F84A30FDF794FA002800F0F4 -:10D10000BD804F4F3B78002B40F0B8800820F7F7E8 -:10D110009AFC4C4C0146206090B1464B42794FF44A -:10D12000614183F838208268DA63F7F78FFE206860 -:10D130000821F7F781FE20680821FDF741FE9DE0F8 -:10D14000414B08201B684FF461429B7800930346D3 -:10D15000FFF700FD206040B1012342793B70354B61 -:10D1600083F838208268DA6388E0384B1B78002B1C -:10D1700000F0848004233B70FFF74AFE7EE083B911 -:10D18000294FDFF8B080386898F81C10F7F754FE84 -:10D190003868D8F82010F7F759FE38680421FDF7F1 -:10D1A000DDFD23681B78012B10D1294FDFF8848027 -:10D1B000386898F82410F7F73FFE3868D8F8281038 -:10D1C000F7F744FE38680421FDF7C8FD23681B7893 -:10D1D000022B0DD1174CE06A94F83010F7F72CFEB3 -:10D1E000E06A616BF7F732FEE06A0421FDF7B6FDF5 -:10D1F000FDF718FA002841D0114F3B7813F0FB0FD0 -:10D200003CD0124B0F4C1B7823B320680821FDF74C -:10D21000A5FD04233B70FFF7FBFD2DE0A8050020D2 -:10D22000A9050020AC050020B0050020D405002091 -:10D2300055070020741C0020400F00205C060020D1 -:10D240006C06002070060020DC0D0020D20D0020AE -:10D2500048060020DFF83480206898F83810F7F787 -:10D26000EBFD2068D8F83C10F7F7F0FD20680821A6 -:10D27000FDF774FD04233B7000232360357001E04B -:10D280004C342DE703B0BDE8F08300BF741C0020D0 -:10D2900037B53D490B7813F0010F03F0040268D055 -:10D2A000002A6FD1980764D443F004030B70374B06 -:10D2B0001A88374B1A80374B9A681C4612F4806FD5 -:10D2C00005D00420FDF7BAFE08B1FDF757FDA368AD -:10D2D0001B0357D58020FDF7B1FE08B1FDF74EFDC9 -:10D2E0002D4D2B78012B4DD18020F7F7ACFB2B4C2B -:10D2F0000146206090B14279294B4FF4E1311A7018 -:10D300008268284B1A60F7F7A1FD20680221F7F721 -:10D3100093FD20688021FDF753FD0EE000904FF44F -:10D32000E13280200223FFF715FC206028B142790A -:10D330001B4B1A7082681B4B1A6023680BB92B7049 -:10D3400020E0194B194C1B680021236404F14C00A8 -:10D35000022314222B706164A16404F036FD04F1F1 -:10D360006C03236604F1D003636604F59A73A36625 -:10D3700008E03AB90220FF21012203B0BDE83040A5 -:10D38000F7F712BD03B030BDD6270020E00400201F -:10D39000480E00202C200020E20D00201820002044 -:10D3A0001C2000202020002028200020741C0020A9 -:10D3B0002DE9F341F7F7DCFBA94D07462B68C31AAB -:10D3C000002BC0F2ED8100F5C333A0332B60A54BD9 -:10D3D0002A791E78C6F38006B21A18BF01222E7170 -:10D3E0004EB1002A00F0DC819F4B5A789A700122DE -:10D3F0005A701A701EE09C4B2AB1DA7842F0020291 -:10D40000DA709A785A70D9788A0705D4964A906863 -:10D41000381AC043C00F00E00120934A187048B189 -:10D42000CC0707D513799149013303F00303137136 -:10D43000CB5C53708C4C23784BB3F9F7DBFEB020F8 -:10D44000F9F7D4FE4020F9F7D1FE0020F9F7CEFE1F -:10D450001020F9F7CBFE4FF4806808F1FF38002068 -:10D460001FFA88F8F9F7A4FEB8F1000FF5D140468D -:10D47000F9F731FF7E4B627853F82200F9F754FD3B -:10D48000E37823F00203E3707A4B3B44A3606378B4 -:10D49000052B00F27281DFE813F0080070011B0019 -:10D4A000770006001B010024D5E07349734A7448D5 -:10D4B000F8F728FD0120F9F70EFF7148F9F734FD60 -:10D4C000704B6F4870491A68F8F71CFD02204FE155 -:10D4D0006E4B9A68984612F0020F2ED06C4C0A23BD -:10D4E00021786C4FB1FBF3F203FB12133978DBB2F6 -:10D4F000634800916849F8F705FDFDF79DF80120A4 -:10D50000F9F7E9FE5E48F9F70FFD644B3A781868C1 -:10D5100024788378642102FB13444C434178022031 -:10D52000CB1A5A43B4FBF2F4E4B2F9F7D4FE214625 -:10D530001520F9F7ADFC032400E00124D8F80830E9 -:10D54000180540F11A81564B56491F680968642333 -:10D5500097FBF3F203FB1273009149485249F8F725 -:10D56000D1FCFDF769F82046F9F7B5FE4448F9F714 -:10D57000DBFCFEF78DFA0746601CF9F7ACFE1520C0 -:10D580003946F9F785FCF8E00120484FF9F7A3FE8A -:10D590004748F9F7C9FC3B68990715D5454938480C -:10D5A000B1F90020B1F90230B1F90410032400915F -:10D5B0004149F8F7A7FCFDF73FF80220F9F78BFE89 -:10D5C0002F48F9F7B1FC00E002243B68DA0718D5D0 -:10D5D0003A492B48B1F90020B1F90230B1F90410F1 -:10D5E00004F1010800913649F8F78CFCFDF724F8A6 -:10D5F0002046F9F770FE2248F9F796FC5FFA88F8A2 -:10D6000044463B681B0740F1B8802E491C48B1F9DD -:10D610000020B1F90230B1F9041000912A49F8F75D -:10D6200071FCFDF709F82046A2E00E2C00F0A58061 -:10D6300060080130F9F74FFE2046F9F752FC3B78BD -:10D64000A34206D92020F9F7B7FD601CC0B2F9F754 -:10D6500048FC0234E4B21D4F3B78A342E5D88CE08D -:10D660000C1E0020D6270020B80700201455010802 -:10D67000AC000020404B4C00DF700108046301083F -:10D68000111E0020C4000020E77001082C2000209B -:10D69000C005002094000020F2700108BC050020A5 -:10D6A000C4050020C80500200A7101084C020020B2 -:10D6B0001F710108B404002035710108FC0300202B -:10D6C000457101087C02002055710108630A0020A1 -:10D6D000354C364994F854273548F8F713FC0120A7 -:10D6E000F9F7F9FD3248F9F71FFC324B32491F7840 -:10D6F0002F483A46F8F706FC0220F9F7ECFD2C48D3 -:10D70000F9F712FC0A2303FB07472C4997F8572720 -:10D710002748F8F7F7FBFCF78FFF0320F9F7DBFD4D -:10D720002348F9F701FC264997F856272048F8F7CF -:10D73000E9FBFCF781FF0420F9F7CDFD1C48F9F760 -:10D74000F3FB204997F85A271948F8F7DBFBFCF759 -:10D7500073FF0520F9F7BFFD1548F9F7E5FB1448FD -:10D76000194997F85B27F8F7CDFBFCF765FF062012 -:10D77000F9F7B1FD0E48F9F7D7FB8EB9B020F9F7EC -:10D7800035FD0820F9F732FD1720F9F72FFDEC7E63 -:10D790000E4B185D013404F00304F9F70DFDEC762F -:10D7A00002B0BDE8F08100BF2C20002065710108A7 -:10D7B000111E00203C0E00207171010882710108C9 -:10D7C0008E7101089A710108A7710108B4710108EE -:10D7D0003F4A2DE9F84F916840F201130B4040F2A7 -:10D7E00001118B4293460AD13A4B1A7F93F81D9050 -:10D7F0005A77B9EB020918BF4FF0010901E04FF069 -:10D8000001094FF00008344B5FFA88F41B78A342FB -:10D810005CD9324B324E1B68324F23B93B685B896F -:10D8200026F814304FE03A68072C94BF12F804A091 -:10D83000A246294851469847DBF808300546DB05E3 -:10D8400009D5B9F1000F06D0274B50461B68294671 -:10D850001B68DB699847A5F2EE2240F2DC5392B2D6 -:10D860009A4288BF3B68DBF8082088BF5D8942F296 -:10D87000010313402BB31D4B1978164B01F0030223 -:10D8800002EB840293F87E0003EB4202D5831A4632 -:10D8900020B9032915D9012183F87E1002EBC403B6 -:10D8A000198CDD8B02EB44020D44598C9B8C0D448A -:10D8B0001D44ADB2A2F8805004232DB295FBF3F5C0 -:10D8C000ADB226F8145008F101089CE7BDE8F88FC6 -:10D8D0002C2000200C1E0020630A00206C0A00206F -:10D8E0001A0700203C01002040020020E40D002027 -:10D8F0002DE9F74F2A4B157C9B68019003F04009F6 -:10D9000003F4007C03F40058032D45D80C246C4329 -:10D91000244B0198E618377A013538423AD0E35C57 -:10D920004BB1012B07D0032B04D0042B14BF0423CD -:10D93000032300E00223DFF870A01F010AEB0704B5 -:10D94000B9F1000F06D11AF807B0ABF1030BBBF128 -:10D95000010F1FD9BCF1000F06D0B8F1000F03D1A1 -:10D960001AF80770042F15D04F7B94F80CA007EA23 -:10D970000A0ABA450ED14F68606887420AD38F6899 -:10D98000A068874206D8137094605660D160157401 -:10D99000104602E0EDB2B7E7002003B0BDE8F08F1B -:10D9A0002C2000206400002018550108094B30B5D8 -:10D9B0009D68094B05F480551868084B1C680023C6 -:10D9C0000DB1828800E0A28805495A520233182B13 -:10D9D000F6D130BD2C200020A81E0020AC1E002057 -:10D9E000DC0F0020F8B50024204BE0B21F78B842CD -:10D9F0000CD21F4B33F810101E4B53F820301BB1C4 -:10DA00000B2801D8DB6898470134EDE71A4B9B6877 -:10DA10005B032AD50025194E2B46EAB2BA4224D21E -:10DA2000726854689C4218D02046FCF77EFFEFF3E2 -:10DA30001283502282F3128811494FF0280CA28CD5 -:10DA40000CFB001092B201324262A28ADBB292B2A7 -:10DA500042F00102A28283F3118856F8043F0022AB -:10DA60001B6801351A802346D7E7F8BDE12700205F -:10DA7000A4270020380900202C2000203409002091 -:10DA8000CC1E00202DE9F041FDF714FB10B90A204F -:10DA9000F7F7B0F9824C4FF4EF622046814904F069 -:10DAA0008BF994F854374FF4E072022B84BF0023B3 -:10DAB00084F8543794F854377B4E02FB034303F544 -:10DAC000057393F850203360022A84BF002283F844 -:10DAD000502093F85030754A13700A2202FB03431A -:10DAE000734A03F256731360A36842F201021A40AC -:10DAF0003AB944F208021A401AB9694A43F4005389 -:10DB00009360A368D90703D54FF40050FCF72FFDAD -:10DB1000A3685A0409D50820FCF729FD4FF40050EA -:10DB2000FCF725FD0120FCF722FDA3681B0706D5A5 -:10DB30004FF40050FCF71BFD0120FCF718FDA36813 -:10DB40009F040ED54FF40040FCF711FD4FF4006028 -:10DB5000FCF70DFD4FF48030FCF709FD4020FCF789 -:10DB600006FDA3685D0603D54FF48030FCF7FFFC8B -:10DB7000A368980408D503F42063B3F5206F03D19C -:10DB80004FF40060FCF7F3FC4A4D4B4B2F461D60F1 -:10DB9000FEF726FA494B05F11C0201201A60FDF739 -:10DBA000CCF901460120FDF797F8002849D0022062 -:10DBB000FDF7C3F901460220FDF78EF8002840D09A -:10DBC0002020FDF7BAF901462020FDF785F8A3686B -:10DBD000190601D5002834D01020FDF7AEF9014612 -:10DBE0001020FDF779F8A3681A0700D548B3042080 -:10DBF000FDF7A3F901460420FDF76EF830B90820BF -:10DC0000FDF79BF901460820FDF766F8A3685B0560 -:10DC100003D400231A46194609E00028F9D110E080 -:10DC200079B90121C00708D40C33302B0BD024481C -:10DC30001844007A8507F5D5F2E70132D2B2022AFC -:10DC4000F2D9FEF7F7F9F6F785FF1E4D1E4B326845 -:10DC50001D601E4B101D186002F175010023A846BF -:10DC6000CD5C55B901EB030E9EF802C09EF803E0AF -:10DC7000F44502D2164B1D7002E00433A02BEFD105 -:10DC8000144B15490B60154950330B601178144B38 -:10DC9000012903D0022929D0124928E0124926E09F -:10DCA0002C20002000F80108E80300203C0E002092 -:10DCB000980500203C2100203C010020D80F0020C6 -:10DCC00064000020FC200020340E0020380E0020CC -:10DCD000480000202021002004040020AC05002082 -:10DCE00098000020957E0008ED7C000833491960FB -:10DCF000334B02F5D9721A60FCF772FD3568314B6F -:10DD000005F5D3721A60304B00229A802F4B304AAF -:10DD1000304E136005F5B3723260A3F122027260D7 -:10DD20002E332D4A05F5D771F36005F5D8731160D0 -:10DD30007361C6F808803761B4F8F00000F020FF86 -:10DD4000F061B4F8F20000F01BFF95F85830306233 -:10DD5000337695F874301836737094F825312A1D8F -:10DD600033731E4BB5F862011E601D4B1A601D4BCC -:10DD700005F160021A601C4B05F164021A601B4B2E -:10DD800005F25D121A601A4BC3F8008000F0FCFE29 -:10DD90000146184801F000F8174900F049FF174BF9 -:10DDA00017491860E86D00F043FF01464FF07C50C2 -:10DDB00000F0F2FF134B1860BDE8F0813D810008D0 -:10DDC0008C050020242000204C0A00202421002063 -:10DDD00070040020A41E0020A4050020A40400203C -:10DDE000D4030020F0040020C80200207C0500209D -:10DDF00084050020000061444C3D0F44880500204C -:10DE0000DB0F4940EC04002001480249FCF74ABD01 -:10DE100000080040441F002001480249FCF742BDB1 -:10DE2000000400401C1F00204FF080400149FCF717 -:10DE300039BD00BFF41E002001480249FCF732BD85 -:10DE4000002C0140CC1E002001480249FCF72ABDED -:10DE5000002C0140CC1E002038B5204CD4F8F03006 -:10DE60001D88ADB2AA0618D5D4F8CC201AB198886E -:10DE700080B2904711E09B88D4F8BC20D4F8B4104D -:10DE8000DBB28B54D4F8BC20D4F8AC300132B2FBF6 -:10DE9000F3F103FB1123C4F8BC302B061DD5D4F8D5 -:10DEA000C820D4F8C4100D4B8A4210D0D3F8B80063 -:10DEB000D3F8F010805C0132C0B28880D3F8B01083 -:10DEC000B2FBF1F001FB1022C3F8C82038BDD3F833 -:10DED000F030DA6822F08002DA6038BDCC1E002013 -:10DEE0000F4BD3F844211188090618D5D3F81C111B -:10DEF000D3F8180181420ED0D3F80C01405C0131F7 -:10DF0000C0B29080D3F80421B1FBF2F002FB1011F3 -:10DF1000C3F81C117047D36823F08003D3607047A7 -:10DF2000CC1E00200C480D4B4FF400525A60D0F824 -:10DF300028214FF6FE7311680B401360D0F81821AA -:10DF4000D0F81C319A4202D0F430FAF757BF0123BF -:10DF500080F83831704700BFCC1E0020000002401E -:10DF6000F6F720BEF6F71EBE084A13689B020BD5D3 -:10DF7000074B0021197007494FF6FE7308680340EC -:10DF80000B604FF400135360704700BF0000024065 -:10DF9000CA2700206C000240F9F7CABCF9F7C8BCD8 -:10DFA000FAF70ABDFAF708BD074B1A685969490420 -:10DFB00008D5520406D54FF480425A61034B012222 -:10DFC00083F84821704700BF00040140CC1E0020A8 -:10DFD00010B51B4B1A78510731D51A4C22F00402A8 -:10DFE0001A70A3685A050AD5FEF7C4FF0420012160 -:10DFF000FDF733F818B104F59670FEF7DFFEA3685D -:10E000001B031CD5104B1A78012A0ED90F4C012284 -:10E01000206821791A70F6F70FFF2068A168F6F7DB -:10E0200015FF20688021FCF799FE80200121FDF773 -:10E0300014F820B10648BDE81040FEF7BFBE10BD81 -:10E04000D62700202C200020E20D002018200020E0 -:10E050005821002070B5FBF7F1FE38B3144C237A39 -:10E060000BB9A38070BD134D2E78C6F38000FBF76B -:10E07000F7FE90B1104B46F002061A680F4B51891B -:10E080002E7019805189598052899A800C4AD26821 -:10E090005288DA80E3880133E380FBF7BBFE10B9D6 -:10E0A0002B785B0702D4BDE8704091E770BD00BFDC -:10E0B0004C0A0020D6270020480A00201A0700201A -:10E0C000182000200F4B1A6842F001021A605968AC -:10E0D0000D4A0A405A601A6822F0847222F4803293 -:10E0E0001A601A6822F480221A605A6822F4FE022A -:10E0F0005A604FF41F029A60044B4FF000629A601E -:10E10000704700BF001002400000FFF800ED00E083 -:10E11000024B1A6801321A60704700BF28200020A5 -:10E1200008B5084BB3F8D800074B1A780023D9B2CA -:10E13000914204D2054921F813000133F7E7FFF7B4 -:10E1400051FCFEE728200020E1270020A427002022 -:10E1500081F0004102E000BF83F0004330B54FEA98 -:10E1600041044FEA430594EA050F08BF90EA020F05 -:10E170001FBF54EA000C55EA020C7FEA645C7FEA98 -:10E18000655C00F0E2804FEA5454D4EB5555B8BFBB -:10E190006D420CDD2C4480EA020281EA030382EA2C -:10E1A000000083EA010180EA020281EA0303362DBE -:10E1B00088BF30BD11F0004F4FEA01314FF4801C91 -:10E1C0004CEA113102D0404261EB410113F0004FA3 -:10E1D0004FEA03334CEA133302D0524263EB43035A -:10E1E00094EA050F00F0A780A4F10104D5F1200EF8 -:10E1F0000DDB02FA0EFC22FA05F2801841F1000153 -:10E2000003FA0EF2801843FA05F359410EE0A5F126 -:10E2100020050EF1200E012A03FA0EFC28BF4CF057 -:10E22000020C43FA05F3C01851EBE37101F000450D -:10E2300007D54FF0000EDCF1000C7EEB00006EEB1A -:10E240000101B1F5801F1BD3B1F5001F0CD34908A4 -:10E250005FEA30004FEA3C0C04F101044FEA4452FB -:10E2600012F5800F80F09A80BCF1004F08BF5FEA82 -:10E27000500C50F1000041EB045141EA050130BD62 -:10E280005FEA4C0C404141EB010111F4801FA4F105 -:10E290000104E9D191F0000F04BF01460020B1FA5A -:10E2A00081F308BF2033A3F10B03B3F120020CDA92 -:10E2B0000C3208DD02F1140CC2F10C0201FA0CF070 -:10E2C00021FA02F10CE002F11402D8BFC2F1200CD5 -:10E2D00001FA02F120FA0CFCDCBF41EA0C0190408B -:10E2E000E41AA2BF01EB0451294330BD6FEA0404D4 -:10E2F0001F3C1CDA0C340EDC04F11404C4F12002BF -:10E3000020FA04F001FA02F340EA030021FA04F3D0 -:10E3100045EA030130BDC4F10C04C4F1200220FA27 -:10E3200002F001FA04F340EA0300294630BD21FA65 -:10E3300004F0294630BD94F0000F83F4801306BF2B -:10E3400081F480110134013D4EE77FEA645C18BF1F -:10E350007FEA655C29D094EA050F08BF90EA020FB6 -:10E3600005D054EA000C04BF1946104630BD91EAAE -:10E37000030F1EBF0021002030BD5FEA545C05D1B1 -:10E380004000494128BF41F0004130BD14F58004F0 -:10E390003CBF01F5801130BD01F0004545F0FE4164 -:10E3A00041F470014FF0000030BD7FEA645C1ABF99 -:10E3B000194610467FEA655C1CBF0B46024650EAD0 -:10E3C000013406BF52EA033591EA030F41F40021FC -:10E3D00030BD00BF90F0000F04BF0021704730B582 -:10E3E0004FF4806404F132044FF000054FF0000157 -:10E3F00050E700BF90F0000F04BF0021704730B518 -:10E400004FF4806404F1320410F0004548BF4042EC -:10E410004FF000013EE700BF42004FEAE2014FEA41 -:10E4200031014FEA02701FBF12F07F4393F07F4F1C -:10E4300081F06051704792F0000F14BF93F07F4F4E -:10E44000704730B54FF4607401F0004521F0004191 -:10E4500020E700BF50EA010208BF704730B54FF017 -:10E4600000050AE050EA010208BF704730B511F01C -:10E47000004502D5404261EB41014FF4806404F154 -:10E4800032045FEA915C3FF4DCAE4FF003025FEAD6 -:10E49000DC0C18BF03325FEADC0C18BF033202EB5E -:10E4A000DC02C2F1200300FA03FC20FA02F001FAB8 -:10E4B00003FE40EA0E0021FA02F11444C1E600BF57 -:10E4C00070B54FF0FF0C4CF4E06C1CEA11541DBF0A -:10E4D0001CEA135594EA0C0F95EA0C0F00F0DEF8D5 -:10E4E0002C4481EA030621EA4C5123EA4C5350EABA -:10E4F000013518BF52EA033541F4801143F480130B -:10E5000038D0A0FB02CE4FF00005E1FB02E506F09B -:10E510000042E0FB03E54FF00006E1FB03569CF0F0 -:10E52000000F18BF4EF0010EA4F1FF04B6F5007FF6 -:10E5300064F5407404D25FEA4E0E6D4146EB060668 -:10E5400042EAC62141EA55514FEAC52040EA5E50F1 -:10E550004FEACE2EB4F1FD0C88BFBCF5E06F1ED89B -:10E56000BEF1004F08BF5FEA500E50F1000041EBD2 -:10E57000045170BD06F0004646EA010140EA02007F -:10E5800081EA0301B4EB5C04C2BFD4EB0C0541EAA1 -:10E59000045170BD41F480114FF0000E013C00F3B6 -:10E5A000AB8014F1360FDEBF002001F0004170BDDA -:10E5B000C4F10004203C35DA0C341BDC04F11404F3 -:10E5C000C4F1200500FA05F320FA04F001FA05F27F -:10E5D00040EA020001F0004221F0004110EBD3704C -:10E5E00021FA04F642EB06015EEA430E08BF20EA78 -:10E5F000D37070BDC4F10C04C4F1200500FA04F31B -:10E6000020FA05F001FA04F240EA020001F00041AC -:10E6100010EBD37041F100015EEA430E08BF20EA1F -:10E62000D37070BDC4F1200500FA05F24EEA020E67 -:10E6300020FA04F301FA05F243EA020321FA04F096 -:10E6400001F0004121FA04F220EA020000EBD3704D -:10E650005EEA430E08BF20EAD37070BD94F0000F4D -:10E660000FD101F00046400041EB010111F4801F81 -:10E6700008BF013CF7D041EA060195F0000F18BF32 -:10E68000704703F00046520043EB030313F4801F6E -:10E6900008BF013DF7D043EA0603704794EA0C0F28 -:10E6A0000CEA135518BF95EA0C0F0CD050EA41063E -:10E6B00018BF52EA4306D1D181EA030101F00041BB -:10E6C0004FF0000070BD50EA410606BF10461946E3 -:10E6D00052EA430619D094EA0C0F02D150EA0136EF -:10E6E00013D195EA0C0F05D152EA03361CBF104630 -:10E6F00019460AD181EA030101F0004141F0FE41CF -:10E7000041F470014FF0000070BD41F0FE4141F452 -:10E71000780170BD70B54FF0FF0C4CF4E06C1CEA52 -:10E7200011541DBF1CEA135594EA0C0F95EA0C0F07 -:10E7300000F0A7F8A4EB050481EA030E52EA0335C2 -:10E740004FEA013100F088804FEA03334FF08055E3 -:10E7500045EA131343EA12634FEA022245EA111510 -:10E7600045EA10654FEA00260EF000419D4208BFC1 -:10E77000964244F1FD0404F5407402D25B084FEA6E -:10E780003202B61A65EB03055B084FEA32024FF41A -:10E7900080104FF4002CB6EB020E75EB030E22BF77 -:10E7A000B61A754640EA0C005B084FEA3202B6EB37 -:10E7B000020E75EB030E22BFB61A754640EA5C00E6 -:10E7C0005B084FEA3202B6EB020E75EB030E22BF76 -:10E7D000B61A754640EA9C005B084FEA3202B6EB77 -:10E7E000020E75EB030E22BFB61A754640EADC0036 -:10E7F00055EA060E18D04FEA051545EA16754FEA98 -:10E8000006164FEAC30343EA52734FEAC2025FEAB5 -:10E810001C1CC0D111F4801F0BD141EA00014FF044 -:10E8200000004FF0004CB6E711F4801F04BF014315 -:10E830000020B4F1FD0C88BFBCF5E06F3FF6AFAE31 -:10E84000B5EB030C04BFB6EB020C5FEA500C50F1C1 -:10E85000000041EB045170BD0EF0004E4EEA113144 -:10E8600014EB5C04C2BFD4EB0C0541EA045170BD4B -:10E8700041F480114FF0000E013C90E645EA060E8F -:10E880008DE60CEA135594EA0C0F08BF95EA0C0FBD -:10E890003FF43BAF94EA0C0F0AD150EA01347FF405 -:10E8A00034AF95EA0C0F7FF425AF104619462CE7DC -:10E8B00095EA0C0F06D152EA03353FF4FDAE10463F -:10E8C000194622E750EA410618BF52EA43067FF490 -:10E8D000C5AE50EA41047FF40DAF52EA43057FF420 -:10E8E000EBAE12E74FEA410212F5001215D211D534 -:10E8F0006FF47873B3EB625212D94FEAC12343F03D -:10E90000004343EA505311F0004F23FA02F018BFBE -:10E91000404270474FF00000704750EA013005D187 -:10E9200011F0004008BF6FF0004070474FF000004A -:10E93000704700BF4A0011D212F5001211D20DD556 -:10E940006FF47873B3EB62520ED44FEAC12343F0F5 -:10E95000004343EA505323FA02F070474FF000009F -:10E96000704750EA013002D14FF0FF3070474FF04E -:10E97000000070474FEA4102B2F1E04324BFB3F513 -:10E98000001CDCF1FE5C0DD901F0004C4FEAC00226 -:10E990004CEA5070B2F1004F40EB830008BF20F00A -:10E9A0000100704711F0804F21D113F13872BCBFC4 -:10E9B00001F00040704741F480114FEA5252C2F119 -:10E9C0001802C2F1200C10FA0CF320FA02F018BF62 -:10E9D00040F001004FEAC1234FEAD32303FA0CFCB5 -:10E9E00040EA0C0023FA02F34FEA4303CCE77FEA44 -:10E9F000625307D150EA01331EBF4FF0FE4040F48E -:10EA00004000704701F0004040F0FE4040F400003C -:10EA1000704700BF80F0004002E000BF81F000417D -:10EA200042001FBF5FEA410392EA030F7FEA226CB4 -:10EA30007FEA236C6AD04FEA1262D2EB1363C1BF44 -:10EA4000D218414048404140B8BF5B42192B88BFB3 -:10EA5000704710F0004F40F4000020F07F4018BFD6 -:10EA6000404211F0004F41F4000121F07F4118BFF6 -:10EA7000494292EA030F3FD0A2F1010241FA03FC9E -:10EA800010EB0C00C3F1200301FA03F100F0004386 -:10EA900002D5494260EB4000B0F5000F13D3B0F14E -:10EAA000807F06D340084FEA310102F10102FE2ABD -:10EAB00051D2B1F1004F40EBC25008BF20F001002D -:10EAC00040EA03007047490040EB000010F4000FDB -:10EAD000A2F10102EDD1B0FA80FCACF1080CB2EB6E -:10EAE0000C0200FA0CF0AABF00EBC25052421843CD -:10EAF000BCBFD0401843704792F0000F81F4000172 -:10EB000006BF80F400000132013BB5E74FEA410344 -:10EB10007FEA226C18BF7FEA236C21D092EA030FB0 -:10EB200004D092F0000F08BF0846704790EA010F2A -:10EB30001CBF0020704712F07F4F04D1400028BF57 -:10EB400040F00040704712F100723CBF00F5000039 -:10EB5000704700F0004343F0FE4040F4000070476F -:10EB60007FEA226216BF08467FEA2363014642021B -:10EB700006BF5FEA412390EA010F40F4800070472E -:10EB80004FF0000304E000BF10F0004348BF4042D4 -:10EB90005FEA000C08BF704743F0964301464FF010 -:10EBA00000001CE050EA010208BF70474FF000036C -:10EBB0000AE000BF50EA010208BF704711F00043AD -:10EBC00002D5404261EB41015FEA010C02BF84467D -:10EBD0000146002043F0B64308BFA3F18053A3F5DC -:10EBE0000003BCFA8CF2083AA3EBC25310DB01FA23 -:10EBF00002FC634400FA02FCC2F12002BCF1004FA7 -:10EC000020FA02F243EB020008BF20F00100704737 -:10EC100002F1200201FA02FCC2F1200250EA4C008B -:10EC200021FA02F243EB020008BF20EADC707047D1 -:10EC30004FF0FF0C1CEAD0521EBF1CEAD15392EADF -:10EC40000C0F93EA0C0F6FD01A4480EA010C4002BB -:10EC500018BF5FEA41211ED04FF0006343EA501015 -:10EC600043EA5111A0FB01310CF00040B1F5000F57 -:10EC70003EBF490041EAD3715B0040EA010062F106 -:10EC80007F02FD2A1DD8B3F1004F40EBC25008BFF0 -:10EC900020F00100704790F0000F0CF0004C08BF0E -:10ECA00049024CEA502040EA51207F3AC2BFD2F1DB -:10ECB000FF0340EAC250704740F400004FF00003E9 -:10ECC000013A5DDC12F1190FDCBF00F00040704723 -:10ECD000C2F10002410021FA02F1C2F1200200FA61 -:10ECE00002FC5FEA310040F1000053EA4C0308BF28 -:10ECF00020EADC70704792F0000F00F0004C02BF79 -:10ED0000400010F4000F013AF9D040EA0C0093F0F3 -:10ED1000000F01F0004C02BF490011F4000F013B4D -:10ED2000F9D041EA0C018FE70CEAD15392EA0C0FBB -:10ED300018BF93EA0C0F0AD030F0004C18BF31F026 -:10ED4000004CD8D180EA010000F00040704790F0FC -:10ED5000000F17BF90F0004F084691F0000F91F0A0 -:10ED6000004F14D092EA0C0F01D142020FD193EA66 -:10ED70000C0F03D14B0218BF084608D180EA0100EE -:10ED800000F0004040F0FE4040F40000704740F0CA -:10ED9000FE4040F4400070474FF0FF0C1CEAD05298 -:10EDA0001EBF1CEAD15392EA0C0F93EA0C0F69D0F4 -:10EDB000A2EB030280EA010C49024FEA402037D05F -:10EDC0004FF0805343EA111143EA10130CF0004056 -:10EDD0008B4238BF5B0042F17D024FF4000C8B4246 -:10EDE00024BF5B1A40EA0C00B3EB510F24BFA3EB26 -:10EDF000510340EA5C00B3EB910F24BFA3EB9103F6 -:10EE000040EA9C00B3EBD10F24BFA3EBD10340EA4F -:10EE1000DC001B0118BF5FEA1C1CE0D1FD2A3FF695 -:10EE200050AF8B4240EBC25008BF20F0010070474A -:10EE30000CF0004C4CEA50207F32C2BFD2F1FF03ED -:10EE400040EAC250704740F400004FF00003013A1E -:10EE500037E792F0000F00F0004C02BF400010F4C2 -:10EE6000000F013AF9D040EA0C0093F0000F01F0D6 -:10EE7000004C02BF490011F4000F013BF9D041EAF8 -:10EE80000C0195E70CEAD15392EA0C0F08D142022B -:10EE90007FF47DAF93EA0C0F7FF470AF084676E7FE -:10EEA00093EA0C0F04D14B023FF44CAF08466EE7D7 -:10EEB00030F0004C18BF31F0004CCAD130F00042A5 -:10EEC0007FF45CAF31F000437FF43CAF5FE700BFFD -:10EED0004FF0FF3C06E000BF4FF0010C02E000BF26 -:10EEE0004FF0010C4DF804CD4FEA40024FEA4103C8 -:10EEF0007FEA226C18BF7FEA236C11D001B052EA7E -:10EF0000530C18BF90EA010F58BFB2EB030088BF43 -:10EF1000C81738BF6FEAE17018BF40F001007047B2 -:10EF20007FEA226C02D15FEA402C05D17FEA236C94 -:10EF3000E4D15FEA412CE1D05DF8040B704700BFDB -:10EF4000844608466146FFE70FB5FFF7C9FF002872 -:10EF500048BF10F1000F0FBD4DF808EDFFF7F4FFAB -:10EF60000CBF012000205DF808FB00BF4DF808ED44 -:10EF7000FFF7EAFF34BF012000205DF808FB00BF67 -:10EF80004DF808EDFFF7E0FF94BF012000205DF889 -:10EF900008FB00BF4DF808EDFFF7D2FF94BF01203A -:10EFA00000205DF808FB00BF4DF808EDFFF7C8FF33 -:10EFB00034BF012000205DF808FB00BF4FEA40028B -:10EFC000B2F1FE4F0FD34FF09E03B3EB12620DD997 -:10EFD0004FEA002343F0004310F0004F23FA02F001 -:10EFE00018BF404270474FF00000704712F1610FA8 -:10EFF00001D1420205D110F0004008BF6FF000407F -:10F0000070474FF00000704742000ED2B2F1FE4F41 -:10F010000BD34FF09E03B3EB126209D44FEA0023E7 -:10F0200043F0004323FA02F070474FF000007047AE -:10F0300012F1610F01D1420202D14FF0FF3070474F -:10F040004FF00000704700BF73B96AB9002908BFCC -:10F050000028BCBF00204FF00041C4BF6FF000414A -:10F060004FF0FF3000F03CB882B0EC462DE9005084 -:10F0700000F006F8DDF804E002B00CBC704700BFF9 -:10F080002DE9704F089E14461D468046894600F0C3 -:10F0900029F804FB01F3A4FB00AB00FB0532934409 -:10F0A000B8EB0A0869EB0B09C6E90089BDE8708F67 -:10F0B0002DE9704F089E14461D468046894600F093 -:10F0C00061F900FB05F5A0FB04AB04FB0154A3446C -:10F0D000B8EB0A0869EB0B09C6E90089BDE8708F37 -:10F0E000704700BF00292DE9F00FC0F2A180002475 -:10F0F000002BC0F29880154606460F46002B3FD1E4 -:10F100008A4258D9B2FA82F34BB1C3F1200201FA14 -:10F1100003F720FA02F29D4000FA03F61743290C88 -:10F12000B7FBF1F201FB1277A8B200FB02F34FEA42 -:10F13000164C4CEA0747BB4209D97F1902F1FF3C44 -:10F1400080F00581BB4240F20281023A2F44FF1A4F -:10F15000B7FBF1F301FB137100FB03F0B6B246EA13 -:10F160000141884208D9491903F1FF3780F0F18045 -:10F17000884240F2EE80023B43EA0242002303E071 -:10F180008B420AD900231A461046194614B1404250 -:10F1900061EB4101BDE8F00F7047B3FA83F8B8F1B5 -:10F1A000000F40F088808B4202D3824200F2E2805E -:10F1B00000230122E8E712B90123B3FBF2F5B5FA07 -:10F1C00085F2002A3AD17F1B280C1FFA85FC012307 -:10F1D000B7FBF0F100FB11770CFB01F24FEA164888 -:10F1E00048EA0747BA4207D97F1901F1FF3802D22E -:10F1F000BA4200F2C4804146BF1AB7FBF0F200FBEE -:10F2000012700CFB02FCB6B246EA0040844507D9F6 -:10F21000401902F1FF3702D2844500F2AE803A462F -:10F2200042EA0142B0E7E443524263EB430362E740 -:10F23000404261EB41014FF0FF3459E79540C2F184 -:10F24000200927FA09F126FA09F99740280CB1FBA1 -:10F25000F0F800FB18111FFA85FC0CFB08F349EAD3 -:10F2600007094FEA194747EA01418B4206FA02F6BD -:10F2700008D9491908F1FF327AD28B4278D9A8F11E -:10F2800002082944C91AB1FBF0F300FB13170CFB69 -:10F2900003F21FFA89F949EA0747BA4207D97F19E9 -:10F2A00003F1FF3160D2BA425ED9023B2F44BF1A4C -:10F2B00043EA08438CE7C8F1200225FA02F103FA79 -:10F2C00008FC27FA02F320FA02F207FA08F741EAEB -:10F2D0000C0C4FEA1C49B3FBF9F109FB11331FFA7F -:10F2E0008CFA0AFB01FB17433A0C42EA03439B45A5 -:10F2F00005FA08F008D913EB0C0301F1FF3235D2FF -:10F300009B4533D902396344CBEB0303B3FBF9F2DA -:10F3100009FB12330AFB02FABFB247EA0347BA45B8 -:10F3200008D917EB0C0702F1FF331BD2BA4519D9E4 -:10F33000023A674442EA0145A5FB0001CAEB070710 -:10F340008F424FF000030AD305D02A461CE76246DD -:10F35000FDE63B4610E706FA08F68642F5D26A1E3D -:10F36000002311E71A46E5E70B46A0E71146CBE775 -:10F37000904687E74346424606E7023A50E702399D -:10F380002F4439E72DE9F00F144605460E46002BB1 -:10F3900043D18A4253D9B2FA82F757B1C7F1200656 -:10F3A00020FA06F601FA07F302FA07F400FA07F565 -:10F3B0001E43210CB6FBF1F201FB1266A0B200FB6A -:10F3C00002F32F0C47EA0646B34209D9361902F177 -:10F3D000FF3780F0FD80B34240F2FA80023A2644C3 -:10F3E000F61AB6FBF1F301FB136100FB03F0ADB2BB -:10F3F00045EA0141884208D9091903F1FF3680F036 -:10F40000E980884240F2E680023B43EA0242002360 -:10F4100010461946BDE8F00F70478B424CD8B3FA3E -:10F4200083F6002E4FD18B4202D3824200F2DD8060 -:10F43000BDE8F00F0023012210461946704712B9AB -:10F440000124B4FBF2F4B4FA84F2002A40F0828082 -:10F45000091B260CA7B20123B1FBF6F006FB101125 -:10F4600007FB00F24FEA154C4CEA01418A4207D9EA -:10F47000091900F1FF3C02D28A4200F2C8806046BE -:10F48000891AB1FBF6F206FB121107FB02F7ADB2C7 -:10F4900045EA0145AF4208D92C1902F1FF3180F04D -:10F4A0009B80A74240F29880023A42EA004210460E -:10F4B0001946BDE8F00F704700231A46104619465A -:10F4C000BDE8F00F7047C6F1200522FA05F703FAF0 -:10F4D00006F421FA05F301FA06FB20FA05F53C4390 -:10F4E0004FEA1448B3FBF8FC08FB1C331FFA84F9FD -:10F4F00009FB0CFA45EA0B0B4FEA1B4545EA0343AF -:10F500009A4502FA06F204D91B190CF1FF356FD3A4 -:10F51000AC46CAEB0303B3FBF8F508FB153309FB54 -:10F5200005F91FFA8BFB4BEA0347B94504D93F198C -:10F5300005F1FF3362D31D4645EA0C4CACFB0223B8 -:10F54000C9EB07079F424FF000054AD346D06246F9 -:10F550002B465DE79440C2F1200921FA09FC914055 -:10F5600020FA09F9260CBCFBF6F806FB18CCA7B26A -:10F5700007FB08F349EA01094FEA194141EA0C4C3B -:10F58000634500FA02F509D91CEB040C08F1FF32BF -:10F590003BD2634539D9A8F10208A444C3EB0C0C53 -:10F5A000BCFBF6F306FB13C107FB03F21FFA89F954 -:10F5B00049EA01418A4207D9091903F1FF3022D2F1 -:10F5C0008A4220D9023B2144891A43EA084343E78F -:10F5D0003A4605E7334618E70A4666E7B0409042E8 -:10F5E000B5D20CF1FF32002312E7334632460FE763 -:10F5F0009A458DD9ACF1020C23448AE7B9459AD9D2 -:10F60000023D274498E70346DEE79046C6E7023806 -:10F61000214435E74FF0FF3C06E000BF4FF0010CFE -:10F6200002E000BF4FF0010C4DF804CD4FEA410C51 -:10F630007FEA6C5C4FEA430C18BF7FEA6C5C1BD01E -:10F6400001B050EA410C0CBF52EA430C91EA030F9F -:10F6500002BF90EA020F0020704710F1000F91EAFC -:10F66000030F58BF994208BF90422CBFD8176FEACA -:10F67000E37040F0010070474FEA410C7FEA6C5C98 -:10F6800002D150EA013C07D14FEA430C7FEA6C5C9F -:10F69000D6D152EA033CD3D05DF8040B704700BFCB -:10F6A0008446104662468C461946634600E000BF19 -:10F6B00001B5FFF7B7FF002848BF10F1000F01BDEB -:10F6C0004DF808EDFFF7F4FF0CBF012000205DF8B6 -:10F6D00008FB00BF4DF808EDFFF7EAFF34BF01203B -:10F6E00000205DF808FB00BF4DF808EDFFF7E0FFD4 -:10F6F00094BF012000205DF808FB00BF4DF808ED25 -:10F70000FFF7CEFF94BF012000205DF808FB00BF8B -:10F710004DF808EDFFF7C4FF34BF012000205DF86D -:10F7200008FB00BF1C481D49026800608A4200F0C7 -:10F730001D80002100F004B8194B5B584350043180 -:10F740001848194B42189A42FFF4F6AF174A00F0D6 -:10F7500003B8002342F8043B154B9A42FFF4F9AF7B -:10F76000FEF7B0FC00F038F8FFF7FEBF114E12486C -:10F7700030601248016821F070610160410201604F -:10F780000F4C182020600F490F4808600F48D0F830 -:10F7900000D0406800470000F04F0020EFBEADDE13 -:10F7A000B07E010800000020340100203801002054 -:10F7B000F427002018100240090000000400014056 -:10F7C000140C0140000C01404434434400F0FF1F7E -:10F7D000FFF7FEBF000000002DE9804893B0F0F76E -:10F7E00097FCB14EB14CD6F80880002318F0080FF2 -:10F7F0002370374600F0E78063681B7A042B00F221 -:10F80000E080DFE803F00303058AB100237AD9E042 -:10F81000627AA64B002A00F0D48000225A7293F834 -:10F820002020120700F1CD80D97A9A7A01F00700E2 -:10F8300042EA00225A621A7B02F03F00400140EA8D -:10F84000D1019962597B890041EA92119A7B02F0B9 -:10F85000010041EA8021D962D97B01F00F00C0018B -:10F8600040EA52021A631A7C02F07F00000140EA6B -:10F8700011115963597C490041EAD212997C01F077 -:10F88000030042EA40229A63DA7C02F01F00800102 -:10F8900040EA9101D963197DC90041EA5212997D6C -:10F8A0001A645A7D01F0070042EA00225A64DA7DA8 -:10F8B00002F03F00400140EAD1019964197E8900BD -:10F8C00041EA92115A7E02F0010041EA8021D96496 -:10F8D000997E01F00F00C00140EA52021A65DA7EFB -:10F8E00002F07F00000140EA11115965197F4900BB -:10F8F00041EAD212597F01F0030042EA40229A65A0 -:10F900009A7F02F01F00800140EA9101D965D97FFA -:10F91000C90041EA52121A6651E094F86420634B20 -:10F92000002A4ED0002283F8642093F86620012A32 -:10F9300047D193F88A20102A84BF102283F88A20A6 -:10F9400094F88A105A4A0023D8B2884202F102027F -:10F9500035D212F8010C12F8025C40EA0525554830 -:10F9600040F823500133EFE794F8CC204F4B42B3DB -:10F97000002283F8CC2093F8CD20A82A21D193F837 -:10F98000E050F5B9494901EB450393F8D00093F8ED -:10F99000D13003EB0020FEF71DFD3FA3D3E9002388 -:10F9A000FEF7B8FE3EA3D3E90023FEF7D5FBFEF732 -:10F9B000C1FF414B43F825000135082DE2D1012359 -:10F9C00000E00023237018F4804F08D094F804312D -:10F9D00023B1364B002283F80421012323702378BE -:10F9E00043B118F4807F05D0304BD3F808311B6841 -:10F9F0001B689847314B22781B6832B92B4AD2F8E2 -:10FA00000C219A1AD243D20F00E0012292B3F2F7EE -:10FA10006BFA94F81021254B002A00F0CC83D3F820 -:10FA200014114D0742F16881D3F81821100707D44B -:10FA3000B3F81C2122F00802A3F81C2102F05CB9E3 -:10FA4000B3F81C0100F0080292B2002A42F054817F -:10FA500040F00800A3F81C01D3F82401C3F83421B6 -:10FA6000C3F82001B3F83001C3F83821A3F8280106 -:10FA700002F042B9D4F83C21511CC4F83C11052ACB -:10FA800000F29183DFE812F01C00AE006E031C014F -:10FA900068038A03AFF300809A999999999919405C -:10FAA00000000000007077402C200020380100206A -:10FAB000A0010020C40100201C020020BC2700205F -:10FAC000D4F81421784D120740F16D83D5F8402108 -:10FAD0009A1A002AC0F2678303F5C33805F5A270AD -:10FAE00008F1A008C5F84081F7F744FD6F4B05F514 -:10FAF000A27001461A78F4F777FE95F84A1105F5D9 -:10FB0000A27011F0040F17D0C5F84C810022BB1869 -:10FB10000025A3F8FE50644B855A03F5A87E22F811 -:10FB20000E5003F5AB7E22F80E500232062AEED1BB -:10FB300021F0040183F84A1194F85C315A4AA3B1C8 -:10FB4000B2F84411B6F8FE30CB1AA2F84431B2F83C -:10FB50004611B6F80031CB1AA2F84631B2F8481176 -:10FB6000B6F80231CB1AA2F84831D4F84C314E4ADB -:10FB7000002B00F018834E49C3EB08038B4202F5BB -:10FB8000A87502F5AB7119D84A4BDA6882F0080201 -:10FB9000DA600023C25A35F903E017B2BE45C4BF8C -:10FBA000DFF818E123F80E2031F903E0BE45BCBFB1 -:10FBB000414FDA530233062BECD1F4E20023C2F8B2 -:10FBC0004C3135F903E0C85EFA1870444FF0020E6C -:10FBD000734490FBFEF0062BA2F8FE00F1D1FDF776 -:10FBE00079F8E0E2D4F814212F4D500740F1DB8280 -:10FBF000D5F860219A1A002AC0F2D582C5F8603182 -:10FC000095F86431012B14D002D3022B29D0CAE21B -:10FC1000D5F870319847D5F874319847012385F8A5 -:10FC20006431B5F86A21D5F860311344C5F8603104 -:10FC3000B9E2D5F878319847D5F86C319847D5F8BE -:10FC40006031B5F8682105F5C0701344C5F860311E -:10FC500005F5C271D5F87C319847022385F86431E7 -:10FC6000A1E2D5F89001D5F88C1100784B1C002743 -:10FC7000834285F86471D5F888E1D5F8802103D1F5 -:10FC8000012385F894313B460748C4F88C3100EBDA -:10FC90008101C1F8982100EB8301D1F898117244D9 -:10FCA000521AC4F888217EE238010020CB270020B8 -:10FCB0007FC3C901000C01408E0200208802002091 -:10FCC000D4F81421510703D5B04991F8941111B912 -:10FCD000D70640F16882D4F85822AC4DC2EB030B32 -:10FCE00046F2A712934540F25E82A94FC5F85832FA -:10FCF000B7F80080B8F1000F2FD0D5F89031D5F8C3 -:10FD00005C221878D5F888310138B3FBF0F008236D -:10FD100092FBF3F1521A1044C5F85C0290FBF3F029 -:10FD2000FEF732FF9B49FFF737F89B4902F080FB53 -:10FD300001464FF07E50FEF771FE9849FEF778FFBE -:10FD4000FFF73CF908F1FF380023C5F86002A7F877 -:10FD50000080C5F86432C5F86832D4F89051D4F800 -:10FD6000883128780138B3FBF0F0FEF709FF8949A4 -:10FD7000FFF712F8884902F05BFB01464FF07E5016 -:10FD8000FEF74CFE8549FEF753FF02F083FA6F68D9 -:10FD90008146D4F86C02FEF7F7FE3946FEF748FFBD -:10FDA0008046D4F86002C0EB0900FEF7EDFE39464C -:10FDB00081464FF07E50FEF731FE01464846FEF781 -:10FDC00037FF01464046FEF72BFE02F063FAB4F916 -:10FDD0007072B4F97232002FB8BF7F42002BB8BFE7 -:10FDE0005B429F42B8BF1F46DFF8C4813FB2FA2F83 -:10FDF0008246D8F8000014DCFEF7C6FE814638467D -:10FE0000FEF7C2FE01466648FEF708FE0146484678 -:10FE1000FEF70EFF6249FEF7BFFFFFF7CFF8074678 -:10FE200001E04FF0FF377B1EC62BC8F8007006D8E4 -:10FE3000C7EB0A03C4F87432C4F86C722EE0D4F82D -:10FE40007432002FDFF84491C3EB0A0A02DCC9F8D0 -:10FE50006CA223E0C7F59670FEF796FE5149FEF7B7 -:10FE60009BFF80463846FEF78FFE4146FEF7E0FED8 -:10FE700007465046FEF788FE414682464FF07E50C8 -:10FE8000FEF7CCFD01465046FEF7D2FE014638464D -:10FE9000FEF7C6FDFFF792F8C9F86C02424B1868EE -:10FEA0000193FEF76DFE41490746FEF7C1FE82460B -:10FEB000D4F88002FEF768FE8046D4F88402FEF78C -:10FEC00063FE01464046FEF767FFD4F888120490AF -:10FED000FEF7AEFE3946FEF7ABFE4FF07C51D4F88C -:10FEE0006482D5F80C90D4F86C720290FEF7A0FEF4 -:10FEF0005146FEF79DFE5146024640460392FEF7EC -:10FF000097FE039A01461046FEF78AFDD4F8681260 -:10FF1000FEF786FD4946FEF78BFE82463846FEF721 -:10FF200033FE494602464FF07E500392FEF776FDBF -:10FF3000039A01461046FEF77BFE01465046FEF747 -:10FF40006FFDDDF808C0C4F868028146614640468E -:10FF5000FEF766FD0022C4F86402C4F87822C4F8F3 -:10FF60007C22C4F88022C4F88422019B80461A6057 -:10FF7000074B1B88002B40F016810D4B1B68013B83 -:10FF8000C62B17D80149C1F8247119E038010020A7 -:10FF9000C027002080E6C547B1DC423ED048874AF2 -:10FFA000000061440000C842C4270020BD378635E8 -:10FFB000A00000204846FFF701F8A54AC2F8240136 -:10FFC000D4F88C02381AFEF7DFFDA249FEF730FEA6 -:10FFD00081465846FEF7D4FD01464846FEF7DCFE52 -:10FFE000FEF7ECFF40F2DC539B4A9842A8BF18464C -:10FFF0009042B8BF10460A21C4F88C72FAF7A8FAEA +:1027600044D1494B4B485A704B4B41F020011A68F9 +:102770005B683180011DA367626706F013F80123CF +:1027800032E022F0300232803F4A537873BB01219D +:1027900051701A46414C424900205052211D04F10B +:1027A000080C5052002143F80C109C441053CCF8F4 +:1027B0000400CCF80810023204F1300C583443F80D +:1027C0000C1019519C441C44042ACCF80400CCF889 +:1027D00008106060A16003F11403DBD106E03388C8 +:1027E00023F030033380002384F870303B6813F407 +:1027F000006F338814BF43F4807323F480733380F5 +:102800006B79082B02D00E2B40F08D80338823F09B +:102810004003338087E0012200E002225FFA82F861 +:1028200008F1FF3385F8543709F062F80BF06EFABF +:1028300002202821424603F017F8EDE4B8F1000F1A +:1028400002D07E2B3FF4E6AC637E972B7FF4CCACBA +:10285000144B4FF4C8721A80DEE400BF9A040020C3 +:10286000802700208C050020D4090020540200207D +:10287000000C0140E00400207A05002082020020C4 +:10288000C4050020240E002048000020200A00205B +:1028900062020020300E0020D0050020380E0020FB +:1028A000DC2700206C0400200022BB2B039201D106 +:1028B000022303E0B72B04D14FF6FE73ADF80E30C0 +:1028C0000AE0BE2B01D1022304E0BD2B7FF4A4ACAF +:1028D0004FF6FE73ADF80C303368BDF80C10B3F84A +:1028E00054200A44A3F85420BDF80E10B3F8562023 +:1028F0000A44A3F8562008F05DFF0023A3768BE47A +:102900000A4B00220021DA651A66C3F8FC20C3F8DE +:102910000021C3F80421C3F80811C3F80C11C3F84F +:102920001011FFF79CBB05B0BDE8F08FBC0D002077 +:10293000664B2DE9F04FB3F90600654B87B01D6873 +:102940002B8998420EDBB0F5FA6FAF7907DAC21A1D +:102950005743A3F5FA6397FBF3F7643703E0C7F136 +:10296000640700E064275B4B5B4AB3F81A1193F9E4 +:10297000EC3016685B4204919BB20021059334460B +:102980000A46524BDDF810C0CB5E40F2E63E0393A0 +:10299000CCEB030303F2F31CF44503D8002BB8BFC0 +:1029A0005B4201E04FF4FA73022ADFF8388131D03C +:1029B00096F85DE1BEF1000F04D07345CCBFCEEBBD +:1029C000030300234FF0640EDFF814A193FBFEFC19 +:1029D0006FF0630B3AF81C900BFB0C3B0CF1010CF5 +:1029E0003AF91CA00FFA89FCCCEB0A0C0CFB0BFC8F +:1029F0009CFBFEFCCC4428F801C095F804C003FB06 +:102A00000CFC364B9CFBF3F373449BB27B4393FB70 +:102A1000FEFE1BE096F85EE1BEF1000F04D07345A8 +:102A2000CCBFCEEB03030023DDF814C003FB0CFE88 +:102A3000A8F804E095F805E0002BB8BF5B4203FB63 +:102A40000EFE264B9EFBF3FE0EF1640EB31893F8B8 +:102A50000480DFF894C00EFB08F8642398FBF3F8B9 +:102A600002F80C8094F80E900CF103080EFB09F9A3 +:102A700099FBF3F902F8089094F818800CF1060C11 +:102A80000EFB08FE9EFBF3F302F80C30DDF80CE0C1 +:102A9000049B9E45DFF84CE004DA3EF801305B42CF +:102AA0002EF801300132032A01F1020104F1010480 +:102AB0007FF467AF074EB6F81C31984216DBB0F5CD +:102AC000FA6FA8BF4FF4FA6011E000BF960600202D +:102AD0008C05002030200020E80300200CFEFFFFC2 +:102AE000D00E002062020020DE0E00201846C01A20 +:102AF0004FF47A725043C3F5FA63B0FBF3F36427E3 +:102B0000A34C93FBF7F204EB42016FF0630000FB70 +:102B10000233098B04EB4202B2F91A000AB2821A9C +:102B2000534393FBF7F739449A4F9B4D3B88AEF8DC +:102B300006105A063DD5994B1888994B1B88C01A28 +:102B400000B20CF065F997490CF0B6F980460FF029 +:102B5000F7FB814640460FF067FC8046B5F902005E +:102B60000CF056F98246B5F900000CF051F94946CF +:102B700083460CF0A1F941460346504602930CF0FF +:102B80009BF9029B014618460CF08CF80CF05AFB9E +:102B90004946288050460CF08FF9414681465846F8 +:102BA0000CF08AF9014648460CF07EF80CF04AFB1E +:102BB0006880B26840F602031340002B53D07A4B72 +:102BC00006211D88236B1D4494F83430256301339E +:102BD000DBB2B3FBF1F084F8343001FB103313F0B7 +:102BE000FF0F40D1930706D502F05EFC02F046FCD1 +:102BF000674B83F83500B368180532D56B4BA16B72 +:102C00005A7B6B4B33F81200082391FBF3F280B22E +:102C10008A1A0244A26392FBF3F292B240F6E443B2 +:102C20005A43644B40F6FF71B2FBF1F219684FF45E +:102C30007A73C8888988121A5A4392FBF1F2554375 +:102C40005D4995FBF3F30A60D4E91001C01841EB2C +:102C5000E371C4E910010023584A0CF039FB584BCA +:102C60001860002323635749494A0B6894F835805C +:102C700013F4805318BF012382F84830B3688A46A2 +:102C800013F4807F504D2CD0DFF850912878D9F87C +:102C90000030C0F380001B685B68984760B1012377 +:102CA00084F84930D9F800301B68DB68984718B1C0 +:102CB000374B022283F84920D9F800301B689B6803 +:102CC000984728B12B7859075CBF022384F8493014 +:102CD000D9F800301B689B69984710B1002384F82D +:102CE00049303A4B1A6892060DD5DAF8003013F4E1 +:102CF000C06F05D0364B1B789B0701D4012300E041 +:102D0000002384F84A3094F84920214B022A02D14A +:102D10004C204E211EE0012A06D153204D214C2289 +:102D20000B4601F0BDFF2BE093F84A20012A03D1A6 +:102D3000532001464E2206E093F84820012A04D190 +:102D40005320014602464D23EBE7B8F1000F04D0B3 +:102D500053204D210A464423E3E73A88170603D55A +:102D600053204D210246DBE71A4A12781AB1192086 +:102D700001F06AFF04E0404683F84B8002F06DFDED +:102D80002B7858072CD5144B08225A6183E000BFDA +:102D9000D00E00205402002062020020E004002037 +:102DA000200E002035FA8E3CFC040020F4060020A2 +:102DB00004070020B0050020B8050020407E050073 +:102DC000BC05002050020020D52700204C02002026 +:102DD000820200209A040020000C0140D809002043 +:102DE000DAF80020D10703D4B74943F001030B7090 +:102DF000B6490B6813F0020302D0B5490988A1B99E +:102E0000B449098801B12BB9B34B1B88003318BFF3 +:102E1000012300E0012343B1B04BD96881F00801E0 +:102E2000D9602B7823F001032B70AD4B1B781F0763 +:102E300003D42B7823F001032B70D00203D52B7819 +:102E400023F001032B702B78A64A13F0010F05D055 +:102E50000023E364A14B082119610BE0E16C1368C6 +:102E600041B9A14903F5F42303F59073CB649B4B5F +:102E700008215961E36C12686BB1D21A002A0ADB8F +:102E8000964A03F5F423D16803F5907381F00801A5 +:102E9000D160954AD36409F039FA944B1B7813B189 +:102EA00004F026FAF9E3012005F094FE002800F072 +:102EB000F483DFF8589299F84A30012B40F0E78309 +:102EC0008B4A8C4BD9F80010C2F8009019609246DA +:102ED000884A106802F024FD002800F0D283854B58 +:102EE000186802F018FDDAF8003093F84820DAB9D3 +:102EF000B0F124014A424A4183F84820002AE7D130 +:102F00002B785B07E4D4232802D104F0F1F9DFE742 +:102F1000D4F8E8301B7D8342DAD1774A774B1A60C8 +:102F2000774A784BDA60D3E7012A04D14D2814BFE1 +:102F300000220222A2E3022A04D13C2814BF00226C +:102F400003229BE3032A0AD140284FF0000200F23B +:102F500095831A71DA715871987104228EE3042AEC +:102F600006D19A7983F8490050409871052285E38B +:102F7000052AADD159791A799142997906D94140FA +:102F80009971511C197113441872A1E7814240F0E4 +:102F9000728393F8490006F071FD002840F06683C3 +:102FA000DAF8003093F84930C82B00F0DD8043D8C0 +:102FB0002D2B00F0F08224D8252B00F0CD8206D8EE +:102FC000212B00F02382232B00F0688186E3292B3C +:102FD00000F0CD822B2B00F0D682272B40F07E8391 +:102FE000002002F0E3FC02F0ADFA474FA7F8E6003C +:102FF00002F0A8FAA7F8E80002F0A4FAA7F8EA009D +:1030000031E3332B00F0DB820CD82F2B00F0ED8264 +:10301000312B40F063833C4FC02002F0C7FC07F126 +:103020008008F8E2412B00F0D282442B00F0158397 +:10303000352B40F0538353E1D02B00F0F58169D854 +:10304000CC2B00F07B8106D8C92B00F02782CA2B3D +:1030500000F0A28042E3CE2B00F0128240F2EF811A +:1030600002F070FA02F06EFA274FDFF8A480A7F89A +:10307000D00002F067FAA7F8D20002F063FAD8F89D +:1030800000B0A7F8D40002F05DFAABF8A80102F096 +:1030900059FA02F061FAD8F8008002F053FA00EB16 +:1030A00080004000A8F8520002F042FA87F80401BC +:1030B00002F03EFA87F8060102F03AFA87F80501B5 +:1030C00002F036FACFE200BFD52700204C020020E4 +:1030D000C42700206C040020CC270020000C0140F5 +:1030E00082020020C0270020D00E0020D42700201C +:1030F000DC050020E0050020EFBEADDEF04F002033 +:103100000400FA0500ED00E030200020200F002030 +:10311000E8030020D42B00F0438108D8D22B10D034 +:1031200040F2E18102F00EFAC94B18809BE2EF2BCE +:1031300025D0FA2B00F0AE81D62B40F0CF820027AD +:1031400026E12B7803F0040303F0FF07002B40F087 +:103150008A8202F0EDF9BF4B022883F8540740F24F +:10316000698183F8547765E1002702F0EBF9BA4BE7 +:10317000D8530237102FF8D10122B84B88E1B84F4D +:10318000D7F8008002F0DEF9A8F856003F6802F098 +:10319000D9F9A7F8540066E2B14B00271A6898469F +:1031A0001278022A61D1D8F800B002F0C1F907F113 +:1031B00008020BEB820B0BF027FEAA490BF030FF45 +:1031C000CBF80400D8F800B002F0B2F907F10A0217 +:1031D0000BEB820B0BF018FEA3490BF021FFCBF891 +:1031E0000800D8F800B002F0A3F907F10E020BEBCB +:1031F000820B0BF009FE9D490BF012FF0137032FE4 +:10320000CBF80400CFD1072FD8F800B016D102F0C8 +:103210008FF90BF0F9FD93490BF002FFCBF8480052 +:10322000D8F800B002F084F90BF0EEFD8D490BF0F8 +:10323000F7FECBF84C0002F07BF912E002F078F9CF +:103240000BEB07031871D8F800B002F071F90BEB23 +:1032500007039873D8F800B002F06AF90BEB070384 +:10326000187601370A2FCED1FDE1D8F800B002F070 +:103270005FF90BEB07031871D8F800B002F058F9AA +:103280000BEB07039873D8F800B002F051F90BEB81 +:10329000070301370A2F1876E7D1E4E102F048F975 +:1032A000272821D86E4B00F11C081B6803EB880807 +:1032B00002F03EF96E4B08F1050703F58A72197AA0 +:1032C000814203D00C339342F9D10DE01B7888F88A +:1032D000053002F02DF9787002F02AF9B87053E049 +:1032E00002F026F90B2804D90120002102F040FB4E +:1032F000B9E14FF0060808FB00F0594B00F5887063 +:103300001B6803EB000802F013F90328ECD888F8D7 +:103310000A0002F00DF988F8050002F009F988F8B2 +:10332000060002F005F988F8070002F001F988F8B4 +:10333000080002F0FDF888F8090094E14D4FD7F835 +:10334000008002F0F5F888F80000D7F8008002F05D +:10335000EFF888F80100D7F8008002F0E9F888F863 +:103360000400D7F8008002F0E3F888F80500D7F8E9 +:10337000008002F0DDF888F80600D7F8008002F03F +:10338000D7F888F802003F6802F0D2F8F8706AE1D6 +:1033900002F0D8F8384BD8530237102FF8D162E139 +:1033A0004FF000082E4F08F12C0B3968029102F003 +:1033B000C9F802994FEACB021144C88039680192DA +:1033C000029102F0BFF8019A02991144088101921A +:1033D00002F0B8F80728019A02D839680A445073F5 +:1033E000A0F57A7292B2B2F57A7F03D83A6802EB0E +:1033F000CB0250813F6802F09BF808F1010807EB0F +:10340000CB03B8F1080F1873CCD12CE10027144B73 +:10341000D3F8008002F08CF808EBC7030137082FBF +:1034200083F86D01F3D11EE12B785F0700F11B815A +:1034300004F066F808F05CFA0AF068FC13E12B78F7 +:10344000580700F110810D4B4FF4C8721A800AE141 +:103450007A05002030200020960600203C02002043 +:10346000E8030020000020410000C84200007A4428 +:10347000884C01088C050020BC0F00206C04002043 +:103480002B78590700F1EF80984B1A7842F004022C +:103490001A70E8E02B785A07CCD51FE102F048F803 +:1034A000924B1A7810B142F0020201E022F00202BF +:1034B0001A7002F03DF88E4B8E4F187002F04CF8E7 +:1034C000386002F049F8786002F03CF88A4B1880C6 +:1034D00002F038F8894B188094F8043143F0020365 +:1034E00084F80431BFE002F023F8019002F034F8D0 +:1034F000029002F031F8804602F02EF8074602F002 +:1035000021F802F01FF802F013F8019A029B92B919 +:103510007B4A82E808017B4B1A8822F010021A804D +:10352000724B1A7842F001021A70002F00F09B8053 +:10353000754B1F6097E0102A40F09580734A82E82F +:1035400008010FB1704B1F607048714B0222011DC2 +:103550001A7005F027F986E0002002F027FA002310 +:10356000B36001F0F9FFB3681843B0607BE000205E +:1035700002F01CFA01F0E6FFA6F8080101F0E2FFF4 +:10358000A6F80A016FE0002002F010FA01F0D0FF67 +:10359000604B587167E0002002F008FA01F0C8FFA4 +:1035A00086F8180101F0CEFFA6F81E0101F0CAFF4F +:1035B000A6F81A0101F0C6FFA6F81C0153E000208E +:1035C00002F0F4F901F0B4FF86F820014BE000208E +:1035D00002F0ECF9002701F0ABFF4E4B3B44013702 +:1035E000082F83F81001F6D13DE0002002F0DEF94B +:1035F000484F07F1400801F0A5FFA7F8D40101F0FA +:1036000097FF87F8D60101F093FF043787F8D301BD +:103610004745F0D127E001F095FF00F03F00A7F803 +:10362000560101F08FFFB7F85621800100F4F863CE +:103630001343A7F8563101F07BFF000187F85401CE +:1036400001F076FF97F8543100F00F00184387F827 +:10365000540104374745DED105E0002002F0A6F909 +:10366000012384F80531002002F0A0F9DAF80030D7 +:10367000987902F06CF9DAF80030002283F84820DB +:1036800026E494F8053113B1234A244BDA60244B25 +:1036900009F14C0999457FF40EAC22490B689B0651 +:1036A00016D5214BD4F808211B689A1A002A0FDB83 +:1036B0000F4A1278042A0BD91C4A03F5123303F57A +:1036C000F873C2F808311A4BDA6882F01002DA6037 +:1036D000184B9B683BB11848984704E00120002133 +:1036E00002F046F9C2E707B0BDE8F08F8202002081 +:1036F000C4050020D0050020C2050020C005002020 +:10370000240E00205402002058020020300E002019 +:103710002C0E0020302000200400FA0500ED00E00F +:10372000B80F00204C020020C0270020D00E00203F +:10373000000C0140EC030020DC0F00202DE9F04FCD +:10374000974B91B01B68BBB9964C2378013B042B77 +:1037500000F2F086DFE813F00B060B060B06DE0620 +:10376000C406206802F0D7F88F4B04461B681B780C +:103770004BB1012B00F0ED80894C206802F0D0F8AD +:103780000028EED1E0E72428884D0CD006D80A287E +:1037900000F08E800D2800F08B80C6E02A2806D02D +:1037A0002C2804D0C1E02B706B70AB70CEE06A782F +:1037B0002E782A4400217D4BD170EEB9DA789E74C0 +:1037C000472A19D11A79502A16D15A79472A07D18E +:1037D0009A79472A04D1DA79412A01D101229A74CF +:1037E0006A79724B522A07D19A794D2A04D1DA7933 +:1037F000432A04BF02229A74AB7C6C4F012B02D087 +:10380000022B36D049E0B31E072B46D8DFE803F081 +:10381000040810141C27452C07F070FA68613CE07E +:10382000EA78624B532A38D15A6952425A6134E0DD +:1038300007F064FAA86130E0EA785C4B572A2CD193 +:103840009A6952429A6128E0EB78302B584B1A78EB +:103850008CBF42F0020222F002021A701DE000202A +:1038600007F0A6FA287718E0002007F0A1FAE8830D +:1038700013E0072E06D0082E0FD1012007F098FA8A +:1038800078840AE0012007F093FA41F21843584384 +:103890004FF47A72B0FBF2F33B84013600232A2CFA +:1038A000424A2E706B704CD1012182F824104DE0F9 +:1038B00095F82430002B34D03C4BDB78402B04D9D6 +:1038C000A3F137021201D2B202E01B0103F0F002B1 +:1038D0002B79A978402B8CBF373B303BDBB21344AC +:1038E000DBB29942314A1BD1937C012B08D0022BC9 +:1038F00016D1118C2F4B528C19802F4B1A800FE050 +:103900002B4909788E070CD52C49506908609069BD +:103910004860107F2A490870D18B2A4A118000E044 +:103920000023002285F8242010E06B781F4A0E2B1C +:1039300003D8591C13445170DC7095F824301B4A8D +:103940001BB991784C40947000E0002303F0010310 +:1039500061E1164B002193F82520082A00F25A81D4 +:10396000DFE802F00B0514324353718D9A00622890 +:1039700001D1022207E083F82510B52C40F04A81DE +:1039800093F82520013283F8252043E1032283F8B0 +:10399000252083F8260083F8270083F8280039E1E2 +:1039A0001C0A0020FC090020180A0020E00F00205B +:1039B00082020020C00500203E180020D005002013 +:1039C000C4050020C2050020042283F8252093F8B6 +:1039D000272093F828100244D2B283F827200A4403 +:1039E00083F8282083F8290014E1052283F8252094 +:1039F00093F8272093F828100244D2B283F82720A6 +:103A00000A4483F82820588504E1062183F825100C +:103A100093F8271093F828002144C9B283F827109F +:103A2000014483F82810598D6C4A01EB0424A4B298 +:103A3000B4F5007F89BF00215485518582F8251097 +:103A400000229A85E6E093F8272093F82810024494 +:103A5000D2B283F827200A4483F828209A8DC72AF7 +:103A600003D85E49114481F83000013292B29A8540 +:103A70005B8D934240F0CE800722584B83E70822AB +:103A800083F8252093F82730834200F0C380534AFF +:103A9000002382F82530BEE083F8251093F8281023 +:103AA0004E4A814240F0B68092F82910062947D04C +:103AB00004D8022912D003292CD0ABE012295CD003 +:103AC000302940F0A78092F83410454A102988BF69 +:103AD000102111701078434900225CE04249506B7C +:103AE0004860906B0860116C4FF47A7091FBF0F1B4 +:103AF0003E48018092F8F8103D4A19B1117841F022 +:103B0000020102E0117821F002011170012283F814 +:103B1000F92055E092F8351011F0010105D092F826 +:103B20003420D41E6242624100E00A4683F8F82045 +:103B3000002A45D12E4A117821F0020111703FE090 +:103B400092F83B1011F0010105D092F83A20D01EF6 +:103B50004242424100E00A4683F8F82022B9244A52 +:103B6000117821F00201117093F85F10214A117051 +:103B7000B3F85C10204A118022E0516C1F4801808C +:103B8000916C42F2107091FBF0F11D48018001210F +:103B900082F8FA1014E0824201F10C0110DA11F8F7 +:103BA000045C184C155511F8035C174C155511F8A9 +:103BB000015C164C15550D78154C15550132EAE788 +:103BC00093F8F930054A2BB392F8FA3013B3002377 +:103BD00082F8F93082F8FA3001231CE0E00F00206F +:103BE0004418002010100020D0050020C20500203D +:103BF00082020020C4050020A0000020C005002093 +:103C00003E18002045180020551800206518002097 +:103C1000751800200023002B3FF4AEADA54BA64E37 +:103C20009A68DA6032689A60A44B1A6842F02002FF +:103C30001A60A34B1A78012A0CBF002201221A70C5 +:103C4000A04B1A7891077FF597AD9F490978042911 +:103C50007FF692AD9D49097801F0040101F0FF0063 +:103C600011B922F001021A701B78964F13F0010F60 +:103C7000974C984D11D180B19B070ED5964B286873 +:103C80006A6818605A6005F035FD944B1B88A4F8EB +:103C9000FC303B7843F001033B7094F8FE304FF06A +:103CA0000509013393FBF9F909EB8909C9EB03090C +:103CB0008B4B8C481B7884F8FE900593831D03EB97 +:103CC000890907900023DFF80CE2874A53F80E00B9 +:103CD000864F985090FBF7FC02F1080743F807C0A5 +:103CE000834F03EB0E0107FB0C0742F2107097FBAA +:103CF000F0F00691079980B221F8020F02F1100A44 +:103D000003EB830B0490079153F80A0059F80B104A +:103D100049F80B70C1EB000808EB0700734F4FF038 +:103D2000050843F80A0090FBF8F007FB0C00059922 +:103D3000183201299850774608D1DDF810E0AEF12D +:103D40000202B2F5797F9CBF069908600433082B04 +:103D5000B9D1DFF87C813068D8F84C31C01A0BF04B +:103D600053F864490BF05CF933684FF07E51C8F8A2 +:103D70004C3181460BF03EFA10B94FF07E5000E016 +:103D800048460CAAC4F85001534B00920DAA019268 +:103D900097E803000CCB05F06BFC0C9B56496422A2 +:103DA000B3FBF2F30D980B80544B90FBF2F21A80A8 +:103DB000444A474E127812F0010208BF1A8098F860 +:103DC000543108BF0A80002B3AD0D6F850114FF07A +:103DD0007E500BF025F9D6F8583181462868C01A74 +:103DE0000BF016F849460BF067F80BF02BFAD6F8F3 +:103DF0005C211FFA80FA68680FFA8AFA801A0BF0C1 +:103E000007F83F4B19680BF057F849460BF054F888 +:103E10000BF018FAB6F9623100B2C218B6F9603187 +:103E20000221534492FBF1F293FBF1F392B29BB265 +:103E3000A6F86621A6F86431A6F86221A6F86031DA +:103E4000012388F854312F4B79681B88386803F0B8 +:103E500030031F4E1F4DC8F85C11C8F85801002BE5 +:103E60003FF48AAC06F5B873009306F5BA73019374 +:103E7000D6F86821D6F86C3105F0FAFB6B68D6F8F5 +:103E80006C01C01A0AF0C4FF1D4B19680BF014F83E +:103E90000BF0D8F9D6F868312A68C6F87C019B1A6D +:103EA000C6F878310E4B1B78012B2DD0022B00F079 +:103EB000F58061E4FC0900202C2000204C02002049 +:103EC000D40F002082020020C4050020D527002046 +:103ED000E00F0020D0050020240E0020E004002088 +:103EE0002C0E0020DE1000200C110020809698007F +:103EF000806967FF00007A444018002042180020C3 +:103F00004C00002054020020D6F89C41D6F8903195 +:103F1000D6F88021D6F8947104F1004005930492FC +:103F200007970BF08FF9074620460BF08BF98C4B67 +:103F3000D6F850511B68D6F898618A4C08900696BE +:103F400009934FF0000ADFF83C9259F81A60A9F182 +:103F5000140230463AF802800AF05AFF04990AF037 +:103F6000ABFF0BF06FF9C8EB000080B209F1280934 +:103F70002AF809000FFA80F948460AF049FF059926 +:103F80000AF09AFF0BF05EF91FFA80FB09EB0600BE +:103F90000AF03EFF07990AF08FFF29460AF08CFFCE +:103FA00021680AF081FE0BF04DF9B84204DB089A53 +:103FB0009042A8BF104600E038460AF029FF206072 +:103FC0000BF040F958441FFA80FB606808F1310893 +:103FD000301A0AF01DFF29460BF022F8099B2061D8 +:103FE00002469878D4F8089003920AF00DFF5E49D3 +:103FF0000AF062FF01464FF07E500BF011F829469F +:104000000AF052FE014628460BF00AF8039A84464D +:1040100049461046CDF80CC00AF044FEDDF80CC04D +:10402000014660460AF048FF014648460AF03CFE59 +:104030001FFA88F8B8F1620F014620616660A0603F +:104040000ED906980AF038FF0BF0FCF8474AB0F595 +:10405000FA6FA8BF4FF4FA609042B8BF104600E074 +:104060000020834440F6B8320FFA8BFB9345A8BF7B +:1040700093463F4A0A219345B8BF934601FB0AF194 +:104080003C4A54F8140B2AF802B03B4A0AF1020ADF +:10409000BAF1040F88503FF46FAB54E7304BD6F8B9 +:1040A00070911F68B6F8A451B7F808A04FEA5903F9 +:1040B0009A4528BF9A462BB29A4502DC1FFA8AFA23 +:1040C0000BE02E49D6F850010AF0F6FE0BF0BAF8D4 +:1040D00028441FFA80FAA6F8A4A1D8F87451D8F899 +:1040E000A861AE1B304605F073FB0028D8BF4042E4 +:1040F00041F293139842CCBF00200120002843D006 +:1041000030460AF085FE1E490AF0D6FE0EF08CF904 +:10411000064648460AF078FE014630460AF0CCFED4 +:104120000BF090F880B240F6B83203B29342A8BFC9 +:1041300013460F4AA8F8AC019342ACBFEB18AB187A +:1041400048F6A042934203DDA3F50C43A03B04E0F4 +:10415000002BBCBF03F50C43A033C8F8B03115E009 +:10416000200A0020680E0020DB0FC94030F8FFFF56 +:1041700048F4FFFF3C0E0020900E00200000C842D3 +:10418000D302373958110020C8F8B051D4F8B02103 +:10419000C2F50C50283004920AF03AFEAA490AF0FF +:1041A0008BFE05460EF0CCF80F9028460EF03CF939 +:1041B000D4F8C051D4F8B431D4F8B8210E9005F138 +:1041C000004007930A920BF03DF8059028460BF04B +:1041D00039F8D4F85081D4F8BC410B9009949B4C29 +:1041E000002550460AF014FE0EAB53F815100AF0E5 +:1041F00063FEDFF894B206463BF905000AF008FEBC +:10420000014630460AF04EFD0BF01CF8904B06B20A +:10421000B6F57A7FA8BF4FF47A769E42B8BF1E46A5 +:10422000B0B20BF13C0B25F80B0000B20AF0F0FD28 +:10423000079983460AF040FE0BF004F880B208901C +:104240000A9958460AF038FE41460AF035FE2168C0 +:104250000AF02AFD0AF0F6FF059B984204DB0B9A50 +:104260009042A8BF104600E005980AF0D1FD8346B1 +:10427000206060681434301A0AF0CAFD41460AF022 +:10428000CFFE54F80C3C44F8040C0246B878069370 +:1042900003920AF0B9FD6F490AF00EFE01464FF095 +:1042A0007E500AF0BDFE41460AF0FEFC0146404643 +:1042B0000AF0B6FE039A844606991046CDF80CC063 +:1042C0000AF0F0FCDDF80CC0014660460AF0F4FD8F +:1042D000014606980AF0E8FC44F8106C014644F8E0 +:1042E000040C44F80C0C09980AF0E6FD0AF0AAFF49 +:1042F000089E064458460AF0A5FF304440F6B832FE +:1043000000B29042A8BF1046534A0A219042B8BF5B +:1043100010466943514AA852514A0235042D41F8CA +:1043200002B07FF45EAF3B792BB1049B642293FB18 +:10433000F2F24C4B1A803B884B4C99450ED9D4F87D +:10434000A831D4F87401C01A05F042FA42F2107391 +:104350000028B8BF404298427FF70EAA434B012283 +:104360001A70B4F8FC203F4B1A80FFF705BA404A98 +:10437000116890460F7817B1012F0DD0ADE0012BD9 +:1043800000F2AB8062783B4B03EB02133A4A596868 +:10439000106801F0BBFA9DE0374E306801F0B1FAC9 +:1043A000B146002800F099802378344D022B29D0A3 +:1043B000032B31D0012B40F09080314B1F686B698B +:1043C000FB1A632B40F289802B69042B18D8DFF885 +:1043D000A480306808EB0313596801F097FA6B78F2 +:1043E000366808EB03139D6815F8011B19B13046B8 +:1043F00001F0A8FAF8E723696761013323616CE0F3 +:10440000022068E06A781B4B306803EB021359689E +:1044100001F07CFA03205EE02B7E03B92F76227E2A +:10442000164B012A36D11A697B2A2FD8D8F80030CA +:104430009B782BB9134BD9F80000995C01F082FAF4 +:1044400023690133236125E0D3023739900E002020 +:1044500018FCFFFFDB0FC94048F4FFFF3C0E0020B3 +:10446000680E00207A050020E00F00202C0E0020AE +:10447000180A00200C4701081C0A0020FC09002033 +:104480002C2000209C4D01084411002000221A61BC +:1044900002221A76227E294B022A18D11A690F2A83 +:1044A00013D8D8F80030997859B95B78244903EBD0 +:1044B00003130B441A44D9F8000092F87D1001F060 +:1044C00041FA23690133236101E003221A76237E36 +:1044D000022B02D9042000F06DFC0023636029E068 +:1044E0006368052201336360637801200133DBB226 +:1044F000B3FBF2F202EB82029B1A6370114B0022B3 +:104500001B68A360104B1A70104B1A7822F002023D +:104510001A700DE00B4B1A68A368D21A40F6C41348 +:104520009A4207D90A4B05201A6822F020021A6025 +:1045300000F040FC11B0BDE8F08F00BFFC09002086 +:104540009C4D01082C200020C40500208202002080 +:104550004C02002070B50E46202115460DF0F5FCEA +:104560000446B8B1441C20460DF051FDB0F5617F02 +:1045700005DB40F634039842A8BF184601E04FF42B +:1045800061701923A0F5617090FBF3F030702B7807 +:1045900001332B70204620210DF0D7FC0446B8B122 +:1045A000441C20460DF033FDB0F5617F05DB40F67D +:1045B00034039842A8BF184601E04FF461701923F4 +:1045C000A0F5617090FBF3F070702B7801332B70C5 +:1045D000204670BD70B586B005460DF0C3FCC0B274 +:1045E00008BB044606236343444A03F588731268F4 +:1045F00019201344591D4D789A7A454305F5617584 +:104600005B7900958D78684300F561700190C878FA +:10461000029009793A4803912146013401F098FC4F +:104620000C2CDFD168E028460DF0F1FC0B285FDC94 +:1046300006267043314B00F588701E682021064421 +:104640000023681C8DF817300DF07FFC741D0546A3 +:1046500058B1451C28460DF0DAFC032805D89DF812 +:104660001730607101338DF81730284620210DF086 +:104670006CFC054658B1451C28460DF0C8FC0D28B9 +:1046800005D870719DF8173001338DF81730284622 +:10469000611C0DF11702FFF75DFF20210DF055FCA5 +:1046A000054658B1451C28460DF0B1FC0C2805D82C +:1046B0009DF81730E07001338DF81730284620211F +:1046C0000DF043FC50B101300DF0A1FC0D2805D8D0 +:1046D0009DF81730207101338DF817309DF8173091 +:1046E000062B09D02046002106220DF0FAFB03E03C +:1046F00004480C2101F02CFC06B070BDE80300203A +:1047000007640108CF680108F0B585B007460DF0D1 +:1047100029FCC0B2E0B90446324B04F11C021B680C +:10472000192003EB8203591D8D785A79454305F50D +:1047300061759B790095C978484300F561700190D7 +:1047400021462948013401F003FC282CE4D146E03D +:1047500038460DF05CFC27283DDC224B00F11C069E +:104760001B68781C03EB8606202100238DF80F3090 +:104770000DF0EBFB751D044658B1441C20460DF0AE +:1047800046FC152805D870719DF80F3001338DF85F +:104790000F30204620210DF0D8FB044658B1441CB0 +:1047A00020460DF034FC0D2805D89DF80F306870B8 +:1047B00001338DF80F302046A91C0DF10F02FFF7D1 +:1047C000C9FE9DF80F30042B09D028460021042291 +:1047D0000DF087FB03E00548282101F0B9FB05B087 +:1047E000F0BD00BFE803002027640108CF6801087E +:1047F000F0B5884C884A23689D8AADB2E9B211F0C1 +:10480000010F32D0198821F400610904090C1980C4 +:10481000198889B241F480611980002111707F49A3 +:1048200008787F49A8B1507818B97E480078FF28E9 +:104830000FD1012050707C480078022804D11888DC +:1048400080B240F400601880097841F001011982BB +:1048500002E1097801F0FE011982724B1B78FF2BEF +:1048600000F0FA80FF231370F6E08F073CD5BFF30A +:104870005F8F6D490878C0B2012814D1674D2D783B +:104880008DB155787DB1198821F480610904090C36 +:104890001980BFF35F8F198B1988907089B241F42A +:1048A000007119801BE0188BBFF35F8F0878022816 +:1048B0000BD15A48007840B1507830B1198821F4B2 +:1048C00080610904090C1980C0E00978032906D128 +:1048D0005249097819B15178002940F0B780998878 +:1048E00089B241F48061B6E04E075BD50121917039 +:1048F0004A49097800293AD05178002937D04A49E5 +:1049000010780978494D022919881ED921F480614F +:104910000904090C19801F8A2E68C1B2FFB240B287 +:104920003754188880B240F4007018808B1C1370C4 +:10493000236828681D8A013149B2EDB2455499882F +:1049400089B241F48061998027E089B241F4007115 +:1049500019801E8A2D68C1B2F6B240B22E541B8A4D +:10496000481C40B2DBB203312B54117015E0517872 +:1049700011B92F49097841B1198889B241F4007100 +:10498000198013780133137007E0198889B241F454 +:1049900080711980204B0121597021680B88D8053E +:1049A000FCD459E001F0400101F0FF061E48F1B1CE +:1049B0001E49B3F810C00F6811785FFA8CFCCDB2B5 +:1049C0006E1C49B2F6B207F801C01670077876B2CD +:1049D000F11C8F4205D1998821F480610904090CEA +:1049E00099800378B34237D10235157034E0290637 +:1049F00032D511784DB26F1C1ED00E4E0131366883 +:104A0000C9B2755D1170EDB21D82007849B288425D +:104A100022D11BE030130020A41100203813002005 +:104A200035130020361300204413002040130020CB +:104A3000371300203C130020134916700978C9B2BF +:104A400019821249097809B9017829B9998821F49C +:104A500080610904090C99800D4B92F900101878B7 +:104A60000C4B421C91420DD100225A709B7833B1FD +:104A70002268938823F440731B041B0C9380064B1D +:104A800000221A70F0BD00BF36130020381300203A +:104A900044130020A4110020451300202DE9F04FFD +:104AA000624C63686249581C0A78894602F0FF0C20 +:104AB0000AB10346F6E7277B667BA57B2169636025 +:104AC000E0461FFA88F213B21F2B00F39380594976 +:104AD00001EB8300C278807831F82310C0F1FF0029 +:104AE00080B2002861D0C0F1FF0050433C23B1FBED +:104AF000F3FA0012BAF1050F5AD8DFE80AF0030BF7 +:104B00001A283846161A4E43C5B2B6FBF3F62E44A1 +:104B1000F6B248E0B1FBF3F703FB1717BFB2C5B21B +:104B2000C7F13C07101A4743B7FBF3F72F4416466B +:104B300029E0B1FBF3F503FB1515C7B2ADB2101AAE +:104B40004543B5FBF3F53D44EDB2164630E0B1FB0D +:104B5000F3F603FB1616B6B2C7B2C6F13C06101A3E +:104B60004643B6FBF3F63E441546F6B220E0B1FBF1 +:104B7000F3F703FB1717C6B2BFB2101A4743B7FBD0 +:104B8000F3F737441546FFB212E0B1FBF3F503FB30 +:104B90001515ADB2C6B2C5F13C05101A4543B5FBBB +:104BA000F3F53544EDB2174602E0154616461746B2 +:104BB0004FEA072A4AEA064A4AEA050A1723012168 +:104BC00099400CF1170211EA0A0FC3EB02021A49CD +:104BD0000CBF0920112092B213F1FF338854EED29A +:104BE0000CF1180C08F101081FFA8CFC1FFA88F868 +:104BF000124966E7012389F80030114B628140F2C7 +:104C00002A3227736673A5732161A4F808C05A601D +:104C10000C4A00219184118889B241F00101118070 +:104C20001A6842F001021A60BDE8F08FA41100205A +:104C3000CE27002014060020280A0020B0110020F2 +:104C40006C0002400004004038B5114B114D1A7839 +:104C5000114C29688AB162690244914217D300203D +:104C6000187000F0FAFD2B6863610C4B1A780AB1DA +:104C7000013A1A700123237638BD6269C832914225 +:104C800005D30120187000F0E8FD2B68636138BD82 +:104C90001B0F00202C200020A41100209A040020CB +:104CA00037B5214D8DF807306B7E8DF8062002AAAE +:104CB0008DF804008DF805101A4412F8042C443ABB +:104CC000D2B20F2A29D81949022B31F8124003D841 +:104CD00014B12046FFF7B8FF6B7E134A022B09D9A7 +:104CE000134B19685369091B8B4203D20023537677 +:104CF000104A13702B7E012B00D09CB96B7E022BC7 +:104D000002D8094A013353760B4B002028761870DD +:104D100003B0BDE8304000F0A0BD022B4FF0C80446 +:104D2000D7D9D9E703B030BDA41100206E4E0108D9 +:104D30002C2000209A0400201B0F002030B585B0E5 +:104D400004AC002524F8025D0091ADF80600214670 +:104D5000102000F0F1FE9DF80600214600F0ECFE68 +:104D60009DF80700214600F0E7FE9DF8000021466F +:104D700000F0E2FE9DF80100214600F0DDFE9DF806 +:104D80000200214600F0D8FE9DF80300214600F005 +:104D9000D3FE9DF80E002946C043C0B200F0CCFE01 +:104DA000024B1A68024B1A6005B030BD2C2000205F +:104DB000FC0500200449054B0968002218701A619F +:104DC00059611A76704700BF2C200020FC09002092 +:104DD000114B70B51B685E89104B186880F310008A +:104DE000301A09F04BFC00220D4B09F0ADFC0446D3 +:104DF00030460D4609F042FC02460B462046294645 +:104E000009F0CCFD09F0B2FE6428A8BF642020EAB6 +:104E1000E070C0B270BD00BFB0050020BC0500202E +:104E200000005940104B043033F91030B3F5617F66 +:104E300005DB40F633029342A8BF134601E04FF46E +:104E4000617308781922504300F28330984208DADF +:104E50004878504300F283309842B4BF00200120CC +:104E600070470020704700BF960600204D4B2DE98B +:104E7000F74FB3F9000009F0CBFF4B490AF01CF8DB +:104E800004460DF0D1FA074620460DF059FA474B7B +:104E900006461B68DFF8208193F80390444DB9F172 +:104EA000000F4CD0DFF814A1B8F90200BAF80230B4 +:104EB000C9F100041FFA83FB1BB2C01A04F088FC7E +:104EC000A04203DB4845A8BF484600E02046BAF8A8 +:104ED00000308344B8F900009AB21BB21FFA8BFB72 +:104EE000C01A0192AAF802B004F072FCA042019A22 +:104EF00003DB4845B4BF04464C461444A4B20FFA41 +:104F00008BF0AAF8004009F083FF804620B209F038 +:104F10007FFF31460446404609F0CEFF39468146C0 +:104F2000204609F0C9FF0146484609F0BBFE214969 +:104F30000AF076F80AF086F9288040461DE0B8F9B4 +:104F4000020009F065FF8146B8F9000009F060FF32 +:104F500031460446484609F0AFFF394680462046B0 +:104F600009F0AAFF0146404609F09CFE11490AF0EB +:104F700057F80AF067F928804846394609F09CFF3F +:104F800031460746204609F097FF0146384609F0AA +:104F90008BFE08490AF044F80AF054F9688003B01F +:104FA000BDE8F08FE004002035FA8E3C200A002096 +:104FB000DC270020000020413C0E0020380E00209D +:104FC000084BDA68D10709D4DA68520708D4DB68DD +:104FD00013F0100F0CBF042003207047012070470E +:104FE00002207047002002401E4B2DE9F0431A7842 +:104FF0001D460AB31C4B07781E781C4B93F800C063 +:1050000002231B4A03F10108D45C344104F00F046D +:10501000BC420CD20B2C0AD812F8039012F808806C +:1050200002EB840209EA0C0408EB04241461023345 +:10503000102BE6D100232B7003788B420FD90C4B39 +:1050400093F8400060B10B4A890012780B4418694C +:1050500002B1400800F5777080B2BDE8F08300200F +:10506000BDE8F08340010020DC090020DD090020BC +:10507000C0110020DE09002007299ABF024B33F837 +:1050800021000020704700BF1C020020024B53F893 +:105090002100C0F3CF007047C401002008B5074BC2 +:1050A00053F8210009F0B0FE054909F005FF054954 +:1050B00009F0FAFD0AF0ECF880B208BD5C010020AE +:1050C0000000203F00005C44014B33F811007047A2 +:1050D00096060020014B33F811007047441200205F +:1050E000034B4FF4805208B11A6170475A61704700 +:1050F00000080140034B4FF4805208B15A617047D9 +:105100001A6170470008014038B50C680546204612 +:105110000CF028FF214602462868BDE838400CF014 +:1051200029BFCB78F0B5DA0648BF8A78098803F042 +:105130000F0548BF154311F0FF0F1DD00468002272 +:105140000127974007EA0106BE4211D197004FF0B0 +:105150000F0C0CFA07FC05FA07F724EA0C04282BBD +:1051600044EA070401D1466102E0482B08BF06610A +:105170000132082AE4D10460FF291FD944680022C3 +:1051800002F108060127B74007EA0106BE4211D125 +:1051900097004FF00F0C0CFA07FC05FA07F724EA0A +:1051A0000C04282B44EA070401D1466102E0482B95 +:1051B00008BF06610132082AE2D14460F0BD10B593 +:1051C0000446FFF7FDFE012806D11CB1FFF7F8FEEB +:1051D000013CF8E7052010BD002C08BF052010BDDC +:1051E0008A6810B50C6A036814430A6923F4FF4304 +:1051F00014434A6923F0700314438A691443CA694B +:1052000014434A6A14438A6A224313430360CB68F7 +:1052100043600B6883604B68C36010BD02684FF643 +:10522000FE73134003600023036043608360C36028 +:105230002A4B984222D02A4B984229D0294B984297 +:1052400030D0294B984237D0284B98423ED0284B3B +:10525000984206D153F8682C42F4700243F8682C47 +:105260007047244B984206D153F87C2C42F0706270 +:1052700043F87C2C7047204B984206D153F8042CFD +:1052800042F00F0243F8042C70471C4B984206D1A1 +:1052900053F8182C42F0F00243F8182C7047184BC2 +:1052A000984206D153F82C2C42F4706243F82C2C0F +:1052B0007047144B984206D153F8402C42F4704288 +:1052C00043F8402C7047104B984205D153F8542CAA +:1052D00042F4702243F8542C704700BF080002408B +:1052E0001C000240300002404400024058000240CE +:1052F0006C00024080000240080402401C0402408E +:105300003004024044040240580402402DE9F843AE +:10531000574B0C460168013AC3F842108188A3F844 +:105320004610072A42D8DFE802F0040A10182229A2 +:105330002F35B3F842202280B3F8442013E0B3F8AD +:1053400044202280B3F8422005E0B3F842205242C4 +:105350002280B3F84420524205E0B3F84420524280 +:105360002280B3F842206280B3F846301DE0B3F8E3 +:10537000422052422280B3F8442012E0B3F8442085 +:105380002280B3F842200CE0B3F842202280B3F828 +:10539000442005E0B3F8442052422280B3F8422072 +:1053A00052426280B3F846305B42A380314B1B7897 +:1053B000002B5AD1B4F9000009F02AFD8046B4F957 +:1053C000020009F025FD0746B4F9040009F020FDAC +:1053D000294D06462968404609F06EFDE968814678 +:1053E000384609F069FD0146484609F05DFCA969A7 +:1053F0008146304609F060FD0146484609F054FCFC +:105400000CF0D4FF69682080404609F055FD2969F9 +:105410008146384609F050FD0146484609F044FCF3 +:10542000E9698146304609F047FD0146484609F0E2 +:105430003BFC0CF0BBFFA9686080404609F03CFDD6 +:1054400069698046384609F037FD0146404609F053 +:105450002BFC296A0746304609F02EFD01463846E6 +:1054600009F022FC0CF0A2FFA080BDE8F88300BF89 +:10547000C0110020380000200C070020074B084A0C +:105480001B7812889A4207D3064A1268907898428D +:105490008CBF00200120704700207047B405002019 +:1054A000B80D0020B005002010B5194B93F8482026 +:1054B000511C83F84810174902F007024878164932 +:1054C00003EB420331F81010A3F84A1000231846EA +:1054D000124A9A5A02331044102B80B2F8D1C008F5 +:1054E00009F096FC0E4909F0E7FC0E4909F098FD19 +:1054F0000D4B04461B68187809F08AFC01462046CB +:1055000009F0DAFC09F0C4FE084B187010BD00BFAA +:10551000C0110020F4060020040700200A12002019 +:105520003333534000F07F45B0050020B405002020 +:10553000034B1B68DA79511CD9711344187A7047F0 +:10554000DC05002010B5FFF7F3FF0446FFF7F0FF7E +:1055500004EB002080B210BD10B5FFF7F3FF044646 +:10556000FFF7F0FF04EB004010BD0B4AA2F130033F +:10557000197A81420BD00C339342F9D1074B197A37 +:10558000014004D10C339342F9D1084603E0184698 +:105590000BB15868704770479800002068000020E1 +:1055A00000230549DAB2595C814203D001330C2B48 +:1055B000F7D11A46104670473C6401082DE9F047C0 +:1055C0008278C6781E4BC2F1640802EB820C54420A +:1055D0005FFA88F84FEA4C0CC6F16409A4B203F1F3 +:1055E0001807A5B228B2002804DC002D14BF154608 +:1055F000012500E0454600FB00FA6D430AFB06FA70 +:105600009AFBF5F54D4468434FF00A0A90FBFAF017 +:10561000604480B258800D88B1F802A000B2C5EB9A +:105620000A0A00FB0AF04FF47A7A90FBFAF005447C +:1056300023F8025F0A34BB42A4B2D2D1BDE8F0879E +:10564000E60E002010B544780078002303FB03F138 +:105650001939614301F6C4115943414340F6C4125C +:1056600091FBF2F1034A22F813100133072BEDD11D +:1056700010BD00BFD00E002010B5044C2068FFF70D +:10568000E1FF20680249BDE8104097E78C05002043 +:105690000021002010B5094A094913688C68126876 +:1056A0009342F8D1074A106811684FF47A72504358 +:1056B000001BB0FBF1F002FB030010BD2C2000200A +:1056C00010E000E0DC06002038B5104C0123054650 +:1056D00084F84030FFF7DEFFE36D41F28832C31AF1 +:1056E0009342236684BF002384F8643094F86430C6 +:1056F000EDB20F2BE065E55403D1054B01221A7082 +:1057000038BD024A013382F8643038BDC011002030 +:105710004001002010B50446FFF7BCFF0D4B41F2DD +:1057200088319A6E9866821A8A42DA6684BF0022AD +:1057300083F8702093F87030074A142BD45403D1A7 +:10574000064B01221A7010BD024A013382F87030F4 +:1057500010BD00BFC011002005020020040200207F +:1057600010B50446FFF796FF164A536F5067C31AE9 +:10577000B3F57A6F84BF002382F8783092F87830DE +:1057800023B9A82C1CD110490B7006E0022B02D1C2 +:105790000E490C7001E0242B01D80D49CC54013383 +:1057A000DBB282F87830094A12785200053293420F +:1057B00006D1044B002283F87820034B01221A7093 +:1057C00010BD00BFC01100209C010020C2010020BC +:1057D0009D01002038B50446FFF75CFF114B40F6F1 +:1057E000C411DA6FD867821A8A4284BF002283F814 +:1057F000802093F880200AB90F2C11D10A4800218B +:10580000017052B1094D182A154405F8014C04D114 +:10581000012283F88010027038BD013283F88020A5 +:1058200038BD00BFC011002041010020420100200E +:1058300038B50446FFF72EFF0546FFF72BFF401B48 +:10584000A042FAD338BD10B504462CB14FF47A709B +:10585000FFF7EEFF013CF8E710BD08B5014B1B68F0 +:10586000984708BDD82700202DE9F04106460F468D +:1058700090460025EBB2434518D20024E3B2B34270 +:105880000FD20B4B0120DA68013482F00802DA6093 +:10589000FFF7E3FF3846FFF7D6FF0020FFF7DDFFF5 +:1058A000ECE73C20FFF7CFFF0135E3E7BDE8F081EF +:1058B000000C014040F2DB14604308B50D4B102290 +:1058C0005A6108221A61841E0A4B2046DA6882F067 +:1058D0001002DA60DA6882F00802DA60FFF7B3FFDC +:1058E0000120FFF7BAFF1920FFF7ADFF0020FFF7F7 +:1058F000B4FFE9E7000C014008B503685B6998470D +:1059000008BD08B503681B69984708BD08B503685A +:10591000DB68984708BD08B503689B68984708BDD1 +:1059200008B503685B68984708BD10B5044C20684B +:10593000FFF7F6FF18B12068FFF7EDFFF6E710BD9F +:10594000E41B002008B503681B68984708BD064B98 +:1059500010B5044621461868FFF7F4FF034B1B6897 +:105960009A7954409C7110BDE0050020DC050020B0 +:1059700038B5044624200D46FFF7E9FF4D20FFF718 +:10598000E6FF002C084C0CBF3E202120FFF7DFFF74 +:105990002368002228469A71FFF7D9FF236893F8FD +:1059A0004900BDE83840D2E7DC0500200146002070 +:1059B000DEE7F8B50E4E0F4C0F4DC1B2074630680A +:1059C00084F88110FFF7BEFF2B6894F881109A7954 +:1059D00030684A409A71C7F3072184F88110FFF7B5 +:1059E000B1FF2B6894F881109A794A409A71F8BDFA +:1059F000E0050020C0110020DC050020F8B51B4D9B +:105A00001B4C1C4F0646C1B2286884F88210FFF771 +:105A100099FF3B6894F882109A7928684A409A71F5 +:105A2000C6F3072184F88210FFF78CFF3B6894F8D7 +:105A300082109A7928684A409A71C6F3074184F81F +:105A40008210FFF77FFF3B6894F882109A792868EC +:105A50004A409A71310E84F88210FFF773FF3B6859 +:105A600094F882109A794A409A71F8BDE0050020B6 +:105A7000C0110020DC05002010B5441E14F8011FE1 +:105A800021B1034B1868FFF75DFFF7E710BD00BFBA +:105A9000D81B0020014B186854E700BF2C130020CE +:105AA000014B014618684DE71C20002010B5044644 +:105AB0007F2C06D964F07F00C0B2FFF7F1FFE40944 +:105AC000F6E7E0B2BDE81040EAE7430083EAE070A1 +:105AD000ECE770B5104E114C114D4720FFF7E0FF79 +:105AE0003078FFF7E3FF23682868C01AFFF7EDFF5F +:105AF00063686868C01AFFF7E8FF0A4B1888FFF769 +:105B0000D5FF094B1888FFF7D1FF337823742B6832 +:105B1000A3606B68E36070BDC4050020141C002006 +:105B2000D0050020C2050020C0050020014B1868E8 +:105B300008E700BF1C200020A0F17D03012B70B5F9 +:105B400004460D460A4E05D830687D21FFF7FAFE5F +:105B500084F0200430682146FFF7F4FE35B12B882D +:105B60001C4404EB142404F0FF042C8070BD00BF1F +:105B7000EC05002038B5054C05465E212068FFF78E +:105B8000E1FE20682946BDE83840DBE6A405002098 +:105B9000014B5E211868D5E6A405002010B50A4C1B +:105BA0005E280146206805D15D21FFF7CBFE206805 +:105BB0003E2105E05D2903D1FFF7C4FE20683D21A9 +:105BC000BDE81040BEE600BFA405002010B50446A5 +:105BD000C0B2FFF7E3FFC4F30720BDE81040FFF7B2 +:105BE000DDBF064B1B6803EBC00090F9063019427D +:105BF0000CBF01204FF0FF30704700BFA81E0020EF +:105C00000A4B1A6802EBC002D379FF2B07D0084970 +:105C10000978994203D9074A32F8130004E00728AB +:105C2000D4BF908840F2DC5000B27047A81E00201C +:105C3000DF0900209606002010B5054C00202188C1 +:105C400003F05DFE61880120BDE8104003F057BEFF +:105C5000120000202DE9F04F0C68836889B0D0F85D +:105C600000A0D0F804800646204603938B460CF033 +:105C700067FB074620460CF0D7FBDBF80440814663 +:105C800020460CF05DFB054620460CF0CDFBDBF812 +:105C900008200446104601920CF052FB019A8346FC +:105CA00010460CF0C1FB39460290584609F004F941 +:105CB00039460490029809F0FFF859460590484685 +:105CC00009F0FAF802990690484609F0F5F82946D5 +:105CD0000790584609F0F0F80146504609F0ECF8F4 +:105CE00021468346069809F0E7F80146059808F032 +:105CF000DBFF0146404609F0DFF80146584608F050 +:105D0000D3FF21468346049809F0D6F80146079848 +:105D100008F0C8FF0146039809F0CEF8014658463E +:105D200008F0C2FF3060029905F1004009F0C4F8A4 +:105D30000146504609F0C0F821468346079809F00D +:105D4000BBF80146049808F0ADFF0146404609F053 +:105D5000B3F80146584608F0A7FF21468346059848 +:105D600009F0AAF80146069808F09EFF014603983C +:105D700009F0A2F80146584608F096FF21467060E7 +:105D8000504609F099F82946044609F1004009F007 +:105D900093F80146404609F08FF80146204608F086 +:105DA00083FF39460446284609F086F801460398E1 +:105DB00009F082F80146204608F076FFB06009B08D +:105DC000BDE8F08F2DE9F04F064689B00F46154625 +:105DD0009B462978002900F0B880252902D001359A +:105DE0003046B0E06C78302C03D002354FF000091B +:105DF00003E0AC784FF001090335A4F13003092B1F +:105E00004FF000081AD8A4F13003DAB2092A07D8F3 +:105E10000A2B13DC0A2202FB083815F8014BF2E7C3 +:105E2000A4F16103052B02D8A4F15703F0E7A4F114 +:105E30004103052B02D8A4F13703E9E76C2C03BF1B +:105E40002C78012201350022632C66D006D8252C3F +:105E500077D0582C3FD0002C77D0BAE7732C63D082 +:105E600002D8642C11D0B4E7752C02D0782C32D033 +:105E7000AFE70BF1040A05ACDBF800000A2112B110 +:105E80000022234613E0234620E00BF1040A05AC70 +:105E9000DBF8000072B1002806DA2D238DF81430EB +:105EA00040420DF1150300E023460A21002203F0D1 +:105EB00097FA0DE0002806DA2D238DF814304042C1 +:105EC0000DF1150300E023460A21002203F060FAD9 +:105ED000D34600941AE00BF1040303930DF1140A66 +:105EE000DBF80000102132B1583C62426241534657 +:105EF00003F076FA06E0B4F158035A425A41534689 +:105F000003F046FADDF80CB0CDF800A03046394673 +:105F100042464B4603F0A0FA5BE730469BF8001080 +:105F20000BF10404B8470AE0DBF800303046009378 +:105F30003946424600230BF1040403F08DFAA346D0 +:105F400047E730462146B84743E709B0BDE8F08F40 +:105F50000FB407B50A4904AB08680A4953F8042B83 +:105F600009680193FFF72EFF074B1868FFF7C9FC7C +:105F70000028F9D003B05DF804EB04B0704700BF0F +:105F8000D8060020D40600202C130020F8B50746C0 +:105F90000BF0E8FF044638B9194B1A485A791A4BE6 +:105FA000013A53F8221028E03846184922460BF0EF +:105FB000E1FF60B91648FFF75FFD164C54F8041F67 +:105FC00019B11548FFF7C4FFF8E7144805E00025AC +:105FD0000D4B53F8256026B91148BDE8F840FFF78E +:105FE0004BBD3846314622460BF0C4FF0135002830 +:105FF000EED1034B0B485D713146BDE8F840A7E791 +:106000003020002048640108FC4F01081A6E010886 +:106010005C640108F84F01086F6401083E680108DC +:10602000736401088864010870B504460BF09AFF98 +:1060300008B91E482EE020461D490CF00DF800243A +:106040002646254678B12CB1012C06D10BF0DFFF96 +:10605000064602E00BF0DBFF05461549002001343F +:106060000BF0FAFFEEE70B2D04D9BDE870401148A4 +:106070000C216DE7012C07DC0F4B294633F9152065 +:106080000E48BDE8704063E7A6F57A73B3F57A7FF2 +:1060900003D90B48BDE870405AE70A482946324602 +:1060A000FFF756FF044B23F8156070BD9A64010892 +:1060B000D8660108D4640108BC0F0020FA64010806 +:1060C00012650108346501082DE9F74304460BF019 +:1060D00049FFC0B290B9304C054694F8D711B4F8D6 +:1060E000D42194F8D6312D48009129460135FFF787 +:1060F0002FFF102D04F10404EFD14AE020460BF0ED +:1061000086FF0F28054636DC204620210BF01DFFB8 +:10611000234FEDB2D7F80090441CAD000026204676 +:106120000BF075FF5FFA86F8B8F1010F83B208D063 +:10613000B8F1020F0BD0B3F5B47F1ED23A685353B7 +:106140000AE0FF2B19D83B682B44987004E0FF2B22 +:1061500013D83B682B44D87020462C210BF0F5FE59 +:10616000044608B1441C02E0B8F1020F05D1013623 +:10617000032ED4D10DE00B4806E009EB0500002109 +:1061800004220BF0AEFE0848102103B0BDE8F04336 +:10619000DEE603B0BDE8F083302000204D65010845 +:1061A000240A00206165010885650108F0B5002317 +:1061B0001946CEB200220C2505FB02F70D48D4B2D9 +:1061C0003F5CB74203D00132042AF4D10BE0FF2C2C +:1061D00009D0094A05FB04001A4492F82C21074C07 +:1061E0000133A25C02720131052901D0032BE0D9F1 +:1061F000F0BD00BF68000020302000203C64010892 +:1062000010B54F20FFF7CCF90C4C84F82C0100207E +:10621000FFF7C6F94FF4E133C4F83031C4F8343134 +:10622000C4F83831C4F83C31522384F82D0184F885 +:106230002E0184F82F0184F8403110BD3020002059 +:1062400070B50546441E14F8011F61B1064E304674 +:106250000BF07BFE0028F6D0861B0448631B3044FD +:1062600080F81031EFE770BD646B0108302000202A +:1062700030B587B005460C4603A800210C220BF070 +:1062800030FE2846002108F0D3FF20B128462A49D5 +:1062900008F00AFD03E02846274908F003FD2749D6 +:1062A00008F00AFE08F0CEFF054685EAE570A0EB8F +:1062B000E57069460A2203F0BBF800239D42037093 +:1062C000ACBF20232D2368468DF80C300BF04AFE1E +:1062D000012807D130238DF80D308DF80E308DF860 +:1062E0000F300CE0022805D130238DF80D308DF8E9 +:1062F0000E3004E0032804BF30238DF80D306946CA +:1063000003A80BF015FE03A80BF02CFE0338C5B252 +:106310002A4603A920460BF04FFE00236355204672 +:1063200007490BF005FE03A9204629440BF000FEA7 +:10633000204607B030BD00BF6F12033A00007A4418 +:10634000936501082DE9F04389B004460BF00AFE7D +:10635000C6B2002E6CD18B48FFF78EFB8A4C2069A9 +:10636000002108F03DFF40BB013688483146FFF769 +:10637000EFFD206904A9FFF77BFF01468448FFF782 +:10638000E7FD606904A9FFF773FF01468048FFF746 +:10639000DFFDA06904A9FFF76BFF01467C48FFF70A +:1063A000D7FDE06904A9FFF763FF01467948FFF7CD +:1063B000CFFD0C2E04F11004D1D10025764C2F46D0 +:1063C0002B464FF00008B04504F1100415DA1846CA +:1063D00054F8101C08F068FC54F80C1C8146284640 +:1063E00008F062FC54F8081C0546384608F05CFCCE +:1063F00008F101084B460746E5E768480193029516 +:106400000397FFF739FB002401ABE058644920F003 +:10641000004008F00DFF634B634A0434002814BFAA +:1064200010461846FFF728FB0C2CEDD15F4891E091 +:1064300020465F4905220BF09DFD38B9524B0022E2 +:1064400003441030C0281A61F8D197E0204659491A +:1064500004220BF08FFD06462046002E40D120215D +:106460000BF073FD002800F08980451C28460BF0D6 +:1064700079FD34468046504B53F824600EB94F489E +:1064800068E0284631465FFA88F20BF073FD671C1E +:1064900020BB3D4B0021C2181030C02811619C4622 +:1064A000F7D1474B002403EBC702D2F804E098462B +:1064B000BEF1000F04D143483146FFF749FD55E0D6 +:1064C00018F837309C42F6DA23010CEB030510353F +:1064D00073440FCB013485E80F00F1E73C46CAE76F +:1064E0000BF095FD461E0B2E074643DC204620216F +:1064F0000BF02BFD054640B1451C284602F0B2FECC +:10650000214B3F01D851012400E0044628462021B8 +:106510000BF01BFD054640B1451C284602F0A2FECB +:10652000194B013403EB06135861284620210BF068 +:106530000CFD054640B1451C284602F093FE124B67 +:10654000013403EB06139861284620210BF0FDFC73 +:1065500018B91D48FFF790FA10E0013002F082FEF2 +:10656000094B032C03EB0616F061F2D11748FFF735 +:10657000E9FE03E016480C21FFF7EAFC09B0BDE88C +:10658000F08300BF9D65010830200020C865010828 +:10659000CE6501080868010844200020D265010882 +:1065A0000AD7233C99650108956501083E680108F2 +:1065B000E1650108E7650108FC4F01087364010803 +:1065C0001C460108EC650108FC6501080967010823 +:1065D000366601080A88F0B54B888F880E89CD8809 +:1065E000002A3AD1048C834A24F001042404240CA8 +:1065F0000484018B048C89B221F0F30141EA061670 +:10660000B6B29042A4B246EA070743F0010315D0A0 +:1066100002F50062904211D0B0F1804F0ED0A2F589 +:10662000983290420AD002F58062904206D002F57C +:106630008062904218BF24F00A0401D124F00204C1 +:10664000234307830384038B23F00C031B041B0CDD +:106650000383038B9BB21D4344E0042A44D1048C82 +:10666000644A24F010042404240C0484018B048C58 +:1066700021F440710905090D41EA063189B241EA68 +:1066800007279042A4B2BFB212D002F50062904236 +:106690000ED0B0F1804F0BD0A2F59832904207D0C7 +:1066A00002F58062904203D002F58062904207D1E9 +:1066B00024F0200444EA03139BB243F0100304E0E7 +:1066C00024F0A00443F01003234307830384038BC7 +:1066D00023F440631B041B0C0383038B9BB243EA2C +:1066E0000525ADB20583F0BD082A018C3ED121F409 +:1066F00080710904090C0184818B3E4A89B221F022 +:10670000F301048C41EA0616B6B29042A4B246EAFE +:10671000070712D002F5006290420ED0B0F1804F10 +:106720000BD0A2F59832904207D002F580629042D9 +:1067300003D002F58062904207D124F4007444EA49 +:1067400003239BB243F4807304E024F4206443F4F5 +:106750008073234387830384838B23F00C031B0400 +:106760001B0C8383838B9BB21D4341E021F480513A +:106770000904090C0184828B048C22F440721205F6 +:10678000120D42EA072242EA06361A4AA4B29042A1 +:10679000B6B212D002F5006290420ED0B0F1804F36 +:1067A0000BD0A2F59832904207D002F58062904259 +:1067B00003D002F58062904207D124F4005242EAED +:1067C000033292B242F4805205E047F6FF52224073 +:1067D00043F480531A4386830284838B23F44063FB +:1067E0001B041B0C8383838B9BB243EA0525ADB24C +:1067F0008583F0BD002C01401FB50123ADF80830A2 +:106800000023ADF80C30ADF80A30094BADF8041098 +:106810001B7801A9012B08BF0323ADF8062008BF90 +:10682000ADF80C30FFF7D6FE05B05DF804FB00BFF5 +:106830008807002038B510F80E2C044650F8043CA8 +:1068400052B9012200F80E2C20F80C1C197B186894 +:106850000222BDE83840CFE730F80C2C20F80A1CA3 +:10686000891A89B220F8081C074A10F80F0C002575 +:1068700022F8101004F80E5C1868197B2A46FFF7FE +:10688000BBFF04F8065C38BD441200201F4B10B556 +:106890005A6802F00C02042A03D0082A04D01C4AC9 +:1068A00014E01C4A126811E05A685968C2F3834226 +:1068B000C90302F1020201D4174906E0596811F434 +:1068C000003F1449096818BF49084A4302605968E3 +:1068D000124AC1F30311545C0168E14041605C68F5 +:1068E000C4F30224145D21FA04F484605C68C4F3E8 +:1068F000C224145DE140C1605B68C3F381331A4474 +:10690000137CB1FBF3F1016110BD00BF0010024028 +:1069100000127A002400002000093D0050000020F1 +:10692000024B1A6922EA0000186170470010024009 +:10693000954B2DE9F74F1B78013B012B00F220818D +:10694000924B1E78864240F01B81914B1B78022BA4 +:1069500000F016818F4B904D13F806808F4B83F813 +:1069600000808F4B1A7801921AB18E4B33F91600C2 +:1069700007E08C4A2B6832F9160003F100432B60C4 +:10698000404208F045FA884908F04AFBDFF838A28F +:106990000446DAF800B00021584608F021FC002730 +:1069A000DFF82C92002859D0D9F800B0204659467B +:1069B00008F03EFC68B17D4B2A687B491A60C9F833 +:1069C0000040204608F078FA08F03CFC784BD8806C +:1069D000BDE05846394608F02BFC002800F0B7808F +:1069E000744B1A78002A31D12046296808F05AF9E8 +:1069F0004FF07E5108F0FEFB6F4C28B160686F4984 +:106A000008F05AFA60600FE06D49606808F054FAC7 +:106A1000DFF8CCA18346514608F0ECFB10B9C4F86E +:106A200004B001E0C4F804A0624A01231370654B6E +:106A300000221B68C9F8007043449A72019A82F0E0 +:106A40000103574A1370604B1F6080E05F4BCAF828 +:106A500000401A68554BFA325A6078E02046594691 +:106A600008F0C8FB48B1584A4F491460204608F066 +:106A700023FA08F0E7FB4E4BD880534BD9F800902F +:106A8000D3F800A04846514608F00CF94F4B834616 +:106A90001968464B5A688A1A002A0BDA4FF07E5161 +:106AA00008F0C6FB002852D02046514608F0C0FB33 +:106AB00000284CD03D4A4846116808F0B9FB3E4CCE +:106AC00038B120683E4908F0F7F93C492060A068D9 +:106AD00007E058464FF0804108F0AAFB28B1A068B3 +:106AE000374908F0E9F9A06004E02068334908F06C +:106AF000E3F92060334B2C492068D3F8009008F06C +:106B0000DBF908F0C5FB09F80800A06808F0C0FB35 +:106B1000019AC84482F00103214A88F814001370D6 +:106B2000294B1F602A4B1F60224B1A780132D2B2C8 +:106B3000032A01D01A700AE000221A701E4B254960 +:106B4000586808F0B9F908F0A3FB88F80A001EB9E4 +:106B5000174B1A8864321A80114A13780BB11E4BF6 +:106B600000E01E4B2B600F4B33F9160008F050F974 +:106B70000D4908F055FA0146286808F093F800E03E +:106B8000084603B0BDE8F08F04050020580500203A +:106B900068050020604501080805002069050020FF +:106BA00059050020A8030020000020415C120020AD +:106BB000861800205A0500206C0500200AD7833F64 +:106BC000EC51783F640500205C0500202C2000205B +:106BD0006005002000007A440000A0410000A0C130 +:106BE0006F12833A10B50848FEF746FF074B1C6842 +:106BF0002046FEF786FE18B90A20FEF724FEF7E7C6 +:106C0000034A044BDA6010BD5E660108D81B002001 +:106C10000400FA0500ED00E008B50748FEF72CFF78 +:106C2000064A002313729363054A137006F0E0FCD2 +:106C3000BDE80840FFF7D6BF6A6601085C12002075 +:106C4000D427002008B50448FEF716FF04F050FED4 +:106C5000BDE80840FFF7C6BF966601082DE9F04F72 +:106C6000002487B007460491924605938046254646 +:106C7000022DDFF888914FEA450607D10498437941 +:106C8000B9F904001B3343435B1148E0524B39F917 +:106C9000151033F9153003EB4101CAF10003994295 +:106CA00003DB5145B4BF0B4653464C49059A31F9B5 +:106CB00006B0915FCBEB030303EB010B02F0C0FACC +:106CC00098B1474B58465B5D039308F0A1F84549DE +:106CD00008F0A6F9039B01461846FFF729FE414933 +:106CE00008F0EAF808F0AEFA83463F4B1988C80767 +:106CF00011D404988A07037939F9060003F11B03BC +:106D000000FB03F34FEA231309D57A7C02FB0BFB4C +:106D100003EB2B2303E0FB7903FB0BF31B11334A3B +:106D200098F80AB0905F042290FBF2F0181A7B5D8D +:106D30002F4A4343DB1101932E4B01351988A35889 +:106D400001FB00FC4FEAEC2C0BFB0C33DFF8B0C06E +:106D5000B3F5001FA8BF4FF400136345B8BF6346E7 +:106D6000A3504FEA633C244B0909E258E050821AD1 +:106D70004FF6FF70B0FBF1F14A4303F10C0003F151 +:106D8000180B215854F80B90921189442250CDF8D9 +:106D90000890914498F8142044F80B1002FB09F174 +:106DA00001980912084403F12402604490530198A9 +:106DB00003F12C02A050032D03F1380203F1440328 +:106DC00044F802C0E15008F1010804F104047FF422 +:106DD0004FAF07B0BDE8F08FDC270020A8030020EC +:106DE0008E4E01080000204154020020F4040020CF +:106DF000B80E0020FC04002098120020620200203F +:106E00000000E0FF2DE9F04F89B00793994B0692FF +:106E1000B3F90220B3F90030002AB8BF5242002B68 +:106E2000B8BF5B4200249A42B8BF1A46039005924D +:106E30002646A04627460494A3462546DFF86092DE +:106E4000B9F8003099075AD0022D58D0894BDDF897 +:106E500018C0F25E884BF35E03EB4202CCF10003F4 +:106E60009A4203DB63469A42B8BF1346834ADDF871 +:106E70001CC036F902A03CF90620CAEB030303EB61 +:106E8000020A02F0DDF990B17D4B504615F803B0CF +:106E900007F0BEFF7B4908F0C3F801465846FFF7EC +:106EA00047FD784908F008F808F0CCF982460398C5 +:106EB0006423C2796FF0040102FB0AF292FBF3F241 +:106EC000C37E01FB03FB5A4505DB03EB83039A42B8 +:106ED000B4BF93469B466C4A42F21071A358534488 +:106EE0008B42A8BF0B4669498B42B8BF0B4603993A +:106EF000A35091F811A00AFB03F31B130493B9F8F4 +:106F0000003003F00302012A01D1022D3DD1594A7C +:106F10005F49B75E895F039A81EAE170A0EBE17097 +:106F200012F805C05B4AB0F5206F54F802801DDCF2 +:106F3000022D15D05020784390FBFCFC042091FBDF +:106F4000F0F1C1EB0C0CE0445348B8F57A5FA8BFF0 +:106F50004FF47A588045ACBF42F80480105107E0E6 +:106F600087EAE770A0EBE7706428E3DD00211151A8 +:106F7000484AA1587D2291FBF2F8039A2A44927A5A +:106F800002FB08F8402298FBF2F89A0716D5022D6A +:106F900014D0059BDDF814C0C3F5FA720CFB08F0A1 +:106FA0007B43DDF810C002FB0B3302FB0C024FF4F5 +:106FB000FA7193FBF1F392FBF1F208E0DB0701D5E4 +:106FC000022D02D142463B4601E0049A5B4630491D +:106FD000DFF8D0A0715A4FF0040C0FFA81F915F8C0 +:106FE0000AA099FBFCF00AFB00F06FF04F0A90FB3F +:106FF000FAF01844294B019036F903A0F152CAEB7C +:10700000090999FBFCF903F1140A03F1080C54F87F +:107010000C0054F80A1044F80C90DFF88CC00144BE +:1070200015F80CC0494402910CFB01F14FF0200C03 +:1070300091FBFCF144F80A000198C1EB0209A3F1AD +:107040002C0C814426F80C900135A3F1240C44F853 +:107050000C004942A3F11800032DA3F10C032250A8 +:10706000E15006F1020604F104047FF4E7AE09B032 +:10707000BDE8F08F62020020DC270020A80300207A +:107080008E4E010800002041180E0020F0D8FFFFAE +:10709000F4040020B80E002080C1FFFFE812002099 +:1070A00054020020DE0E0020E40E00202DE9F04FF7 +:1070B00089B007937A4B814618880491059207F0AE +:1070C000A3FE784907F0F8FE002403904F462546BA +:1070D0002646022EDFF80CA20BD10499BAF904005F +:1070E0004B790A33584307F093FE6F4907F098FF36 +:1070F00044E06E4B3AF90520EB5E05991A444B4289 +:107100009A4203DB0B469A42B8BF1346684AAA5E0E +:107110009B1A079A505F184407F07AFE654907F0FA +:107120007FFF804602F08CF828B1634B4146985DA2 +:10713000FFF7FEFB8046614B1A88D10705D5404614 +:10714000D9F8441007F0B8FE18E004993AF90500A0 +:107150000B7901921433584307F05AFE524907F055 +:107160005FFF019A8346930709D5D9F84810404636 +:1071700007F0A2FE0146584607F096FD8346504AA6 +:10718000505F07F045FE4F4AD16807F095FE8246F2 +:107190005146584607F086FD396A804607F08CFE56 +:1071A000DFF844B106900399404607F085FEF96A7E +:1071B00007F082FE54F80B1007F076FD4249804636 +:1071C00008F018F838B94046404908F031F820B1C5 +:1071D000DFF8F88001E0DFF8F0804BF80480DFF89A +:1071E0000CB1504654F80B1007F05CFD44F80BA0AE +:1071F000034603994FF07E50029307F011FF029B64 +:107200000146184607F058FE0BF10C03E2580BF14B +:10721000180B54F80B10824610460192029307F0A7 +:1072200043FD514607F040FD019A029B44F80B20B4 +:1072300044F803A0264907F0F3FEB96B07F03CFEC3 +:107240002449824607F0D6FF38B95046224907F054 +:10725000EFFF20B1DFF880A001E0DFF878A006980A +:10726000414607F021FD514607F01CFD0BF09EF84A +:107270001A4BB0F57A7FA8BF4FF47A709842B8BF26 +:1072800018460136164B032EE85204F1040405F1AA +:10729000020507F104077FF41CAF09B0BDE8F08FC9 +:1072A000FC040020BD37863500004842DC27002062 +:1072B000A8030020000020418E4E01085402002047 +:1072C000F4040020EC03002000007AC300007A439D +:1072D00000004040000096C30000964318FCFFFFEA +:1072E000BC12002062020020C40E002008130020FF +:1072F0002DE9F047734A86B013789146DFF8D881BC +:10730000C3B90122D8F8001089F800206E4A1A4447 +:107310005068884203D00C33302BF7D1002202236F +:1073200053726A4B6A48C3F8D010FEF7A5FB694850 +:10733000FEF7A2FBD8F80000FEF7F2FA002800F0F2 +:10734000BE80654B614C1868FEF7E5FA09280146D6 +:1073500001D03F284FD14FF0000AA56B5F4F564632 +:107360002DB15F4839682A460AF004FE10B9BA46C2 +:1073700006B93E465B4B0C379F42F1D3CEB137681E +:10738000DAF800E02B46F85C1EF80310814201D0C9 +:10739000A3630EE05A1C41B92D2B06D8A2632344E7 +:1073A000202022441872117203E04D4958541346AC +:1073B000E9E7A36B0BB1564512D04B48FEF75CFBD7 +:1073C000564509D856F80C0BFEF756FBD8F80000C6 +:1073D0000921FEF7B7FAF3E73E48FEF74DFB00251B +:1073E000A36B9D42A6D23E4BD8F80000595DFEF734 +:1073F000A9FA0135F4E7A36B33B904283BD104F1B2 +:107400000800FFF709FC5AE00C2801D137488CE747 +:107410000A2901D00D2949D13548FEF72DFBA36B70 +:10742000E21800231372227A232A17D00493314BD7 +:107430002B4E009303A8294915220C2303960AF02A +:10744000EAFD054638B100680AF08CFD0130AB68F2 +:107450003044984702E02848FEF70EFB2048002100 +:1074600030220AF03EFD0023A36399F80030002B80 +:107470007FF45DAF23E00C28C8D07F2903D159E702 +:107480002F2B3FF657AFA1F12002D2B25E2A3FF672 +:1074900051AF13B920293FF44DAF5A1CA263D8F85D +:1074A00000001C442172FEF74DFA43E77F29E7D123 +:1074B000013BA363002223441A72104838E706B048 +:1074C000BDE8F087D4270020680000205C1200206F +:1074D0009D660108D5660108D81B002030530108BD +:1074E000641200202C540108DA660108DF660108E6 +:1074F0003E68010809510008EA66010806670108AC +:107500002DE9F04FD84AD94C85B01068516802ABCC +:1075100003C3DFF8908300214FF4EF6220460AF0A6 +:10752000E0FC04F50573C8F80030D14B0025DFF806 +:1075300078A31D7004F25673CAF8003003236371F8 +:107540000223A36040F24C404FF41673A4F8F030CD +:10755000A4F81C01FA2340F26C70A4F8F230A4F8ED +:107560001E012A231920A4F8EE3084F825014FF4D7 +:10757000FA7340F27E40A4F8F630A4F8D00020233D +:1075800040F23A7084F8F430A4F8D2006E234FF43D +:107590007A7084F80431A4F8D4002B2340F27E5092 +:1075A00084F80531A4F8D600212340F2EA500126E0 +:1075B000552240F2DC514FF01E0B4FF0320984F897 +:1075C0000631A4F8D8004FF4C87340F2B4502270CA +:1075D000A4F80831A4F81A11A4F8DA00A4F8DE30EF +:1075E00084F8EC6084F821B184F8246184F8276180 +:1075F000A4F8DC90A4F8E0908DE80600FEF700FE09 +:1076000040F6AC53A381D8F8003028271720A57383 +:1076100018761F7183F80EB05F7183F80FB058763B +:107620001D700B20019A1872142058721875502082 +:1076300098776420D8774FF0080E782083F813E00D +:107640005873DFF868C28B484FF00E0E9A7183F8BA +:107650000AE02D224FF05A0E4FF00A0B1A745A7797 +:1076600083F80BE01F73DA7583F821609D7683F849 +:1076700007905D74DD769D741D7783F815B0C3F8AF +:1076800024C0D86318644FF08240D8624FF07C5019 +:1076900098637948C3F828C05864784A7848DFF876 +:1076A00010C200991A635A639864C3F84CC084F8F6 +:1076B00056E74FF0410EA4F85E1784F857E784F8B8 +:1076C0005A5784F85B5784F8589784F8595784F8C8 +:1076D0005C579A666B4A0421DA666B4A83F8581045 +:1076E0001521D86583F8607083F861701A6783F894 +:1076F0007460A3F85450A3F85650A3F8525083F87E +:1077000064106248FEF79CFDD8F800304FF44872D0 +:10771000A3F86221C82283F8A7214FF49662A3F848 +:10772000A82140F2D932A3F8AA2140F6430283F8F7 +:107730005F7183F86061A3F8AC2183F85D5183F831 +:107740005E5183F8645183F8A6B11A4647465646FF +:107750004FF47F71A2F866114FF4FA61A2F8681134 +:1077600002A840F2DC51A2F86A11415D013582F8AD +:107770006C11082D4FF0FF0182F86D1102F1080223 +:10778000E6D1012283F8AE2183F8AF2183F8B0213E +:10779000C82183F8B6216422A3F8B211A3F8B82156 +:1077A00014214FF4967283F8B411A3F8BA211E2164 +:1077B000282283F8B511A3F8BC210023E218103366 +:1077C0000021C02B1161F9D13148002140220AF07B +:1077D00088FB00232F49E218595804330868382BD6 +:1077E000C2F8D401F6D12C48002180220AF079FB9E +:1077F0002A4B294D03F1300E186859682A4603C2F6 +:10780000083373451546F7D1254D01F0CDFE01F043 +:1078100007FF01F0E1FE3F68284639464FF4E07269 +:107820000AF056FB394605F5E0704FF4E0720AF0B5 +:107830004FFB336805F563725968186803C21989EC +:1078400011801A68C5F896235A68C5F89A231B89CF +:10785000A5F89E33012384F82434022384F8E43508 +:1078600005B0BDE8F08F00BF904E01083020002029 +:10787000140E00208FC2753DCDCC4C3D9A99193F16 +:107880000000A040F6287C3F3D0A773F0A670108C8 +:1078900004220020B445010884210020984E0108EC +:1078A00004240020E80300208C0500200000204074 +:1078B0000000404008B50548FEF7DEF8FFF720FE5F +:1078C00004F016F8BDE80840FFF78CB9136701080B +:1078D00010B50A4C23681BB105F006FC0023236099 +:1078E000074B1B7813B1012B03D010BD4FF400627E +:1078F00001E04FF48052034B1A8010BD4007002076 +:1079000045070020000000202DE9F04F012828BF86 +:107910000120142101FB00F389B0DFF8BCB1019014 +:107920000BEB03025BF803706548019B654E076033 +:10793000F469037110691589B2F80A9020435468FC +:1079400049EA0508F0610222C4F8108020468DF84B +:107950000E1003A9ADF80C808DF80F2001F0DAFFAE +:107960004FF0080AA268154203D10A20FDF760FF14 +:10797000F8E70A206561FDF75BFF25610A20FDF746 +:1079800057FFBAF1010AEDD10A20C4F81490FDF7AF +:107990004FFF0A206561FDF74BFF0A202561FDF7C7 +:1079A00047FF0222C4F8109020468DF80F2003A94B +:1079B0001C228DF80E20ADF80C8001F0ABFF424A7E +:1079C0009742326905D142F4001232614FF400103F +:1079D00004E042F4800232614FF48000FEF7A0FF21 +:1079E000BA8803A822F440721204120CBA803A88B2 +:1079F000012592B242F001023A80BC88FEF746FFB0 +:107A000024F03F04059831492404B0FBF1F1240C23 +:107A10000C43A4B2BC803A88142322F00102120461 +:107A2000120C3A802A4A0024B0FBF2F24FF496700E +:107A3000414392B24FF47A70002A91FBF0F108BFF3 +:107A40000122013142F4004289B23984BA833A8872 +:107A500003A892B242F001023A803A8822F481628D +:107A600022F002021204120C3A804FF480423A8152 +:107A7000019A8DF80D4003FB02B77B7B8DF80E4019 +:107A80008DF80C308DF80F5003F09AF83B7B9DF881 +:107A90000F208DF80C308DF80D408DF80E401AB186 +:107AA00003A803F08DF807E0590903F01F039D4078 +:107AB000084A203142F8215009B0BDE8F08F00BFDC +:107AC00030130020001002400054004040420F00DC +:107AD000804F120000E100E0C84E010808B5054BD8 +:107AE0001A88013292B21A80034B1879FFF70CFF03 +:107AF000002008BD3C1800203013002013B51E4B99 +:107B00004000C0B2587102AC1868997104F8012D98 +:107B100000210122DA71DC6019721C611A755A7534 +:107B2000997538B38288920515D40288D4050DD48E +:107B300047F230520188890502D5013AFAD112E0A4 +:107B40008AB1028892B242F480720280828892B234 +:107B500042F44072828047F23052597D11B1013AAD +:107B6000FBD100E012B9FFF7B9FF03E0024B987DAB +:107B700080F0010002B010BD301300200246402109 +:107B80003C20BBE7024680213C20B7E708B55038CF +:107B9000C0B2FFF7F7FF0020FFF7F4FFBDE8084091 +:107BA0001020EFE7772048210122A7E7772058210E +:107BB0000122A3E7064B002193F82020054B9201F8 +:107BC000343219707720F42102F0FC0296E700BFEE +:107BD0005C07002018200020034B00221A70772039 +:107BE000F4212E228AE700BF1820002010B5174C80 +:107BF00023681BB105F078FA002323606B218022F3 +:107C00006820FFF77BFF6420FDF71DFE192100228D +:107C10006820FFF773FF6B2103226820FFF76EFFD8 +:107C2000372102226820FFF769FF094B1A211A78D1 +:107C30006820FFF763FF1B2118226820FFF75EFF13 +:107C4000BDE8104068201C21102257E740070020A3 +:107C50003900002008B51920FDF7F5FD6820152131 +:107C60000022FFF74BFF10B90320FDF723FE0C4B5A +:107C700016211A78682042F01802FFF73FFF1721FB +:107C800000226820FFF73AFF3D2101226820FFF71C +:107C900035FFBDE8084068203E2101222EE700BFE5 +:107CA0003A00002013B500222A211C20FFF726FFEE +:107CB0000E2102221C20FFF721FF0F2103221C208E +:107CC000FFF71CFF2B2112221C20FFF717FF164B7A +:107CD00002249A69154842F004029A612023ADF803 +:107CE000043004230DEB03018DF806308DF80740B6 +:107CF00001F010FE22462C211C20FFF7FFFE2D2153 +:107D000001221C20FFF7FAFE2E2100221C20FFF783 +:107D1000F5FE2A2105221C20FFF7F0FE044B4FF44C +:107D200080721A8002B010BD0010024000080140AD +:107D30000000002008B50F2108221820FFF7DEFE02 +:107D40000E2218201021FFF7D9FE024B4FF480526B +:107D50001A8008BD0000002008B5134B53201B7883 +:107D60002D2108227BB1FFF7C9FE31210A225320C1 +:107D7000FFF7C4FE2C210C225320FFF7BFFE532037 +:107D80003821902209E0FFF7B9FE31210A22532061 +:107D9000FFF7B4FE53202C210A22FFF7AFFE034B5E +:107DA00040F209121A8008BD44070020000000209C +:107DB00010B540001C4CC0B26071A17101200021BF +:107DC000E17120722275607520682361E360A175FE +:107DD00040B383889B0515D40388D9050DD447F299 +:107DE00030530288920502D5013BFAD112E08BB1E3 +:107DF00003889BB243F48073038083889BB243F46F +:107E00004073838047F23053627D12B1013BFBD156 +:107E100000E01BB9BDE81040FFF760BE024B987D43 +:107E200080F0010010BD00BF3013002037B50622DE +:107E3000044603216B461E20FFF7BAFF9DF8013070 +:107E40009DF80000154D43EA002000B206F0E0FF67 +:107E5000296807F031F807F0F5F99DF80330208024 +:107E60009DF8020043EA002000B206F0D1FFA968A5 +:107E700007F022F807F0E6F99DF80530A0809DF89C +:107E8000040043EA002000B206F0C2FF696807F070 +:107E900013F807F0D7F9608003B030BD3C00002034 +:107EA00007B5002101AB03227720FFF781FF9DF882 +:107EB00005009DF80430000240EA03409DF80630BA +:107EC000184303B05DF804FB08B5FFF7E9FF014B69 +:107ED000986108BD3013002008B5FFF7E1FF014BA2 +:107EE000D86108BD30130020104B13B51B78104C1F +:107EF00013B9238C0133238401ABF62103227720AD +:107F0000FFF756FF9DF805309DF804201B0243EA59 +:107F100002439DF806201343064AB2F92020C2F11D +:107F20000802D340636202B010BD00BF18200020D9 +:107F3000301300205C0700200B4B13B51B780B4C53 +:107F400013B9238C0133238401ABF621022277205D +:107F5000FFF72EFF9DF804209DF8053043EA022329 +:107F6000238502B010BD00BF182000203013002070 +:107F700013B5062204466B463B216820FFF718FF25 +:107F80009DF800209DF8013043EA022323809DF8EC +:107F900002209DF8033043EA022363809DF8042009 +:107FA0009DF8053043EA0223A38002B010BD13B54B +:107FB000062204466B4643216820FFF7F9FE9DF830 +:107FC00000209DF8013043EA022323809DF802201F +:107FD0009DF8033043EA022363809DF804209DF856 +:107FE000053043EA0223A38002B010BD07B5232069 +:107FF000FDF729FC6820752101220DF10703FFF729 +:10800000D7FE28B19DF80700B0F1680358425841E7 +:1080100003B05DF804FB13B50222044601AB1B213B +:108020006820FFF7C5FE9DF804209DF8053043EA5F +:10803000022303F54E534FF48C72103393FBF2F38B +:108040002333238002B010BD13B5062204466B46CD +:108050001D216820FFF7ACFE9DF800209DF801303F +:1080600043EA022323809DF802209DF8033043EA6F +:10807000022363809DF804209DF8053043EA022323 +:10808000A38002B010BD13B5062204466B46012141 +:108090001C20FFF78DFE9DF801309DF800209DF813 +:1080A000021043EA022242F38D02042392FBF3F210 +:1080B00022809DF8032042EA012242F38D0292FBC6 +:1080C000F3F262809DF804109DF8052042EA012237 +:1080D00042F38D0292FBF3F3A38002B010BD13B5FF +:1080E000062204466B4602211820FFF761FE9DF828 +:1080F00000309DF801209B0803EB022323809DF8AC +:1081000002309DF803209B0803EB022363809DF857 +:1081100004309DF805209B0803EB0223A38002B0E6 +:1081200010BD2F4B2DE9F3411B780546002B39D0AC +:10813000002426462746A04608226B4653203221BB +:10814000FFF736FE9DF801209DF80030013403EB67 +:1081500002231BB29DF8032098449DF80230E4B23C +:1081600003EB02231BB21F449DF805209DF8043049 +:10817000202C03EB02231BB21E449DF8073003F0B2 +:108180007F0301D0002BD7D1164B98FBF4F897FB57 +:10819000F4F796FBF4F6A5F800806F80AE8083F8C4 +:1081A0002A401AE006226B4653203221FFF700FED8 +:1081B0009DF801209DF8003003EB02232B809DF8F1 +:1081C00003209DF8023003EB02236B809DF805200D +:1081D0009DF8043003EB0223AB8002B0BDE8F081D0 +:1081E000440700203013002013B5224C23689A8ADC +:1081F00092B20192019A12F4706F1CBF0122A27513 +:10820000019A12F4E06F29D01A8B9A8822F48062C6 +:108210001204120C9A80019A91051FD41A889205B3 +:108220001CD41A88D0050ED51A88D105FCD41A881A +:1082300092B242F400721A801A889205FCD4207916 +:10824000FFF762FB0AE01A8892B242F400721A80C9 +:108250009A8822F440721204120C9A802268938A3F +:1082600023F470631B041B0C93820023637502B01C +:1082700010BD00BF301300200B4B07B59A690B48A7 +:1082800042F010029A614FF40053ADF8043002231B +:108290008DF8073001A910238DF8063001F03AFB64 +:1082A00003B05DF804FB00BF001002400010014065 +:1082B00010B50446204609F055FE10F0FF0F06D118 +:1082C0000C4B0D481978BDE81040FDF741BE204623 +:1082D00009F09DFE02280CD8064B0A221870074BA5 +:1082E000074C02FB0030074B06301860FDF7C4F95D +:1082F000E0E710BD140E0020296701088027002048 +:10830000096701088C0500201FB50123ADF808306E +:10831000ADF80410002301A9ADF80A30ADF80C3017 +:10832000ADF80620FEF756F905B05DF804FB10B570 +:10833000A0F5127494F83C22C2B9A36A616A99420A +:1083400029D0591CA069A162C05C2369C0B29942BE +:108350004FEA400343F40073A4F83E324FF00A039F +:1083600084F83D3228BFA262012312E094F93D3225 +:108370007BB1B4F83E1220464B08A4F83E3201F01F +:10838000010101F0ACFA94F83D32013B84F83D3232 +:1083900001E084F83C3294F83832002B4FD194F845 +:1083A00039320133DBB2092B84F8393204D120464B +:1083B000BDE8104001F07EBA0A2B40D194F83B3260 +:1083C0002BB9B4F8403243F00103A4F8403263798A +:1083D000D9071CD5B4F84002820501D4C30705D4DF +:1083E000B4F844320133A4F8443210E0E36AC0F335 +:1083F00047000BB198470AE0E3696269D054E2692B +:10840000E3680132B2FBF3F103FB1123E3610122C4 +:1084100084F8382294F83B220023012A84F8393268 +:108420000DD1A27984F83B32236B012A1868197B9D +:1084300014BF02220022BDE81040FFF765BF10BD47 +:1084400010B5A0F513746379DB074CD594F8383276 +:1084500013B3236B1868828DC2F34E02828494F8A2 +:108460003C2222B1B4F842220132A4F84222A2797D +:10847000197B012A0CBF02220022FFF745FF0123CE +:1084800084F83B32002384F8393284F83A3284F895 +:108490003832A4F8403210BD94F83B322046012B0C +:1084A00004BF94F8393284F83A3201F003FA94F8B0 +:1084B0003B12236BA27949B9012184F83B128A420D +:1084C0001868197B0CBF0222002208E0002184F802 +:1084D0003B12012A1868197B14BF02220022BDE852 +:1084E0001040FFF711BF10BD426A10B58469A15456 +:1084F000416A02690131B1FBF2F402FB14124262DB +:10850000426B32B11368DB0708D4BDE8104002F0BB +:10851000EFBA036DDA6842F08002DA6010BD2DE92F +:10852000F84FFDF7B7F88B4E8B4A33680546C31AF0 +:10853000934240F29580894B8949002209789A70CC +:108540001A71DA775A75874A9977197511680A226C +:1085500091FBF2F11977091259778349096891FB68 +:10856000F2F283F82020121283F821207F4B804AF8 +:108570001978804B91761B7813F0020F134602D1C5 +:108580002D23D3766BE004298CBF33223222DA7696 +:10859000794A7A4C1768DFF8089297FBF4FC09FBDC +:1085A0000C7A4FF0060808FB0AFA5068744A0CEB84 +:1085B0008C0C9AFBF2FB02FB1BAA0CEB8C0C4FFA07 +:1085C0008BFB0BEB8C0C1FFA8CFC90FBF4F483F808 +:1085D0000AC04FEA1C2C83F80BC009FB040C08FBF3 +:1085E0000CFCFF0F5F729CFBF2F702FB17C26421C9 +:1085F00092FBF1F25A7412129A74624AC00F1288F6 +:108600009873242042439AFBF1FA92FBF1F15E4AFF +:10861000D9711288C1F30721DA74120A1A755B4AFC +:10862000197211880A22B1FBF2F202F5FA7292B2C3 +:1086300004EB84045A75120A7FB204EB84049A7521 +:10864000534A07EB8404A4B2128883F80CA0DC73AD +:108650004FEA2A2A240A83F80DA01C741A77356081 +:108660003379DFF8F0804BB94A4C2068FDF758F9B0 +:10867000494B1B78002B44D1012848D8F068354C71 +:10868000002865D027793FB1236940F6B732EB1A4D +:1086900093420AD8BDE8F88F012323713D4B022194 +:1086A0001868FDF729F9277528E0637D394A43B931 +:1086B00010680121E3602371FDF71EF9FDF735F91C +:1086C0001CE0013BDBB26375217D94F816E03BB9F9 +:1086D0004B1C0EF1010E237584F816E010680BE0B8 +:1086E000034613F8017B0EF1010E39441068217521 +:1086F000E36084F816E03946FDF724F93561BDE8FA +:10870000F88F0028BAD02068FDF705F91DE002288F +:10871000224F03D0FDF709F9012303E03A781AB19B +:10872000C8F808503B70A9E7D8F80830EB1AB3F541 +:108730007A6FA3D3012320683B70FDF7ECF807465E +:108740002068FDF7E8F8802F98D103F071F995E7DC +:10875000BDE8F88F5C1300203F0D0300580D00208A +:10876000B4050020B8050020BC050020C405002089 +:10877000840D002082020020D00500208096980001 +:1087800040420F00C005002040180020C205002014 +:1087900042180020E41B0020F01B00206400002091 +:1087A000806967FFF7B50368174C184D23600B68A5 +:1087B000174E6360006800F09DFF95E80300154BBD +:1087C0000196009394E80C0000F052FF3668124BBB +:1087D00060681E606B68114FC01A06F019FB104BE1 +:1087E000196806F069FB06F02DFD22682B68786099 +:1087F000D31A3B600B4B1E600B4B1B68DA880B4B8C +:108800001A8003B0F0BD00BF48110020D005002041 +:108810005411002050110020901100205811002008 +:108820004C00002088110020200A00208411002024 +:108830002DE9F043142285B0814688461B4800216B +:1088400009F04FFB03261A4B0027B74224DA13F82E +:10885000042C0021C8B2013112B1501E0240F9E7C8 +:108860001C7AD1B2013214B1611E0C40F9E7421AF0 +:10887000002A0EDD01ACA3F10C0595E8070084E8A1 +:10888000070093E8070085E8070094E8070083E8FD +:10889000070001370C33D8E7013ED4D1034A4846DC +:1088A000414605B0BDE8F04304F044BE7413002017 +:1088B000740000200022064B13445968814203D003 +:1088C0000C32302AF7D1002300225A725A607047C6 +:1088D0006800002038B50E4D04462B68834207D14E +:1088E0000121FFF7E7FF284600214C2209F0F9FAA1 +:1088F000EB6CA3420AD120460121FFF7DBFFBDE864 +:108900003840044800214C2209F0EBBA38BD00BFC2 +:10891000200F00206C0F002010B50023054A1A44D8 +:108920005468844203D00C33302BF7D100225172AB +:1089300010BD00BF680000202DE9F34706461F4622 +:108940004FF41473734347489246C41880460EB9D7 +:10895000454A02E0012E04D1444A22631032C4F891 +:108960003421434A0025C250032363714FF48073BE +:108970004FF00109E3602361D4F8343184F83C52AC +:1089800084F8389284F8395284F84662586804F1C1 +:1089900034029B68626104F59C72A261E162256207 +:1089A000E561A5626562A4F84252A4F84452ADF8AC +:1089B00004300225102301A9C4F808A0A7718DF87E +:1089C00006308DF8075000F0A5FF236B01A9586809 +:1089D0009B688DF80750ADF8043048238DF80630B9 +:1089E00000F098FF4946204600F079FF3220FCF75E +:1089F0002AFF204BD4F834911B681D46B5FBFAF1D1 +:108A0000B1F5803F03D3012DF8D96D08F6E71A4A76 +:108A10004846B3FBF2F289B2D2B203F093F84FF4B6 +:108A200014735E43154B06F5127608EB060548F8FD +:108A3000063048462946002201F08EFF266B012FA2 +:108A400014BF022200223068317BFFF75DFC0C4B23 +:108A500030466B60291D002201F07EFF204602B0E7 +:108A6000BDE8F08788130020D4610108F461010893 +:108A7000F04E0108A800002040420F002F8300089C +:108A80004184000803460A4690F84602D96A9B7959 +:108A900052E7F8B5002207463749130101F11800E3 +:108AA000185CB84204D00132082AF5D10020F8BD84 +:108AB000324E0B44183306F2CC45082F0FCB344608 +:108AC00085E80F001BD009D8022F0ED0042F16D036 +:108AD000012F4FD12A4B1B685B6847E0202F42D003 +:108AE000402F06D0102F45D122E0254B1B689B68F4 +:108AF00002E0234B1B681B69C6F8D03436E0214BDB +:108B00001B681B7853B1013B012B0AD900F032FDE1 +:108B1000002814BF4FF46143002304E04FF41653C0 +:108B200001E04FF49643C4F8D034C4F8D43421E0C3 +:108B3000154B1B681B7A042B1CD8DFE803F00A0ACC +:108B4000030A0A00114BC6F8D034C6F8D434032304 +:108B500006E04FF4E133C6F8D034C6F8D43401232C +:108B600084F8D93406E0064B1B68DB68C6F8D434B9 +:108B70002846F8BD0648F8BDF04E01085C130020F9 +:108B8000B80F0020A00500203C010020A0860100B5 +:108B90002818002010B50446FFF77BFF0146204649 +:108BA000FFF746FE4368187A10F0010018BF5868B6 +:108BB00010BD38B505460C46FFF76BFF0146284649 +:108BC000FFF736FE28B143681B7A1C420CBF002019 +:108BD000012038BD38B50B4B05469B685A050ED5AC +:108BE00000F0C8FC044650B10820E9B2FFF7E1FFED +:108BF00030B1054B1C78231F5C425C4100E001242E +:108C0000204638BD30200020E8050020032810B59C +:108C10000F4B0DD80F4A126894888C4208D2D28824 +:108C20008A4205D9012202FA00F01A78104318701E +:108C30001B780F2B0BD1064B00221A70064B99881C +:108C400008B2142802DD1439998010BD9A8010BD35 +:108C50003818002028200020C8090020024B9A88DC +:108C600001329A80704700BFC8090020074B1A687C +:108C7000074B1178B3F9040053780B4403EB8303DB +:108C80009842D4BF00200120704700BF2820002058 +:108C9000C8090020064BB3F90400064B1B681B787B +:108CA00003EB83039842D4BF00200120704700BF2C +:108CB000C80900202820002010B50446FFF7EAFF6D +:108CC000002814BF2046002000F0010010BD024B18 +:108CD00001221A72704700BFC8090020014B187AA0 +:108CE000704700BFC8090020034BB3F90400D0F15E +:108CF000010038BF00207047C8090020014B002246 +:108D00009A807047C809002003685A1C02601970D5 +:108D10007047016B0346C26810B5406941B1196CD8 +:108D2000541A005D013918BF0A46C0B21A6410BD5A +:108D3000196A405C0131B1FBF2F402FB1412C0B2BB +:108D40001A6210BD026B03691AB15168013B026CD3 +:108D500002E0C169026A013B881A1840C0B270473C +:108D6000436B13B190F844007047826A436AD31A88 +:108D700058425841704743799B070AD5436A826934 +:108D8000D154426A03690132B2FBF3F103FB1123B0 +:108D900043627047437913F0010307D0C368C16988 +:108DA000026A013B881A1840C0B2704718467047E3 +:108DB000437910B513F0010304460DD0FFF7EAFF25 +:108DC00058B1226A6369985CE3680132B2FBF3F13F +:108DD00003FB1123236210BD184610BD426A806A4E +:108DE000131A5842584170474171704710F80A3CB5 +:108DF0000133DBB20A2B00F80A3C0AD910F8123C06 +:108E000023B910F8131C034A22F81130002300F88C +:108E10000A3C704744120020334A10B5136C906826 +:108E20001944081A40F68C2398429160D060516032 +:108E300013463CD9127893F945108A420BD1111F81 +:108E4000082908D893F84610182901D8013103E001 +:108E500083F8442002E0002183F8461093F944107F +:108E60008A421CD1204991F84710C1B1002191429A +:108E70001E4806DA03EB8104246920F81140013111 +:108E8000F5E7511E00EB41011630814203D000246A +:108E900021F8024FF9E7164908780130087083F885 +:108EA0004520002201211A7083F8471010BD92F866 +:108EB0004710B9B1A0F2EF2440F2DA518C4208D841 +:108EC00011780B2905D80B1D0131117042F82300D0 +:108ED00010BD002283F84720991804320020302A60 +:108EE0000861F9D110BD00BF8C070020441200209A +:108EF000281E0020024B1A6C01321144196470477D +:108F00008C070020024B53F820301B6819807047F3 +:108F1000B4080020074BA1F57A7153F820304FF4C4 +:108F20007A701A681B894B4393FBF0F39BB2138052 +:108F3000704700BFB40800202DE9F04F504A514E51 +:108F40001768738984463089A7EB032785B003919E +:108F500087FB0001B288CB111404C209F08842EAF1 +:108F6000416287FB000114EB020872884FF0000594 +:108F70004FEAC2344FEA1022B08945EB030942EAB6 +:108F800001620B1287FB000114EB020A4FEAD05278 +:108F900042EA41224FF0000545EB030B12F5FA605F +:108FA0004FEAE15343F10001CDE90001B0F5FA6F5A +:108FB00071F1000147DAA2FB024502FB03F105262D +:108FC00005EB4105A4FB060106FB05114D104FEA18 +:108FD0003004B8EB040869EB050984082A4844EA20 +:108FE00081748D104FF0FF31BAEB040A6BEB050B67 +:108FF000DDE9004584428D4125DA40F6AC50121877 +:109000004FF0000143EB010302FB03F1A2FB02233B +:109010006FF0060003EB4103544200FB0344A2FB44 +:10902000000118EB000821444FF00B0449EB010943 +:10903000A2FB040104FB031149104FEA3000BAEB14 +:10904000000A6BEB010B114B1A68A2FB0A0102FB31 +:109050000B11420D42EAC1224B15B2EB080263EB41 +:109060000903D00B40EA4340BCF1000F01D0CCF81B +:109070000000039808B10099016005B0BDE8F08FC9 +:10908000481300204807002024FAFFFF4C1300205B +:10909000324B2DE9F0411C88314B0A265A89B3F92D +:1090A0001250A41A1A89ED025443B3F91420E413A0 +:1090B000224495FBF2F22244DA615643A2F57A6229 +:1090C00002FB02F4B3F90480B3F902C0B3F90E70E5 +:1090D00002FB0CFC02FB08F2B3F90C80241367437B +:1090E00004FB08F4241404EB62320232DC88921090 +:1090F00002F50042B3F920506243B3F900304FEA61 +:10910000EC2404EBE72404EB8304AC40154B02345D +:109110001B68D20BA3EBA4044CF250332B416343E6 +:1091200055BF5B00B3FBF2F3B3FBF2F35B001A1223 +:10913000524340F6DE3462430B4C08365C43241441 +:1091400004EB224202F6CF62361103EB221300B188 +:10915000036001B10E60BDE8F08100BF581300202C +:109160005C0700205413002043E3FFFF2DE9F84F74 +:109170002E4E04463768384609F0E2F80546384670 +:1091800009F052F976688046304609F0D9F88346EE +:10919000304609F049F9D4F8049006462946484675 +:1091A00005F08AFEA76882464146384605F084FEEF +:1091B0000146504605F076FD21688246584605F086 +:1091C0007BFE41460446484605F076FE314605F0F2 +:1091D00073FE0146204605F067FD314604463846D9 +:1091E00005F06AFE294605F067FE0146204605F0B7 +:1091F0005BFD0146504609F0A5F90D4905F05CFEFE +:109200000C4905F00DFF0C4B196805F04DFD0B499D +:1092100005F006FF09F0CAF883B21A0444BF00F54E +:10922000B4739BB218B2BDE8F88F00BFCC04002025 +:109230000000E144DB0F494080070020000020418E +:10924000064B1B7803F0040303F0FF001BB1044B33 +:109250001888C0F3C01000F001007047D527002027 +:10926000540200202DE9F04102780346202A00F143 +:109270000100F9D0092AF7D02D2A02D10346414D29 +:1092800004E02B2A08BF03464FF07E551E460024FB +:10929000334616F8012BA2F13007F9B209290DD88F +:1092A0003949204605F008FE0446384605F0B0FD71 +:1092B0000146204605F0F8FC0446E9E72E2A17D1BE +:1092C000314F334616F8010B3038C2B2092A0FD895 +:1092D00005F09EFD394605F0A3FE0146204605F047 +:1092E000E3FC29490446384605F0E6FD0746E8E771 +:1092F0001A7802F0DF02452A38D15A782D2A02D195 +:109300000233012604E02B2A14BF01330233002666 +:10931000013B002713F8012F303AD1B2092903D8B5 +:109320000A2101FB0727F5E7B7F59A7F28BF4FF41D +:109330009A77B8464FF07E51B8F1070F07D9084623 +:10934000124905F0B9FDA8F108080146F4E707F055 +:10935000070737B108460C4905F0AEFD013F01464D +:10936000F7E72EB1204605F05BFE04E04FF07E519A +:10937000204605F0A1FD0146284605F09DFDBDE80B +:10938000F08100BF000080BF0000204120BCBE4C27 +:10939000F0B50124B0FBF4F58D4201D34C43F9E75D +:1093A0000026DCB1B0FBF4F504FB1500B4FBF1F4CE +:1093B0001EB9002D01DC002CF3D1092D03F10107AA +:1093C0005FFA85FC04DD002A0CBF5725372500E035 +:1093D000302565441D7001363B46E2E71C70F0BD48 +:1093E000F0B50124B0FBF4F58D4201D34C43F9E70D +:1093F0000026DCB1B0FBF4F504FB1500B4FBF1F47E +:109400001EB9002D01DC002CF3D1092D03F1010759 +:109410005FFA85FC04DD002A0CBF5725372500E0E4 +:10942000302565441D7001363B46E2E71C70F0BDF7 +:1094300070B50646B6FBF2F40846154614B1204650 +:10944000FFF7F6FF05FB1464024B1B5D00F8013BC0 +:1094500070BD00BF3A6701082DE9F041069C002B62 +:1094600006460F460CBF4FF020084FF03008234649 +:1094700013F8011B09B9154603E0002AFBDD013A88 +:10948000F6E7002D04DD30464146B847013DF8E7D8 +:1094900014F8011B11B13046B847F9E7BDE8F08177 +:1094A00080EAE073A3EBE0738B4206DB002801DD6A +:1094B000401A704702D00844704700207047034BA1 +:1094C0009A6822EA00009860704700BF30200020B0 +:1094D0000E4B1B78BBB10E4B1B681A78032A06D1C2 +:1094E0000C4B187802288CBF0020012070475B7855 +:1094F00023B1094B1868C0F3C0407047074B187878 +:10950000C0F3800070470120704700BF520D00205B +:10951000A0050020E805002050020020D5270020EB +:10952000114A30B50028B8BF4042104C90FBF2F30E +:1095300004FB03003C2568430D4D90FBF2F22D68BF +:109540002D7B25B903EB830303EB830301E0C3EB1E +:10955000031302EB830304FB02020B804FF47A73C4 +:1095600092FBF3F24A8030BD80969800806967FFD5 +:10957000C8050020034B1B681878C31E5842584189 +:10958000704700BFA005002008B5064808F0EAFCB7 +:10959000C0B2142805D8034A431C20211154D8B264 +:1095A000F7E708BDA91B0020094A0A48002310B5A7 +:1095B000116803701A46CC1864880CB9CC5C24B1CD +:1095C00004330132802BD2B2F5D1027010BD00BF3E +:1095D000100600209406002010B50B4B0B4819789C +:1095E0000B4B5A784B085C1E047001F001010948CE +:1095F0000B44037008495308581E087002F001021A +:10960000064913440B7010BDCD060020C80600208B +:1096100038180020CA060020CB060020C90600200A +:10962000F0B50F4A0F4816780F4A002317684370A9 +:109630001A4619460546D0B2B0420CD217F822009D +:10964000013204099C4200F00F00A8BF631C88424D +:10965000A8BF411CEFE76B70044B1970F0BD00BF51 +:10966000940600203818002010060020CD060020A7 +:10967000F8B5101A0C461F4605F0CAFB0546381B04 +:1096800005F0C6FB174B079E196805F015FC294627 +:109690000446284605F010FC21460746204605F002 +:1096A0000BFC0146384605F0FFFA09F0D5F80E49E3 +:1096B00005F002FC05F0ECFD069B2146186005F163 +:1096C000004008F03FFF094905F0F6FB084905F0A6 +:1096D000EBFA05F0B7FD0028BCBF00F50C40A03048 +:1096E0003060F8BD4C0000202C7D8E3FA00CB345AF +:1096F00000A00C4610B505F08BFB0021044605F0D8 +:1097000097FD08B1204601E004F10040054905F04D +:1097100087FC054905F0D0FB08F012FE034B1860EA +:1097200010BD00BF8096184B35FA8E3C4C000020CF +:1097300070B50446007905F067FB1E4905F070FC22 +:109740001D4D1E4E2860A07B05F05EFB194905F0FB +:1097500067FCEE606860607905F056FB184905F01B +:109760005FFC184D2860E07B05F04EFB114905F0C9 +:1097700057FC6860607E05F047FB134905F050FC1C +:10978000EE60A860A07905F03FFB0D4905F048FCAC +:109790000E4D2860207C05F037FB064905F040FCA3 +:1097A0006860A07E05F030FB074905F039FCEE60EB +:1097B000A86070BD0000C842601100200000FA449B +:1097C000000020417011002000007A449411002014 +:1097D00044F25063984203DDA0F50C40A038704776 +:1097E000034B9842BCBF00F50C40A030704700BF4F +:1097F000B0B9FFFF2DE9F041038A87890446BFB263 +:109800000D461F40002F36D0B7FA87F34FF00042C5 +:10981000DA40D24391B21B3B21821740042BF1D88E +:10982000DFE803F0221F1C1903006B6A33B103F158 +:10983000FF3800231FFA88F86B6203E0B4F82C802D +:109840001FFA88F82E6A002EDCD033683046414675 +:1098500098477668F7E72868A18E08E06868218F46 +:1098600005E0A868A18F02E0E868B4F8401003683A +:1098700089B29847C6E7BDE8F0810C4B800A984250 +:109880000CD003D8B0F5801F0ED00BE0084B9842E7 +:1098900006D04933984205D1002070470220704716 +:1098A00003207047FE207047012070470100100020 +:1098B0000200100090F83B3210B57BB990F83A32B4 +:1098C00090F83922934209D201219940B0F84042E0 +:1098D00001332143A0F84012DBB2F3E710BD8379D6 +:1098E000012B03D1D1F1010138BF0021D0F834316F +:1098F0005A681B8909B11361704753617047044B63 +:1099000053F820301BB107289CBF1B681980704793 +:10991000E40800202DE9F0410F88002347FA03F204 +:10992000D2072BD58A7803F0070512F0100F18BF65 +:1099300091F803C002F00F0618BF46EA0C06AD000E +:109940004FF00F0C0CFA05FC06FA05F5DC0850F890 +:109950002480282A28EA0C0C45EA0C0540F82450FB +:1099600005D101229A40C46824EA020205E0482A8F +:1099700004D101229A40C4682243C2600133102BF3 +:10998000CCD1BDE8F08100BF2DE9F047054608F0D5 +:10999000E9FA2E4B0446D3F808809A4690B92C4831 +:1099A000FCF76AF82B4B53F8241049B10123A3406C +:1099B00013EA080F02D02848FCF7CAFA0134F1E78D +:1099C000264821E028462649224608F0D3FA58B90D +:1099D0002448FCF751F8244C54F8041F0029EFD018 +:1099E0001D48FCF7B5FAF7E72B7800262D2B03BFAF +:1099F000013504F1FF344FF001094FF00009154B18 +:109A000053F8267027B91948BDE8F047FCF734B879 +:109A100028463946224608F0ADFAA8B90120B040E0 +:109A2000B9F1000F03D0FFF74AFD114804E040EA06 +:109A30000800CAF808000F48FCF71EF839460E481F +:109A4000BDE8F047FCF784BA0136D8E730200020A3 +:109A50005F670108585001086F6401083E680108FB +:109A60001A6E0108726701085450010887670108DF +:109A70009E670108A8670108086801082DE9F04FF2 +:109A8000692887B0044600F0A78200F296802E284D +:109A900000F0398562D8242800F009852BD82028C9 +:109AA00000F08282222800F0BE83012840F05C850D +:109AB0002C20FBF77BFF0020FBF749FF2046FBF73C +:109AC00046FF0020FBF743FF4320FBF740FF4C20FD +:109AD000FBF73DFF4620FBF73AFF4C20FBF737FF33 +:109AE0002046FBF734FF0020FBF731FF0020FBF797 +:109AF0002EFF0024F0E0282800F0E18412D8262868 +:109B000040F03285924C0320FBF750FFB4F9E60099 +:109B1000FBF74FFFB4F9E800FBF74BFFB4F9EA009D +:109B200000F034BC2A2800F0D5842C2840F01C8595 +:109B3000874C0720FBF73AFF94F81801FBF707FF63 +:109B4000B4F91E01FBF735FFB4F91A01FBF731FF39 +:109B5000B4F91C01FBF72DFF00F0C2BC642800F033 +:109B6000E3801AD8322800F0BB840AD8302840F0AD +:109B7000FB84774C8020FBF719FF04F1800500F08F +:109B8000D8BC342800F06F83402840F0ED840820D2 +:109B9000FBF70CFF002400F0ACBC662800F09C81B1 +:109BA000C0F0F080672800F0D081682840F0DC84A5 +:109BB0001020FBF7FBFE002406E2732800F0BA83B6 +:109BC00055D86D2800F01B8212D86B2800F0008455 +:109BD00040F2BB835F4C0620FBF7E8FEB4F90000BF +:109BE000FBF7E7FEB4F90200FBF7E3FE5A4B0EE287 +:109BF0006F2800F06782C0F00D82702800F081822B +:109C0000722840F0B184524C1620FBF7CFFE0020A2 +:109C1000FBF7CFFEB4F9D000FBF7CBFE4F4DB4F904 +:109C2000D200FBF7C6FEB4F9D400FBF7C2FE2B68E6 +:109C3000B3F9A801FBF7BDFE0020FBF7BAFE002038 +:109C4000FBF7DCFE2B68B3F952000A2390FBF3F01C +:109C5000FBF7AFFE94F80401FBF779FE94F80601D8 +:109C6000FBF775FE94F80501FBF771FEE5E3782834 +:109C700000F0778110D8752800F0C982C0F01483F5 +:109C8000762800F0B683772840F06E84344D0024A7 +:109C90002878FBF78BFE42E3A42800F0D08310D88D +:109CA000A02840F061840C20FBF780FE2D4B186843 +:109CB000FBF7A4FE2C4B1868FBF7A0FE2B4B186893 +:109CC000FAE3F02800F0E683FE2840F04D840820F7 +:109CD000FBF76CFE0024D5E3254B1B68185D0134AF +:109CE000FBF735FE042CF7D1224B00241878FBF744 +:109CF00060FE214B185D0134FBF729FE0B2CF8D1D7 +:109D000000241E4B185D0134FBF721FE082CF8D10E +:109D10000720FBF71CFE0024194B185D0134FBF7EC +:109D200016FE072CF8D188E30720094CFBF73EFE0E +:109D3000E620FBF70CFE6079FBF709FE0020FBF73D +:109D400006FE94F82631002B0CBF04200C20B3E350 +:109D500030200020A8030020E0040020E8030020B9 +:109D6000D61B0020E8F7FF1FECF7FF1FF0F7FF1FDF +:109D7000AC000020D6270020B1670108BD670108AC +:109D8000C66701080B20FBF711FEB64BB3F90000C4 +:109D9000FBF70FFEB44B188800B2FBF70AFEB34B7B +:109DA0001B68C3F3C000C3F38002800040EA420096 +:109DB000C3F340021043C3F3401240EAC20003F071 +:109DC00010031843FBF7F5FDA94B1A8812F0010F99 +:109DD0000CBF0020022012F0020F0CBF0021042152 +:109DE00012F0040F0CBF0023102312F0400F0CBF21 +:109DF00000242024019312F0100F9E4B02940CBFFC +:109E000000244FF4007412F0200F1B6803940CBF61 +:109E100000244FF4806412F4807F04940CBF00246B +:109E20004FF4006402F0080B03F4807A059403F405 +:109E3000805903F4005803F4004C03F4803E03F40B +:109E4000003703F4802603F4002503F4801403F0A4 +:109E5000C00343EA0B0343EA0A0343EA090343EA64 +:109E6000080343EA0C0343EA0E0E834B4EEA07074E +:109E70003E431B7835432C43C3F380032343034302 +:109E80000B430199029C0B4303992343049C0B430E +:109E90000599234312F4007F43EA01030CBF00221B +:109EA0004FF400121A43754B00201C780346A3425E +:109EB0000CD273495D5C012101FA05F5154218BF0A +:109EC000994003F1010318BF0843F0E7FBF796FD43 +:109ED0006C4B93F8540709E31220FBF767FD6A4BBC +:109EE0006A4C1B88B3F5806F22D90025605F082378 +:109EF00090FBF3F00235FBF75CFD062DF6D1644CC8 +:109F0000B4F90000FBF755FDB4F90200FBF751FD71 +:109F1000B4F904005F4CFBF74CFDB4F90000FBF70B +:109F200048FDB4F90200FBF744FDB4F904002DE24A +:109F3000B4F90000FBF73DFDB4F90200FBF739FD71 +:109F4000B4F90400FBF735FDD9E71020FBF72EFD2F +:109F50000024514B185D0134FBF7F9FC102CF8D1AB +:109F600016E23820FBF722FD00254C4E05F12C04AB +:109F70003368E4002344B3F90600FBF71AFD3368A5 +:109F800001352344B3F90800FBF713FD336823447C +:109F9000B3F90A00FBF70DFD33681C44207BFBF787 +:109FA000D6FC082DE1D1F3E10820FBF7FFFC0024EB +:109FB0003A4B1B6803EBC40393F86D010134FBF7C4 +:109FC000C6FC082CF4D1E3E1354B185D0134FBF7F6 +:109FD000BEFC102CF8D1DBE1324D00242878400083 +:109FE00000F0FE00FBF7E2FC2B789C4280F0D08171 +:109FF0002D4B33F91400FBF7DCFC0134F4E70620A9 +:10A00000FBF7D4FC294B1868FBF7F8FC284BB3F995 +:10A010000000BBE10720FBF7C9FC264B4FF6FF749D +:10A020001878FBF794FC244B1868A042A8BF204680 +:10A0300020EAE07000B2FBF7BCFC204BB3F9000053 +:10A04000FBF7B7FC0F4B93F80C211D4B1868002849 +:10A05000B8BF40420AB10A235843A042A8BF2046D5 +:10A0600000B293E1FC0400203C1800204C020020C8 +:10A070005402002050020020D5270020D61B0020CB +:10A08000C01B00203020002000000020B40400206D +:10A09000F40400207C02002012000020E8030020CD +:10A0A000A8270020DF090020960600205C0200207F +:10A0B000C8030020B4050020BC050020BE0D002010 +:10A0C000B8050020B34C0720FBF770FC2368187814 +:10A0D000FBF73DFC23685878FBF739FC23681879B7 +:10A0E000FBF735FC23685879FBF731FC2368987936 +:10A0F000FBF72DFC23689878FBF729FC2368D878B8 +:10A10000F4E1A54D1E20FBF751FC2B6800241B78C1 +:10A11000022B69D12B68A14903EB8403586A04F030 +:10A12000CBFE08F043F9FA28A8BFFA2020EAE07035 +:10A13000C0B2FBF70CFC2B68994903EB8403186B46 +:10A1400004F0BAFE08F032F9FA28A8BFFA2020EA93 +:10A15000E070C0B2FBF7FBFB2B68924903EB840372 +:10A16000D86B04F0A9FE08F021F96428A8BF642088 +:10A1700020EAE070C0B20134FBF7E9FB032CC9D13F +:10A18000072C2B681ED1986C844904F095FE08F0CA +:10A190000DF9FA28A8BFFA2020EAE070C0B2FBF758 +:10A1A000D6FB2B687D49D86C04F086FE08F0FEF8DB +:10A1B000FA28A8BFFA2020EAE070C0B2FBF7C7FB7C +:10A1C00000200BE023441879FBF7C1FB2B682344E4 +:10A1D000987BFBF7BCFB2B682344187E0134FBF70C +:10A1E000B6FB0A2CCCD1D3E02B6823441879FBF7BB +:10A1F000AEFB2B682344987BFBF7A9FB2B68234419 +:10A20000187E0134FBF7A3FB0A2CEDD1C0E02F2010 +:10A21000FBF7CCFB644C14F8010F002800F0B88069 +:10A22000FBF795FBF7E7A020FBF7C0FB00245A4B98 +:10A2300004F11C021B680C2103EB82035D1D5B4AC9 +:10A240005B79013401FB0323187AFBF780FB687804 +:10A25000FBF77DFBA878FBF77AFBE878FBF777FB49 +:10A26000282CE4D194E04820FBF7A0FB002506262B +:10A270006E43494B06F588761B6801351E44B07A5B +:10A28000FBF765FB7079FBF762FBB079FBF75FFBCF +:10A29000F079FBF75CFB307AFBF759FB707AFBF740 +:10A2A00056FB0C2DE3D173E0002701240025404B21 +:10A2B0001B789D4222DA3F4BE95C00233B4A03EBCB +:10A2C00002089A5C8A4204D00C33B3F58A7FF5D138 +:10A2D00012E0D8F8040007F045FE81460CB9264686 +:10A2E00001E0074408E04E4506DAD8F80430985DEE +:10A2F000FBF72DFB0136F6E70135D8E7002C47D0F8 +:10A30000F8B2FBF753FB0024D0E7284A99189A5C6F +:10A3100082420BD00C33B3F58A7FF6D101342B780F +:10A320009C4235D2234BE05C0023EEE7087AFBF732 +:10A330000EFBF3E70820FBF739FB0124E0B2013400 +:10A34000FBF705FB092CF9D122E01020FBF72EFBCF +:10A35000194B1A4C187800F00200FBF7F8FA184B6A +:10A360001878FBF7F4FA2068FBF748FB6068FBF706 +:10A3700045FB144BB3F90000FBF71BFB124BB3F981 +:10A380000000FBF716FB114BB3F90200FBF711FBC2 +:10A390000120EAE08C050020E803002000002041B5 +:10A3A0000000C84200007A44874F0108884C010829 +:10A3B000D61B0020C01B002082020020D0050020F8 +:10A3C000C4050020C2050020C00500203C18002064 +:10A3D000674C0520FBF7EAFAB4F90400FBF7E9FA49 +:10A3E000B4F90600FBF7E5FA624B187800F00100BB +:10A3F0007CE0FBF79DF806461220FBF7D7FA0EB972 +:10A400005D4B02E0102E03D15C4B1D685C6801E0DF +:10A41000002425463046FBF79AFA2846FBF7EEFA69 +:10A420002046FBF7EBFA564B1868FBF7E7FA0020DB +:10A43000FBF7BFFA0020FBF7BCFA002056E04C4DBA +:10A440000024287A2E4680000130C0B2FBF7AEFA15 +:10A45000287AFBF77CFA337A9C4299D2494D285DE1 +:10A46000FBF775FA05F11003185DFBF770FA05F1BB +:10A470002003185D3035FBF76AFA285DFBF767FAB1 +:10A480000134E8E7404B185F0234FBF792FA082CDE +:10A49000F8D17DE73D4C0420FBF788FA2368B3F937 +:10A4A0005600FBF786FA2368B3F954006EE70420E0 +:10A4B000FBF77CFA364B9868FBF7A0FA68E7344C58 +:10A4C0000420FBF773FAB4F90801FBF772FAB4F948 +:10A4D0000A015BE70120FBF769FA2D4B587905E08B +:10A4E0000120FBF763FA2A4B93F82001FBF72FFAC0 +:10A4F0004EE7274B234493F810010134FBF727FA6A +:10A50000082CF6D144E74020FBF750FA204C04F128 +:10A510004005B4F9D401FBF74CFA94F8D601FBF7E7 +:10A5200016FA043494F8D301FBF711FAAC42F0D1D7 +:10A530002EE7B4F85601043400F03F00FBF739FA77 +:10A54000B4F85201C0F38410FBF733FA94F85001C9 +:10A550000009FBF7FCF994F8500100F00F00FBF73D +:10A56000F6F9AC42E5D113E7002007B0BDE8F08F63 +:10A570003C180020D40F0020240E0020300E0020B4 +:10A58000580200204518002086180020E80300200B +:10A590003020002007B5064B06480093064B074ABB +:10A5A0001968074BFBF7D4FC03B05DF804FB00BF50 +:10A5B000C6670108D3670108C8000020B167010819 +:10A5C000BD67010810B50748FBF756FA0024064B93 +:10A5D0000648E218E15852680C34FBF7B9FCFC2C31 +:10A5E000F5D110BDEF670108305301080568010877 +:10A5F00037B582880446836810060D4606D529497A +:10A600004FF4E07091F8541700FB0133D10504D5E5 +:10A6100025490A20097800FB013302F03F02042A91 +:10A6200012D006D8012A0DD0022A2FD193F900109A +:10A630002DE0102A0AD0202A0AD0082A26D1B3F900 +:10A64000001024E0197822E0198820E019681EE043 +:10A6500069461868FBF70CFE01461448FBF778FCC6 +:10A66000F5B1E06804F0D4FB6946FBF701FE014652 +:10A670000F48FBF76DFC206904F0CAFB6946FBF745 +:10A68000F7FD01460A48FBF763FC09E00021094891 +:10A69000FBF75EFC25B10848E1682269FBF758FC2E +:10A6A00003B030BD30200020140E00206B72010872 +:10A6B0006A720108086C01080D6801082DE9F04173 +:10A6C000002407462546114B3946E65804EB03089B +:10A6D000304607F083FC58B10D483146FBF738FC93 +:10A6E00040460021FFF784FF0A48FBF731FC0135A3 +:10A6F000143440F604339C42E5D125B90648BDE840 +:10A70000F041FBF7B9B9BDE8F08100BF6C56010814 +:10A71000A56801083E680108146801082DE9F74F93 +:10A72000044607F01FFC054620B1012819D1237803 +:10A730002A2B16D15648FBF79FF90024554B564853 +:10A74000E618E158FBF704FC30462946FFF750FFB6 +:10A750005248FBF791F9143440F604339C42EDD192 +:10A7600092E020463D2107F0F0FB002800F08780B2 +:10A77000034613F8012C202A01D1013BF9E7451CBF +:10A780002846C4EB030A07F042FC83462846FEF73E +:10A7900069FD0026054614237343DFF8F89053F84B +:10A7A000097003EB0908384607F0DCFB03461A463C +:10A7B00020463946019307F0DDFB019B002855D167 +:10A7C0005FFA8AF29A4251D1D8F80C0004F020FBCB +:10A7D0000146284604F022FD002845D0D8F8100094 +:10A7E00004F016FB0146284604F00EFD00283BD07D +:10A7F000B8F804309B064FF0140303FB0696B288AA +:10A8000058BF5D4614062946B36806D524484FF460 +:10A81000E07490F8540704FB0033D00504D52148B8 +:10A820000A24007804FB003302F03F02042A0BD014 +:10A8300004D8013A012A0CD819700AE0102A05D070 +:10A84000202A05D0082A04D1198002E0196000E00E +:10A850001D6039461448FBF77BFB3046002103B0EE +:10A86000BDE8F04FFFF7C4BE104803E001368D2E5F +:10A8700091D10F4803B0BDE8F04FFBF7FDB820467B +:10A8800003B0BDE8F04F19E703B0BDE8F08F00BF9B +:10A890002C6801086C560108A56801083E6801088B +:10A8A00030200020140E0020416801084C68010887 +:10A8B000146801087FB5044607F054FB082824D12A +:10A8C00000231F49E25C09681144497801F0030143 +:10A8D000022908BF203AE2540133082BF1D10025A8 +:10A8E000665D1848314607F030FB28B10135601924 +:10A8F000314607F02AFB18B11348FBF7BDF81CE0FE +:10A90000082DEDD12046FBF79BFC1048FBF7B4F86F +:10A9100000230F4A04A91A4492F810210A44094955 +:10A92000595C0133082B02F80C1CF2D100230948B2 +:10A9300001A98DF80C30FBF70BFB04B070BD00BF14 +:10A94000CC000020646B01086C6801088C68010869 +:10A950003020002008680108F8B504680546204644 +:10A960000E461746FEF789FF032845D82B7B9B0828 +:10A970009AB246B94FF0020C0CFA03F3A18989B2DE +:10A9800021EA0303A3810A2101FB00211B4B43F8A9 +:10A990002160043143F8217046B12A7B02259208D8 +:10A9A00005FA02F2A1890A4392B2A281282202FB8F +:10A9B000003000F12002EFF31286502383F3128857 +:10A9C0000023C1180D6915B115600A6904320433FA +:10A9D000102BF6D100231360F3B283F31188036ABE +:10A9E00023B1A3899BB243F0010304E0A38923F0C0 +:10A9F00001031B041B0CA381F8BD00BFD01E002067 +:10AA000070B5046D4279A38902F0040123F4005368 +:10AA10001B041B0C0546866886B0A38101F0FF006D +:10AA200021B14FF480604FF4005100E0014612F074 +:10AA3000010F14BF0423002312F0020F1CBF43F0C8 +:10AA400008039BB212F0080F228A18BF0C2392B29F +:10AA500022F4405211432182A28992B222F4B052D0 +:10AA600022F00C02104303439BB2A381A38A01A8E6 +:10AA700023F440731B041B0CA382FBF707FF194947 +:10AA8000049A039B8C4208BF1346A289192159439B +:10AA900012B2002AB4BF7600B600B1FBF6F164230F +:10AAA000B1FBF3F21201100903FB1011A08900B2EF +:10AAB000002806DAC9003231B1FBF3F303F00703D3 +:10AAC00005E009013231B1FBF3F303F00F031A4340 +:10AAD00092B22B6D22819A8992B242F400529A81ED +:10AAE00006B070BD00380140417189E7816087E799 +:10AAF000826A8169436B1144D960416A914203D9EA +:10AB00008A1A5A60816204E001698A1A5A60002236 +:10AB10008262002280F844201A6842F001021A6022 +:10AB2000704738B5114B124C9968124B1A681D4684 +:10AB30005288114203D0FAF7ADFD206011E0FAF718 +:10AB4000A9FD236898420CD9C01A0B4B3B22B0FBDD +:10AB5000F2F01B68B0F5967FC8BF4FF0FF3003B12D +:10AB600018602B685A68054B5A6138BD000C0140CB +:10AB700090180020E0030020DC03002000040140C6 +:10AB800070B5064600240B4BE518AA8816420AD079 +:10AB9000E1580948FBF7DCF928460021FFF728FDBA +:10ABA0000648FAF769FF143440F604339C42EAD1B0 +:10ABB00070BD00BF6C560108A16801083E6801081D +:10ABC0000D4B0278D9684378C943C1F30221C1F122 +:10ABD000040103FA01F1094B0901C9B21A4482F8D0 +:10ABE000001302780120510902F01F0200FA02F25C +:10ABF00043F82120704700BF00ED00E000E100E0D5 +:10AC0000134B026810B51C68D1430C401C605C6893 +:10AC10002140596019680A431A6002689C68D14350 +:10AC20000C409C60DC682140D9604179102906D134 +:10AC3000996811439960D9680A43DA6010BD01F13F +:10AC4000804303F5823319680A431A6010BD00BFC0 +:10AC500000040140254B10B55343254A254C12688A +:10AC60000139B2FBF3F20388013AA04289B292B2F1 +:10AC70009BB212D004F50064A0420ED0B0F1804F18 +:10AC80000BD0A4F59834A04207D004F58064A0420C +:10AC900003D004F58064A04202D123F070039BB27C +:10ACA000154CA04206D004F58064A0421CBF23F4DA +:10ACB00040739BB203800F4B8185984202850FD071 +:10ACC00003F5006398420BD003F54063984207D028 +:10ACD00003F58063984203D003F58063984201D165 +:10ACE000002303860123838210BD00BF40420F0072 +:10ACF000A8000020002C014000100040284BF0B5B7 +:10AD00001D6800222748165C1418AB19597801F009 +:10AD1000040101F0FF0371B10132102AF2D10020C9 +:10AD2000F0BD1BB103EB83035B00DBB210F8012B1A +:10AD3000303A1344DBB2221A022AF2DC00218442A8 +:10AD40000AD919B101EB81014900C9B210F8012BF0 +:10AD5000303A1144C9B2F2E72E2E14D1601C002201 +:10AD60000424067802EB8202AF197F7852007F0735 +:10AD700092B203D5303A3244013092B2013C14F021 +:10AD8000FF04EED100E0002207480624414364207E +:10AD900000FB02120548B2FBF4F200FB0320F0BDF9 +:10ADA000CC000020E30F002040420F008096980066 +:10ADB00030B5002213460D495C5C9CB12E2C04D1A9 +:10ADC000013378B11C1800250D550A246243C95C73 +:10ADD000A1F13004092C9CBF303A52180E2B03D835 +:10ADE0000133E8E7104630BD002030BDE30F0020FE +:10ADF0000FB407B504AB53F8042B002004490193AA +:10AE0000FAF7E0FF03B05DF804EB04B0704700BF51 +:10AE10002D5B00080EB40FB505AB53F8042B019061 +:10AE2000064901A80393FAF7CDFF019B00221A708F +:10AE300004B05DF804EB03B0704700BF098D000853 +:10AE40002DE9F0438DB0054607F08CF8C0B200281C +:10AE500058D104467F4B00211E68142207A807F032 +:10AE600040F8A500002303A905A8039305937719CB +:10AE70000B7183801A46DFF8F0E1B7F802C03EF8A4 +:10AE8000138018EA0C0F0CD00EF10A0E0DF13008E9 +:10AE900013F80EE002F1010C424402F824EC5FFAD0 +:10AEA0008CF20133052BE6D100231A46DFF8C0E10E +:10AEB000B7F802C013F80E8018EA0C0F0CD00EF190 +:10AEC000060E0DF1300813F80EE002F1010C4244B9 +:10AED00002F81CEC5FFA8CF20133062BE6D1735DAD +:10AEE0008DE803001A0907A85B4903F00F03FFF779 +:10AEF00091FF2146594807AA0134FBF729F8202C75 +:10AF0000A8D1A3E0284607F082F81F28044600F3E2 +:10AF1000918028462021E4B207F017F81F2C01D9B0 +:10AF20004F4888E04B4B471C1B68002103EB84040F +:10AF30002046042206F0D5FF00254A4B07AE3046D6 +:10AF400000210A2215F803905FFA85F806F0C9FF80 +:10AF50000023FA5CF91832B10A2B04D04A4502D01A +:10AF6000F2540133F5E74A4501F1010767D1B8F121 +:10AF7000020F0DD0B8F1030F0CD0B8F1010F0BD0B8 +:10AF8000304607F044F82378C0B243EA00100AE0E4 +:10AF9000002219E0002226E0304607F038F8237836 +:10AFA00000F00F001843207038E00133062B0AD060 +:10AFB0002D4800F115069E5D8E42F6D10344D97BE3 +:10AFC00063880B43638001320CA9D3B20B4413F89E +:10AFD000141C19B30023EBE7412B1DD0542B08BFE1 +:10AFE00004230ED00132D3B20DF13008434413F8DC +:10AFF000143C9BB1492B01D1002302E0572B07D110 +:10B000000123194931F8131063880B436380E9E782 +:10B01000462BE1D10223F4E70323F2E70135042DA7 +:10B020008BD10124FEF7C0FAFEF7FAFAFEF7D4FA44 +:10B0300064B975E70D482021FAF78AFF06E020463B +:10B040000021042206F04DFF0024EBE70DB0BDE81F +:10B05000F08300BF10060020AB680108B768010844 +:10B0600085650108DF4F0108C44F0108C368010866 +:10B07000D34F01082DE9F0418CB01D469DF84830B2 +:10B080008846012B174608D1A84B984240F04681CC +:10B09000042203F548431A6165E0A54B98425ED14E +:10B0A000A448A54B87600360A44BA907436103F143 +:10B0B000C00383614FF0C003C36003619C4B036511 +:10B0C00003F104038364C36403F5484303F15403A9 +:10B0D0000363A3F11403D3F8D42F436342F48042F3 +:10B0E000C3F8D42FD3F8D02F42F00102C3F8D02FE9 +:10B0F0004FF002038DF803304FF40073ADF80030C9 +:10B100004FF018038DF8023003D58D486946FEF7DD +:10B1100001FC1C232A078DF8023003D588486946B4 +:10B12000FEF7F8FB4FF48063ADF8003048238DF84C +:10B130000230EB0703D582486946FEF7EBFB0E238E +:10B140008DF804300022012301A88DF805308DF818 +:10B1500006208DF80730774CFFF732FD55E0734B32 +:10B16000984240F0DF80774B734A9F601A60C0229C +:10B17000DA601A61744AAE075A6102F1C0029A613C +:10B180006A4A1A6502F104029A64DA646F4BDA695A +:10B1900042F40032DA615A6942F001025A614FF01A +:10B1A00002038DF803304FF00403ADF800304FF088 +:10B1B00018038DF8023003D561486946FEF7AAFBF3 +:10B1C0001C232C078DF8023003D55D486946FEF735 +:10B1D000A1FB0823ADF80030E8074FF048038DF8D5 +:10B1E000023003D556486946FEF794FB26238DF8B6 +:10B1F00004300022012301A88DF805308DF80620C7 +:10B200008DF80730FFF7DCFC4E4C0026012384F854 +:10B2100044302662E661A6626662C4F82C806571DD +:10B22000A760A6712046FFF7EBFB15F0090F31D0A0 +:10B23000206B002826D0E36C039601934FF48053D3 +:10B240000A9380230693E3680596049320230993C9 +:10B2500063690796029308960B96F9F7DFFF01A939 +:10B26000206BF9F7BDFF236B1A6842F001021A60E8 +:10B27000226D918A89B241F0400191825B689BB254 +:10B28000236407E0236D4FF6DF721A80DA6842F01C +:10B290002002DA6015F00A0F2CD0606B28B3A36C83 +:10B2A000002601934FF480530A9380230693236969 +:10B2B0000296049310230393059607960896099621 +:10B2C0000B96F9F7ABFF606B01A9F9F789FF636B88 +:10B2D0001A6842F002021A605E605E60236D9A8A0C +:10B2E00092B242F080029A8204E0236DDA6842F062 +:10B2F0008002DA60236D29079A8992B242F40052E3 +:10B300009A819A8A03D592B242F0080203E022F0B1 +:10B3100008021204120C9A82204604E0044B984260 +:10B320003FF4BEAE00200CB0BDE8F0810044004008 +:10B3300000380140C41F0020E44F01089418002089 +:10B3400000080140701F0020141A00200010024065 +:10B3500010B50446204606F005FE10F0FF0F07D199 +:10B360000B4B0C4893F85417BDE81040FAF7F0BDAA +:10B37000204606F04CFE022808D8054B064C83F800 +:10B38000540700F0B5FA02F0C1FCE3E710BD00BFBE +:10B39000302000202D670108096701082DE9F04FD2 +:10B3A000844985B0054606F0A5FD83490028284656 +:10B3B0000CBF0124072406F09DFD80490028284683 +:10B3C00008BF022406F096FD002808BF0424E10708 +:10B3D00040F1BE807A48FAF7BBFD0020FFF7DAF8AB +:10B3E000784F7948FAF7B4FD7848FAF7B1FD7A79E1 +:10B3F000774B784803EB82035969FAF7A9FD38695E +:10B40000002103F0EDFE00285CD13D460646D5F84C +:10B4100010800021404603F0E3FE00284ED10136A3 +:10B420006D483146D5F814B0D5F818A0D5F81C9061 +:10B43000FAF78EFD4046002103F0DCFE10B16748AC +:10B44000FAF786FD69464046FAF712FF014664485E +:10B45000FAF77EFD5846002103F0CCFE10B15F489C +:10B46000FAF776FD69465846FAF702FF01465C484E +:10B47000FAF76EFD5046002103F0BCFE10B15748AC +:10B48000FAF766FD69465046FAF7F2FE014654485F +:10B49000FAF75EFD4846002103F0ACFE10B14F48BC +:10B4A000FAF756FD69464846FAF7E2FE01464D486E +:10B4B000FAF74EFD0C2E05F11005A8D14A48711C73 +:10B4C000FAF746FD4948FAF743FD494DD7F8088099 +:10B4D00055F8041F19B14748FAF73AFDF8E70D4649 +:10B4E000454B53F8256056B10123AB4013EA080FD2 +:10B4F00003D042483146FAF72BFD0135F0E74048CA +:10B50000FAF726FD31467B1893F8103104AA13444C +:10B510003C4A8A5C0131082903F8102CF3D100233E +:10B52000694639488DF80830FAF712FD3748FAF7BE +:10B530000FFD3748FFF784FC3648FAF709FD344819 +:10B54000FAF7C2FD3448FAF703FD4020FFF718FB75 +:10B55000A2071AD53148FAF7FBFC3148FAF7F8FC94 +:10B560002B48FFF7F5FE2F48FAF7F2FC2848F9F7C9 +:10B57000CBF82D48FAF7ECFC2548F9F72BF82648CC +:10B58000FAF7E6FC8020FFF7FBFA63070FD52748A0 +:10B59000FAF7DEFC2648FAF7DBFC1D48FCF788FECC +:10B5A0001D48FAF7D5FC4FF48070FFF7E9FA05B0B3 +:10B5B000BDE8F08FE56801082E780108EC68010805 +:10B5C000F2680108302000200069010812690108B2 +:10B5D000E44F01081E69010829690108D8660108BD +:10B5E0006B720108086801083169010843690108A4 +:10B5F0005450010853690108585001086169010855 +:10B600006E690108646B01087A69010883690108A1 +:10B61000096701088F6901083E6801089D690108F2 +:10B62000B0690108BE690108C8690108D769010845 +:10B63000E86901082DE9F04F87B0984682460F4629 +:10B6400016469DF84040FDF724FA0DF1080E054618 +:10B65000034600F1100C18685968724603C208339B +:10B6600063459646F7D12B7B0BB90396049650465B +:10B6700002A9FDF7DDF8054640B14368586830B1CE +:10B68000504602A92A4601F055FFF4E733E0AB68C3 +:10B6900095F800B093F80090B9F1040F2BD8DFE8CB +:10B6A00009F003062A0F11000094144801E0144821 +:10B6B0000094394632464346FFF7DCFC04460BE073 +:10B6C000002000E00120394623463246FDF734F9D8 +:10B6D00041460446FAF710F964B10A4B84F8049025 +:10B6E00003EB8B03C3F800436B6820465C60514654 +:10B6F000FDF712F9204607B0BDE8F08F0038014091 +:10B700000044004094180020F7B5274C274DE3690A +:10B71000284643F48043E361236901A943F480434D +:10B72000236118238DF806304FF42043ADF8043020 +:10B7300003238DF80730FEF7EDF804234FF480461D +:10B740000DEB030128468DF806304FF48057ADF815 +:10B750000460FEF7DFF81023284601A98DF80630B3 +:10B76000ADF80470FEF7D6F82F61236930463343F5 +:10B770002361FBF7D5F80E4B1A8802F4415242F4CC +:10B78000457242F003021A809A8B22F4006212047E +:10B79000120C9A8307221A821A8892B242F040024F +:10B7A0001A8003B0F0BD00BF00100240000C014041 +:10B7B0000038004008B500F09BF802F0A7FABDE899 +:10B7C00008400F2014210122FAF74EB870B50A4E36 +:10B7D00000EB800006440024331913F8A00C074B3B +:10B7E00001341D786840FCF7C9F9052CF4D12846CE +:10B7F000BDE87040FCF7C2B9AC500108E02700205A +:10B80000642928BF6421F8B501FB00F7642497FB85 +:10B81000F4F40546E4B20026F3B2A34204D29F201A +:10B82000FFF7D4FF0136F7E7AC420BD2142097FBA9 +:10B83000F0F0C4EB84136638C4EB83031844C0B241 +:10B84000FFF7C4FF0134E4B2AC4238BF9A20F7D30B +:10B85000F8BD0F4B10B50446185CFFF7B7FF0D4B52 +:10B8600033F91430B3F57A7F05DBB3F5FA6FA8BF6F +:10B870004FF4FA6301E04FF47A73A3F57A730A2266 +:10B8800093FBF2F10920C9B2BDE81040FFF7B8BF41 +:10B89000646B01089606002010B5441E14F8010FD1 +:10B8A00010B1FFF793FFF9E710BD0F4B1A78552A37 +:10B8B00016D15A88B2F5EF6F12D11A79BE2A0FD17C +:10B8C00093F874270020EF2A0CD113F8012B504075 +:10B8D000064A9342F9D1D0F1010038BF00207047E9 +:10B8E00000207047704700BF00F8010878FF01088A +:10B8F0004A4B55222DE9F3411A704FF4EF625A80FA +:10B90000BE221A71EF2283F87427002283F875276C +:10B9100011461E46B35C0132B2F5EF6F81EA0301B6 +:10B92000F8D13E4B3E4A83F875173E4B04275A60C8 +:10B9300002F188325A600020013F17F0FF075DD006 +:10B94000384B3422384CDA60C4F309037BB1331925 +:10B9500003F17843A3F5FC33D3F800804FF4005093 +:10B9600000230193F9F72BFC0428E5D11BE04FF4E9 +:10B970003020F9F724FC0428DED12A4D4FF4302082 +:10B980002B6943F002032B616C612B6943F0400388 +:10B990002B61F9F714FC2A6941F6FD731340042862 +:10B9A0002B61D4D0C8E71F4D4FF400502B6943F0F2 +:10B9B00001032B611FFA88F32380F9F700FC0428A8 +:10B9C00012D1A31C0193019B4FEA1848A3F80080F1 +:10B9D0004FF40050F9F7F3FB2B6941F6FE721A4061 +:10B9E00004282A6106D0A7E72B6941F6FE721A40A7 +:10B9F0002A61A1E70D4B04349C42A5D1094B0428D0 +:10BA00001A6942F080021A6102D1FFF74EFF10B9A5 +:10BA10000A20F9F74FFF02B0BDE8F0813020002086 +:10BA2000230167450020024000F8010878FF010863 +:10BA30008A2802D08E2809D07047094B1B689B06C4 +:10BA40000DD5084B1B7853B9074A03E0054B1B780B +:10BA50002BB9064A064B1A60064B2D221A70704706 +:10BA60004C02002060130020840D0020580D00209F +:10BA700068130020711300207FB52B4B2B4C9A6963 +:10BA8000206042F001029A61294D03881026ADF82A +:10BA900004302846022301A98DF807308DF806608E +:10BAA000FDF738FF236828465B88ADF8043004238F +:10BAB0000DEB03018DF80630FDF72CFF22680F20F7 +:10BAC000137A03F003018900884003F0FC0303F1BB +:10BAD000804303F580339D6825EA0000012505FABF +:10BAE00001F198609868014399605368114A02A86F +:10BAF0005361029300238DF80C308DF80E508DF8B1 +:10BB00000D60FFF77DF823680B4A5B7A59B203F0AA +:10BB10001F039D404909094B42F821501A68084B00 +:10BB20003C3A1A6004B070BD00100240E0030020EF +:10BB3000000C01400004014000E100E02C20002046 +:10BB4000D803002013B504460068FFF783F8236884 +:10BB500001A81A8892B242F001021A80637B002287 +:10BB60008DF8043001238DF805308DF806208DF80E +:10BB70000730FFF725F802B010BD10B5AE20FCF776 +:10BB800001F8D420FBF7FEFF8020FBF7FBFFA82085 +:10BB9000FBF7F8FF3F20FBF7F5FFD320FBF7F2FFA1 +:10BBA0000020FBF7EFFF4020FBF7ECFF8D20FBF7B9 +:10BBB000E9FF1420FBF7E6FFA120FBF7E3FFC82015 +:10BBC000FBF7E0FFDA20FBF7DDFF1220FBF7DAFFDF +:10BBD0008120FBF7D7FFCF20FBF7D4FFD920FBF75D +:10BBE000D1FFF120FBF7CEFFDB20FBF7CBFF40209E +:10BBF000FBF7C8FFA420FBF7C5FFA620FBF7C2FF99 +:10BC0000AF20FBF7BFFFA620FBF7BCFFAE20FBF782 +:10BC1000B9FF2020FBF7B6FF0020FBF7B3FFB020F1 +:10BC2000FBF7B0FF4020FBF7ADFF0020FBF7AAFFBA +:10BC30001020FBF7A7FF4FF48064013C0020A4B262 +:10BC4000FBF79CFF002CF8D18120FBF79BFFC8205D +:10BC5000FBF798FFBDE81040AF20FBF793BF2DE93D +:10BC6000F341F9F717FDAB4D07462B68C31A002BBC +:10BC7000C0F2F08100F5C333A0332B60A64B2A79C4 +:10BC80001E78C6F38006B21A18BF01222E714EB17B +:10BC9000002A00F0DF81A14B5A789A7001225A7075 +:10BCA0001A7020E09D4B2AB1DA7842F00202DA7075 +:10BCB0009A785A70D9788A0705D4984A9068381AC1 +:10BCC000C043C00F00E00120944A187058B1CC075F +:10BCD00009D513799249013303F0030313710B441F +:10BCE00093F8803253708D4C23784BB3FFF745FFA8 +:10BCF000B020FBF747FF4020FBF744FF0020FBF795 +:10BD000041FF1020FBF73EFF4FF4806808F1FF3839 +:10BD100000201FFA88F8FBF731FFB8F1000FF5D1CA +:10BD20004046FBF733FF7F4B627853F82200FFF762 +:10BD3000B3FDE37823F00203E3707B4B3B44A36045 +:10BD40006378052B00F27381DFE813F008007101BE +:10BD50001B00770006001C010024D5E07349744ADB +:10BD60007448FFF757F80120FBF710FF7148FFF701 +:10BD700093FD714B6F4871491A68FFF74BF8022029 +:10BD800050E16F4B9A68984612F0020F2ED06D4C1E +:10BD90000A2321786C4FB1FBF3F203FB12133978BD +:10BDA000DBB2644800916949FFF734F8FDF7ECFB1A +:10BDB0000120FBF7EBFE5F48FFF76EFD644B3A781E +:10BDC000186824788378642102FB13444C4341783B +:10BDD0000220CB1A5A43B4FBF2F4E4B2FBF7D6FECE +:10BDE00021461520FFF70CFD032400E00124D8F8BC +:10BDF0000830180540F11B81564B57491F680968E8 +:10BE0000642397FBF3F203FB1273009149485349F3 +:10BE1000FFF700F8FDF7B8FB2046FBF7B7FE4548F3 +:10BE2000FFF73AFDF8F7D4FF0746601CFBF7AEFEBC +:10BE300015203946FFF7E4FCF9E00120484FFBF7F5 +:10BE4000A5FE4848FFF728FD3B68990715D54649E8 +:10BE50003848B1F90020B1F90230B1F904100324D7 +:10BE600000914249FEF7D6FFFDF78EFB0220FBF75B +:10BE70008DFE3048FFF710FD00E002243B68DA0732 +:10BE800018D53B492B48B1F90020B1F90230B1F97E +:10BE9000041004F1010800913649FEF7BBFFFDF7DD +:10BEA00073FB2046FBF772FE2248FFF7F5FC5FFAB2 +:10BEB00088F844463B681B0740F1B9802E491D486D +:10BEC000B1F90020B1F90230B1F9041000912B4909 +:10BED000FEF7A0FFFDF758FB2046A3E00E2C00F074 +:10BEE000A68060080130FBF751FE2046FFF7B1FC49 +:10BEF0003B78A34206D92020FFF768FC601CC0B243 +:10BF0000FFF7A7FC0234E4B21D4F3B78A342E5D80B +:10BF10008DE000BFA41B0020D5270020340700209F +:10BF2000AC500108B0000020404B4C00796B010878 +:10BF3000C6670108A91B0020C8000020816B01080A +:10BF400030200020B4050020980000208C6B0108F0 +:10BF5000B0050020B8050020BC050020A46B010836 +:10BF60004C020020B96B0108B4040020CF6B01081B +:10BF7000FC030020DF6B01087C020020EF6B01084E +:10BF8000DF090020354C364994F854273548FEF730 +:10BF900041FF0120FBF7FAFD3248FFF77DFC324BF1 +:10BFA00032491F782F483A46FEF734FF0220FBF74C +:10BFB000EDFD2C48FFF770FC0A2303FB07472C49D3 +:10BFC00097F857272748FEF725FFFDF7DDFA0320EE +:10BFD000FBF7DCFD2348FFF75FFC264997F856275F +:10BFE0002048FEF717FFFDF7CFFA0420FBF7CEFD40 +:10BFF0001C48FFF751FC204997F85A271948FEF7CB +:10C0000009FFFDF7C1FA0520FBF7C0FD1548FFF752 +:10C0100043FC1448194997F85B27FEF7FBFEFDF730 +:10C02000B3FA0620FBF7B2FD0E48FFF735FC8EB9D8 +:10C03000B020FBF7A7FD0820FBF7A4FD1720FBF7B6 +:10C04000A1FDEC7E0E4B185D013404F00304FFF7F4 +:10C05000BDFBEC7602B0BDE8F08100BF30200020CF +:10C06000FF6B0108A91B0020140E00200B6C0108B7 +:10C070001C6C0108286C0108346C0108416C010833 +:10C080004E6C01082DE9F3412D4B1B78042B50D148 +:10C090004020F9F76AFA044670B12046F9F731FCFE +:10C0A00018B90A20F9F7CFFBF7E7264B20461B68A3 +:10C0B0001969F9F72BFC0BE0224B21461B68009015 +:10C0C0001A6940200323FFF7B5FA0446002830D050 +:10C0D0001D4D286841798B0703D441F00201F9F71F +:10C0E0000BFC1A4B08221A6110221A612868F9F712 +:10C0F00017FC58B1144B154E082718687761F9F7EB +:10C100000AFC01462046F9F71DFC37612046F9F785 +:10C1100007FC0028EAD00D4E102777612046D5F89D +:10C120000080F9F7F8FB01464046F9F70BFC376150 +:10C13000DCE7074802B0BDE8F041F9F79DBC00BF5D +:10C14000FC090020F80900201C0A0020000C014016 +:10C15000856C01082DE9F743124C814604F19808DB +:10C1600094F84A60C6B9D9F804200025009501204A +:10C1700029460323FFF75EFA074620B97EB94FF43C +:10C1800096420126F1E7204629464C2205F0A9FEF9 +:10C190000123276084F84A304C344445E0D103B091 +:10C1A000BDE8F083200F0020F7B5524B524C2360BE +:10C1B000F9F7FCFF0120FCF70DFD002800F084805A +:10C1C0004E4BFF2118461622256805F08AFE0022F4 +:10C1D00002704B4A0121126803469707817504D506 +:10C1E00041700321817502218170560704D5997D24 +:10C1F000481C98750320585412F00A0F0CD09A7DF1 +:10C2000004219954511CC9B205205854D11C023242 +:10C210009975D2B2062199543A4FBA68900604D55E +:10C22000997D481C987507205854110608D5997DAA +:10C2300009205854881C01319875C9B20A205854F5 +:10C240007979082901D00E2904D1997D481C987567 +:10C250000B205854997D4FF00C0E481CC0B212F0C0 +:10C26000040F264E987503F801E003D00231B17532 +:10C2700010213154997D97F84571481CC0B24FF098 +:10C28000120E002F0CBF002702F001071B4E9875FD +:10C2900003F801E01FB10231B17513213154997DCA +:10C2A0001427481CC0B298755F549305134E03D5EC +:10C2B00002311523B175335413480021982205F03B +:10C2C00010FE2846FFF746FF0220FCF783FC70B102 +:10C2D0000220F9F74AF92568084C0146A06130B9F7 +:10C2E0000090AA6802200323FFF7A4F9A06103B01D +:10C2F000F0BD00BF5C210020B80F0020C01B002053 +:10C300004C02002030200020200F0020A44B2DE9FB +:10C31000F3411B78002B00F07381FDF7D9F8A14F92 +:10C3200006463B78834200F06B819F4D2B681B785B +:10C33000002800F0E88063BB0420F9F716F99B4C55 +:10C3400001462060DFF86C8290B143794FF41651BA +:10C3500088F81C308368C8F82030F9F7D7FA2068CD +:10C360000221F9F7C9FA20680421FCF7D5FA10E098 +:10C370008F4B04201B684FF416529B7800930223C6 +:10C38000FFF758F94379206088F81C308368C8F8B3 +:10C3900020302B6893F80080B8F1010F2BD10420D6 +:10C3A000F9F7E3F8834C0146606288B143794FF4B2 +:10C3B000964184F828308368E362F9F7A7FA606A47 +:10C3C0004146F9F799FA606A0421FCF7A5FA12E0F0 +:10C3D0000090434604204FF49642FFF72BF943792F +:10C3E000606284F828308368E3620379033B012BA1 +:10C3F00098BF84F830802B681D78022D41D104202D +:10C40000F9F7B3F86B4C0146606388B143794FF498 +:10C41000964184F838308368E363F9F777FA606B04 +:10C420002946F9F769FA606B0421FCF775FA0CE00C +:10C4300000902B4604204FF49642FFF7FBF8437917 +:10C44000606384F838308368E363656B5A4C94F812 +:10C450004A30022B09D094F89620022A00F0CE80B0 +:10C460001BB14C34002A18BF0024544B1C6044B14B +:10C47000204600214C2205F034FD0223256084F87B +:10C480004A30FDF777F8002800F0B6804C4D2B7845 +:10C49000002B40F0B1800820F9F767F8494C0146BD +:10C4A000206090B1434B42794FF4614183F84020C2 +:10C4B00082685A64F9F72AFA20680821F9F71CFA09 +:10C4C00020680821FCF728FA96E03F4B08201B68FB +:10C4D0004FF461429B7800930346FFF7ABF820606E +:10C4E00040B1012342792B70324B83F8402082689F +:10C4F0005A6481E0354B1B78002B7DD004232B70D0 +:10C50000FFF752FE78E083B9284CDFF8A880206856 +:10C5100098F81C10F9F7F0F92068D8F82010F9F70E +:10C52000F5F920680421FCF7C5F92B681B78012B6D +:10C530000DD1204C606A94F82810F9F7DDF9606A93 +:10C54000E16AF9F7E3F9606A0421FCF7B3F92B68B3 +:10C550001B78022B0DD1174C606B94F83810F9F74B +:10C56000CBF9606BE16BF9F7D1F9606B0421FCF753 +:10C57000A1F9FCF7FFFF00283ED0114D2B7813F0F6 +:10C58000FB0F39D0114B0F4C1B780BB320680821DF +:10C59000FCF790F904232B70FFF706FE2AE000BF9A +:10C5A0009C0500209D050020A0050020A40500207A +:10C5B000C8050020C01B0020200F0020D805002047 +:10C5C000E8050020EC050020B40D0020520D0020ED +:10C5D000DFF83480206898F84010F9F78DF920686A +:10C5E000D8F84410F9F792F920680821FCF762F9AD +:10C5F00004232B70002323603E7001E04C3434E7A9 +:10C6000002B0BDE8F08100BFC01B002037B53D4936 +:10C610000B7813F0010F03F0040268D0002A6FD1E9 +:10C62000980764D443F004030B70374B1A88374BD8 +:10C630001A80374B9A681C4612F4806F05D004208C +:10C64000FCF7A8FA08B1FCF745F9A3681B0357D516 +:10C650008020FCF79FFA08B1FCF73CF92D4D2B78B0 +:10C66000012B4DD18020F8F780FF2B4C0146206034 +:10C6700090B14279294B4FF4E1311A708268284B0E +:10C680001A60F9F743F920680221F9F735F92068B3 +:10C690008021FCF741F90EE000904FF4E132802058 +:10C6A0000223FEF7C7FF206028B142791B4B1A70A6 +:10C6B00082681B4B1A6023680BB92B7020E0194B62 +:10C6C000194C1B680021A36404F1540002231422B6 +:10C6D0002B70E164216505F004FC04F17403A3668A +:10C6E00004F1D803E36604F59E73236708E03AB9C2 +:10C6F0000220FF21012203B0BDE83040F9F7B4B8B1 +:10C7000003B030BDD5270020E0040020200E00201B +:10C7100030200020BA0D00201C2000202020002006 +:10C72000242000202C200020C01B00202DE9F04FE9 +:10C730008E4C8BB02378023B042B00F2EA83DFE8B7 +:10C7400013F007002B0005009900D60010267BE0AF +:10C75000874B1A68874B1B6864339A4240F2D9832F +:10C760001026854D854B2A689846985C2F4638B12F +:10C77000F9F796F92A68013E02F101022A60F0D128 +:10C780003B6818F80330002B40F0C383032222706B +:10C79000794A13607A4A6BE0774D7A4B2E6893F8AA +:10C7A0000080052E3FD8754FC8F1080807EB8603B7 +:10C7B000586E05F0D7FB002E14BF02230923704EDC +:10C7C00008FB1308346833680F33A34202DA444588 +:10C7D00027D10AE04445FADA2B6807EB83035B6E46 +:10C7E000185DF9F75DF90134EDE7674B5B79012BD3 +:10C7F00008D00A20F9F754F92B6801332B60002385 +:10C80000336086E32C20F9F74BF92B6807EB83079D +:10C81000FC6F013C14F8010F0028EAD0F9F740F949 +:10C82000F8E7346075E3584B9B681A064CBF042345 +:10C8300005232370002358E0F9F732F92A68013EF6 +:10C8400002F101022A6009D04B4D4C4B2A689846F0 +:10C850001A4492F894002F460028EDD13B684344D7 +:10C8600093F89430002B40F0548305222270424A02 +:10C8700013604EE3404D2B680B2B32D8DFE803F0FA +:10C8800006330A330D33131F24292D333F48FEF797 +:10C89000AFFA28E03E483F490EE03F483F49404A52 +:10C8A000FEF7A6FA1FE0384B0A2193F854273D48BB +:10C8B00001FB023393F85617FEF79AFA13E0324B56 +:10C8C0003948B3F8D010F7E72F4B3848B3F8D210F7 +:10C8D000F2E7374B3748D968EEE7374B37481988C6 +:10C8E000EAE7062323702B6801332B6011E3344DF4 +:10C8F000344B2C681B682360334B1A6862605A689B +:10C900009B68A260E360314B1A6822615A689B6899 +:10C910006261A3612E4B1A68E2615A689B682262C9 +:10C9200063622C4B1A8822855A8862859A88DB8834 +:10C93000A285E385284B1A8822865A889B886286BE +:10C94000A386264B1A88E2865A889B8822870D4A3E +:10C950006387117800238B4244DA214804EB4302B9 +:10C9600030F8130001339087F5E700BFBA0D0020BF +:10C970002C200020081C00200C1C00202C54010836 +:10C98000601D0020E127002030200020A56E010856 +:10C99000C26E0108C6670108DA6E0108B1670108B6 +:10C9A000BD670108F16E0108FE6E0108106F0108F5 +:10C9B000EC030020226F010800000020356F010801 +:10C9C000281C0020C0270020C4120020D012002004 +:10C9D000DC12002062020020F4040020B4040020D5 +:10C9E000A8270020B14B5B89A4F85E30B04BD3F888 +:10C9F0000090984619F01F02019240F0868049206D +:10CA0000F9F74EF8D8F80000F9F750F82068F9F770 +:10CA10004DF86068F9F759F8A068F9F756F8E0683A +:10CA2000F9F753F82069F9F750F86069F9F74DF80C +:10CA3000A069F9F74AF8E069F9F747F8206AF9F7C9 +:10CA400044F8606AF9F741F8B4F92800F9F73DF8BD +:10CA5000984FB4F92A00F9F738F8B4F92C00F9F72F +:10CA600034F8B7F8D030B4F92E000126C01AF9F71F +:10CA70001DF8B4F93000F9F728F8B4F93200F9F7E5 +:10CA800024F8B4F93400F9F720F8B4F93600F9F7CE +:10CA90001CF8B4F93800F9F718F8B4F93A00F9F7C6 +:10CAA00014F8B4F93C00B7F8D030C01AF8F7FEFF1C +:10CAB000814803789E420ADA04EB4603B3F93C004E +:10CAC000B4F93C300136C01AF8F7FFFFF0E77B7984 +:10CAD000012B06D12B68B3F95E00A0F2DC50F8F709 +:10CAE000F4FF2B68754A76496B60AB609B1A9B100C +:10CAF0004B430321013393FBF1F101EB41015B1A3D +:10CB0000642101FB03222A60FEE150206E68F8F7E1 +:10CB1000C7FFAA682B6810681B68002718446B6859 +:10CB20001B68A0EB4300F8F7D0FFE219F319506837 +:10CB30005B680437C01AF8F7C8FF0C2FF5D1002343 +:10CB4000E118F2180969126903F1080004338A1A1E +:10CB50000C2B69464250F3D10022134602A881589B +:10CB600001F120003F2820D801F108000F2806D845 +:10CB70000231032904D9002B08BF012300E002235E +:10CB800004320C2AEAD1012B029813D0022B1FD0B9 +:10CB9000039B00F0030003F003039B0043EA001033 +:10CBA000049B03F0030318431EE004AA01A84FF0FE +:10CBB000000A1DE000F00F0040F04000F8F770FFA1 +:10CBC000049B03F00F02039B42EA0310C0B20BE088 +:10CBD00000F03F0040F08000F8F762FF9DF80C0085 +:10CBE000F8F75EFF9DF81000F8F75AFF002769E09C +:10CBF00052F804194FEA8A0A01F18007FF2F10D971 +:10CC000001F50047B7F5803F02D24AF0010A08E07B +:10CC100001F50001B1F1807F34BF4AF0020A4AF009 +:10CC2000030A8242E4D16AF03F00C0B2F8F738FF4D +:10CC30004FF0000B0AF00301022910D003291BD08A +:10CC4000012903D002A911F80B0024E002AA52F82E +:10CC50000B70F8B2F8F724FFC7F307201BE002AB14 +:10CC600053F80B70F8B2F8F71BFFC7F30720F8F77B +:10CC700017FFC7F307400EE002A850F80B70F8B298 +:10CC8000F8F70EFFC7F30720F8F70AFFC7F30740CE +:10CC9000F8F706FF380E0BF1040BF8F701FFBBF1B4 +:10CCA0000C0F4FEAAA0AC5D1A0E700BF120000206E +:10CCB000101C002030200020E1270020341C002020 +:10CCC000295C8FC2E219F319D069DB690437C01AF5 +:10CCD000F8F7FBFE0C2FF5D10023E218B2F928106B +:10CCE000F218B2F928208A1A02A941F81320023357 +:10CCF000082BF2D1884B06AF03F1100E1868596863 +:10CD00003A4603C2083373451746F7D105AA01A86E +:10CD1000002352F804199B00DBB269B101F1080746 +:10CD20000F2F02D843F0010306E08031FF2994BFA2 +:10CD300043F0020343F003038242EAD10AA800EB66 +:10CD4000131203F00F03034412F8107C13F8103C85 +:10CD50004FF0000B43EA0717FFB23846F8F7A0FE82 +:10CD600007F00302022A15D0032A19D0012A25D17F +:10CD70000AA901EB8B0252F8200C52F81C1C00F09F +:10CD80000F0040EA0110C0B2F8F78AFE0BF1010B68 +:10CD9000BF0813E00AAB03EB8B0212F8200C0BE088 +:10CDA0000AA800EB8B0252F8202CD0B20092F8F7C0 +:10CDB00077FE009AC2F30720F8F772FE0BF1010B21 +:10CDC000BBF1030F4FEA9707CADD00272A6807F176 +:10CDD000180332F913006A68013732F91310AA6890 +:10CDE00032F9133002220B4493FBF2F3C01AF8F726 +:10CDF0006CFE032FEAD100272A6807F118035B00B5 +:10CE00001A44B2F906006A6801371A44B2F90610EA +:10CE1000AA681344B3F9063002220B4493FBF2F3E1 +:10CE2000C01AF8F752FE032FE6D100273B490B78D2 +:10CE30009F4217DA2A6807F11C035B001A44B2F913 +:10CE400004006A6801371A44B2F90410AA6813444E +:10CE5000B3F9043002220B4493FBF2F3C01AF8F743 +:10CE600034FEE3E72E4B5A791F46012A06D1B4F966 +:10CE70005E00B6F95E30C01AF8F727FE6B682A68C4 +:10CE8000AB60284B28496A60D21A92104A430321AA +:10CE9000013292FBF1F101EB4101521A642101FBD5 +:10CEA00002332B60BB681B062ED5204C204D226818 +:10CEB0002B689A4209D162686B689A4205D1019A3F +:10CEC0000F2A10D119F47E6F0DD14820F8F7E8FD34 +:10CED0002068F8F7FAFD6068F8F7F7FD23682B6023 +:10CEE00063686B600EE0134A114B11782A7C914203 +:10CEF00008D1114A99681068884203D15268DB68EA +:10CF00009A4201D0F8F7E5FDD8F800300133C8F8AF +:10CF100000300BB0BDE8F08FCD550108E1270020AF +:10CF200030200020341C0020295C8FC2240E0020F9 +:10CF3000141C0020C4050020D00500204B8810B52B +:10CF4000DC0607D52C4B14791B6853F824402B4B77 +:10CF500043F820404B889B0607D5274B54791B6824 +:10CF600053F82440254B43F820404B881C070DD52F +:10CF7000234B0C781B78B3EB141F07DB1E4BD478C4 +:10CF80001B6853F824401D4B43F820404B889B07F7 +:10CF90000DD51C4B0C781B78B3EB141F07DC164B1C +:10CFA00054781B6853F82440144B43F820404B88B6 +:10CFB000DC070ED5144B0C781B7804F00F049C4250 +:10CFC00007DC0D4B14781B6853F824400B4B43F8D7 +:10CFD00020404B885B070ED50C4B09781B7801F07D +:10CFE0000F01994207DB044B92781B6853F822200B +:10CFF000024B43F8202010BD240A00201406002014 +:10D00000CB060020C9060020C8060020CA06002062 +:10D01000234B70B519684FF47A73B1FBF3F1214BD0 +:10D0200021481A78214B224D1B78F8F791FF214BAC +:10D0300021481968214B2E68B1FBF3F1F8F788FFFE +:10D0400000241F4BE2B253F8221049B1012303FA26 +:10D0500002F2324202D01B48F8F77AFF0134F0E7BF +:10D060002A6892070DD5184A1848127803EB8203F4 +:10D07000196AF8F76DFF164B197A11B11548F8F7D0 +:10D0800067FF1548F8F7F8FCBDE87040134B1448EB +:10D090001A88144B92B219884FF4EF63F8F758BF0F +:10D0A0002C200020B4050020087201089800002000 +:10D0B0004C020020A80000204672010840420F00E8 +:10D0C000E05501086F640108D72700206472010849 +:10D0D000580400206E7201083E6801083C180020C8 +:10D0E00072720108FC0400200C4B07B51B6819681C +:10D0F00019B10B4A9069014391619A889868ADF81B +:10D10000042002228DF8072004220DEB02018DF885 +:10D110000620FCF7FFFB03B05DF804FB400700208E +:10D12000001002402DE9F74FA24E0C463778054615 +:10D130001146006891469B4622467B1C06F8043B3C +:10D14000FDF788FDAB686868ADF8043018238DF8EA +:10D15000063001A902238DF80730FCF7DBFB2B7B9F +:10D160003F0106EB070A2C680C2B00F2F280DFE887 +:10D1700013F00D00F000F000F0004D00F000F000A2 +:10D18000F0008200F000F000F000B600238C8A4826 +:10D1900023F001031B041B0C2384218CA288238B06 +:10D1A000844223F073034FEA03434FEA134389B2E7 +:10D1B00092B243F0700314D000F50060844210D0A6 +:10D1C00000F5406084420CD000F58060844208D0B5 +:10D1D00000F58060844204D021F0020141F0030197 +:10D1E00007E021F00E0122F4407241F0030142F405 +:10D1F0008072A2802383A4F834B02184238B23F08F +:10D2000008031B041B0C43F0080332E0238C6A481C +:10D2100023F010031B041B0C2384218CA288238B76 +:10D22000844223F4E6434FEA03434FEA134389B2AF +:10D2300092B243F4E04308D000F50060844204D089 +:10D2400021F0200141F0300107E021F0E00122F45B +:10D25000406241F0300142F48062A2802383A4F84E +:10D2600038B02184238B23F400631B041B0C43F48C +:10D27000006323836DE0238C4F4823F480731B04E9 +:10D280001B0C2384218CA288A38B844223F073037C +:10D290004FEA03434FEA134389B292B243F070035B +:10D2A00008D000F50060844204D021F4007141F4FC +:10D2B000407107E021F4606122F4405241F4407172 +:10D2C00042F48052A280A383A4F83CB02184A38BB3 +:10D2D00023F008031B041B0C43F0080338E0B4F8E8 +:10D2E00020C0354A2CF4805C4FEA0C4C4FEA1C4CB1 +:10D2F000A4F820C0B4F820C0A388B4F81C802CF493 +:10D30000005C28F4E6484FEA08484FEA0C4C4FEA24 +:10D3100018484FEA1C4C94429BB248F4E0484CF445 +:10D32000405C03D002F50062944203D123F48043B1 +:10D3300043F48043A380A4F81C80A4F840B0A4F870 +:10D3400020C0A38B23F400631B041B0C43F4006375 +:10D35000A383AB7B43B1B4F844306FEA43436FEA35 +:10D3600053439BB2A4F8443023889BB243F001039B +:10D3700023802B7B0C2B14D8DFE803F00713131347 +:10D380000A1313130D131313100004F1340307E0F1 +:10D3900004F1380304E004F13C0301E004F140032C +:10D3A000F3515046AAF80890CAF8044003B0BDE80B +:10D3B000F08F00BF641D0020002C014040F2E933D3 +:10D3C0000E4A1189890709D5908140F2E9330B4A49 +:10D3D0001189C9070DD59089C0B27047013B9BB236 +:10D3E000002BEDD1064BFF201A88013292B21A8031 +:10D3F0007047013B9BB2002BE9D1F3E700380040B6 +:10D40000F2060020434A2DE9F84F916840F20113DB +:10D410000B4040F201118B4293460CD13E4B93F8E6 +:10D42000C42093F8C59083F8C520B9EB020918BF52 +:10D430004FF0010901E04FF001094FF00008374BB0 +:10D440005FFA88F41B78A34261D9354B354E1B68CF +:10D45000354F23B93B685B8926F8143054E03A68AD +:10D46000072C94BF12F804A0A2462C4851469847B6 +:10D47000DBF808300546DB0509D5B9F1000F06D009 +:10D480002A4B50461B6829461B68DB699847A5F262 +:10D49000EE2240F2DC5392B29A4288BF3B68DBF83E +:10D4A000082088BF5D8942F20103134053B3204B2B +:10D4B0001978194B01F0030202EB840293F826015C +:10D4C00003EB4202A2F8C6501A4620B9032919D923 +:10D4D000012183F8261102EBC403B3F8C810B3F896 +:10D4E000C65002EB44020D44B3F8CA10B3F8CC3076 +:10D4F0000D441D44ADB2A2F8285104232DB295FB72 +:10D50000F3F5ADB226F8145008F1010897E7BDE82D +:10D51000F88F00BF30200020641D0020DF090020AC +:10D52000E8090020960600203C010020400200206F +:10D53000BC0D00202DE9F74F2A4B157C9B6801900C +:10D5400003F0400903F4007C03F40058032D45D890 +:10D550000C246C43244B0198E618377A0135384285 +:10D560003AD0E35C4BB1012B07D0032B04D0042B42 +:10D5700014BF0423032300E00223DFF870A01F017F +:10D580000AEB0704B9F1000F06D11AF807B0ABF1A6 +:10D59000030BBBF1010F1FD9BCF1000F06D0B8F18E +:10D5A000000F03D11AF80770042F15D04F7B94F8A1 +:10D5B0000CA007EA0A0ABA450ED14F686068874294 +:10D5C0000AD38F68A068874206D8137094605660AB +:10D5D000D1601574104602E0EDB2B7E7002003B049 +:10D5E000BDE8F08F30200020680000202C56010894 +:10D5F000094B30B59D68094B05F480551868084BF8 +:10D600001C6800230DB1828800E0A28805495A52A7 +:10D610000233182BF6D130BD30200020AC1E002084 +:10D62000B01E0020BC0F0020F8B50024204BE0B253 +:10D630001F78B8420CD21F4B33F810101E4B53F812 +:10D6400020301BB10B2801D8DB6898470134EDE787 +:10D650001A4B9B685B032AD50025194E2B46EAB26C +:10D66000BA4224D2726854689C4218D02046FCF713 +:10D6700004F9EFF31283502282F3128811494FF01C +:10D68000280CA28C0CFB001092B201324262A28ADA +:10D69000DBB292B242F00102A28283F3118856F803 +:10D6A000043F00221B6801351A802346D7E7F8BDE6 +:10D6B000E1270020A8270020B40800203020002007 +:10D6C000B0080020D01E00202DE9F04FAE4E85B0EE +:10D6D0003778032F14D9AD4BAD48B3F90410B0F926 +:10D6E00004200029B8BF49426FF063035B1A9A42D5 +:10D6F00004DB01F164039342A8BF134683801FE05B +:10D70000012F1DD8A34BA44C1B78013B142B00F216 +:10D71000E181DFE813F09100DF01DF0168009F0085 +:10D72000DF01DF012F01DF01DF01DF01DF01DF01A9 +:10D73000BD00DF01DF01DF01DF01DF01A101B80171 +:10D74000924B9649B3F806A0914B0968B3F8028052 +:10D75000B3F80090B3F904B0914C02910025BD429A +:10D7600004F11004CED20FFA8AF001F051FB54F804 +:10D77000101C01F0A1FB03460FFA88F0019301F0A1 +:10D7800047FB54F8081C01F097FB019B0146184623 +:10D7900001F08AFA03460FFA89F0019301F038FB91 +:10D7A00054F80C1C01F088FB019B0146184601F05F +:10D7B0007BFA029A034692F90000019340420BFB68 +:10D7C00000F001F025FB54F8041C01F075FB019BEF +:10D7D0000146184601F068FA01F034FD714B23F858 +:10D7E00015000135BBE702210420F8F7FAF9684D6E +:10D7F0000121AF8878431FFA80F80420F8F7F1F987 +:10D800006D8800FB05801FFA80F80420F8F7F8F90E +:10D810004044208102210520F8F7E3F978430121F3 +:10D8200087B20520F8F7DDF900FB057087B2052007 +:10D83000F8F7E6F938440BE005200121F8F7D1F9B3 +:10D84000534B9D88684385B20520F8F7D9F92844E1 +:10D8500060813FE1544B00201D68F8F7D1F9DFF8F3 +:10D86000648195F90630B8F902203227534393FBBF +:10D87000F7F3184420800120F8F7C2F995F90E302B +:10D88000B8F90020534393FBF7F73844608021E157 +:10D89000464B1B7813F0040F454B02D11B689B8845 +:10D8A0000BE01968394A0B88B2F9062049889A4278 +:10D8B00003DB9142B4BF0B461346E381E289394B47 +:10D8C000394F1A803B4B1B681D7845B30220F8F78F +:10D8D00097F93A68B2F91030518A984203DB0BB2DB +:10D8E0009842B8BF0346344909684889C3EB000E23 +:10D8F000324B0FFA8EFE19880FFA81FCF44501DADB +:10D900000D4401E001DD4D1B1D8092F91620B3F995 +:10D9100000305343642293FBF2F31844A080284B59 +:10D920001B88DB050CD5194B1A88D7F80090E280CC +:10D9300022819A88184F62815B880325A38101E0C8 +:10D94000134BF1E709EBC50393F90630B7F90680ED +:10D95000284608FB03F8642398FBF3F8A7F8068031 +:10D96000F8F74EF901354044072DF88007F102071A +:10D97000E8D1AFE00D4B1B7813F0040F0C4B23D113 +:10D980001B689B882CE000BFE1270020620200207A +:10D99000BC120020940500201200002098050020F1 +:10D9A00004090020A8270020A81E0020D527002059 +:10D9B000B01E0020B41E0020B81E0020A41E0020AF +:10D9C00054020020A80300201968AD4A0B88B2F960 +:10D9D000062049889A4203DB9142B4BF0B461346A6 +:10D9E000E381E289A74BA84D1A80A84B03201B882E +:10D9F0000121DF0503D5F8F7F4F8A14F02E0F8F7AD +:10DA0000F0F8A34FB7F80280022100FB08F01FFADC +:10DA100080F90320F8F7E5F83F88012100FB079023 +:10DA2000E8800420F8F7DDF800FB08F002211FFA77 +:10DA300080F80420F8F7D5F800FB07802881032040 +:10DA4000F8F7DEF8E3881844E0800420F8F7D8F807 +:10DA50002389184420813DE001210420F8F7C1F812 +:10DA60008B4D6F88784387B204202781F8F7C8F878 +:10DA70003844208101210520F8F7B3F82D88684348 +:10DA800085B26581E0E6824B0325B3F804909846A1 +:10DA900028460221F8F7A5F800FB09F0012187B21A +:10DAA0002846F8F79EF8C5F106035B0838F81330EE +:10DAB00000FB037087B224F815702846F8F7A0F829 +:10DAC000384424F815000135072DE1D16C4BDA8874 +:10DAD0006C4B1A806F4DDFF8E491AB6813F0200FA8 +:10DAE00034D00020F8F78CF8208080460120F8F729 +:10DAF00087F8694B644F1B6860801A0626D5674B10 +:10DB00001B681B7813F0020F654B23D0D9F800C0B7 +:10DB1000B3F900109CF90E209CF906C0B3F902304D +:10DB20004A43CCF1000C03FB0CF3322192FBF1F2DF +:10DB30006FF0310C92B293FBFCFC9444E04493FBF5 +:10DB4000F1F1A7F800800A4410447880D9F8001059 +:10DB5000002319E0D9F80010B3F902C091F90620AA +:10DB6000B3F900300CFB02FC32229CFBF2FCE044D7 +:10DB7000A7F8008091F90E104B4393FBF2F2E3E714 +:10DB8000E2520233102B0CD0E05E31F9232001EB7E +:10DB9000830790427F88F3DB3AB28242A8BF0246F5 +:10DBA000EEE73E4B1B681B785B0704D4354934789D +:10DBB000088801231BE03B4B00241F780423043F0B +:10DBC000FFB25FFA87F84FFA88F2D4420BD4364A94 +:10DBD00003F10109381932F813105FFA89F9C0B25C +:10DBE000FBF78DFE4B460134042CECD1DEE7A3425B +:10DBF00008D231F9132000B28242A8BF104680B289 +:10DC00000133F4E7294B4FEA44081A68AB6803F480 +:10DC100080550395244D03F01009254BB5F9066096 +:10DC2000244D1B782F68244D03F00403DBB2D5F894 +:10DC300000C002930023434562D0B2F802A004B2B0 +:10DC4000544505DD0F4CC0EB0A0A1D5B55441D53BE +:10DC5000039D0C4C002D33D07D8931F903A0AE42D9 +:10DC6000CBBFBCF802509588B2F802B0BCF800B047 +:10DC7000AA4503DBDA45B4BF55465D46E55238E0B8 +:10DC800062020020A8270020120000205402002079 +:10DC9000BC1200203020002050020020BC1E0020BA +:10DCA000A80300208B07002096060020B01E00204D +:10DCB000D5270020B81E0020AC1E0020A81E002082 +:10DCC00031F903A01588B2F802B0AA4503DBDA45A2 +:10DCD000B4BF55465D46E55204EB030ABC89A64233 +:10DCE00007DAB9F1000F01D1148800E09488AAF88E +:10DCF0000040029C14B9044C1C5BCC5202339AE7DE +:10DD000005B0BDE8F08F00BFBC0F00202DE9F04149 +:10DD1000FDF7CBFD10B90A20F7F7CCFD824C4FF48C +:10DD2000EF622046814904F0D3F894F854374FF459 +:10DD3000E072022B84BF002384F8543794F85437E0 +:10DD40007B4E02FB034303F5057393F850203360C9 +:10DD5000022A84BF002283F8502093F85030754A7D +:10DD600013700A2202FB0343734A03F256731360D3 +:10DD7000A36842F201021A403AB944F208021A407A +:10DD80001AB9694A43F400539360A368D90703D5CD +:10DD90004FF40050FBF793FBA3685A0409D5082001 +:10DDA000FBF78DFB4FF40050FBF789FB0120FBF7DD +:10DDB00086FBA3681B0706D54FF40050FBF77FFBDB +:10DDC0000120FBF77CFBA3689F040ED54FF40040B5 +:10DDD000FBF775FB4FF40060FBF771FB4FF48030ED +:10DDE000FBF76DFB4020FBF76AFBA3685D0603D5DC +:10DDF0004FF48030FBF763FBA368980408D503F465 +:10DE00002063B3F5206F03D14FF40060FBF757FB9D +:10DE10004A4D4B4B2F461D60F8F7C8F9494B05F1A9 +:10DE20001C0201201A60FAF734FE01460120FAF7BD +:10DE3000FFFC002849D00220FAF72BFE0146022001 +:10DE4000FAF7F6FC002840D02020FAF722FE01461F +:10DE50002020FAF7EDFCA368190601D5002834D07C +:10DE60001020FAF716FE01461020FAF7E1FCA3682D +:10DE70001A0700D548B30420FAF70BFE0146042028 +:10DE8000FAF7D6FC30B90820FAF703FE014608205D +:10DE9000FAF7CEFCA3685B0503D400231A461946A3 +:10DEA00009E00028F9D110E079B90121C00708D4B0 +:10DEB0000C33302B0BD024481844007A8507F5D555 +:10DEC000F2E70132D2B2022AF2D9F8F799F9F7F75C +:10DED000D3FB1E4D1E4B32681D601E4B101D18607B +:10DEE00002F175010023A846CD5C55B901EB030E84 +:10DEF0009EF802C09EF803E0F44502D2164B1D7056 +:10DF000002E00433A02BEFD1144B15490B601549E7 +:10DF100050330B601178144B012903D0022929D00A +:10DF2000124928E0124926E03020002000F80108BC +:10DF3000E8030020140E00208C0500204021002062 +:10DF40003C010020B80F00206800002000210020C4 +:10DF50000C0E0020100E002048000020242100207C +:10DF600004040020A00500209C000020056E00088D +:10DF70005D6C000833491960334B02F5D9721A60A1 +:10DF8000FBF7D6FB3568314B05F5D3721A60304B81 +:10DF900000229A802F4B304A304E136005F5B37241 +:10DFA0003260A3F1220272602E332D4A05F5D7713B +:10DFB000F36005F5D87311607361C6F808803761A6 +:10DFC000B4F8F00000F020FFF061B4F8F20000F0C7 +:10DFD0001BFF95F858303062337695F87430183658 +:10DFE000737094F825312A1D33731E4BB5F8620106 +:10DFF0001E601D4B1A601D4B05F160021A601C4B20 +:10E0000005F164021A601B4B05F25D121A601A4B8F +:10E01000C3F8008000F0FCFE0146184801F000F84B +:10E02000174900F049FF174B17491860E86D00F0D9 +:10E0300043FF01464FF07C5000F0F2FF134B186095 +:10E04000BDE8F081AD700008200A002028200020E3 +:10E05000C80900202821002070040020A81E0020EC +:10E0600098050020A4040020D4030020F004002020 +:10E07000C80200207C0500208405002000006144C7 +:10E080004C3D0F4488050020DB0F4940EC04002084 +:10E0900001480249FBF7AEBB00080040481F0020C2 +:10E0A00001480249FBF7A6BB00040040201F0020E6 +:10E0B0004FF080400149FBF79DBB00BFF81E0020D8 +:10E0C00001480249FBF796BB002C0140D01E0020FE +:10E0D00001480249FBF78EBB002C0140D01E0020F6 +:10E0E00038B5204CD4F8F0301D88ADB2AA0618D54A +:10E0F000D4F8CC201AB1988880B2904711E09B8860 +:10E10000D4F8BC20D4F8B410DBB28B54D4F8BC20C3 +:10E11000D4F8AC300132B2FBF3F103FB1123C4F8A5 +:10E12000BC302B061DD5D4F8C820D4F8C4100D4B34 +:10E130008A4210D0D3F8B800D3F8F010805C0132D6 +:10E14000C0B28880D3F8B010B2FBF1F001FB10220E +:10E15000C3F8C82038BDD3F8F030DA6822F0800266 +:10E16000DA6038BDD01E00200F4BD3F8442111884F +:10E17000090618D5D3F81C11D3F8180181420ED026 +:10E18000D3F80C01405C0131C0B29080D3F8042177 +:10E19000B1FBF2F002FB1011C3F81C117047D368F9 +:10E1A00023F08003D3607047D01E00200C480D4B35 +:10E1B0004FF400525A60D0F828214FF6FE731168D0 +:10E1C0000B401360D0F81821D0F81C319A4202D0CD +:10E1D000F430FCF78DBC012380F83831704700BF64 +:10E1E000D01E002000000240FCF79BBCFCF799BC4D +:10E1F000084A13689B020BD5074B00211970074989 +:10E200004FF6FE73086803400B604FF40013536031 +:10E21000704700BF00000240CE2700206C00024083 +:10E22000F9F7E2BFF9F7E0BFF6F7E2BAF6F7E0BABE +:10E23000074B1A685969490408D5520406D54FF4AA +:10E2400080425A61034B012283F84821704700BF86 +:10E2500000040140D01E002010B51B4B1A78510756 +:10E2600031D51A4C22F004021A70A3685A050AD557 +:10E27000FEF74CF804200121FAF79BFC18B104F5D5 +:10E280009670FDF767FFA3681B031CD5104B1A7827 +:10E29000012A0ED90F4C0122206821791A70F7F754 +:10E2A0002BFB2068A168F7F731FB20688021FAF783 +:10E2B00001FB80200121FAF77CFC20B10648BDE873 +:10E2C0001040FDF747BF10BDD527002030200020AB +:10E2D000BA0D00201C2000205C21002070B5FAF748 +:10E2E000D9FC38B3144C237A0BB9A38070BD134DFD +:10E2F0002E78C6F38000FAF7DFFC90B1104B46F0A1 +:10E3000002061A680F4B51892E7019805189598065 +:10E3100052899A800C4AD2685288DA80E3880133A5 +:10E32000E380FAF7A3FC10B92B785B0702D4BDE8B1 +:10E33000704091E770BD00BFC8090020D5270020BC +:10E34000C4090020960600201C2000200F4B1A68EC +:10E3500042F001021A6059680D4A0A405A601A6870 +:10E3600022F0847222F480321A601A6822F4802229 +:10E370001A605A6822F4FE025A604FF41F029A6033 +:10E38000044B4FF000629A60704700BF00100240DB +:10E390000000FFF800ED00E0024B1A6801321A603D +:10E3A000704700BF2C20002008B5084BB3F8D800F8 +:10E3B000074B1A780023D9B2914204D2054921F8BB +:10E3C00013000133F7E7FFF72FF9FEE72C200020B9 +:10E3D000E1270020A827002081F0004102E000BFD3 +:10E3E00083F0004330B54FEA41044FEA430594EA15 +:10E3F000050F08BF90EA020F1FBF54EA000C55EA50 +:10E40000020C7FEA645C7FEA655C00F0E2804FEA20 +:10E410005454D4EB5555B8BF6D420CDD2C4480EA02 +:10E42000020281EA030382EA000083EA010180EA32 +:10E43000020281EA0303362D88BF30BD11F0004F80 +:10E440004FEA01314FF4801C4CEA113102D04042B6 +:10E4500061EB410113F0004F4FEA03334CEA1333F1 +:10E4600002D0524263EB430394EA050F00F0A78009 +:10E47000A4F10104D5F1200E0DDB02FA0EFC22FA04 +:10E4800005F2801841F1000103FA0EF2801843FAF8 +:10E4900005F359410EE0A5F120050EF1200E012AE9 +:10E4A00003FA0EFC28BF4CF0020C43FA05F3C01827 +:10E4B00051EBE37101F0004507D54FF0000EDCF1A0 +:10E4C000000C7EEB00006EEB0101B1F5801F1BD349 +:10E4D000B1F5001F0CD349085FEA30004FEA3C0C4D +:10E4E00004F101044FEA445212F5800F80F09A8043 +:10E4F000BCF1004F08BF5FEA500C50F1000041EB47 +:10E50000045141EA050130BD5FEA4C0C404141EB4A +:10E51000010111F4801FA4F10104E9D191F0000F71 +:10E5200004BF01460020B1FA81F308BF2033A3F1F4 +:10E530000B03B3F120020CDA0C3208DD02F1140CEB +:10E54000C2F10C0201FA0CF021FA02F10CE002F126 +:10E550001402D8BFC2F1200C01FA02F120FA0CFC1F +:10E56000DCBF41EA0C019040E41AA2BF01EB045168 +:10E57000294330BD6FEA04041F3C1CDA0C340EDC66 +:10E5800004F11404C4F1200220FA04F001FA02F3A9 +:10E5900040EA030021FA04F345EA030130BDC4F167 +:10E5A0000C04C4F1200220FA02F001FA04F340EA5C +:10E5B0000300294630BD21FA04F0294630BD94F00D +:10E5C000000F83F4801306BF81F480110134013DF4 +:10E5D0004EE77FEA645C18BF7FEA655C29D094EA65 +:10E5E000050F08BF90EA020F05D054EA000C04BFE3 +:10E5F0001946104630BD91EA030F1EBF00210020CE +:10E6000030BD5FEA545C05D14000494128BF41F06C +:10E61000004130BD14F580043CBF01F5801130BDD0 +:10E6200001F0004545F0FE4141F470014FF000005B +:10E6300030BD7FEA645C1ABF194610467FEA655C0C +:10E640001CBF0B46024650EA013406BF52EA0335AE +:10E6500091EA030F41F4002130BD00BF90F0000F9C +:10E6600004BF0021704730B54FF4806404F13204D8 +:10E670004FF000054FF0000150E700BF90F0000F91 +:10E6800004BF0021704730B54FF4806404F13204B8 +:10E6900010F0004548BF40424FF000013EE700BF88 +:10E6A00042004FEAE2014FEA31014FEA02701FBF18 +:10E6B00012F07F4393F07F4F81F06051704792F0EA +:10E6C000000F14BF93F07F4F704730B54FF4607464 +:10E6D00001F0004521F0004120E700BF50EA0102AF +:10E6E00008BF704730B54FF000050AE050EA01025C +:10E6F00008BF704730B511F0004502D5404261EBCC +:10E7000041014FF4806404F132045FEA915C3FF40C +:10E71000DCAE4FF003025FEADC0C18BF03325FEAA5 +:10E72000DC0C18BF033202EBDC02C2F1200300FA5A +:10E7300003FC20FA02F001FA03FE40EA0E0021FA7F +:10E7400002F11444C1E600BF70B54FF0FF0C4CF469 +:10E75000E06C1CEA11541DBF1CEA135594EA0C0F1F +:10E7600095EA0C0F00F0DEF82C4481EA030621EA5A +:10E770004C5123EA4C5350EA013518BF52EA033595 +:10E7800041F4801143F4801338D0A0FB02CE4FF047 +:10E790000005E1FB02E506F00042E0FB03E54FF077 +:10E7A0000006E1FB03569CF0000F18BF4EF0010E6F +:10E7B000A4F1FF04B6F5007F64F5407404D25FEA6B +:10E7C0004E0E6D4146EB060642EAC62141EA55511E +:10E7D0004FEAC52040EA5E504FEACE2EB4F1FD0C60 +:10E7E00088BFBCF5E06F1ED8BEF1004F08BF5FEADE +:10E7F000500E50F1000041EB045170BD06F0004690 +:10E8000046EA010140EA020081EA0301B4EB5C043C +:10E81000C2BFD4EB0C0541EA045170BD41F4801134 +:10E820004FF0000E013C00F3AB8014F1360FDEBF59 +:10E83000002001F0004170BDC4F10004203C35DA35 +:10E840000C341BDC04F11404C4F1200500FA05F3B8 +:10E8500020FA04F001FA05F240EA020001F0004259 +:10E8600021F0004110EBD37021FA04F642EB0601CF +:10E870005EEA430E08BF20EAD37070BDC4F10C04F9 +:10E88000C4F1200500FA04F320FA05F001FA04F2BD +:10E8900040EA020001F0004110EBD37041F10001A9 +:10E8A0005EEA430E08BF20EAD37070BDC4F12005B4 +:10E8B00000FA05F24EEA020E20FA04F301FA05F21C +:10E8C00043EA020321FA04F001F0004121FA04F2C4 +:10E8D00020EA020000EBD3705EEA430E08BF20EA94 +:10E8E000D37070BD94F0000F0FD101F000464000CE +:10E8F00041EB010111F4801F08BF013CF7D041EA50 +:10E90000060195F0000F18BF704703F00046520053 +:10E9100043EB030313F4801F08BF013DF7D043EA24 +:10E920000603704794EA0C0F0CEA135518BF95EADA +:10E930000C0F0CD050EA410618BF52EA4306D1D161 +:10E9400081EA030101F000414FF0000070BD50EA80 +:10E95000410606BF1046194652EA430619D094EA0A +:10E960000C0F02D150EA013613D195EA0C0F05D1F4 +:10E9700052EA03361CBF104619460AD181EA030148 +:10E9800001F0004141F0FE4141F470014FF0000000 +:10E9900070BD41F0FE4141F4780170BD70B54FF09B +:10E9A000FF0C4CF4E06C1CEA11541DBF1CEA13551B +:10E9B00094EA0C0F95EA0C0F00F0A7F8A4EB0504FD +:10E9C00081EA030E52EA03354FEA013100F08880F4 +:10E9D0004FEA03334FF0805545EA131343EA1263BD +:10E9E0004FEA022245EA111545EA10654FEA002672 +:10E9F0000EF000419D4208BF964244F1FD0404F52B +:10EA0000407402D25B084FEA3202B61A65EB030586 +:10EA10005B084FEA32024FF480104FF4002CB6EB43 +:10EA2000020E75EB030E22BFB61A754640EA0C00C3 +:10EA30005B084FEA3202B6EB020E75EB030E22BF03 +:10EA4000B61A754640EA5C005B084FEA3202B6EB44 +:10EA5000020E75EB030E22BFB61A754640EA9C0003 +:10EA60005B084FEA3202B6EB020E75EB030E22BFD3 +:10EA7000B61A754640EADC0055EA060E18D04FEA91 +:10EA8000051545EA16754FEA06164FEAC30343EA31 +:10EA900052734FEAC2025FEA1C1CC0D111F4801FFE +:10EAA0000BD141EA00014FF000004FF0004CB6E7F7 +:10EAB00011F4801F04BF01430020B4F1FD0C88BF96 +:10EAC000BCF5E06F3FF6AFAEB5EB030C04BFB6EBA1 +:10EAD000020C5FEA500C50F1000041EB045170BD94 +:10EAE0000EF0004E4EEA113114EB5C04C2BFD4EBC1 +:10EAF0000C0541EA045170BD41F480114FF0000E45 +:10EB0000013C90E645EA060E8DE60CEA135594EAC0 +:10EB10000C0F08BF95EA0C0F3FF43BAF94EA0C0FC3 +:10EB20000AD150EA01347FF434AF95EA0C0F7FF438 +:10EB300025AF104619462CE795EA0C0F06D152EA8C +:10EB400003353FF4FDAE1046194622E750EA410670 +:10EB500018BF52EA43067FF4C5AE50EA41047FF481 +:10EB60000DAF52EA43057FF4EBAE12E74FEA4102E4 +:10EB700012F5001215D211D56FF47873B3EB62520F +:10EB800012D94FEAC12343F0004343EA505311F036 +:10EB9000004F23FA02F018BF404270474FF00000C8 +:10EBA000704750EA013005D111F0004008BF6FF006 +:10EBB000004070474FF00000704700BF4A0011D27C +:10EBC00012F5001211D20DD56FF47873B3EB6252C7 +:10EBD0000ED44FEAC12343F0004343EA505323FAD3 +:10EBE00002F070474FF00000704750EA013002D148 +:10EBF0004FF0FF3070474FF0000070474FEA41027E +:10EC0000B2F1E04324BFB3F5001CDCF1FE5C0DD98A +:10EC100001F0004C4FEAC0024CEA5070B2F1004FD4 +:10EC200040EB830008BF20F00100704711F0804FD7 +:10EC300021D113F13872BCBF01F00040704741F49C +:10EC400080114FEA5252C2F11802C2F1200C10FAA0 +:10EC50000CF320FA02F018BF40F001004FEAC12384 +:10EC60004FEAD32303FA0CFC40EA0C0023FA02F328 +:10EC70004FEA4303CCE77FEA625307D150EA0133FE +:10EC80001EBF4FF0FE4040F44000704701F00040CE +:10EC900040F0FE4040F40000704700BF80F00040AC +:10ECA00002E000BF81F0004142001FBF5FEA410364 +:10ECB00092EA030F7FEA226C7FEA236C6AD04FEA64 +:10ECC0001262D2EB1363C1BFD218414048404140A9 +:10ECD000B8BF5B42192B88BF704710F0004F40F45B +:10ECE000000020F07F4018BF404211F0004F41F477 +:10ECF000000121F07F4118BF494292EA030F3FD043 +:10ED0000A2F1010241FA03FC10EB0C00C3F1200355 +:10ED100001FA03F100F0004302D5494260EB4000E4 +:10ED2000B0F5000F13D3B0F1807F06D340084FEA4F +:10ED3000310102F10102FE2A51D2B1F1004F40EB44 +:10ED4000C25008BF20F0010040EA030070474900AC +:10ED500040EB000010F4000FA2F10102EDD1B0FA77 +:10ED600080FCACF1080CB2EB0C0200FA0CF0AABF6C +:10ED700000EBC25052421843BCBFD040184370470A +:10ED800092F0000F81F4000106BF80F40000013210 +:10ED9000013BB5E74FEA41037FEA226C18BF7FEAE7 +:10EDA000236C21D092EA030F04D092F0000F08BF29 +:10EDB0000846704790EA010F1CBF0020704712F010 +:10EDC0007F4F04D1400028BF40F00040704712F14F +:10EDD00000723CBF00F50000704700F0004343F0B4 +:10EDE000FE4040F4000070477FEA226216BF0846EA +:10EDF0007FEA23630146420206BF5FEA412390EAAD +:10EE0000010F40F4800070474FF0000304E000BFA2 +:10EE100010F0004348BF40425FEA000C08BF704753 +:10EE200043F0964301464FF000001CE050EA010217 +:10EE300008BF70474FF000030AE000BF50EA01022C +:10EE400008BF704711F0004302D5404261EB410119 +:10EE50005FEA010C02BF84460146002043F0B6433E +:10EE600008BFA3F18053A3F50003BCFA8CF2083A63 +:10EE7000A3EBC25310DB01FA02FC634400FA02FC6C +:10EE8000C2F12002BCF1004F20FA02F243EB020073 +:10EE900008BF20F00100704702F1200201FA02FCD5 +:10EEA000C2F1200250EA4C0021FA02F243EB0200C8 +:10EEB00008BF20EADC7070474FF0FF0C1CEAD0520C +:10EEC0001EBF1CEAD15392EA0C0F93EA0C0F6FD0CD +:10EED0001A4480EA010C400218BF5FEA41211ED0AB +:10EEE0004FF0006343EA501043EA5111A0FB013197 +:10EEF0000CF00040B1F5000F3EBF490041EAD3716C +:10EF00005B0040EA010062F17F02FD2A1DD8B3F1E7 +:10EF1000004F40EBC25008BF20F00100704790F056 +:10EF2000000F0CF0004C08BF49024CEA502040EAA8 +:10EF300051207F3AC2BFD2F1FF0340EAC25070476E +:10EF400040F400004FF00003013A5DDC12F1190FAC +:10EF5000DCBF00F000407047C2F10002410021FA1E +:10EF600002F1C2F1200200FA02FC5FEA310040F136 +:10EF7000000053EA4C0308BF20EADC70704792F0AF +:10EF8000000F00F0004C02BF400010F4000F013AE7 +:10EF9000F9D040EA0C0093F0000F01F0004C02BFE2 +:10EFA000490011F4000F013BF9D041EA0C018FE751 +:10EFB0000CEAD15392EA0C0F18BF93EA0C0F0AD057 +:10EFC00030F0004C18BF31F0004CD8D180EA01007D +:10EFD00000F00040704790F0000F17BF90F0004F16 +:10EFE000084691F0000F91F0004F14D092EA0C0FF8 +:10EFF00001D142020FD193EA0C0F03D14B0218BF8B +:10F00000084608D180EA010000F0004040F0FE40D0 +:10F0100040F40000704740F0FE4040F4400070476C +:10F020004FF0FF0C1CEAD0521EBF1CEAD15392EAEB +:10F030000C0F93EA0C0F69D0A2EB030280EA010CDB +:10F0400049024FEA402037D04FF0805343EA111174 +:10F0500043EA10130CF000408B4238BF5B0042F1D2 +:10F060007D024FF4000C8B4224BF5B1A40EA0C0077 +:10F07000B3EB510F24BFA3EB510340EA5C00B3EBA9 +:10F08000910F24BFA3EB910340EA9C00B3EBD10F97 +:10F0900024BFA3EBD10340EADC001B0118BF5FEAE9 +:10F0A0001C1CE0D1FD2A3FF650AF8B4240EBC25012 +:10F0B00008BF20F0010070470CF0004C4CEA5020D3 +:10F0C0007F32C2BFD2F1FF0340EAC250704740F422 +:10F0D00000004FF00003013A37E792F0000F00F014 +:10F0E000004C02BF400010F4000F013AF9D040EA92 +:10F0F0000C0093F0000F01F0004C02BF490011F426 +:10F10000000F013BF9D041EA0C0195E70CEAD1531D +:10F1100092EA0C0F08D142027FF47DAF93EA0C0F04 +:10F120007FF470AF084676E793EA0C0F04D14B02E8 +:10F130003FF44CAF08466EE730F0004C18BF31F09A +:10F14000004CCAD130F000427FF45CAF31F0004394 +:10F150007FF43CAF5FE700BF4FF0FF3C06E000BF2D +:10F160004FF0010C02E000BF4FF0010C4DF804CD50 +:10F170004FEA40024FEA41037FEA226C18BF7FEA60 +:10F18000236C11D001B052EA530C18BF90EA010F62 +:10F1900058BFB2EB030088BFC81738BF6FEAE170F1 +:10F1A00018BF40F0010070477FEA226C02D15FEA8D +:10F1B000402C05D17FEA236CE4D15FEA412CE1D0F9 +:10F1C0005DF8040B704700BF844608466146FFE7C0 +:10F1D0000FB5FFF7C9FF002848BF10F1000F0FBDA2 +:10F1E0004DF808EDFFF7F4FF0CBF012000205DF89B +:10F1F00008FB00BF4DF808EDFFF7EAFF34BF012020 +:10F2000000205DF808FB00BF4DF808EDFFF7E0FFB8 +:10F2100094BF012000205DF808FB00BF4DF808ED09 +:10F22000FFF7D2FF94BF012000205DF808FB00BF6C +:10F230004DF808EDFFF7C8FF34BF012000205DF84E +:10F2400008FB00BF4FEA4002B2F1FE4F0FD34FF070 +:10F250009E03B3EB12620DD94FEA002343F0004343 +:10F2600010F0004F23FA02F018BF404270474FF0F1 +:10F270000000704712F1610F01D1420205D110F078 +:10F28000004008BF6FF0004070474FF0000070472B +:10F2900042000ED2B2F1FE4F0BD34FF09E03B3EB00 +:10F2A000126209D44FEA002343F0004323FA02F02C +:10F2B00070474FF00000704712F1610F01D1420218 +:10F2C00002D14FF0FF3070474FF00000704700BF91 +:10F2D00073B96AB9002908BF0028BCBF00204FF0ED +:10F2E0000041C4BF6FF000414FF0FF3000F03CB868 +:10F2F00082B0EC462DE9005000F006F8DDF804E09D +:10F3000002B00CBC704700BF2DE9704F089E144638 +:10F310001D468046894600F029F804FB01F3A4FB52 +:10F3200000AB00FB05329344B8EB0A0869EB0B090C +:10F33000C6E90089BDE8708F2DE9704F089E14461C +:10F340001D468046894600F061F900FB05F5A0FBEB +:10F3500004AB04FB0154A344B8EB0A0869EB0B09A6 +:10F36000C6E90089BDE8708F704700BF00292DE90C +:10F37000F00FC0F2A1800024002BC0F29880154647 +:10F3800006460F46002B3FD18A4258D9B2FA82F383 +:10F390004BB1C3F1200201FA03F720FA02F29D40BB +:10F3A00000FA03F61743290CB7FBF1F201FB1277C1 +:10F3B000A8B200FB02F34FEA164C4CEA0747BB42E7 +:10F3C00009D97F1902F1FF3C80F00581BB4240F270 +:10F3D0000281023A2F44FF1AB7FBF1F301FB1371CC +:10F3E00000FB03F0B6B246EA0141884208D9491948 +:10F3F00003F1FF3780F0F180884240F2EE80023B5B +:10F4000043EA0242002303E08B420AD900231A4652 +:10F410001046194614B1404261EB4101BDE8F00FBE +:10F420007047B3FA83F8B8F1000F40F088808B4240 +:10F4300002D3824200F2E28000230122E8E712B9FF +:10F440000123B3FBF2F5B5FA85F2002A3AD17F1B0E +:10F45000280C1FFA85FC0123B7FBF0F100FB1177A4 +:10F460000CFB01F24FEA164848EA0747BA4207D9AF +:10F470007F1901F1FF3802D2BA4200F2C48041463E +:10F48000BF1AB7FBF0F200FB12700CFB02FCB6B225 +:10F4900046EA0040844507D9401902F1FF3702D2FD +:10F4A000844500F2AE803A4642EA0142B0E7E443C6 +:10F4B000524263EB430362E7404261EB41014FF08C +:10F4C000FF3459E79540C2F1200927FA09F126FADD +:10F4D00009F99740280CB1FBF0F800FB18111FFA4E +:10F4E00085FC0CFB08F349EA07094FEA194747EA8C +:10F4F00001418B4206FA02F608D9491908F1FF3298 +:10F500007AD28B4278D9A8F102082944C91AB1FBF2 +:10F51000F0F300FB13170CFB03F21FFA89F949EA19 +:10F520000747BA4207D97F1903F1FF3160D2BA42C7 +:10F530005ED9023B2F44BF1A43EA08438CE7C8F167 +:10F54000200225FA02F103FA08FC27FA02F320FA56 +:10F5500002F207FA08F741EA0C0C4FEA1C49B3FB28 +:10F56000F9F109FB11331FFA8CFA0AFB01FB17436F +:10F570003A0C42EA03439B4505FA08F008D913EB1D +:10F580000C0301F1FF3235D29B4533D90239634474 +:10F59000CBEB0303B3FBF9F209FB12330AFB02FACC +:10F5A000BFB247EA0347BA4508D917EB0C0702F187 +:10F5B000FF331BD2BA4519D9023A674442EA0145E2 +:10F5C000A5FB0001CAEB07078F424FF000030AD3E7 +:10F5D00005D02A461CE76246FDE63B4610E706FAE0 +:10F5E00008F68642F5D26A1E002311E71A46E5E7BF +:10F5F0000B46A0E71146CBE7904687E743464246D5 +:10F6000006E7023A50E702392F4439E72DE9F00FB7 +:10F61000144605460E46002B43D18A4253D9B2FA0E +:10F6200082F757B1C7F1200620FA06F601FA07F370 +:10F6300002FA07F400FA07F51E43210CB6FBF1F2BB +:10F6400001FB1266A0B200FB02F32F0C47EA06464C +:10F65000B34209D9361902F1FF3780F0FD80B34279 +:10F6600040F2FA80023A2644F61AB6FBF1F301FBA7 +:10F67000136100FB03F0ADB245EA0141884208D9AD +:10F68000091903F1FF3680F0E980884240F2E680F4 +:10F69000023B43EA0242002310461946BDE8F00F40 +:10F6A00070478B424CD8B3FA83F6002E4FD18B4271 +:10F6B00002D3824200F2DD80BDE8F00F0023012278 +:10F6C00010461946704712B90124B4FBF2F4B4FA9B +:10F6D00084F2002A40F08280091B260CA7B2012385 +:10F6E000B1FBF6F006FB101107FB00F24FEA154CD8 +:10F6F0004CEA01418A4207D9091900F1FF3C02D2C4 +:10F700008A4200F2C8806046891AB1FBF6F206FB15 +:10F71000121107FB02F7ADB245EA0145AF4208D925 +:10F720002C1902F1FF3180F09B80A74240F29880B3 +:10F73000023A42EA004210461946BDE8F00F70470F +:10F7400000231A4610461946BDE8F00F7047C6F16F +:10F75000200522FA05F703FA06F421FA05F301FA67 +:10F7600006FB20FA05F53C434FEA1448B3FBF8FCCE +:10F7700008FB1C331FFA84F909FB0CFA45EA0B0B52 +:10F780004FEA1B4545EA03439A4502FA06F204D9BB +:10F790001B190CF1FF356FD3AC46CAEB0303B3FB67 +:10F7A000F8F508FB153309FB05F91FFA8BFB4BEA4B +:10F7B0000347B94504D93F1905F1FF3362D31D460C +:10F7C00045EA0C4CACFB0223C9EB07079F424FF004 +:10F7D00000054AD346D062462B465DE79440C2F10D +:10F7E000200921FA09FC914020FA09F9260CBCFBFA +:10F7F000F6F806FB18CCA7B207FB08F349EA0109A3 +:10F800004FEA194141EA0C4C634500FA02F509D967 +:10F810001CEB040C08F1FF323BD2634539D9A8F147 +:10F820000208A444C3EB0C0CBCFBF6F306FB13C1AB +:10F8300007FB03F21FFA89F949EA01418A4207D915 +:10F84000091903F1FF3022D28A4220D9023B214418 +:10F85000891A43EA084343E73A4605E7334618E77F +:10F860000A4666E7B0409042B5D20CF1FF32002361 +:10F8700012E7334632460FE79A458DD9ACF1020CB8 +:10F8800023448AE7B9459AD9023D274498E70346BD +:10F89000DEE79046C6E70238214435E74FF0FF3CEB +:10F8A00006E000BF4FF0010C02E000BF4FF0010C7A +:10F8B0004DF804CD4FEA410C7FEA6C5C4FEA430CF3 +:10F8C00018BF7FEA6C5C1BD001B050EA410C0CBF42 +:10F8D00052EA430C91EA030F02BF90EA020F0020A4 +:10F8E000704710F1000F91EA030F58BF994208BF0B +:10F8F00090422CBFD8176FEAE37040F001007047C8 +:10F900004FEA410C7FEA6C5C02D150EA013C07D11E +:10F910004FEA430C7FEA6C5CD6D152EA033CD3D069 +:10F920005DF8040B704700BF8446104662468C4663 +:10F930001946634600E000BF01B5FFF7B7FF002896 +:10F9400048BF10F1000F01BD4DF808EDFFF7F4FFBF +:10F950000CBF012000205DF808FB00BF4DF808ED4A +:10F96000FFF7EAFF34BF012000205DF808FB00BF6D +:10F970004DF808EDFFF7E0FF94BF012000205DF88F +:10F9800008FB00BF4DF808EDFFF7CEFF94BF012044 +:10F9900000205DF808FB00BF4DF808EDFFF7C4FF3D +:10F9A00034BF012000205DF808FB00BF1C481D4942 +:10F9B000026800608A4200F01D80002100F004B857 +:10F9C000194B5B58435004311848194B42189A425E +:10F9D000FFF4F6AF174A00F003B8002342F8043BE7 +:10F9E000154B9A42FFF4F9AFFEF7B0FC00F038F87F +:10F9F000FFF7FEBF114E124830601248016821F037 +:10FA000070610160410201600F4C182020600F49B5 +:10FA10000F4808600F48D0F800D040680047000049 +:10FA2000F04F0020EFBEADDEC07F010800000020D7 +:10FA30003801002038010020F4270020181002406F +:10FA40000900000004000140140C0140000C0140BA +:10FA50004434434400F0FF1FFFF7FEBF00000000E6 +:10FA60002DE9804893B0F0F753FBB14EB14CD6F876 +:10FA70000880002318F0080F2370374600F0E78055 +:10FA800063681B7A042B00F2E080DFE803F00303D5 +:10FA9000058AB100237AD9E0627AA64B002A00F0E9 +:10FAA000D48000225A7293F82020120700F1CD80F2 +:10FAB000D97A9A7A01F0070042EA00225A621A7B48 +:10FAC00002F03F00400140EAD1019962597B890070 +:10FAD00041EA92119A7B02F0010041EA8021D96249 +:10FAE000D97B01F00F00C00140EA52021A631A7C70 +:10FAF00002F07F00000140EA11115963597C49006E +:10FB000041EAD212997C01F0030042EA40229A6352 +:10FB1000DA7C02F01F00800140EA9101D963197D6F +:10FB2000C90041EA5212997D1A645A7D01F007001A +:10FB300042EA00225A64DA7D02F03F00400140EAC6 +:10FB4000D1019964197E890041EA92115A7E02F02E +:10FB5000010041EA8021D964997E01F00F00C001C3 +:10FB600040EA52021A65DA7E02F07F00000140EAA4 +:10FB700011115965197F490041EAD212597F01F0EC +:10FB8000030042EA40229A659A7F02F01F0080013A +:10FB900040EA9101D965D97FC90041EA52121A663B +:10FBA00051E094F86420634B002A4ED0002283F881 +:10FBB000642093F86620012A47D193F88A20102AFE +:10FBC00084BF102283F88A2094F88A105A4A0023AE +:10FBD000D8B2884202F1020235D212F8010C12F8B2 +:10FBE000025C40EA0525554840F823500133EFE711 +:10FBF00094F8CC204F4B42B3002283F8CC2093F8EA +:10FC0000CD20A82A21D193F8E050F5B9494901EB5C +:10FC1000450393F8D00093F8D13003EB0020FEF7B2 +:10FC20001DFD3FA3D3E90023FEF7B8FE3EA3D3E9B1 +:10FC30000023FEF7D5FBFEF7C1FF414B43F825003B +:10FC40000135082DE2D1012300E00023237018F4D0 +:10FC5000804F08D094F8043123B1364B002283F84A +:10FC6000042101232370237843B118F4807F05D049 +:10FC7000304BD3F808311B681B689847314B22780A +:10FC80001B6832B92B4AD2F80C219A1AD243D20FF0 +:10FC900000E0012292B3F2F727F994F81021254BE6 +:10FCA000002A00F0CC83D3F814114D0742F1D7801D +:10FCB000D3F81821100707D4B3F81C2122F008024A +:10FCC000A3F81C2102F0CBB8B3F81C0100F0080225 +:10FCD00092B2002A42F0C38040F00800A3F81C0151 +:10FCE000D3F82401C3F83421C3F82001B3F830015C +:10FCF000C3F83821A3F8280102F0B1B8D4F83C21A8 +:10FD0000511CC4F83C11052A00F29183DFE812F07F +:10FD10001C00AE006E031C0168038A03AFF3008071 +:10FD20009A999999999919400000000000707740BC +:10FD30003020002038010020A0010020C401002054 +:10FD40001C020020C0270020D4F81421784D12078F +:10FD500040F16D83D5F840219A1A002AC0F26783DA +:10FD600003F5C33805F5A27008F1A008C5F8408175 +:10FD7000F8F75CF86F4B05F5A27001461A78F5F7B5 +:10FD8000C5FA95F84A1105F5A27011F0040F17D0C5 +:10FD9000C5F84C810022BB180025A3F8FE50644B27 +:10FDA000855A03F5A87E22F80E5003F5AB7E22F8A3 +:10FDB0000E500232062AEED121F0040183F84A11D6 +:10FDC00094F85C315A4AA3B1B2F84411B6F8FE3047 +:10FDD000CB1AA2F84431B2F84611B6F80031CB1A6A +:10FDE000A2F84631B2F84811B6F80231CB1AA2F89F +:10FDF0004831D4F84C314E4A002B00F018834E495C +:10FE0000C3EB08038B4202F5A87502F5AB7119D854 +:10FE10004A4BDA6882F00802DA600023C25A35F9E8 +:10FE200003E017B2BE45C4BFDFF818E123F80E2087 +:10FE300031F903E0BE45BCBF414FDA530233062B14 +:10FE4000ECD1F4E20023C2F84C3135F903E0C85E8E +:10FE5000FA1870444FF0020E734490FBFEF0062B2C +:10FE6000A2F8FE00F1D1FBF7A5FCE0E2D4F81421E2 +:10FE70002F4D500740F1DB82D5F860219A1A002AF5 +:10FE8000C0F2D582C5F8603195F86431012B14D0E9 +:10FE900002D3022B29D0CAE2D5F870319847D5F8A1 +:10FEA00074319847012385F86431B5F86A21D5F893 +:10FEB00060311344C5F86031B9E2D5F8783198471C +:10FEC000D5F86C319847D5F86031B5F8682105F55B +:10FED000C0701344C5F8603105F5C271D5F87C31A6 +:10FEE0009847022385F86431A1E2D5F89001D5F84E +:10FEF0008C1100784B1C0027834285F86471D5F87B +:10FF000088E1D5F8802103D1012385F894313B465F +:10FF10000748C4F88C3100EB8101C1F8982100EB4F +:10FF20008301D1F898117244521AC4F888217EE2F4 +:10FF300038010020CF2700207FC3C901000C0140F9 +:10FF40008E02002088020020D4F81421510703D526 +:10FF5000B04991F8941111B9D70640F16882D4F8EC +:10FF60005822AC4DC2EB030B46F2A712934540F268 +:10FF70005E82A94FC5F85832B7F80080B8F1000F7B +:10FF80002FD0D5F89031D5F85C221878D5F8883183 +:10FF90000138B3FBF0F0082392FBF3F1521A10443E +:10FFA000C5F85C0290FBF3F0FEF732FF9B49FFF7C8 +:10FFB00037F89B4902F0C8FA01464FF07E50FEF731 +:10FFC00071FE9849FEF778FFFFF73CF908F1FF381A +:10FFD0000023C5F86002A7F80080C5F86432C5F8B0 +:10FFE0006832D4F89051D4F8883128780138B3FBBE +:10FFF000F0F0FEF709FF8949FFF712F8884902F08F :020000040801F1 -:10000000AD68814629464046FEF712FE074648463F -:10001000FEF7BAFD294680464FF07E50FEF7FEFC03 -:1000200001464046FEF704FE01463846FEF7F8FC5E -:10003000C4F8640202F02EF905218046FAF788FA26 -:10004000B4F8702240F23E6302F21F3292B29A423A -:10005000C4F89002D4F894720AD87D4AB2F87202B9 -:1000600000F21F3080B298428CBF0020012000E0D7 -:10007000002000286AD094F89832754D13BBD5F84B -:100080002021D5F824317548D31AB3F5FA7FA8BFDB -:100090004FF4FA738342A8BF18460A21FAF758FAB8 -:1000A000D5F89C328022DB78584390FBF2F3B3F50D -:1000B000967FA8BF4FF49673A2F5D6729342B8BF4D -:1000C000134601E0664B1B68D4F89C22C8EB03037F -:1000D000517A20205943D57C91FBF0F1D4F83401BA -:1000E000B1F5967FA8BF4FF4967103FB05005D4BF9 -:1000F000B0F5C81FA8BF4FF4C8109842B8BF184643 -:100100004FF40055C4F8340190FBF5F0564DA94268 -:10011000ACBF45184519507FFEF736FD394680467D -:100120000498FEF77DFC01464046FEF781FD4FF046 -:100130006C51FEF77DFDFEF741FF6FF095039628A9 -:10014000A8BF96209842B8BF1846281A049BC4F846 -:100150003801C4F8943226E0B3681D0623D5F3F7BE -:10016000EFFA20E0D4F81421394BD0061BD53F4AD2 -:10017000D3F8A01212683C318A4214D3C3F8A022EB -:10018000D3F8A8723A4A3B4DC3F8A4223B880B200F -:100190002B61F4F7EDFD3B886B6104E0B3689903D4 -:1001A00001D5FDF705F9D4F83C31052B03DD284BCB -:1001B0000022C3F83C21F4F7DBFC2F4B1860B38915 -:1001C0002BB1D4F8AC22821A002AC0F25887184406 -:1001D0001F4D7379C4F8AC02059305F53170D4F85E -:1001E000B832D4F8B072984705F53170014694F8EA -:1001F000CA22F4F7F9FA214B1B88002B00F0B880D3 -:10020000D5F8CC324FF000091B7805F5347504930E -:10021000C8461A4BB3F800A0194BBAF57A7F03D140 -:10022000002243F809202A61164A32F9080053F8DF -:100230000920024443F80920FEF7A6FC2A6901328E -:10024000012A2A6120D1002368602860AB6046E063 -:10025000380100200024744924FAFFFF0CFEFFFF40 -:10026000CC2700200000E7FFD4FEFFFF282000205D -:10027000A0000020000C0140BC270020C82700205F -:1002800044040020FC030020D5F800C0039261461E -:10029000CDF808C00190FEF7C1FB039A83461046D3 -:1002A000FEF772FC01465846FEF776FDDDF808C001 -:1002B00001466046FEF7B4FB019B024611466860AA -:1002C00018460392FEF7AAFB01465846FEF7B0FC1B -:1002D000A968FEF7A5FB039AE8602A60A860684A4F -:1002E000002302F1540BBAF1010F28F8023028F86C -:1002F0000B30DFF89CA12CD12869012807DD0138DB -:10030000FEF742FC0146E868FEF746FD00E00020EB -:1003100002F016FA0346049858B10193FEF734FC34 -:10032000019B01461846FEF73FFE10B14FF47A7369 -:100330001CE0544B4FF47A7259F803300A2003F54D -:10034000FA7393FBF2F32BF808300F210122F4F734 -:100350002BFD08F10208B8F1060F09F1040905F1B7 -:1003600014057FF456AFBAF80030013BAAF800300C -:100370000023454D05F5317205F54671985A595AD5 -:10038000411A99520233062BF3D1D5F8143113F0E8 -:10039000020300F00583D5F8243305F54B70984728 -:1003A00005F54B70014695F83223F4F71DFAB5F8C0 -:1003B000343305F54B78002B45D00022D5F83803AF -:1003C0001346314D38F902C0B5F8341305F54F7EA8 -:1003D000B1F5C87F04BF00214EF803105EF803108A -:1003E000294D61444EF80310043300210C2B28F8EA -:1003F0000210815202F10202E3D1B5F83433012B2D -:100400001CD1D5F83C334FF4C872C83393FBF2F3D8 -:100410000380D5F84033C83393FBF2F34380D5F81B -:100420004433C83393FBF2F2184B1B88D21A8280F4 -:10043000A7F85410A7F85610FCF74CFCB4F8343366 -:10044000013BA4F83433B3685A0740F18480B4F810 -:1004500048230D4B322A1DD1D3F838231188A3F835 -:100460004A1351889288A3F84C13A3F84E23B7F887 -:100470005420A3F85023B7F85620A3F852230BE0DA -:10048000FC0300204404002038010020000000206C -:10049000C8270020002A3CD00021D4F838530A464F -:1004A000914E38F901E0B6F8483306F55576322B0F -:1004B00004BF0023B350B0588B4B7044B05004328B -:1004C00000200C2A28F80100685201F10201E7D14E -:1004D000B3F84823012A17D183F86123052283F852 -:1004E0006223B3F84A2383F860032A80B3F84C23CD -:1004F0006A80B3F84E23AA80B3F85023B3F852337E -:10050000A7F85420A7F85630B4F84833013BA4F8B4 -:10051000483394F86323744BEAB1D3F85453D3F8B7 -:1005200038133220002295FBF0F583F863230D8009 -:10053000D3F8585395FBF0F54D80D3F85C3393FB1B -:10054000F0F06A4B1B88C01A8880A7F85420A7F8DF -:100550005620FCF7BFFBD4F83833B4F82C131A88B4 -:1005600000268A1AA4F82C23B4F82E135A88B14610 -:100570008A1AA4F82E239B88B4F83023D31AA4F83F -:100580003033F4F7F5FAD4F864330546C31A184645 -:100590000493FEF7F5FAD4F868130690FEF748FBCB -:1005A000D4F86C83C4F8645398F800A007903546DB -:1005B0004F4F785FFEF7E8FA0799FEF739FB09A974 -:1005C0008851BAF1000F2DD05046FEF7DDFA0146F2 -:1005D0004FF07E50FEF7E0FB0246114607F1AC0BF0 -:1005E0004FF07E500392FEF719FA56F80B10FEF703 -:1005F0001FFB07F168018446485FCDF808C0FEF78D -:10060000C3FA039AB8371146FEF712FBDDF808C0AB -:1006100001466046FEF704FA4BF80600FEF7CEFCF2 -:10062000785304E007F1B8026837E95BA952314F0B -:100630000436EA5F0235062D02FB0299B8D12B4D34 -:100640004FF0640A2A880AFB09F3524393FBF2FA3B -:10065000AAF1490A07F1080009A91FFA8AFAF4F772 -:1006600099FDBAF13B0FD8F8046011D9B4F99003A1 -:10067000FEF78AFAD4F88C6301463046FEF794FC04 -:10068000194F94F84A31002838D043F0080337E076 -:100690004FF07E513046FEF7C3F901464FF07E50D1 -:1006A000FEF77AFB4FF0000B8246134B304653F8AF -:1006B0001B100193FEF7BCFA024637F90B000392B8 -:1006C000FEF762FA039A01461046FEF7A9F9514671 -:1006D000FEF7AEFA019B43F81B000BF1020BBBF1D6 -:1006E000060FE2D1C2E700BF380100200000002061 -:1006F000FC030020B4040020BC04002023F0080305 -:100700003146D4F8880387F84A3101F08FFE074656 -:10071000C4F89403D4F88403D4F88CB300F10046F1 -:10072000D4F888030146FEF783FA594682465846B4 -:10073000FEF77EFA01465046FEF772F902F000F825 -:100740000146304601F072FEA6490646C4F89803F9 -:100750003846FEF76DFA01F09DFDA249A4F870023B -:100760003046FEF765FA01F095FDD4F81431A4F88F -:1007700072021B0739D59C4809A9F4F70BFDD8F87C -:1007800008904FF07E514846FEF74AF901464FF077 -:100790007E50FEF701FB4FF0000B8246934D48461A -:1007A00005F5677353F81B100193FEF741FA05F541 -:1007B000A271024631F90B000392FEF7E5F9039AA4 -:1007C00001461046FEF72CF95146FEF731FA019B1F -:1007D00043F81B000BF1020BBBF1060FDED11846EC -:1007E000F4F790FDA5F8A80341E0DFF814A209A9E9 -:1007F0000AF10400F4F7CEFC6868D5F808B00146A9 -:10080000FEF716FAD5F80C90594605465846FEF7FD -:100810000FFA01462846FEF703F9494605464846C1 -:10082000FEF706FA01462846FEF7FAF801F088FFBF -:1008300000210546FEF790FBA0B9DAF8040029462E -:10084000FEF7AAFA2946CAF80400DAF80800FEF70B -:10085000A3FA2946CAF80800DAF80C00FEF79CFA59 -:10086000CAF80C006248F4F74DFDA4F8A8036149EA -:100870000698FEF7DDF907F10047814606F10046CC -:10088000B4F9A8030C970D96FEF77EF95A4900F1CA -:100890000040FEF7CDF90E90B4F97C03FEF774F931 -:1008A0000F90B4F97E03FEF76FF91090B4F980034E -:1008B000FEF76AF90CA911900FA8F4F76BFC98F8F1 -:1008C00001304A4D012B19D14C4B1B785E070ED4D9 -:1008D000D5F8AC33402093FBF0F0181AFEF754F92A -:1008E0001199FEF79DF8FEF769FBC5F8AC033F4B85 -:1008F000D3F8AC03402390FBF3F001E0404B1888A1 -:10090000FEF742F901461198FEF788F8D4F8B413BF -:1009100011904846FEF784F801464846FEF73CFA37 -:10092000D4F8B053064629461198FEF777F80146E9 -:100930003046FEF77DF901462846FEF771F8064677 -:10094000C4F8B0030F98D4F8787201F0A3FCD4F87F -:10095000B8532978F9F7FCFD3844C4F878021098A8 -:10096000D4F87C7201F096FC2978F9F7F1FD38444F -:10097000C4F87C023046D4F8807201F08BFC6978B0 -:10098000F9F7E6FD1F4B049D1A6838442A441A60A3 -:10099000D4F88432C4F880020133C4F8843205E00C -:1009A000A5F82C33A5F82E33A5F830330F4F059E4C -:1009B000B7F8C432012EA7F8BC33B7F8C632A7F88F -:1009C000BE3321D1B7F9C223B7F9C83203EB4203D2 -:1009D000032293FBF2F39BB2A7F8C033A7F8C2330C -:1009E00016E000BF4C3D0F44D40400203801002025 -:1009F00004000020BD37863535FA8E3CD62700200E -:100A000000000020C4270020B7F8C832A7F8C03380 -:100A1000F4F7AEF8C14B01261860D7F8C833C7F811 -:100A2000C803C31AA7F8C433F1F784FFD7F8183105 -:100A3000BB4D13F4801387F8106100F08D80B5F87A -:100A40001C31180600F1D480B64B1B78590770D5BD -:100A500095F8CC23B44B12B195F8CD233AB10022CE -:100A6000C7F8D02301221A74002287F8CD231B7CFB -:100A7000D7F8B052032B95F80080A94E05F1040970 -:100A800087F8CC3306D1484606F575714C2201F043 -:100A900093F944E0012B07D106F5757049464C22C5 -:100AA00001F08AF9002302E0022B02D1012386F82B -:100AB0002034012384F8213484F822340023C4F83C -:100AC0002434C4F82834994A94F82034C4F82C9477 -:100AD00013441B7C964A1D4484F83134C4F8D02357 -:100AE000287984F83084FEF74FF89249FEF754F9DC -:100AF000C4F83404A87BFEF747F88F49FEF74CF999 -:100B0000C4F83804287EFEF73FF88C49FEF790F8C9 -:100B1000C4F83C04FEF778FA00232876AB73B7F8E4 -:100B20001C3143F08003A7F81C31012387F84034BF -:100B30005EE04FF00009D5F8D0034946FEF70CFA05 -:100B40008046002854D1FCF7C5F8774BC5F8D09300 -:100B500085F8CC831E744BE0B5F81C9119F0800F1A -:100B60003BD095F8CC23DFF8C0A1511E012924D831 -:100B70007149D5F83804FEF75BF8FEF745FAD5F869 -:100B80002C6495F831846E49B04488F80A00D5F891 -:100B90003C04FEF74DF8FEF737FA88F81400307879 -:100BA000FDF7F2FF0146FDF73BFFFEF72DFAB37AA2 -:100BB000B0703373337DB37506E0032A04D185F832 -:100BC000CC338AF8106004E09AF8103001338AF8C8 -:100BD000103029F08009A7F81C91524B1B785A0756 -:100BE00006D497F840341BB14D4B012283F8CD2336 -:100BF000D7F814914A4A19F0080F524D38D0B2F87C -:100C00002E1101F145039BB28A2B2DD8B2F81C316D -:100C10005B0729D5B2F8A803B2F8423497F84A61C5 -:100C2000C21A92B293B218B2B330BCBF02F5B47319 -:100C30009BB21AB2B32AC4BFA3F5B4739BB23607F2 -:100C400095F8EC00364A13D540B240424343D2F8FF -:100C5000B0021BB2007B43436FF01D0093FBF0F327 -:100C60001944A2F82E1103E0B7F8A833A7F84234CC -:100C700019F0140F00F09880B7F81C21284B02F4EB -:100C80000272002A00F0908093F84A2102F01002CC -:100C900002F0FF0052B1B3F82C1195F92701D3F8F7 -:100CA000382100FB0212A3F82C217DE0D3F8442464 -:100CB000D1789278002947D0B3F830E1B3F9281100 -:100CC0000FFA8EF6C1EB0608B8F1000FB8BFC8F1F5 -:100CD000000890450FDD8E42C8BF52421FFA8EFEBB -:100CE000C8BF92B2C3F834017244012083F84804AB -:100CF000A7F8302158E093F848242AB1D3F82421EA -:100D000083F84804C3F82021D7F83831D7F84C24A9 -:100D100019441388528899423FE000BFBC27002045 -:100D200038010020D62700200000002038440108A8 -:100D30000000A0410000204100007A445555553F75 -:100D40009A99993F2C200020B3F92801B3F930611A -:100D5000361A86EAE67EAEEBE67E96450ADD02228C -:100D600096FBF2F6A84A1660012283F8982283F8CF -:100D700048240AE093F848243AB1D3F8242183F8B0 -:100D80009812C3F8202183F84814D7F84C14D7F8E8 -:100D900038210B88024449889A4203DB8A42B4BF57 -:100DA00013460B46A7F83031D7F8B032974E93F878 -:100DB00064810493B8F1000F55D0B6F81C319B073D -:100DC00051D0D6F88403D6F888230146D6F88CB3E0 -:100DD000B6F830A10392FDF72BFF039A03461146A4 -:100DE00010460193FDF724FF019B01461846FDF7CD -:100DF00017FE5946034658460193FDF719FF019B1C -:100E000001461846FDF70CFE01F09AFC01465846D3 -:100E1000FDF7C2FF7E498346FEF7B2F8F8B958469F -:100E200001F0B4FAD6F85014FDF702FF01F032FADF -:100E3000B0F5617FA8BF4FF46170FDF7A5FE75495D -:100E4000FDF7AAFF01F064FA06464046FDF79CFE56 -:100E50003146FDF7EDFE01F01DFA80B200E0002002 -:100E60008244A7F830A119F0200F00F08B80B7F86A -:100E70001C31DFF898A103F03003002B00F08280D2 -:100E80009AF84A31D8077DD5BAF9A803FDF77CFE58 -:100E90006149FDF7CDFE064601F03AFA804630463C -:100EA00001F0C2F9DAF85434814693F803B0BAF984 -:100EB0005E045A4EBBF1000F34D0BAF85A24CBF17D -:100EC000000A93B212B2801A0193F9F7D9FC504587 -:100ED000019B03DB5845A8BF584600E05046B7F8D1 -:100EE00058140344B7F95C048AB209B29BB2401AA1 -:100EF000A7F85A3403920193F9F7C2FC5045039ABC -:100F0000019B03DB5845B4BF8246DA4692441FFA80 -:100F10008AFAA4F858A418B2FDF736FE83460FFAF1 -:100F20008AF004E0FDF730FE8346BAF95C04FDF771 -:100F30002BFE494682465846FDF77AFE4146034657 -:100F400050460193FDF774FE019B01461846FDF7DC -:100F500065FD3349FDF720FFFEF730F8414630804C -:100F60005846FDF765FE494680465046FDF760FE4F -:100F700001464046FDF754FD2949FDF70DFFFEF7F8 -:100F80001DF87080049E274B301DD3F800C0D7F8A1 -:100F9000601406F15403B5F8F620E047F5F7E2F8DF -:100FA000D7F86434002B60D0184B93F86834013BB9 -:100FB000142B55D8DFE803F00B54543C5754541FFE -:100FC00054545454544454545454543C4400D7F846 -:100FD0006C345B782BB1144B0020998BF9F7E7FC4C -:100FE00043E0124B1B7803F0040303F0FF00002BD7 -:100FF000F1D10146F2E70C4E0020318BF9F7D7FC16 -:101000000120718BEAE700BFCC27002038010020C7 -:101010008FC2753CEFB6B04435FA8E3CD227002023 -:10102000000020419800002000000020D62700206A -:10103000A44E0020718BF9F7BAFC0120B18BCDE7EB -:10104000A04E0020318BF9F7B2FC0120718BF9F72B -:10105000AEFC0220B18BF9F7AAFC0320F18BBDE7AF -:10106000AB68990601D5F4F787F8FCF7BBFC964B03 -:101070001B7823B9AB681A0301D5F5F795FB924BA2 -:101080001B78002B40F0C983DFF85092D9F8083064 -:101090005B0540F1C2838D4D95F87034002B00F054 -:1010A000BC83F9F76DFA002800F0B78395F8713426 -:1010B000002B00F0B283D5F874341B78002B40F07D -:1010C0001C82D5F87804F3F7CBFE002840F0158297 -:1010D000DFF80C82D5F87C24D8F800309A1A7C2AE4 -:1010E00040F20B82C5F87C3495F880340746013312 -:1010F00085F8803407F12400744EC0B2F3F7DAFFAC -:1011000006F55F7333F91700FDF73EFD6D4B824620 -:101110001888FDF739FD01465046FDF73DFE6C4944 -:10112000FDF786FDFDF74AFF013700B2F3F7EEFF4A -:10113000032FDFD13020F3F7BDFFB6F99002F3F7AC -:10114000E5FFF3F7C5FF96F880349F072FD1D6F857 -:101150007C3441F2883293421AD91020F3F7AAFF67 -:10116000D6F86C02642790FBF7F000B2F3F7CEFFDD -:101170002120F3F79FFFD6F86C3293FBF7F007FBC3 -:10118000103787EAE770A0EBE77000B2F3F7BEFF15 -:101190001420F3F78FFFB5F9A803F3F7B7FF1C206E -:1011A000F3F788FF0020F3F7B1FFF3F791FF95F80D -:1011B0008034464E580740F07A810220F3F77AFFD8 -:1011C000D6F884316422323393FBF2F000B2F3F7A5 -:1011D0009DFF0320F3F76EFF3E4B1B7813F0040FC7 -:1011E0004FF0050304D0B6F9300190FBF3F005E0B1 -:1011F000D6F884245289B2FBF3F000B2F3F786FFED -:10120000D9F80830990775D5334E94F88824337887 -:1012100040F63401B2FBF3F24A432A21B2FBF1F269 -:10122000B4F88A14062091FBF3F703FB17173F016C -:10123000BFB247EA0227BFB2C2F303221743F3F754 -:1012400039FF38B2F3F762FFB4F88A2433780132F9 -:1012500092B292FBF3F103FB1123A4F88A3494F8C1 -:1012600088346E265E43152396FBF3F63A204FF042 -:101270006409F3F71FFFB6FBF9F73846F3F746FFAB -:101280003B20F3F717FF09FB176080B20A270530F0 -:1012900090FBF7F000B2F3F739FF2820F3F70AFFCD -:1012A000D4F88C0490FBF7F000B2F3F72FFF042082 -:1012B000F3F700FFD4F884345B899BB1FAF7E8FBBD -:1012C00015E000BF00000020D027002038010020DA -:1012D00000007A44D6270020940000202C20002013 -:1012E00028200020A84BD3F8900480F3100000B20F -:1012F000F3F70CFFD5F81431A34E9A066BD596F888 -:101300004A319B071AD51120F3F7D4FEB6F894049E -:10131000FDF770F898A3D3E90023FDF7D1F8002278 -:101320009A4BFCF71BFFFDF7DDFA00B2F3F7EEFE78 -:101330001920F3F7BFFE0020F3F7E8FE95F84A31D5 -:10134000B5F8966413F0020F08BF00260120F3F7EA -:10135000B1FE30B2F3F7DAFE0920F3F7ABFE00205E -:10136000F3F7D4FE8A4B95F898641B88B3F5967F03 -:101370000BD9854A92F8802402F00F02072A04D87C -:1013800042F20F76B342B8BF1E460520F3F792FE35 -:10139000D5F89C345B7B0BB930B21AE0A6F1200083 -:1013A000FDF728F876A3D3E90023FDF7B3F9FDF79D -:1013B000E1FA00210646FDF7D9FD10B14FF03F419B -:1013C00001E04FF07C513046FDF72AFBFDF7F6FDBA -:1013D00000B2F3F79BFED5F814319F060ED46A4B8A -:1013E0000021D3F89C647068FDF7B6FD00285CD13D -:1013F000B0680021FDF7B0FD002856D195F84A21CC -:10140000614B960703D493F8A024012A07D1012346 -:10141000D5F8A474D5F8A86485F8A0340FE0D3F803 -:101420009C645C497068FDF703FCFDF7C7FD5949F2 -:101430000746B068FDF7FCFBFDF7C0FD06460FA9A7 -:101440003846F9F7C5F81320F3F734FEBDF93C0030 -:10145000F3F75CFE1B20F3F72DFEBDF93E00F3F71A -:1014600055FE2320F3F726FE002FACBF4E2053205D -:10147000F3F74CFE0FA93046F9F7AAF81220F3F75C -:1014800019FEBDF93C00F3F741FE1A20F3F712FEF6 -:10149000BDF93E00F3F73AFE2220F3F70BFE002ED3 -:1014A000ACBF45205720F3F731FEF3F711FE95F856 -:1014B0008034282B21D1344B0022D8F8006083F8E7 -:1014C00080244FF47A73B6FBF3F817203C26F3F729 -:1014D000F1FDB8FBF6F7B7FBF6F006FB1070000263 -:1014E00000B2F3F713FE1820F3F7E4FD06FB1780B4 -:1014F00000B2F3F70BFEF3F7EBFDD5F87434224E90 -:101500001B78012B40F02481F3F732FBD6F8AC3482 -:10151000214AC31A9342074640F2BC8096F88824B9 -:10152000002386F8CE2486F8C424D6F88C2486F8C6 -:10153000B23486F8B43486F8CF3486F8C5340A233A -:1015400092FBF3F286F8CC24121286F8CD24D6F85A -:10155000902492FBF3F386F8D03496F84A211B12BC -:1015600086F8D13496F89834950786F8F63415D471 -:101570002D2386F8F7348AE07B14AE47E17A843F66 -:10158000CDCCCCCCCCCCFC3F380100200000E03FDF -:101590009C0000208096184B3F0D0300042BD4F8CC -:1015A000A454C9488CBF33233223DFF840C386F8E4 -:1015B000F73495FBF0F60CFB06584FF0060E0EFBC9 -:1015C00008F8C24B06EB860698FBF3F903FB198873 -:1015D00006EB86064FFA89F9D4F8A81409EB8606BB -:1015E000B6B291FBF0F084F8E664360A84F8E7645A -:1015F0000CFB00160EFB06F6ED0F84F8E55496FB87 -:10160000F3F503FB1563642293FBF2F384F8ED34E6 -:101610001B12C90F84F8EE34B4F8943484F8EA1439 -:1016200024214B4398FBF2F893FBF2F2B4F808350F -:1016300084F8E324C2F3072284F8E42484F8EF3426 -:10164000B4F896241B0A84F8F0340A23B2FBF3F3AF -:1016500000EB800003F5FA739BB26DB200EB8000E3 -:1016600005EB800084F8F1341B0A80B284F8F23470 -:10167000B4F80A3584F8E88484F8EB044FEA2828A3 -:10168000000A84F8E98484F8EC0484F8F834904B78 -:10169000C3F8AC748E4D95F80C355BB9D5F81005D0 -:1016A000F3F7DEFB95F81D36002B40F04F83012841 -:1016B00000F25483D5F81825854C002A48D094F8B8 -:1016C0000C653EB1D4F81C3540F6B731FB1A8B429D -:1016D0000BD83DE00123D4F81005022184F80C3525 -:1016E000F3F7AAFB84F8206530E094F821355BB964 -:1016F000D4F810050121C4F8183584F80C35F3F737 -:101700009BFBF3F7B2FB21E0013BDBB284F8213510 -:1017100094F8201594F8220543B901304B1C84F845 -:10172000220584F82035D4F810050DE0134613F88F -:10173000012B0130114484F82205D4F8100584F8F7 -:101740002015C4F818351146F3F79CFBC5F81C7535 -:101750005F4CD4F8743425461B78022B1BD1D4F887 -:101760002435C3B1C4F828351B685A4AC4F82C354F -:10177000D4F830351344987CF7F78AFDD4F828352F -:101780009879F3F784FBD4F830350133092B88BFFF -:101790000023C4F83035F8F745FF00283DD094F811 -:1017A0003435013B012B38D8D5F83805F3F758FB11 -:1017B000474C494ED8B1D4F83805F3F74CFB94F8B0 -:1017C0003C2533687E2A0FD102221B2884F8342559 -:1017D000C4F8403505D00D2803D0342801D067283F -:1017E00002D1012385F8443585F83C05DCE73368F0 -:1017F000D4F8402541F658319A1A8A4203D9032376 -:1018000084F8343509E0D4F848259B1A042B04D910 -:1018100094F844350BB1F9F729FFDFF8D4B0DBF8C1 -:101820000830DC037DF5DDAF294C94F84C352546B6 -:10183000002B3DF4D6AF294B1B78002B7DF4D1AFA4 -:10184000F3F796F9D4F850350746C31ADB43DB0F9C -:101850000493D4F85435C31A6FEA030AD4F8583500 -:101860004FEADA7AC31A6FEA03084FEAD878B8F178 -:10187000000F06D1BAF1000F03D1049B002B3DF4F9 -:10188000B0AF4FF0000995F8E0355FFA89F69E4257 -:10189000DFF83CC05ED21249DCF85C35B200096862 -:1018A00013446244C2F860155988C80522D48B05D8 -:1018B0004DD50C4B1B785E0754BF064B0A4B1B687B -:1018C000C2F8603543E000BF8096980040420F00A8 -:1018D000380100203844010828200020CA270020B1 -:1018E0005C600108D627002044440108806967FF36 -:1018F0002C2000201946A54A30460193CDF808C097 -:10190000F7F795FADDF808C0019BBCF81C2112F02E -:10191000400F03D0304619469D4A16E0500703D5C4 -:10192000304619469B4A10E0110703D53046194648 -:10193000994A0AE0900703D530461946974A04E0D1 -:10194000D10704D5964A30461946F7F770FA09F1DF -:10195000010998E79E000023B3421FD0D5F85C250B -:1019600090491A445288520516D501F5AC62D058F8 -:101970000890B1F9E8057821A0F57A7048434FF452 -:101980007A7190FBF1F000F22B1040F2671190FB9E -:10199000F1FE01FB1E0199520433DDE7B8F1000F9F -:1019A0002CD007F5C333A033C4F8583594F8063665 -:1019B0007C4E1BBB86F80736DBF80830980705D548 -:1019C000F2F7CAFF10B1012386F80736D4F80836BB -:1019D000744E1B689B68984728B196F8073643F009 -:1019E000020386F80736704B1B7813F0050F05D1FC -:1019F00094F8073643F0040384F8073694F8072672 -:101A000022B9684B93F80636002B4ED094F8061690 -:101A100011F0010FA1F10C001AD1032906D8634B74 -:101A2000634E12F0040F18BF334600E05F4B0439D9 -:101A3000072904D85F4912F0010F18BF0B46C0B246 -:101A4000032810D85C4912F0020F18BF0B460AE0B9 -:101A5000C0B2032806D8554B584912F0020F18BFE0 -:101A60000B4600E0514B002095F8E015C6B2B1429C -:101A7000DFF830E10CD9DEF85C15B6003144498856 -:101A8000090603D519687644C6F860150130EBE7FE -:101A9000B8F1000F13D05AB194F80626414B013229 -:101AA000D2B2142A09D1002207E0B8F1000F06D003 -:101AB00094F80636002BEFD101E083F80626BAF140 -:101AC000000F23D0B4F92C31B4F92A213221002A95 -:101AD000B8BF5242002BB8BF5B4293FBF1F392FBBD -:101AE000F1F1DBB2C9B28B4238BF0B46344A0BB1BD -:101AF00092FBF3F23A44C4F8542594F80C26294B8F -:101B00000AB9012200E0002283F80C2694F80C2682 -:101B1000244B22B92B4AC3F81026002009E0234A9F -:101B2000F9E7D3F85C1594000E197688760607D489 -:101B3000013095F8E015C2B291421A4BF1D8B8E0E5 -:101B4000B3F92A61192E3FDD11F822E093F814C68B -:101B50000EF00F08E045D3F8106608DC93F815C6C0 -:101B6000BCEB1E1F03DC23443468C3F8604511F846 -:101B7000224095F816E604F00F0CF445094B4BDBB8 -:101B800093F815E6BEEB141F46DC40E05444010810 -:101B90005A44010860440108664401086C44010885 -:101BA0007244010838010020D62700205C6001083B -:101BB000384401083C4401084044010844440108F9 -:101BC000400D030078440108193625DA11F822E0A7 -:101BD00093F814C60EF00F08E045D3F8106608DC41 -:101BE00093F817C6BCEB1E1F03DB23443468C3F80D -:101BF000604511F8224095F816E604F00F0CF44504 -:101C00006A4B09DB93F817E6BEEB141F04DB34685C -:101C100003EB8203C3F86045B5F92C41634B192CE3 -:101C20001BDD11F822E093F814660EF00F0CB4459A -:101C3000D3F810460ADC93F815C6BCEB1E1F05DC72 -:101C4000D4F800E003EB8203C3F860E511F822301A -:101C500003F00F01B1421FDD6AE71934BFF668AF28 -:101C600011F822E093F816660EF00F0CB445D3F885 -:101C700010460ADB93F815C6BCEB1E1F05DCD4F832 -:101C800000E003EB8203C3F860E511F8223003F0B3 -:101C90000F01B142FFF64CAF95F81716B1EB131FC9 -:101CA000FFF646AF414B03EB82022368C2F8603572 -:101CB0003EE7049DE5B193F8192693F8181607F549 -:101CC00043478818013890FBF2F402FB140083F8B4 -:101CD0001B16013183F81A0691FBF2F002FB101279 -:101CE0005037D2B2C3F8507583F81C2683F81826F3 -:101CF000F3F7CEFEFDF775BDCB067EF55CAAD4F8F2 -:101D000018212A4B910207D4B3F81C2122F4007247 -:101D1000A3F81C21FEF74FBAB3F81C1101F40072AE -:101D200092B2002A7EF447AA41F40071A3F81C1174 -:101D3000D3F82411C3F83421C3F82011B3F83011BB -:101D4000C3F83821A3F82811FEF735BA00283FF46C -:101D5000B1ACD5F81005F3F77EF824E00228144C56 -:101D600003D0F3F782F8012304E094F8222022B193 -:101D7000C5F8147584F822309CE4D5F81435FB1AA4 -:101D8000B3F57A6FFFF496AC0123D5F8100584F80B -:101D90002230F3F760F80446D5F81005F3F75BF846 -:101DA000802C7FF487ACF9F747FA83E438010020F0 -:101DB00000000020AFF3008010B50023934203D051 -:101DC000CC5CC4540133F9E710BD0244034693428E -:101DD00002D003F8011BFAE7704700000D4B70B505 -:101DE0001D680022845C2B195B7803F00303012B30 -:101DF0008B5C08BF2034EE18767806F00306012EBF -:101E000008BF2033E41A02D10132002BEAD1204668 -:101E100070BD00BFC800002010B5044622461378EC -:101E20000134002BFAD1CC5CD4540133002CFAD10C -:101E300010BDC9B2024610F8013B1BB18B42F9D16B -:101E4000104670470029FBD018467047034613F828 -:101E5000012B002AFBD1181A013870470F4BF0B53F -:101E60001E680023934215D0C55C7419647804F091 -:101E70000304012CCC5C08BF203537197F7807F0AC -:101E80000307012F08BF20342D1B04D10133002C80 -:101E9000E8D100E000252846F0BD00BFC8000020C2 -:101EA00010B5034632B111F8014B013A03F8014B6A -:101EB000002CF7D11A44934203D0002103F8011BF0 -:101EC000F9E710BD30B503780BB1044604E00B7898 -:101ED000002B18BF002030BD22461078013438B1E5 -:101EE0000023C85C28B1D55C8542F5D10133F8E701 -:101EF00030BD104630BD00210A2200F001B92DE9A5 -:101F0000F04E82468B461F46144612B90020BDE8AB -:101F1000F08E002BFAD00026A642F7D2A5196D0844 -:101F200007FB05B950464946089B9847002802DB45 -:101F300003D06E1C25462C46EEE74846BDE8F08EE1 -:101F4000174B2DE9F0411D680646AC6D0F46FCB9F4 -:101F5000502000F0E3F8A8658460AB6D0460446035 -:101F60001C61DC60AB6D9C615C61AB6DDC629C6292 -:101F7000AB6D5C631C63AB6DDC639C63AB6D5C64DD -:101F80001C64AB6DDC649C64AB6D1C77AB6D5C62F8 -:101F900030463946AA6D0123BDE8F04100F002B891 -:101FA0002C010020F0B508B9106828B3044614F8D5 -:101FB000015B0F4617F8016B3EB1B542FAD10BB188 -:101FC0002046F3E714600370F0BD4DB91560284654 -:101FD000F0BD17F8016BAE4207D0002EF9D11C46B8 -:101FE000234613F8015B0F46F3E715B1002121707A -:101FF00000E02B461360F0BDF0BD000084463F4872 -:102000002DE9F04FD0F800800E46344614F8015BFD -:1020100008EB0500407800F0080000F0FF0708B169 -:102020002646F2E72D2D03D1B41C7578012703E075 -:102030002B2D04BF7578B41C33F010000DD1302D5A -:1020400008D1207800F0DF00582851D1657810239E -:10205000023402E0002B08BF0A23002F0CBF6FF0F0 -:10206000004A4FF0004ABAFBF3F903FB19AA002615 -:10207000304608EB050B9BF801B01BF0040F01D0B4 -:10208000303D0BE01BF0030B1BD0BBF1010F14BF65 -:102090004FF0570B4FF0370BCBEB05059D4210DA95 -:1020A000B6F1FF3F0AD0484506D801D1554503DCBB -:1020B00003FB0050012601E04FF0FF3614F8015BEE -:1020C000D7E7731C0CD1002F4FF022030CBF6FF029 -:1020D00000404FF00040CCF800302AB9BDE8F08F46 -:1020E00007B1404242B106B1611E1160BDE8F08FF8 -:1020F000002B08BF0823B0E7BDE8F08FC800002020 -:1021000030B51346044A05460C4610682946224657 -:10211000BDE83040FFF772BF2C010020024B0146A2 -:10212000186800F003B800BF2C01002070B5CD1C6A -:1021300025F0030508350C2D38BF0C25002D06466B -:102140003FDB8D423DD3214B1C6818462146A1B18F -:102150000B685B1B0ED40B2B03D90B60CC18CD5036 -:102160001FE08C4202D1626802601AE04B68636033 -:102170000C4616E00C464968E9E7154C23681BB984 -:10218000304600F027F820602946304600F022F85B -:10219000431C014615D0C41C24F0030484420AD118 -:1021A000256004F10B00231D20F00700C31A0BD09B -:1021B0005A42E25070BD3046611A00F00BF801300F -:1021C000EED10C233360002070BD00BFE827002053 -:1021D000E427002038B5064C002305460846236056 -:1021E00000F008F8431C02D1236803B12B6038BD0E -:1021F000F0270020094A136863B1184469468842F1 -:1022000002D8106018467047054B0C221A604FF038 -:10221000FF307047034B1360EFE700BFEC2700204F -:10222000F0270020F427002000B5194A20F00043D1 -:10223000934283B0014617DDB3F1FF4F04DBFCF797 -:10224000EDFB03B05DF804FB694601F03BF800F0DC -:102250000302012A0098019911D0022A0AD09AB1EA -:10226000012201F0F3FDECE7002101F0F3F903B0E6 -:102270005DF804FB01F0EEF900F10040E1E701F048 -:10228000E5FD00F10040DCE701F0E4F9D9E700BF2B -:10229000D80F493F30B5C0F3C754A4F17F031E2BBC -:1022A00083B0014620DC581C1BDB162B4FEAD1758E -:1022B00009DDC1F3160040F40000963CA04005B1D2 -:1022C000404203B030BD114B53F825402046FCF787 -:1022D000A7FB019001982146FCF7A0FB20F00043EA -:1022E00033B9002003B030BDFCF768FE03B030BD49 -:1022F000C0F31604C0F3C75044F40004C0F19600C4 -:1023000024FA00F0002DDCD0DAE700BF6C7A010877 -:1023100000B51D4A20F00043934283B0014618DD0A -:10232000B3F1FF4F04DBFCF779FB03B05DF804FB6E -:10233000694600F0C7FF00F00300012818D002280A -:102340000ED0D0B10098019901F084F900F100405D -:10235000EBE70021002201F079FD03B05DF804FBFA -:1023600000980199012201F071FD00F10040DCE7C5 -:102370000098019901F06EF9D7E7009801990122C0 -:1023800001F064FDD1E700BFD80F493F70B58AB0B6 -:10239000054600F023FA224C064694F9003001333A -:1023A00003D0284601F0C4FF10B930460AB070BD12 -:1023B000284601F06BFF4FF07E51FCF7F5FD002839 -:1023C000F3D0184901220023284600920893019176 -:1023D000FCF722F802460B461348CDE90423CDE969 -:1023E000022301F0ABFD94F90030CDE90601022B88 -:1023F0000BD0684601F0A0FD38B1089B53B9DDE968 -:102400000601FCF7B7FA0AB070BD02F00FF82123FD -:102410000360F2E702F00AF8089B0360EFE700BFF1 -:1024200030010020747A0108807A010800F03EBB78 -:102430002DE9F0418AB007460C4600F0C7FB9B4EE1 -:10244000054696F90030013303D0204601F070FFB5 -:1024500018B928460AB0BDE8F081384601F068FF97 -:102460008046002832D120460021FCF775FD002867 -:10247000EFD08F4A0123384601920093CDF8208097 -:10248000FBF7CAFFCDE902012046FBF7C5FF894BE8 -:1024900096F900400022CDE90623631CCDE9040132 -:1024A0000DD0022C0BD0684601F046FD002800F04C -:1024B0009A80089B1BB101F0B9FF089B0360DDE91E -:1024C0000601FCF757FA0AB0BDE8F0813846002152 -:1024D000FCF742FD18B320460021FCF73DFD804685 -:1024E000002855D0724901220023384600920893F3 -:1024F0000191FBF791FFCDE902012046FBF78CFF2C -:1025000096F9004000220023CDE90401CDE906231D -:10251000002CC8D0674B0022CDE90623CFE7284620 -:1025200001F0B8FE8046002862D028460021FCF762 -:1025300013FD00288DD0384601F0ACFE002888D06D -:10254000204601F0A7FE002883D059490422002329 -:102550003846009208930191FBF75EFFCDE9020136 -:102560002046FBF759FF96F9004000220023022C79 -:10257000CDE90401CDE9062300F08880684601F02A -:10258000DBFC002800F08280089B002B97D092E7AC -:10259000204601F07FFE00283FF45BAF204600217B -:1025A000FCF7E4FC00283FF454AF414A01233846CD -:1025B00001920093CDF82080FBF72EFFCDE90201B8 -:1025C0002046FBF729FF3478CDE904010022002CD6 -:1025D00030D0394B022CCDE906232ED101F026FF55 -:1025E00021230360D0E701F021FF2123036060E78E -:1025F000384601F04FFE002897D0204601F04AFEF1 -:10260000002892D0284601F093FE0346D8B9284905 -:1026100001223846089300920191FBF7FDFECDE9B7 -:1026200002012046FBF7F8FE3478CDE90401002CC6 -:1026300031D100220023CDE90623684601F07CFC5D -:102640000028A1D1CAE71A4A032338460093019211 -:10265000CDF82080FBF7E0FECDE902012046FBF734 -:10266000DBFE96F90030CDE90401384643BB134B3D -:102670004FF060420021CDE90623FCF777FC0028EB -:102680003FD196F90030022B7FF478AF01F0CEFEF7 -:102690002223036078E70020002102460B46FCF766 -:1026A00039F8022CCDE9060198D0C6E730010020A8 -:1026B0007C7A01080000F03F0000F0FFFFFFEF47C9 -:1026C0001C4B00220021CDE90623FCF74FFC00281B -:1026D000D7D020464FF07C51FCF7AAFAFBF79CFEBE -:1026E00004460D4601F030FC02460B4620462946C2 -:1026F000FCF7E6FF0028C4D10F4B0022CDE90623EA -:10270000BFE720464FF07C51FCF792FAFBF784FEBE -:1027100004460D4601F018FC02460B4620462946A9 -:10272000FCF7CEFF0028ACD1044B4FF06042CDE95E -:102730000623A6E70000F07F0000F0FFFFFFEFC7D1 -:1027400070B58AB0054600F031FF224C064694F978 -:102750000030013308D0284601F0EAFD20B12846B8 -:102760000021FCF703FC10B930460AB070BD1A49CD -:10277000012200232846019100920893FBF74CFEAA -:102780002478CDE90401CDE902017CB900220023BF -:10279000CDE90623684601F0CFFB88B1089BA3B9B9 -:1027A000DDE90601FCF7E6F80AB070BD0020002163 -:1027B00002460B46FBF7AEFF022CCDE90601E9D13C -:1027C00001F034FE21230360E8E701F02FFE089BAF -:1027D0000360E5E730010020847A0108F8B520F0B5 -:1027E0000043B3F17E5F044610D008DCB3F17C5F98 -:1027F00011DAB3F10C5F00F384809D48F8BD014607 -:10280000FCF70CF90146FCF7C7FAF8BD002840F3C5 -:10281000CD800020F8BD0028C0F2CA8001464FF0EC -:102820007E50FCF7FBF84FF07C51FCF701FA0446B0 -:1028300000F0BCFE8F4906462046FCF7F9F98E49A8 -:10284000FCF7EEF82146FCF7F3F98C49FCF7E6F8C3 -:102850002146FCF7EDF98A49FCF7E2F82146FCF73E -:10286000E7F98849FCF7DAF82146FCF7E1F98649EF -:10287000FCF7D6F82146FCF7DBF9844905462046EB -:10288000FCF7D6F98249FCF7C9F82146FCF7D0F9E4 -:102890008049FCF7C5F82146FCF7CAF97E49FCF7E8 -:1028A000BDF82146FCF7C4F94FF07E51FCF7B8F8AB -:1028B00001462846FCF770FA3146FCF7B9F926F4D0 -:1028C0007F6525F00F05074629462846FCF7B0F935 -:1028D00001462046FCF7A2F8294604463046FCF79C -:1028E0009FF801462046FCF757FA01463846FCF7A8 -:1028F00097F801462846FCF793F80146FCF790F854 -:10290000F8BD0146FCF794F95A490546FCF790F9E1 -:102910005949FCF785F82946FCF78AF95749FCF72D -:102920007DF82946FCF784F95549FCF779F82946E2 -:10293000FCF77EF95349FCF771F82946FCF778F962 -:102940005149FCF76DF82946FCF772F94F490646E4 -:102950002846FCF76DF94E49FCF760F82946FCF76C -:1029600067F94C49FCF75CF82946FCF761F94A49DC -:10297000FCF754F82946FCF75BF94FF07E51FCF761 -:102980004FF801463046FCF707FA01462046FCF7AF -:102990004FF901464148FCF741F801462046FCF753 -:1029A0003DF801463E48FCF739F8F8BD3D48F8BD12 -:1029B0004FF07E51FCF734F84FF07C51FCF738F9BA -:1029C0002C490446FCF734F92B49FCF729F8214639 -:1029D000FCF72EF92949FCF721F82146FCF728F9E4 -:1029E0002749FCF71DF82146FCF722F92549FCF799 -:1029F00015F82146FCF71CF92349FCF711F821468C -:102A0000FCF716F90646204600F0D0FD1F490546A2 -:102A10002046FCF70DF91E49FCF700F82146FCF7AB -:102A200007F91C49FBF7FCFF2146FCF701F91A499D -:102A3000FBF7F4FF2146FCF7FBF84FF07E51FBF764 -:102A4000EFFF01463046FCF7A7F92946FCF7F0F8FE -:102A50001249FBF7E3FF01462846FBF7E1FF014679 -:102A6000FBF7DEFF01461048FBF7D8FFF8BD00BFBB -:102A7000DB0FC93F08EF1138047F4F3A4611243D60 -:102A8000A80A4E3E90B0A63EABAA2A3E2EC69D3D59 -:102A90006133303F2D57014039D119406821A233AD -:102AA000DA0FC93FDB0F4940DA0F494021F00042FD -:102AB000B2F1FF4FF8B5044614DC20F00045B5F143 -:102AC000FF4F06460EDCB1F17E5F3AD08F1707F05C -:102AD000020747EAD07755B9022F2FD0032F2FD105 -:102AE0003148F8BD08462146FBF79AFFF8BDFAB118 -:102AF000B2F1FF4F29D0B5F1FF4F19D0AA1AD21564 -:102B00003C2A19DC002938DB2046FCF745F901F0A6 -:102B1000BDFB01F0A5FA012F2CD0022F22D0002FEF -:102B20002FD02249FBF77CFF2149FBF777FFF8BD47 -:102B3000002E15DB1F48F8BD1E48ECE71C48F8BD09 -:102B4000F8BDBDE8F84001F08BBAB5F1FF4F19D0E0 -:102B5000022FF3D0032FC3D0012F1BD00020F8BDCC -:102B60001548F8BD1149FBF75BFF01461048FBF71C -:102B700055FFF8BD00F10040F8BD3C32C4DA00203A -:102B8000C9E7F8BD022F0CD0032F08D0012F04D0C5 -:102B90000A48F8BD4FF00040F8BD0948F8BD0948A3 -:102BA000F8BD0948F8BD00BFDB0F49C02EBDBB33DF -:102BB000DB0F4940DB0FC93FDB0FC9BFDB0F493FCC -:102BC000DB0F49BFE4CB16C0E4CB16402DE9F04F34 -:102BD00031F0004987B00D460C46074611D020F071 -:102BE000004ABAF1FF4F804605DD514807B0BDE805 -:102BF000F04F01F0B7BBB9F1FF4F07DDBAF17E5FCF -:102C0000F3D14FF07E5007B0BDE8F08F002840DBD5 -:102C10000026B9F1FF4F34D0B9F17E5F4CD0B4F14A -:102C2000804F384655D0B4F17C5F1BD001F02EFBAD -:102C30000146BAF1000F1DD028F04043B3F17E5F8A -:102C400018D04FEAD87808F1FF3856EA080166D064 -:102C5000B9F19A4F74DD374B9A4533DC002C37DBE2 -:102C60000020D0E7B8F1000FE0DB07B0BDE8F04F7F -:102C700000F09CBC002C41DBB8F1000F32DB0846B1 -:102C8000C1E7BAF17E5FBCD027DD002CE8DB284627 -:102C9000B9E7B9F1974F13DAB9F17E5F0ADB4FEA72 -:102CA000E953C3F1960349FA03F202FA03F34B45E1 -:102CB00000F044820026AFE7002C25DB3846A2E76F -:102CC0000226A6E71C4B9A4540F39D82002CC7DDE7 -:102CD0001A480146FBF7ACFF95E7002CC0DA05F176 -:102CE000004090E7AAF17E5A56EA0A0A12D1084635 -:102CF000FBF794FE0146FCF74FF884E74FF07E5057 -:102D0000FCF74AF80146B7E739464FF07E50FCF72A -:102D100043F878E7012EB2D101F1004073E739465C -:102D20003846FBF77BFE0146FCF736F86BE700BF41 -:102D3000807A0108F7FF7F3F0700803FCAF24971A0 -:102D4000BAF5000F80F202824FF09741FBF770FF57 -:102D50006FF017028246B34B4FEAEA51CAF3160AE4 -:102D60007F399A4501EB020C4AF07E5740F3EB8124 -:102D7000AD4B9A4540F3428200220CF1010CA7F5BD -:102D8000000705920599A94B384653F82130CDF834 -:102D900004C0194603920493FBF740FE0499814650 -:102DA0003846FBF73DFE01464FF07E50FBF7F4FF3F -:102DB0000346194648460293FBF73AFF7910039AF7 -:102DC00041F00051BB4601F5802120F47F6727F0D8 -:102DD0000F070A448246114638460392FBF728FF44 -:102DE00001464846FBF71AFE039A814604991046AD -:102DF000FBF714FE01465846FBF710FE0146384625 -:102E0000FBF716FF01464846FBF708FE029B1946F2 -:102E1000FBF70EFF514683465046FBF709FF01467C -:102E20008146FBF705FF8249034648460293FBF7BC -:102E3000FFFE8049FBF7F4FD4946FBF7F9FE7E49AA -:102E4000FBF7EEFD4946FBF7F3FE7C49FBF7E8FD97 -:102E50004946FBF7EDFE7A49FBF7E2FD4946FBF7F1 -:102E6000E7FE7849FBF7DCFD029B01461846FBF7BD -:102E7000DFFE394681465046FBF7D2FD5946FBF747 -:102E8000D7FE4946FBF7CCFD394604903846FBF7A0 -:102E9000CFFE6D490390FBF7C3FD0499FBF7C0FD1E -:102EA00020F47F6929F00F0949463846FBF7C0FE38 -:102EB000494607465846FBF7BBFE634983464846EA -:102EC000FBF7ACFD039A1146FBF7A8FD01460498F9 -:102ED000FBF7A4FD5146FBF7ABFE01465846FBF756 -:102EE0009FFD834659463846FBF79AFD20F47F6ADA -:102EF0002AF00F0A50465549FBF79AFE544981467D -:102F00005046FBF795FE3946034650460293FBF7C1 -:102F100085FD01465846FBF781FD4E49FBF788FECB -:102F2000029B01461846FBF77BFD4B4B059A53F875 -:102F30002210FBF775FDDDF804C007466046FBF77D -:102F400023FE464B059A049053F822B03946484672 -:102F5000FBF766FD5946FBF763FD0499FBF760FD3F -:102F600020F47F6A2AF00F0A04995046FBF756FDB9 -:102F70005946FBF753FD4946FBF750FD01463846DD -:102F8000FBF74CFD24F47F6424F00F04013E56EA65 -:102F900008068146214628460CBF314F4FF07E5728 -:102FA000FBF73CFD5146FBF743FE494606462846E3 -:102FB000FBF73EFE01463046FBF732FD2146064652 -:102FC0005046FBF735FE054601463046FBF728FD27 -:102FD00000288146044620F00048AA4640F3F880C5 -:102FE000B8F1864F00F3C28000F0B280B8F17C5F88 -:102FF00000F3C4804FF00009C84624F47F6424F035 -:103000000F0420461749FBF713FE5146054620469C -:10301000FBF704FD01463046FBF700FD1249FBF7C4 -:1030200007FE23E071C41C00D6B35D009C7A010842 -:1030300042F1533E55326C3E05A38B3EABAAAA3EED -:10304000B76DDB3E9A99193F000040400038763F4B -:10305000A0C39D364F38763F947A01088C7A0108D8 -:10306000000080BF0072313F1872313F864906462A -:103070002046FBF7DDFD01463046FBF7D1FC064656 -:1030800031462846FBF7CCFC29460446FBF7C6FC34 -:1030900001463046FBF7C2FC214606462046FBF7B8 -:1030A000C7FD7A490546FBF7C3FD7949FBF7B6FC36 -:1030B0002946FBF7BDFD7749FBF7B2FC2946FBF734 -:1030C000B7FD7549FBF7AAFC2946FBF7B1FD73492B -:1030D000FBF7A6FC2946FBF7ABFD01462046FBF7B4 -:1030E0009DFC054629462046FBF7A2FD4FF0804196 -:1030F00082462846FBF792FC01465046FBF74CFE01 -:10310000314605462046FBF793FD3146FBF788FC28 -:1031100001462846FBF782FC2146FBF77FFC01466F -:103120004FF07E50FBF77AFC8144B9F5000FC0F2F6 -:10313000A58049463846FBF77BFD64E502F00102B5 -:10314000C2F1020668E5002205921BE6002202E6B3 -:1031500053493046FBF764FC294682464846FBF754 -:103160005DFC01465046FBF71FFF38B138464D491C -:10317000FBF75EFD4B49FBF75BFD44E54FEAE85882 -:10318000A8F17E084FF4000343FA08F32344C3F385 -:10319000C7524548C3F31608A2F17F0140FA01F176 -:1031A000C2F1960248F4000848FA02F8002C23EA1B -:1031B00001012846B8BFC8F10008FBF72FFC824682 -:1031C00051463046FBF72CFC4FEAC859044614E739 -:1031D000364B98450ADC7FF409AF2946FBF71EFC05 -:1031E00001463046FBF7CCFE0028C7D038463049B0 -:1031F000FBF71EFD2E49FBF71BFD04E501234FF4F1 -:1032000000120593BEE54FF07E51FBF707FC2949FC -:103210000746FBF70DFD284981463846FBF708FDB8 -:10322000394682463846FBF703FD4FF07A51834614 -:103230003846FBF7FDFC01462048FBF7EFFB39461B -:10324000FBF7F6FC01464FF07C50FBF7E7FB01462D -:103250005846FBF7EDFC1A49FBF7EAFC01465046DD -:10326000FBF7DCFB074639464846FBF7D9FB20F461 -:103270007F6A2AF00F0A494650467DE6414601F032 -:1032800075F8014656E700BF8CBEBF354CBB3133E5 -:103290000EEADD3555B38A38610B363BABAA2A3EC0 -:1032A0003CAA3833CAF24971FFFF7F000000164381 -:1032B0006042A20D00AAB83F70A5EC36ABAAAA3EA8 -:1032C0003BAAB83F2DE9F04FAB4A20F000449442AE -:1032D00089B006460D4664DDA84A94421CDC0028ED -:1032E000A74940F3EC80FBF799FBA64B24F00F04B1 -:1032F0009C42064664D0A449FBF790FB0146286037 -:103300003046FBF78BFBA049FBF788FB0123686085 -:10331000184609B0BDE8F08F9C4A944262DDB4F1D2 -:10332000FF4F46DAE715863FA4EBC7542046FBF76C -:1033300045FEFBF729FC0346014620460593FBF7B3 -:103340006DFB4FF08741FBF773FC8046FBF736FEC1 -:10335000FBF71AFC0146044640460694FBF75EFB69 -:103360004FF08741FBF764FC00210790FBF7F4FD69 -:10337000002800F0C58020460021FBF7EDFD002865 -:1033800014BF0123022382480221019000913A4692 -:1033900005A8294600F022FA002EC0F2A7800346B5 -:1033A00003E00022286000234A60184609B0BDE807 -:1033B000F08F0146FBF732FB002368602860F4E7DA -:1033C0007449FBF72BFB74490446FBF727FB0146C6 -:1033D00028602046FBF722FB6F49FBF71FFB012308 -:1033E0006860E2E700F052FF6C490746FBF720FCFB -:1033F0004FF07C51FBF714FBFBF7E0FD8246FBF737 -:10340000C3FB5F498346FBF713FC01463846FBF7D5 -:1034100005FB5D4980465846FBF70AFCBAF11F0FD1 -:1034200081464946404618DC5D4B0AF1FF3253F8AD -:10343000223024F0FF029A420FD0FBF7EFFA074642 -:103440002F6039464046FBF7E9FA4946FBF7E6FAB2 -:10345000002E686056DB5346A7E7FBF7DFFAE3155B -:10346000C0F3C7529A1A082A0746E9DD4949584667 -:103470000393FBF7DDFB074639464046FBF7CEFAE0 -:10348000044621464046FBF7C9FA3946FBF7C6FA1F -:10349000414907465846FBF7CBFB3946FBF7BEFAD6 -:1034A000814649462046FBF7B9FA039BC0F3C75251 -:1034B0009B1A192B074641DC2860A046C1E7FBF7A1 -:1034C000AFFA304B24F00F049C42064623D02E491D -:1034D000FBF7A6FA014628603046FBF79FFA2A4917 -:1034E000FBF79EFA4FF0FF3368605EE795E80C004B -:1034F00003F1004102F1004243422A60696054E74F -:10350000032340E707F1004700F100402F606860A7 -:10351000CAF1000349E71F49FBF782FA1E49044636 -:10352000FBF77EFA014628602046FBF777FA1A4936 -:10353000FBF776FA4FF0FF33686036E719495846D3 -:10354000FBF776FB074639462046FBF767FA8046CD -:1035500041462046FBF762FA3946FBF75FFA12490B -:1035600004465846FBF764FB2146FBF757FA8146B1 -:103570004946404661E700BFD80F493FE3CB1640BC -:10358000800FC93FD00FC93F43443537800F4943AF -:10359000247B01080044353708A3852E84F9223F97 -:1035A000A47A010800A3852E32318D2420F0004238 -:1035B000B2F1FF4FF8B5044603462DD25AB30028A6 -:1035C0003DDBB2F5000F4FEAE0502CD37F38C3F358 -:1035D0001603C20743F4000348BF5B0000274010F6 -:1035E0005B003E4619244FF08072B5189D4202DC04 -:1035F0005B1BAE181744013C4FEA43034FEA5202EB -:10360000F3D113B107F001031F447F1007F17C577A -:1036100007EBC050F8BDF8BD0146FBF709FB21469A -:10362000FBF7FEF9F8BD14F400020FD15B0019029C -:1036300002F10102FAD5C2F101021044C6E70146C7 -:10364000FBF7ECF90146FBF7A7FBF8BD012210449C -:10365000BCE700BF2DE9F84320F00046B6F1485F13 -:1036600005460F4649DAFBF7A9FC002800F09D80CB -:1036700029462846FBF7DCFA4E490446FBF7D8FA00 -:103680004D49FBF7CDF92146FBF7D2FA4B49FBF741 -:10369000C5F92146FBF7CCFA4949FBF7C1F92146A8 -:1036A000FBF7C6FA4749FBF7B9F92146FBF7C0FA21 -:1036B0004549FBF7B5F92146FBF7BAFA80462046A3 -:1036C0004FF07C51FBF7B4FA414606462046FBF723 -:1036D000AFFA394604462846FBF7AAFA01462046C7 -:1036E000FBF79CF901463046FBF798F901464FF08D -:1036F0007E50FBF793F9BDE8F8830146FBF798FA93 -:103700002C490446FBF794FA2B49FBF789F921462B -:10371000FBF78EFA2949FBF781F92146FBF788FA76 -:103720002749FBF77DF92146FBF782FA2549FBF78C -:1037300075F92146FBF77CFA2349FBF771F921461D -:10374000FBF776FA214B80469E42B8DD204B9E4225 -:1037500027DC06F17F4631464FF07E50FBF75EF9DD -:10376000814620464FF07C51FBF762FA3146FBF769 -:1037700055F9414606462046FBF75AFA39460446B3 -:103780002846FBF755FA01462046FBF747F9014664 -:103790003046FBF743F901464846FBF73FF9BDE8E1 -:1037A000F883DFF834900B4EDBE74FF07E50BDE836 -:1037B000F88300BF4ED747ADF6740F317CF29334D7 -:1037C000010DD037610BB63AABAA2A3D9999993EC3 -:1037D0000000483F0000903E0000383F2DE9F04FC8 -:1037E000DFB00B93013B0293D31E48BF131DB84CAF -:1037F00006466898DB1054F8204023EAE3730C93E4 -:10380000DB4302EBC30308940693089C029B0C9ACB -:103810001D190991C3EB02071DD4699C3D4404EBBB -:10382000870901354FF0000822AC0AE059F808007A -:10383000FBF7AAF90137AF4244F8080008F1040881 -:1038400009D0002FF2DA01370020AF4244F8080017 -:1038500008F10408F5D1089A002AC0F2DF82089A1C -:103860000B9B02F101089C0022AF4FEA8808274415 -:103870000025029A002AC0F2F28105EB070B4FF0F7 -:1038800000094FF0000A56F809005BF8041DFBF729 -:10389000CFF901465046FBF7C3F809F10409A145E9 -:1038A0008246F0D14AA840F805A004354545E0D14C -:1038B000089A0EAB03EB82030D9391464FEA8903FE -:1038C0000793079A5EAB1344B9F1000F53F850AC5D -:1038D00023DD0DF134084AAF174490440DAD4FF08D -:1038E0006E515046FBF7A4F9FBF768FBFBF74CF968 -:1038F0004FF087418346FBF79BF901465046FBF7A3 -:103900008DF8FBF75BFB594645F8040F57F8040D9B -:10391000FBF786F845458246E1D15046069900F00E -:1039200025FD4FF078510546FBF782F900F0BAFC0F -:103930004FF08241FBF77CF901462846FBF76EF811 -:103940000546FBF73BFB8246FBF71EF9014628467E -:10395000FBF764F8069A8046002A40F3678109F174 -:10396000FF310EA850F82130C2F1080043FA00F2EE -:1039700002FA00F01B1A06989244C0F1070743FAB6 -:1039800007F70EA840F82130002F32DDB9F1000F03 -:103990000AF1010A40F375810EAB079A19461144EA -:1039A000002507E0C2F5807012B143F8040C012530 -:1039B0008B420BD053F8042B002DF3D0C2F1FF0241 -:1039C0008B4243F8042C4FF00105F3D1069B002BEA -:1039D0000DDD012B00F03281022B08D109F1FF33FC -:1039E0000EA951F8232002F03F0241F82320022FB4 -:1039F00070D040460021FBF7AFFA002800F083802A -:103A0000089A09F1FF35AA420DDC079A0EAB0D9812 -:103A10001344002253F8041D834242EA0102F9D103 -:103A2000002A40F0E481089B0EA85A1E50F822306C -:103A3000002B40F0F18100EB8202012352F8041DBB -:103A400001330029FAD04B4499450A933DDADDF859 -:103A50002CA022AACA44DDF8308002EB8A02C844B6 -:103A6000C9EB0309131D03920593699A079B4FEA5B -:103A700089094AAF02EB8808CDF810901F44002551 -:103A800058F8040FFBF780F8029B039A002B505163 -:103A90004FF0000B13DBDDF814A04FF00009AA442F -:103AA00056F809005AF8041DFBF7C2F801465846BB -:103AB000FAF7B6FF09F10409A1458346F0D1049A4B -:103AC0000435954247F804BFDAD1DDF82890F5E6D1 -:103AD0003C7E010841464FF07E50FAF79FFF80463A -:103AE000002D86D006994FF07E5000F03FFC014635 -:103AF0004046FAF793FF804640460021FBF72CFA38 -:103B000000287FF47DAF069B40465942CDF808A0BF -:103B100000F02CFC4FF087410446FBF73BFA0028ED -:103B200000F07F814FF06E512046FBF781F8FBF7E4 -:103B300045FAFBF729F84FF087410546FBF778F87F -:103B400001462046FAF76AFFFBF738FA0EAB43F856 -:103B500029002846FBF732FA069C09F101050834D2 -:103B60000EA9069441F8250006994FF07E5000F00A -:103B7000FDFB002D04464FDB6E1C4FEA8508C6EBAB -:103B8000867A0DF138094AABC1444FEA8A0A984453 -:103B90004FF0000B59F80B00FAF7F6FF2146FBF740 -:103BA00047F84FF06E5148F80B002046FBF740F8FD -:103BB000ABF1040BD3450446ECD1DFF88C92DDF871 -:103BC00020A00024B34603950497BAF1000FB8BFB4 -:103BD000002515DB00263746002501E0A7420FDC53 -:103BE00058F8061059F80600FBF722F80146284657 -:103BF000FAF716FF0137BA45054606F10406EDDA75 -:103C00005EA800EB84030134A345A8F1040843F83F -:103C1000A05CDAD1039D049F689C032C00F298807D -:103C2000DFE814F0CB009C009C00310010D109F1BA -:103C3000FF330EA951F823703F12A5E609F1FF33B7 -:103C40000EA850F8232002F07F0240F82320CEE691 -:103C50004FF07C51FBF79EF958B90746C9E64FF083 -:103C6000000A4AA840F805A0043545457FF401AE96 -:103C70001EE6B9F1000F4FF002070AF1010A3FF703 -:103C80008BAE0025A2E6002D40F3DC804FEA850BC9 -:103C90005EAB36AE05F1FF3A5B4406EB8A0A53F899 -:103CA000A08C54465B4635AABB462F4600E0C8466A -:103CB00054F804594146284601920093FAF7B0FEA1 -:103CC000814649462846FAF7A9FE4146FAF7A8FE7A -:103CD000019AC4F804909442A060009BE7D13D464D -:103CE000012D5F469B4640F3AD805EAB9B445BF885 -:103CF000A04C00E044465AF8049921464846FAF799 -:103D00008FFE804641464846FAF788FE2146FAF77C -:103D100087FE5645CAF80480CAF80800EAD16C1C30 -:103D200006EB84040020083654F8041DFAF778FEE8 -:103D3000B442F9D1002F7ED0369A379B099C00F10E -:103D4000004002F1004203F10043A0602260636082 -:103D5000029A02F007005FB0BDE8F08F002DB8BFF7 -:103D600000200ADB36AE6C1C002006EB840454F8FD -:103D7000041DFAF755FEB442F9D1002F35D000F1F9 -:103D80000043099C014623603698FAF747FE002D50 -:103D900008DD36AC04EB850554F8041FFAF740FE45 -:103DA000AC42F9D10FB100F10040099A5060029A7B -:103DB00002F007005FB0BDE8F08F002D39DB6C1C0E -:103DC00036AE002006EB840454F8041DFAF728FEF2 -:103DD000B442F9D10FB100F10040099A1060029A83 -:103DE00002F007005FB0BDE8F08F0346C9E7069A0E -:103DF0000EAC54F82530083ACDF808A00692002BF6 -:103E00007FF4B2AE04EB850353F8041D013D083A7C -:103E10000029F9D00692A7E6012314E60B9B9C002B -:103E200046E52046FBF7CAF80EAA4D4642F829009F -:103E30009AE60020CEE7099C369A379BA060226064 -:103E4000636085E7002075E7487E01082DE9F843A7 -:103E500020F00043B3F1485F04460F46904603DA72 -:103E6000FBF7ACF8002857D021462046FAF7E0FED1 -:103E700021460546FAF7DCFE294906462846FAF7A8 -:103E8000D7FE2849FAF7CAFD2946FAF7D1FE264996 -:103E9000FAF7C6FD2946FAF7CBFE2449FAF7BEFD2C -:103EA0002946FAF7C5FE2249FAF7BAFD8146B8F16C -:103EB000000F22D038464FF07C51FAF7B9FE494640 -:103EC00080463046FAF7B4FE01464046FAF7A6FDB2 -:103ED0002946FAF7ADFE3946FAF7A0FD1549054621 -:103EE0003046FAF7A5FE01462846FAF799FD014645 -:103EF0002046FAF793FDBDE8F88349462846FAF7CD -:103F000097FE0C49FAF78AFD3146FAF791FE2146F1 -:103F1000FAF786FDBDE8F8832046BDE8F88300BFC8 -:103F2000D3C92E2F342FD7321BEF3836010D50391D -:103F30008988083CABAA2A3E00207047002001492E -:103F4000704700BF0000F87F2DE9F043C1F30A5C21 -:103F5000ACF2FF37132F83B002460B460D4689465D -:103F600080464FEAD17630DC002F4CDB3A493941AC -:103F700001EA030010432DD0490801EA030858EA7A -:103F800002080CD04FF480233B41132F25EA010196 -:103F900041EA030914BF4FF000084FF000482F49D1 -:103FA0004B4601EBC606D6E9004542462046294667 -:103FB000FAF7D4F8CDE90001DDE9000122462B46ED -:103FC000FAF7CAF803B0BDE8F083332F07DDB7F581 -:103FD000806F3ED01046194603B0BDE8F083ACF2C6 -:103FE000134C4FF0FF3121FA0CF10142F2D0490895 -:103FF0000142D4D04FF0804848FA0CFC20EA01017D -:1040000041EA0C08CBE721F000410143E2D0C3F3C1 -:10401000130101434C420C431048590C240B490432 -:1040200004F4002444EA010300EBC601D1E9004591 -:1040300020462946FAF792F8CDE90001DDE90001B2 -:104040002B462246FAF788F821F0004343EAC6716E -:10405000C2E7FAF783F8BFE7FFFF0F00787E010899 -:104060002DE9F04120F00045B5F1A14F0446064688 -:1040700008DBB5F1FF4F6FDC002840F3A0806F48EC -:10408000BDE8F0816E4B9D4277DCB5F1445F68DBA3 -:104090004FF0FF3721462046FAF7CAFD0146804619 -:1040A000FAF7C6FD67490546FAF7C2FD6649FAF711 -:1040B000B7FC2946FAF7BCFD6449FAF7B1FC29467A -:1040C000FAF7B6FD6249FAF7ABFC2946FAF7B0FDFC -:1040D0006049FAF7A5FC2946FAF7AAFD5E49FAF706 -:1040E0009FFC4146FAF7A4FD5C4980462846FAF752 -:1040F0009FFD5B49FAF792FC2946FAF799FD594969 -:10410000FAF78CFC2946FAF793FD5749FAF786FC33 -:104110002946FAF78DFD5549FAF780FC2946FAF74A -:1041200087FD7B1C014640464CD0FAF779FC2146BE -:10413000FAF77EFD4E4B4F4D53F82710FAF76EFC01 -:104140002146FAF76BFC014655F82700FAF766FCA2 -:10415000002E30DBBDE8F0810146FAF761FCBDE8D6 -:10416000F0814549FAF75CFC4FF07E51FAF71CFFED -:1041700000288DD02046BDE8F08100F087F83F4B45 -:1041800004469D4229DCA3F5D0039D4244DC014650 -:10419000FAF746FC4FF07E51FAF740FC4FF08041B1 -:1041A00005462046FAF73CFC01462846FAF7F4FD9E -:1041B000002704466EE700F10040BDE8F08130487A -:1041C000BDE8F081FAF72CFC2146FAF731FD0146F3 -:1041D0002046FAF723FCBDE8F0812A4B9D4214DC0F -:1041E0004FF07F51FAF71AFC4FF07F5105462046F9 -:1041F000FAF71EFD4FF07E51FAF712FC01462846F1 -:10420000FAF7CAFD0227044644E701461E48FAF7BA -:10421000C3FD032704463DE74FF07E51FAF7FEFB4E -:104220004FF07E5105462046FAF7FAFB0146284634 -:10423000FAF7B2FD012704462CE700BFDB0FC93FA8 -:10424000FFFFDF3ED769853C59DA4B3D356B883D32 -:104250006E2EBA3D2549123EABAAAA3E21A215BD3B -:104260006BF16E3D95879D3D388EE33DCDCC4C3E48 -:10427000887E0108987E0108CAF24971FFFF973FC6 -:10428000DB0FC9BFFFFF1B40000080BF20F00040D4 -:10429000704700BF20F00040B0F1FF4FACBF0020DE -:1042A000012070472DE9F04120F00047FD0D7F3DD2 -:1042B000162D064613DC002D80461BDB194F2F41BF -:1042C000074214D01849FAF7ABFB0021FAF76CFE4D -:1042D00068B1002E1BDB28EA0700BDE8F081B7F1CA -:1042E000FF4F04D30146FAF79BFBBDE8F08130464F -:1042F000BDE8F0810C49FAF793FB0021FAF754FE70 -:104300000028F4D0002E08DB0020BDE8F0814FF437 -:10431000000343FA05F5A844DDE7002FE7D0034882 -:10432000BDE8F081FFFF7F00CAF24971000080BF45 -:1043300030F0004001D102207047A0F50003B3F136 -:10434000FE4F01D204207047054B421E9A4201D80D -:1043500003207047B0F1FF4358425841704700BFF7 -:10436000FEFF7F00004870470000C07F38B530F086 -:104370000044024603460D4614D0B4F1FF4F0DD25F -:10438000B4F5000F0FD3E40D2C44FE2C2EDC002CD2 -:104390001DDD23F0FF4343EAC45038BD0146FAF760 -:1043A0003FFB38BD38BD4FF09841FAF741FC194B3F -:1043B00002469D4207DBC0F3C7540346193CE3E7BE -:1043C000154800F02DF81449FAF732FC38BD14F105 -:1043D000160F13DA4CF250339D421146F0DD0F48B0 -:1043E00000F01EF80D49FAF723FC38BD11460B48C2 -:1043F00000F016F80949FAF71BFC38BD04F1190062 -:1044000023F0FF4343EAC0504FF04C51FAF710FC41 -:1044100038BD00BFB03CFFFF6042A20DCAF2497137 -:1044200001F0004120F0004008437047014B18683C -:10443000704700BF2C010020780000FF000000FF43 -:104440003C0000FFF00000FF0001746564666D6AC7 -:1044500069736C67010B020D0A03050B030D0A0358 -:10446000070B030D0A03090B020D0A030A0B040DC7 -:104470000A03080B040D0A031E0000FF4A0100FF97 -:104480002C0100FF0E0100FFD20000FFB40000FF6E -:10449000960000FF5A0000FF0000FFFF5C6001086B -:1044A000984401083C44010878440108404401084C -:1044B0009444010838440108904401088C440108E0 -:1044C00088440108444401088444010880440108E8 -:1044D0007C4401080800000000200000000C01409E -:1044E000100000000020000000100140000C0140FE -:1044F00008001002000C014010001002000C0140E6 -:10450000040014020000000000000000030100008D -:10451000084B010804000000C84A0108040000001C -:10452000884A010802010000684A010800010000F1 -:104530000000000006000000084A01080600000014 -:10454000A84901080101000000000000040000006B -:104550006849010806000000084901080800000039 -:104560008848010808000000084801080800000009 -:104570008847010801010000000000000001000060 -:104580000000000000010000000000000400000026 -:104590004847010806000000E84601080001000045 -:1045A0000000000002010000C846010801010000EF -:1045B000000000000000000000000000AA46010802 -:1045C00092460108744601085C460108A59E000851 -:1045D000619E00083D9E0008159E0008059E00088B -:1045E00055E00008919E0008B59D0008859E0008D2 -:1045F000779E00080000000000C201004061010831 -:10460000636101080100000000E100007861010819 -:104610009A6101080200000000960000AE610108E6 -:10462000D061010803000000004B0000E4610108B4 -:104630000662010804000000802500000D690108E1 -:104640000D690108000100020002000009170000C6 -:104650000100020002000000010700000001080341 -:1046600009030A040B040C040D04040405040604E5 -:104670000704FFFF00020102020203020402050216 -:1046800006020702080309030A040B040C040D04C4 -:10469000FFFF0001080309030A030B030C030D03CA -:1046A0000403050306030703FFFF000201020202E1 -:1046B00003020402050206020702080309030A03B3 -:1046C0000B030C030D03FFFF0000803F0000000000 -:1046D00000000000000080BF0000803F00000000DC -:1046E000000000000000803F0000803F000080BF0D -:1046F0000000803F000080BF0000803F000080BFBE -:10470000000080BF0000803F0000803F0000803F2D -:104710000000803F0000803F0000803F0000803F9D -:10472000000080BF000080BF0000803F000000004C -:1047300000000000000000000000803F00000000BA -:1047400000000000000000000000803F00000000AA -:104750000000803F0000803F0000803F000080BFDD -:10476000000080BF000000000000803F000000004B -:104770000000803F000080BF0000803F0000803FBD -:10478000000080BF000000800000803F0000803FEC -:10479000000000BF0000803F0000803F000000BF1D -:1047A000000080BF0000803F0000803F000080BF0D -:1047B0000000003F0000803F0000803F0000003FFD -:1047C0000000803F0000803F0000803F0000003F6D -:1047D000000080BF000080BF0000803F000080BF5D -:1047E000000000BF000080BF0000803F000000BF4D -:1047F0000000803F000080BF0000803F0000803F3D -:104800000000003F000080BF0000803FF704353FFC -:10481000F70435BF0000803F0000803FF70435BF3C -:10482000F70435BF0000803F0000803FF70435BF2C -:10483000F704353F0000803F0000803FF704353F1C -:10484000F704353F0000803F0000803F000000007B -:10485000000080BF000080BF0000803F000080BFDC -:1048600000000000000080BF0000803F000000004A -:104870000000803F000080BF0000803F0000803FBC -:1048800000000000000080BF0000803F000080BFEB -:104890000000803F000080BF0000803F000080BF1C -:1048A000000080BF0000803F0000803F0000803F8C -:1048B0000000803F0000803F0000803F0000803FFC -:1048C000000080BF000080BF0000803F000080BF6C -:1048D0000000803F0000803F0000803F000080BF5C -:1048E000000080BF000080BF0000803F0000803FCC -:1048F0000000803F000080BF0000803F0000803F3C -:10490000000080BF0000803F0000803F000000BF2B -:10491000D0B35D3F0000803F0000803F000000BF3B -:10492000D0B35DBF0000803F0000803F0000003F2B -:10493000D0B35D3F000080BF0000803F0000003F1B -:10494000D0B35DBF000080BF0000803F000080BF8B -:1049500000000000000080BF0000803F0000803F9A -:10496000000000000000803F0000803F00000000C9 -:104970000000803F000080BF0000803F000080BF3B -:10498000000080BF000000000000803F0000000029 -:104990000000803F0000803F0000803F0000803F1B -:1049A000000080BF000000000000803FD0B35DBF6A -:1049B0000000003F0000803F0000803FD0B35DBF9B -:1049C000000000BF000080BF0000803FD0B35D3F0B -:1049D0000000003F0000803F0000803FD0B35D3FFB -:1049E000000000BF000080BF0000803F000000000A -:1049F000000080BF0000803F0000803F00000000FA -:104A00000000803F000080BF0000803F00000000E9 -:104A1000A8AAAA3F0000803F0000803F000080BF9E -:104A2000B0AA2ABF000080BF0000803F0000803F86 -:104A3000B0AA2ABF000080BF0000803F0000000035 -:104A4000A8AAAA3F000080BF0000803F000080BFEE -:104A5000B0AA2ABF0000803F0000803F0000803FD6 -:104A6000B0AA2ABF0000803F0000803F0000803FC6 -:104A700000000000000000000000803F000080BF38 -:104A800000000000000000000000803F000080BF28 -:104A90000000803F000080BF0000803F000080BF1A -:104AA000000080BF0000803F0000803F0000803F8A -:104AB0000000803F0000803F0000803F0000803FFA -:104AC000000080BF000080BF0000803F00000000A9 -:104AD0000000803F000080BF0000803F000080BFDA -:104AE000000000000000803F0000803F0000803F89 -:104AF000000000000000803F0000803F0000000038 -:104B0000000080BF000080BF0000803F0000000068 -:104B1000A8AAAA3F000000000000803F000080BF5C -:104B2000B0AA2ABF000000000000803F0000803FC4 -:104B3000B0AA2ABF00000000100000000020000002 -:104B4000001001400040000000100140010001027F -:104B50000001030001040001050001060001070037 -:104B6000010800010900010A00010B00010C01030A -:104B7000000000001A6201080000000001000000AF -:104B80001F62010801000000020000002662010807 -:104B900002000000030000002F6201080300000073 -:104BA0000400000035620108050000000500000057 -:104BB0003A62010806000000060000004462010895 -:104BC00007000000070000004D6201080800000017 -:104BD00008000000566201080900000009000000FA -:104BE0005F6201080A0000000A0000006962010813 -:104BF0000B0000000B000000736201080C000000B5 -:104C00000C0000007D6201080D0000000D00000096 -:104C1000856201080E0000000E0000008D62010890 -:104C20000F0000000F000000956201081000000056 -:104C3000100000009E620108110000001100000039 -:104C4000A56201081200000012000000AF62010816 -:104C50001300000013000000B762010814000000F8 -:104C600014000000C26201081500000015000000D9 -:104C7000CC620108160000001600000000000000D1 -:104C8000FF000000B56206010300F00500FF19B542 -:104C90006206010300F00300FD15B5620601030082 -:104CA000F00100FB11B56206010300F00000FA0FED -:104CB000B56206010300F00200FC13B562060103B1 -:104CC00000F00400FE17B562060103000102010EA8 -:104CD00047B562060103000103010F49B5620601F1 -:104CE0000300010601124FB5620601030001120123 -:104CF0001E67B56206080600C80001000100DE6AF2 -:104D000000B562061608000307030000000000312A -:104D1000E501B5620616080003070300510800000C -:104D20008A4102B562061608000307030004E00486 -:104D300000199D03B5620616080003070300000270 -:104D4000020035EF04B56206160800030703008071 -:104D5000010000B2E80040008000000100020004F1 -:104D600049574641540102040810204E45535755F7 -:104D7000442C3A3A00000000482050726F6475637A -:104D8000743A426C61636B626F7820666C69676825 -:104D9000742064617461207265636F72646572204F -:104DA0006279204E6963686F6C6173205368657225 -:104DB0006C6F636B0A4820426C61636B626F782092 -:104DC00076657273696F6E3A310A48204461746186 -:104DD0002076657273696F6E3A310A009665010834 -:104DE000D06601081B67010869670108B6670108FA -:104DF000046801088B6501084F6801080263010817 -:104E00004F680108946501084F6801084820466909 -:104E1000656C642047206E616D653A4750535F6E44 -:104E2000756D5361742C4750535F636F6F72645B91 -:104E3000305D2C4750535F636F6F72645B315D2C44 -:104E40004750535F616C7469747564652C475053A7 -:104E50005F73706565640A48204669656C64204725 -:104E6000207369676E65643A302C312C312C302CFC -:104E7000300A48204669656C64204720707265647A -:104E80006963746F723A302C372C372C302C300A0F -:104E900048204669656C64204720656E636F6469CD -:104EA0006E673A312C302C302C312C310A48204698 -:104EB00069656C642048206E616D653A4750535FA8 -:104EC000686F6D655B305D2C4750535F686F6D6533 -:104ED0005B315D0A48204669656C6420482073692F -:104EE000676E65643A312C310A48204669656C6406 -:104EF000204820707265646963746F723A302C3098 -:104F00000A48204669656C64204820656E636F64BA -:104F1000696E673A302C300A000002020308050A65 -:104F20000B080A0A0B0C0E0E0F0000000054004084 -:104F3000000C0140400080001F2000000000200005 -:104F400000580040000C014000040008212200002D -:104F500000004000000000000000004F00000007BB -:104F6000000700147F147F14242A7F2A12231308B9 -:104F7000646236495522500005030000001C22419E -:104F8000000041221C0014083E081408083E0808CE -:104F90000050300000080808080800606000002089 -:104FA000100804023E5149453E00427F40004261E4 -:104FB0005149462141454B311814127F1027454570 -:104FC00045393C4A49493001710905033649494987 -:104FD00036064949291E00363600000056360000C4 -:104FE000081422410014141414140041221408025D -:104FF00001510906324979413E7E1111117E7F49E6 -:105000004949363E414141227F4141221C7F494965 -:1050100049417F090909013E4149497A7F08080849 -:105020007F00417F41002040413F017F0814224121 -:105030007F404040407F020C027F7F0408107F3E8B -:105040004141413E7F090909063E4151215E7F09E8 -:10505000192946464949493101017F01013F404034 -:10506000403F1F2040201F3F4038403F631408143A -:105070006307087008076151494543007F414100BB -:1050800002040810200041417F0004020102044094 -:1050900040404040010204000020545454787F48AE -:1050A0004444383844444420384444487F385454B5 -:1050B0005418087E090102064949493F7F08040443 -:1050C0007800447D40002040443D007F102844008B -:1050D00000417F40007C0418047C7C08040478387C -:1050E000444444387C14141408081414187C7C08B4 -:1050F0000404084854545420043F4440203C404099 -:10510000207C1C2040201C3C4030403C442810287F -:10511000440C5050503C4464544C44000836410008 -:1051200000007F0000004136080002010204023E38 -:1051300055554122000000000000007900001824AD -:10514000742E24487E4942405D2222225D15167C41 -:10515000161500007700000A55555528000100017A -:1051600000000A0D0A0408142A1422040404041C72 -:1051700000080808000101010101000205020044C5 -:10518000445F444400000402017E2020103E060FCC -:105190007F007F00181800000040502000000A0D1A -:1051A0000A0022142A14081708342A7D1708046AF2 -:1051B00059304845402042004200427E42004200B1 -:1051C0007E7E0042007E7E7E42007E7E7E7E007E6F -:1051D0007E7E7E7E00011E1E646464646464220020 -:1051E000460221008201200043021000010100005C -:1051F00049020100880102004C02120084011100E2 -:105200009001110090011100A0011100A001000007 -:10521000524F4C4C3B50495443483B5941573B41FA -:105220004C543B506F733B506F73523B4E61765200 -:105230003B4C4556454C3B4D41473B56454C3B004E -:1052400004630108FB620108EF6201081F9F000868 -:105250003D9F0008599F00082DAF0008859F00085A -:10526000919F0008020000008025000000C201009C -:1052700000000000200000008025000000C20100A6 -:1052800001000000400000008025000000C2010075 -:1052900000000000010000008025000000C20100A5 -:1052A00000000000100000008025000000C2010086 -:1052B000000300000400000080250000004B0000F7 -:1052C000000000000800000000E1000000E1000014 -:1052D000000400008000000000C2010000C20100C4 -:1052E00000000000E36A0108E86A0108EC6A0108AE -:1052F000FF6A0108F16A0108F76A0108FB6A010800 -:10530000000000000D6901089F6A0108A76A0108F2 -:10531000AF6A0108B76A0108BE6A0108C96A0108D4 -:10532000D16A0108D96A0108DE6A0108000000009C -:105330009001C800C800C800C800C800C800C80064 -:10534000C80064000000C800C800C800C8003200DF -:1053500019AC0008ED9E0008BB9E0008518D0008A6 -:10536000099F00084D8D0008FC6D0108006E0108C2 -:10537000066E01080C6E01080F6E0108166E01081A -:10538000196E01081E6E01082A6E01082D6E0108B3 -:10539000336E01083A6E0108446E01084E6E010832 -:1053A000576E0108656E0108716E0108786E01087C -:1053B0007E6E01088B6E0108966E0108A36E0108CF -:1053C000000000004A6D0108516D0108566D01088A -:1053D000676D0108716D01087C6D0108876D01081A -:1053E000F76A0108926D0108F16A01089B6D0108D6 -:1053F000A56D0108B36D0108B66D0108C66D010801 -:10540000CD6D0108D66D0108E06D0108E86D010859 -:10541000F36D010800000000E56E0108EE6E010862 -:10542000D9B30008126F0108166F01080DB5000806 -:105430002C6F0108316F01081D570008456F0108E6 -:105440004B6F0108FDBE0008246901085C6F01086C -:105450009D890008796F01087E6F0108BDC80008AA -:10546000AD6F01080D690108A97C0008B26F010841 -:10547000BA6F01089D910008CE6F0108D26F010834 -:1054800025550008E56F0108F46F0108EDCC000810 -:105490000E7001080D6901082D54000813700108F1 -:1054A00017700108315F0008267001082A70010892 -:1054B000AD5900083F6F010846700108C1BD0008E2 -:1054C000597001085F7001085DBE00081B77010874 -:1054D0007A70010871C80008897001087A700108A3 -:1054E00081830008957001089A700108D57C000836 -:1054F000D7630108AA70010885550008D870010813 -:10550000CC70010881B20008E17401080D6901083E -:10551000FD53000805040203000000008025000080 -:1055200000C201000600000001000000802500000C -:1055300000C20100070000000300000080250000F9 -:10554000004B00000900000004000000802500005E -:10555000004B000009000000EB710108440000004E -:10556000382000200000000028230000F47101080A -:10557000410000003A20002000000000010000006F -:10558000027201084400000046210020B00400001F -:10559000A406000009720108440000004821002010 -:1055A00000000000D0070000137201084400000052 -:1055B0004A21002000000000D00700001D720108F1 -:1055C000420000004C2100200000000012000000FA -:1055D0002A720108420000004D2100200100000055 -:1055E000FF00000035720108420000004E2100203B -:1055F00000000000010000004A72010844000000A1 -:10560000FC20002000000000D007000057720108B5 -:1056100044000000FE20002000000000D007000031 -:105620006472010844000000002100200000000016 -:10563000D007000070720108440000000221002021 -:1056400000000000D0070000807201084400000044 -:105650000421002000000000D00700009172010822 -:10566000440000000621002000000000D0070000D8 -:105670009C72010844000000082100200000000086 -:10568000D0070000B1720108440000000A21002088 -:1056900032000000007D0000C072010844000000DC -:1056A0000C21002032000000F2010000CF7201083E -:1056B000410000004F210020000000000100000018 -:1056C000DC720108410000005021002000000000B1 -:1056D00001000000EF72010841000000512100208C -:1056E00000000000B4000000FB720108410000004F -:1056F0005221002000000000640000000773010830 -:105700004200000053210020FFFFFFFF01000000C6 -:105710001D73010841000000582100200000000016 -:105720000B000000347301084100000059210020E3 -:10573000000000000B0000004B7301084100000056 -:105740005A210020000000000B00000062730108D5 -:10575000410000005B210020000000000B00000061 -:1057600079730108410000006C2100203000000026 -:105770007E0000008A730108500000005C210020B8 -:10578000B004000000C2010097730108500000003F -:1057900060210020B004000000C20100A4730108D1 -:1057A00050000000642100200000000000C2010041 -:1057B000B17301085000000068210020B00400000F -:1057C00000C20100CA7301084100000054210020FA -:1057D0000000000001000000D77301084100000034 -:1057E000552100200000000004000000E5730108BE -:1057F00041000000562100200000000001000000D0 -:10580000F57301088100000048220020000000001C -:10581000C8000000FF730108810000005222002030 -:1058200000000000C80000000974010881000000A9 -:105830005C22002000000000C80000001374010872 -:10584000810000004922002000000000C800000084 -:105850001E74010881000000532200200000000097 -:10586000C800000029740108810000005D220020AA -:1058700000000000C800000034740108810000002E -:105880004A22002000000000C80000003E74010809 -:10589000810000005422002000000000C800000029 -:1058A00048740108810000005E2200200000000012 -:1058B000C80000005274010884000000F223002098 -:1058C00000000000D00700006074010881000000A3 -:1058D000F62300200000000001000000757401089C -:1058E00084000000F82300200A000000D007000018 -:1058F0008374010884000000FA2300200A000000DD -:10590000D00700009174010881000000F5230020F9 -:1059100000000000640000009F74010841000000C6 -:10592000442100200000000003000000B1740108C1 -:105930004100000070210020000000000300000072 -:10594000C474010841000000712100200000000023 -:1059500001000000D5740108410000007221002000 -:105960000000000001000000E97401086000000070 -:1059700074210020A6FFFFFF5A00000001750108F6 -:1059800060000000782100204CFFFFFFB400000001 -:1059900019750108410000007C2100200000000072 -:1059A0000100000032750108410000007D21002047 -:1059B00000000000010000003D75010844000000E7 -:1059C0003A21002000000000204E00004E75010822 -:1059D000410000003021002000000000FF00000016 -:1059E0005975010841000000312100200A00000023 -:1059F000320000006F7501084100000032210020D4 -:105A00000A00000032000000857501084400000013 -:105A100034210020010000001027000099750108C2 -:105A20004400000036210020000000007206000043 -:105A3000AE75010841000000382100200000000080 -:105A400001000000CC750108410000000E2100207B -:105A50000000000008000000D775010841000000A8 -:105A60000F2100200000000008000000E17501087F -:105A7000410000001021002000000000080000008C -:105A8000EB75010848000000122100204CFFFFFFC9 -:105A900068010000FC750108480000001421002086 -:105AA0004CFFFFFF680100000E760108480000006F -:105AB000162100204CFFFFFF680100001E76010840 -:105AC0004400000022210020640000008403000044 -:105AD00034760108440000001A2100200000000074 -:105AE000000100003D760108410000002021002057 -:105AF00000000000800000004D7601084400000016 -:105B00001C21002064000000E80300005E7601080C -:105B1000440000001E21002064000000E803000093 -:105B200070760108810000009F2300200100000022 -:105B3000FA0000008276010881000000A023002006 -:105B400000000000010000007976010881000000DB -:105B50009D2300200000000020000000977601082F -:105B6000810000009E23002000000000640000006F -:105B7000A476010881000000A4230020000000009A -:105B800096000000BE76010884000000A2230020D9 -:105B90000100000084030000D876010842000000E4 -:105BA00018210020FFFFFFFF01000000EE76010832 -:105BB00082000000EE230020FFFFFFFF0100000035 -:105BC000FC76010882000000EF23002000000000A6 -:105BD000010000000E7701088100000090220020E3 -:105BE000000000000200000023770108010100000E -:105BF0008227002000000000FA0000002B77010837 -:105C00000101000083270020000000006400000064 -:105C10003377010801010000842700200000000004 -:105C2000640000003B770108010100008527002087 -:105C3000000000006400000044770108010100003A -:105C4000862700200000000064000000547701084F -:105C50000101000087270020000000006400000010 -:105C60005D77010801010000882700200000000086 -:105C70006400000066770108040100008A27002004 -:105C8000E8030000D00700007577010881000000DC -:105C9000E623002000000000C8000000847701080F -:105CA00081000000E723002000000000C800000081 -:105CB0009777010884000000E8230020E803000033 -:105CC000D0070000A977010884000000EA23002023 -:105CD00064000000D0070000BB77010884000000CA -:105CE000EC23002064000000B80B0000CD77010811 -:105CF00081000000F023002000000000FF000000F1 -:105D0000DA7701084100000019210020000000009E -:105D100009000000E77701088100000098220020B8 -:105D200000000000FA000000F67701088100000082 -:105D3000A022002000000000640000000578010897 -:105D400081000000A122002000000000640000008B -:105D500013780108A00000009C2200200100000030 -:105D6000140000002378010881000000B422002004 -:105D700000000000010000003278010888000000E7 -:105D800096220020D4FEFFFF2C010000417801087C -:105D90008800000094220020D4FEFFFF2C010000A8 -:105DA0004F78010881000000A422002000000000BC -:105DB000300000005D780108A0000000A82200204B -:105DC00000000000010000006C780108A000000045 -:105DD000AC220020000000000100000078780108DB -:105DE000A0000000B0220020000000000100000020 -:105DF000847801088800000092220020B0B9FFFFDB -:105E000050460000947801088100000040220020E4 -:105E10000000000002000000A378010881000000DB -:105E20004522002000000000C8000000AB780108F7 -:105E3000810000004F22002000000000C800000088 -:105E400006760108810000005922002000000000B1 -:105E5000C8000000B378010881000000442200203F -:105E600000000000C8000000BA78010881000000AE -:105E70004E22002000000000C8000000F575010857 -:105E8000810000005822002000000000C80000002F -:105E9000C1780108810000004622002000000000B7 -:105EA000C8000000C77801088100000050220020CF -:105EB00000000000C8000000187601088100000002 -:105EC0005A22002000000000C8000000CD78010820 -:105ED000A000000068220020000000006400000014 -:105EE000D6780108A0000000742200200000000005 -:105EF00064000000DF780108A0000000802200207C -:105F00000000000064000000E8780108A000000024 -:105F1000642200200000000064000000F078010806 -:105F2000A0000000702200200000000064000000BB -:105F3000F8780108A00000007C220020000000008A -:105F40006400000000790108A00000006C2200201D -:105F5000000000006400000007790108A0000000B4 -:105F60007822002000000000640000000E79010883 -:105F7000A000000084220020000000006400000057 -:105F800015790108A00000008C220020000000000C -:105F90000A00000023790108A000000088220020E8 -:105FA000000000000A0000002F79010881000000B5 -:105FB0004722002000000000C800000035790108D9 -:105FC000810000005122002000000000C8000000F5 -:105FD0003B790108810000005B22002000000000E6 -:105FE000C800000041790108810000004B22002018 -:105FF00000000000C800000049790108810000008D -:106000005522002000000000C8000000517901085E -:10601000810000005F22002000000000C800000096 -:1060200059790108810000004D2200200000000085 -:10603000C80000005F79010881000000572200209D -:1060400000000000C8000000657901088100000020 -:106050006122002000000000C800000000000000D5 -:10606000000000400008014001000000001C002862 -:10607000000000400008014002000000041C00284D -:10608000000000400008014004000000081C002837 -:106090000000004000080140080000000C1C00281F -:1060A000000400400008014040000000001D0028DE -:1060B000000400400008014080000000041D00288A -:1060C00000040040000C014001000000081D0028F1 -:1060D00000040040000C0140020000000C1D0028DC -:1060E000002C01400008014000010000001B0128B5 -:1060F000002C014000080140000800000C1B012892 -:1061000000080040000C014040000000001E002874 -:1061100000080040000C014080000000041E002820 -:1061200000080040000C014000010000081E00288B -:1061300000080040000C0140000200000C1E002876 -:1061400024505542582C34312C312C303030332CE3 -:10615000303030312C3131353230302C302A31452D -:106160000D0A0024504D544B3235312C313135322B -:1061700030302A31460D0A0024505542582C343113 -:106180002C312C303030332C303030312C35373608 -:1061900030302C302A32440D0A0024504D544B32FA -:1061A00035312C35373630302A32430D0A00245031 -:1061B0005542582C34312C312C303030332C303087 -:1061C00030312C33383430302C302A32360D0A003E -:1061D00024504D544B3235312C33383430302A3240 -:1061E000370D0A0024505542582C34312C312C30B4 -:1061F0003030332C303030312C31393230302C309B -:106200002A32330D0A0024504D544B3235312C3193 -:10621000393230302A32320D0A0041524D3B0041B2 -:106220004E474C453B00484F52495A4F4E3B004267 -:1062300041524F3B004D41473B0048454144465287 -:1062400045453B004845414441444A3B0043414D9C -:10625000535441423B0043414D545249473B004750 -:10626000505320484F4D453B0047505320484F4C1A -:10627000443B0050415353544852553B004245451E -:106280005045523B004C45444D41583B004C454421 -:106290004C4F573B004C4C49474854533B004341FB -:1062A0004C49423B00474F5645524E4F523B004FE0 -:1062B00053442053573B0054454C454D4554525987 -:1062C0003B004155544F54554E453B00534F4E41B2 -:1062D000523B00436C65616E666C696768742F257C -:1062E00073202573202F202573202825732900442F -:1062F000656320203920323031340031373A32356D -:106300003A353800386334313737320041766169C5 -:106310006C61626C6520636F6D6D616E64733A0DC4 -:106320000A0025730925730D0A00202564202564C1 -:1063300000556E6B6E6F776E207661726961626C6C -:1063400065206E616D650D0A0043757272656E742D -:106350002073657474696E67733A200D0A002573A3 -:106360002073657420746F200056616C7565206120 -:10637000737369676E6D656E74206F7574206F66D8 -:106380002072616E67650D0A004E4709004F4B0988 -:1063900000437573746F6D206D697865723A200DD6 -:1063A0000A4D6F746F720954687209526F6C6C09F0 -:1063B0005069746368095961770D0A002325643AAE -:1063C00009002573090053616E697479206368655B -:1063D000636B3A09007265736574006C6F616400E9 -:1063E000496E76616C6964206D6978657220747994 -:1063F00070650D0A004C6F61646564202573206D23 -:1064000069780D0A0057726F6E67206E756D626550 -:1064100072206F6620617267756D656E74732C20D3 -:106420006E65656473206964782074687220726F89 -:106430006C6C207069746368207961770D0A004D77 -:106440006F746F72206E756D626572206D757374F6 -:10645000206265206265747765656E203120616E0B -:10646000642025640D0A004D7573742062652061F7 -:106470006E79206F72646572206F662041455452B8 -:10648000313233340D0A0043757272656E742061C7 -:10649000737369676E6D656E743A2000736574205E -:1064A0002573203D200025752C25753A25733A2546 -:1064B00073006C65642025752025730D0A005061FA -:1064C000727365206572726F720D0A00496E766193 -:1064D0006C6964206C656420696E6465783A206D2F -:1064E000757374206265203C2025750D0A004820D4 -:1064F0004669726D7761726520747970653A436C94 -:1065000065616E666C696768740A00482046697246 -:106510006D77617265207265766973696F6E3A2571 -:10652000730A0048204669726D7761726520646164 -:1065300074653A25732025730A00482072635261FE -:1065400074653A25640A0048206D696E7468726F3C -:1065500074746C653A25640A0048206D617874682B -:10656000726F74746C653A25640A0048206779720A -:106570006F2E7363616C653A307825780A00482085 -:106580006163635F31473A25750A00736572766F00 -:106590005B355D00310048204669656C6420492008 -:1065A0006E616D653A6C6F6F704974657261746984 -:1065B0006F6E2C74696D652C61786973505B305D0A -:1065C0002C61786973505B315D2C61786973505B25 -:1065D000325D2C61786973495B305D2C6178697339 -:1065E000495B315D2C61786973495B325D2C617860 -:1065F0006973445B305D2C61786973445B315D2C59 -:1066000061786973445B325D2C7263436F6D6D61B9 -:106610006E645B305D2C7263436F6D6D616E645BA5 -:10662000315D2C7263436F6D6D616E645B325D2C06 -:106630007263436F6D6D616E645B335D2C6779725D -:106640006F446174615B305D2C6779726F44617473 -:10665000615B315D2C6779726F446174615B325D9F -:106660002C616363536D6F6F74685B305D2C616385 -:1066700063536D6F6F74685B315D2C616363536D41 -:106680006F6F74685B325D2C6D6F746F725B305D21 -:106690002C6D6F746F725B315D2C6D6F746F725BFC -:1066A000325D2C6D6F746F725B335D2C6D6F746F28 -:1066B000725B345D2C6D6F746F725B355D2C6D6F2A -:1066C000746F725B365D2C6D6F746F725B375D003B -:1066D00048204669656C642049207369676E65646B -:1066E0003A302C302C312C312C312C312C312C31B6 -:1066F0002C312C312C312C312C312C312C302C31B3 -:106700002C312C312C312C312C312C302C302C30A4 -:106710002C302C302C302C302C3000482046696531 -:106720006C64204920707265646963746F723A30DA -:106730002C302C302C302C302C302C302C302C3079 -:106740002C302C302C302C302C302C342C302C3065 -:106750002C302C302C302C302C342C352C352C3546 -:106760002C352C352C352C350048204669656C6459 -:10677000204920656E636F64696E673A312C312C55 -:10678000302C302C302C302C302C302C302C302C29 -:10679000302C302C302C302C312C302C302C302C18 -:1067A000302C302C302C312C302C302C302C302C08 -:1067B000302C302C300048204669656C6420502015 -:1067C000707265646963746F723A362C322C312CA6 -:1067D000312C312C312C312C312C312C312C312CD1 -:1067E000312C312C312C312C332C332C332C332CB9 -:1067F000332C332C332C332C332C332C332C332CA1 -:10680000332C330048204669656C64205020656E47 -:10681000636F64696E673A302C302C302C302C302A -:106820002C302C302C302C302C302C302C382C3878 -:106830002C382C382C302C302C302C302C302C3068 -:106840002C302C302C302C302C302C302C302C3068 -:10685000000D0A5265626F6F74696E67000D0A4C15 -:10686000656176696E6720434C49206D6F64652CC5 -:1068700020756E7361766564206368616E67657309 -:10688000206C6F73742E0D0A00536176696E670079 -:106890007261746570726F66696C652025640D0A9B -:1068A000000D0A456E746572696E6720434C49207D -:1068B0004D6F64652C207479706520276578697444 -:1068C0002720746F2072657475726E2C206F722091 -:1068D0002768656C70270D0A000D0A2320000D1B28 -:1068E0005B4B001B5B324A1B5B313B314800556EF2 -:1068F0006B6E6F776E20636F6D6D616E642C2074AC -:106900007279202768656C702700082008004145CF -:1069100054523132333400526573657474696E6752 -:1069200020746F2064656661756C747300456E61D8 -:10693000626C65642066656174757265733A2000E7 -:1069400025732000417661696C61626C6520666523 -:106950006174757265733A2000496E76616C696482 -:106960002066656174757265206E616D650D0A0043 -:1069700044697361626C65642000456E61626C6598 -:1069800064200041464E41003031323334353637D1 -:1069900038394142434445464748494A4B4C4D4E9D -:1069A0004F505152535455565758595A00003008B9 -:1069B0001002000200010006000800081001400853 -:1069C0000007100720070004100420080000537976 -:1069D0007374656D20557074696D653A2025642067 -:1069E0007365636F6E64732C20566F6C746167659A -:1069F0003A202564202A20302E3156202825645341 -:106A00002062617474657279290D0A004350552023 -:106A100025644D487A2C2064657465637465642030 -:106A200073656E736F72733A200041434348573A5F -:106A3000202573002E2563004379636C652054691B -:106A40006D653A2025642C20493243204572726FCF -:106A500072733A2025642C20636F6E666967207319 -:106A6000697A653A2025640D0A0061646A72616E74 -:106A7000676520257520257520257520257520251D -:106A8000752025752025750D0A00617578202575FE -:106A90002025752025752025752025750D0A0041B6 -:106AA00044584C333435004D505536303530004D58 -:106AB0004D413834357800424D41323830004C5326 -:106AC0004D333033444C4843004D50553630303010 -:106AD000004D5055363530300046414B45004E6F25 -:106AE0006E65004759524F00414343004241524FA7 -:106AF00000534F4E415200475053004750532B4DC7 -:106B0000414700004F201004430240010880C34366 -:106B1000757272656E74206D697865723A2025739E -:106B20000D0A00417661696C61626C65206D69785F -:106B30006572733A20004D69786572207365742020 -:106B4000746F2025730D0A0055736167653A0D0A4D -:106B50006D6F746F7220696E646578205B76616C0E -:106B600075655D202D2073686F77205B6F722073D1 -:106B700065745D206D6F746F722076616C75650D44 -:106B80000A004E6F2073756368206D6F746F722CEE -:106B9000207573652061206E756D626572205B30B3 -:106BA0002C2025645D0D0A004D6F746F72202564E2 -:106BB000206973207365742061742025640D0A00B8 -:106BC000496E76616C6964206D6F746F72207661B6 -:106BD0006C75652C20313030302E2E323030300D37 -:106BE0000A0053657474696E67206D6F746F72204C -:106BF000256420746F2025640D0A00636F6C6F722A -:106C00002025752025642C25752C25750D0A004935 -:106C10006E76616C696420636F6C6F7220696E645C -:106C200065783A206D757374206265203C20257567 -:106C30000D0A002E006D61737465720072617465D7 -:106C400073000D0A232076657273696F6E0D0A005A -:106C50000D0A232064756D70206D61737465720D6B -:106C60000A000D0A23206D697865720D0A006D69AE -:106C70007865722025730D0A00636D69782025649C -:106C800000636D697820256420302030203020306A -:106C90000D0A000D0A0D0A23206665617475726580 -:106CA0000D0A0066656174757265202D25730D0AE5 -:106CB00000666561747572652025730D0A000D0A02 -:106CC0000D0A23206D61700D0A006D61702025731F -:106CD0000D0A000D0A0D0A23206C65640D0A000DD3 -:106CE0000A0D0A2320636F6C6F720D0A000D0A23D0 -:106CF0002064756D702070726F66696C650D0A0096 -:106D00000D0A232070726F66696C650D0A000D0A0A -:106D100023206175780D0A000D0A232061646A72D0 -:106D2000616E67650D0A000D0A232064756D702081 -:106D300072617465730D0A000D0A23207261746517 -:106D400070726F66696C650D0A0052585F50504D45 -:106D5000005642415400494E464C494748545F4111 -:106D600043435F43414C0052585F53455249414CA5 -:106D7000004D4F544F525F53544F5000534552569D -:106D80004F5F54494C5400534F4654534552494168 -:106D90004C004641494C534146450054454C454DF5 -:106DA000455452590043555252454E545F4D455437 -:106DB00045520033440052585F504152414C4C45BB -:106DC0004C5F50574D0052585F4D53500052535333 -:106DD000495F414443004C45445F5354524950007D -:106DE000444953504C4159004F4E4553484F54313C -:106DF000323500424C41434B424F580054524900F7 -:106E000051554144500051554144580042490047B2 -:106E1000494D42414C005936004845583600464CD1 -:106E200059494E475F57494E470059340048455825 -:106E30003658004F43544F5838004F43544F464C38 -:106E4000415450004F43544F464C4154580041491F -:106E500052504C414E450048454C495F3132305FFD -:106E60004343504D0048454C495F39305F444547E6 -:106E700000565441494C340048455836480050505B -:106E80004D5F544F5F534552564F004455414C435C -:106E90004F505445520053494E474C45434F505470 -:106EA000455200435553544F4D00414552543132E1 -:106EB0003334353637386162636465666768004528 -:106EC00072726F723A20456E61626C6520616E6409 -:106ED00020706C756720696E204750532066697278 -:106EE00073740D0A0061646A72616E67650073688D -:106EF0006F772F7365742061646A7573746D656E46 -:106F0000742072616E6765732073657474696E674F -:106F100073006175780073686F772F7365742061F3 -:106F200075782073657474696E677300636D697832 -:106F30000064657369676E20637573746F6D206D8F -:106F40006978657200636F6C6F7200636F6E66695B -:106F50006775726520636F6C6F727300726573651D -:106F60007420746F2064656661756C747320616E43 -:106F700064207265626F6F740064756D700070726A -:106F8000696E7420636F6E666967757261626C65A5 -:106F90002073657474696E677320696E2061207058 -:106FA00061737461626C6520666F726D00657869EB -:106FB000740066656174757265006C697374206F26 -:106FC00072202D76616C206F722076616C0067658F -:106FD0007400676574207661726961626C65207601 -:106FE000616C756500677073706173737468726F3C -:106FF00075676800706173737468726F7567682075 -:1070000067707320746F2073657269616C006865C6 -:107010006C70006C656400636F6E6669677572659D -:10702000206C656473006D6170006D617070696ED5 -:1070300067206F66207263206368616E6E656C20E6 -:107040006F72646572006D69786572206E616D653E -:10705000206F72206C697374006D6F746F720067BB -:1070600065742F736574206D6F746F72206F757403 -:107070007075742076616C756500696E6465782042 -:10708000283020746F203229007261746570726F2D -:1070900066696C6500736176650073617665206171 -:1070A0006E64207265626F6F74006E616D653D760F -:1070B000616C7565206F7220626C616E6B206F72FF -:1070C000202A20666F72206C6973740073686F7772 -:1070D0002073797374656D207374617475730052D5 -:1070E00065763A202573005461726765743A2025ED -:1070F0007300566F6C74733A2025642E253164201A -:1071000043656C6C733A20256400416D70733A20BE -:1071100025642E253264206D41683A2025640020C4 -:1071200020202020202020582020202020592020EE -:107130002020205A0041203D20253564202535643B -:10714000202535640047203D202535642025356401 -:1071500020253564004D203D2025356420253564EB -:10716000202535640050726F66696C653A2025648D -:1071700000526174652070726F66696C653A2025F3 -:1071800064005243204578706F3A202564005243D2 -:1071900020526174653A20256400522650205261C5 -:1071A00074653A2025640059617720526174653A0C -:1071B000202564007C2F2D5C00434C45414E464CFD -:1071C000494748540041524D4544004241545445BA -:1071D00052590053454E534F52530052580050528B -:1071E0004F46494C45004E415A45006C6F6F7074D4 -:1071F000696D6500656D665F61766F6964616E6378 -:1072000065006D69645F7263006D696E5F636865D8 -:10721000636B006D61785F636865636B00727373A5 -:10722000695F6368616E6E656C00727373695F732A -:1072300063616C6500696E7075745F66696C746516 -:1072400072696E675F6D6F6465006D696E5F74680B -:10725000726F74746C65006D61785F7468726F74BE -:10726000746C65006D696E5F636F6D6D616E640057 -:1072700033645F6465616462616E645F6C6F770044 -:1072800033645F6465616462616E645F68696768E6 -:107290000033645F6E65757472616C0033645F64A3 -:1072A00065616462616E645F7468726F74746C654A -:1072B000006D6F746F725F70776D5F7261746500DF -:1072C000736572766F5F70776D5F7261746500725F -:1072D000657461726465645F61726D006469736195 -:1072E000726D5F6B696C6C5F737769746368007350 -:1072F0006D616C6C5F616E676C6500666C6170736C -:107300005F737065656400666978656477696E6748 -:107310005F616C74686F6C645F646972007365723E -:1073200069616C5F706F72745F315F7363656E610A -:1073300072696F0073657269616C5F706F72745F00 -:10734000325F7363656E6172696F00736572696144 -:107350006C5F706F72745F335F7363656E617269C7 -:107360006F0073657269616C5F706F72745F345F18 -:107370007363656E6172696F007265626F6F745FCF -:10738000636861726163746572006D73705F6261DE -:1073900075647261746500636C695F6261756472C3 -:1073A000617465006770735F6261756472617465B2 -:1073B000006770735F706173737468726F7567686C -:1073C0005F6261756472617465006770735F70728B -:1073D0006F7669646572006770735F736261735F73 -:1073E0006D6F6465006770735F6175746F5F636F65 -:1073F0006E666967006770735F706F735F700067B8 -:1074000070735F706F735F69006770735F706F7325 -:107410005F64006770735F706F73725F7000677096 -:10742000735F706F73725F69006770735F706F7303 -:10743000725F64006770735F6E61765F7000677083 -:10744000735F6E61765F69006770735F6E61765F10 -:1074500064006770735F77705F7261646975730051 -:107460006E61765F636F6E74726F6C735F68656177 -:1074700064696E67006E61765F73706565645F6DE9 -:10748000696E006E61765F73706565645F6D6178CB -:10749000006E61765F736C65775F7261746500730F -:1074A000657269616C72785F70726F76696465721B -:1074B0000074656C656D657472795F70726F766962 -:1074C0006465720074656C656D657472795F73775D -:1074D000697463680074656C656D657472795F6961 -:1074E0006E76657273696F6E006672736B795F6436 -:1074F000656661756C745F6C6174746974756465DC -:10750000006672736B795F64656661756C745F6C3D -:107510006F6E676974756465006672736B795F631B -:107520006F6F7264696E617465735F666F726D61AF -:1075300074006672736B795F756E69740062617452 -:10754000746572795F6361706163697479007662F2 -:1075500061745F7363616C6500766261745F6D6115 -:10756000785F63656C6C5F766F6C746167650076DD -:107570006261745F6D696E5F63656C6C5F766F6C82 -:10758000746167650063757272656E745F6D6574B2 -:1075900065725F7363616C650063757272656E74AA -:1075A0005F6D657465725F6F6666736574006D7597 -:1075B0006C74697769695F63757272656E745F6D0B -:1075C000657465725F6F757470757400616C69675E -:1075D0006E5F6779726F00616C69676E5F6163638C -:1075E00000616C69676E5F6D616700616C69676EF1 -:1075F0005F626F6172645F726F6C6C00616C69676F -:107600006E5F626F6172645F706974636800616C61 -:1076100069676E5F626F6172645F796177006D6147 -:10762000785F616E676C655F696E636C696E6174CB -:10763000696F6E006779726F5F6C7066006D6F7254 -:107640006F6E5F7468726573686F6C6400677972DF -:107650006F5F636D70665F666163746F72006779F8 -:10766000726F5F636D70666D5F666163746F7200E9 -:10767000616C745F686F6C645F6465616462616EA5 -:107680006400616C745F686F6C645F666173745FE3 -:107690006368616E6765007961775F6465616462E4 -:1076A000616E64007468726F74746C655F636F728E -:1076B00072656374696F6E5F76616C75650074687E -:1076C000726F74746C655F636F7272656374696FF7 -:1076D0006E5F616E676C65007961775F636F6E7472 -:1076E000726F6C5F646972656374696F6E00796153 -:1076F000775F646972656374696F6E007472695F45 -:10770000756E61726D65645F736572766F00646536 -:107710006661756C745F726174655F70726F6669C3 -:107720006C650072635F726174650072635F657897 -:10773000706F007468725F6D6964007468725F6571 -:1077400078706F00726F6C6C5F70697463685F72E1 -:10775000617465007961775F72617465007470614E -:107760005F72617465007470615F627265616B70F5 -:107770006F696E74006661696C736166655F6465EC -:107780006C6179006661696C736166655F6F6666DE -:107790005F64656C6179006661696C736166655FE1 -:1077A0007468726F74746C65006661696C7361668D -:1077B000655F6D696E5F75736563006661696C73A3 -:1077C0006166655F6D61785F757365630067696D9C -:1077D00062616C5F666C616773006163635F6861BF -:1077E000726477617265006163635F6C70665F6687 -:1077F0006163746F720061636378795F646561646B -:1078000062616E64006163637A5F64656164626192 -:107810006E64006163637A5F6C70665F6375746F3A -:107820006666006163635F756E61726D6564636156 -:107830006C006163635F7472696D5F706974636823 -:10784000006163635F7472696D5F726F6C6C00627C -:1078500061726F5F7461625F73697A650062617201 -:107860006F5F6E6F6973655F6C7066006261726FE7 -:107870005F63665F76656C006261726F5F63665F0F -:10788000616C74006D61675F6465636C696E6174DF -:10789000696F6E007069645F636F6E74726F6C6C99 -:1078A000657200705F706974636800695F70697405 -:1078B000636800705F726F6C6C00695F726F6C6CF4 -:1078C00000705F79617700695F79617700705F7040 -:1078D000697463686600695F7069746368660064F0 -:1078E0005F70697463686600705F726F6C6C6600CD -:1078F000695F726F6C6C6600645F726F6C6C6600BF -:10790000705F7961776600695F7961776600645FAF -:1079100079617766006C6576656C5F686F72697A0D -:107920006F6E006C6576656C5F616E676C6500708C -:107930005F616C7400695F616C7400645F616C749A -:1079400000705F6C6576656C00695F6C6576656C70 -:1079500000645F6C6576656C00705F76656C0069CD -:107960005F76656C00645F76656C000020202020E7 -:1079700020202020202828282828202020202020DF -:1079800020202020202020202020202088101010BF -:107990001010101010101010101010100404040417 -:1079A000040404040404101010101010104141418C -:1079B00041414101010101010101010101010101F7 -:1079C000010101010101011010101010104242428A -:1079D00042424202020202020202020202020202C7 -:1079E0000202020202020210101010200000000029 -:1079F0000000000000000000000000000000000087 -:107A00000000000000000000000000000000000076 -:107A10000000000000000000000000000000000066 -:107A20000000000000000000000000000000000056 -:107A30000000000000000000000000000000000046 -:107A40000000000000000000000000000000000036 -:107A50000000000000000000000000000000000026 -:107A60000000000000000000000000000000004BCB -:107A7000000000CB61636F7366000000706F776673 -:107A800000000000737172746600000000000000C6 -:107A900000C0153F00000000DCCFD1350000803F62 -:107AA0000000C03F000FC93F000F494000CB964087 -:107AB000000FC9400053FB4000CB164100ED2F41A1 -:107AC000000F49410031624100537B41003A8A4135 -:107AD00000CB9641005CA34100EDAF41007EBC416C -:107AE000000FC94100A0D5410031E24100C2EE4182 -:107AF0000053FB4100F20342003A0A420083104265 -:107B000000CB164200141D42005C234200A529420E -:107B100000ED2F4200363642007E3C4200C7424212 -:107B2000000F4942A2000000F9000000830000009D -:107B30006E0000004E000000440000001500000030 -:107B400029000000FC000000270000005700000092 -:107B5000D1000000F500000034000000DD0000004E -:107B6000C0000000DB000000620000009500000083 -:107B7000990000003C00000043000000900000005D -:107B800041000000FE000000510000006300000002 -:107B9000AB000000DE000000BB000000C5000000DC -:107BA00061000000B7000000240000006E0000002B -:107BB0003A000000420000004D000000D20000002A -:107BC000E000000006000000490000002E00000058 -:107BD000EA00000009000000D1000000920000004F -:107BE0001C000000FE0000001D000000EB00000073 -:107BF0001C000000B100000029000000A7000000E8 -:107C00003E000000E8000000820000003500000097 -:107C1000F50000002E000000BB0000004400000042 -:107C200084000000E90000009C00000070000000DB -:107C300026000000B40000005F0000007E0000008D -:107C4000410000003900000091000000D600000053 -:107C500039000000830000005300000039000000DC -:107C6000F40000009C000000840000005F000000A1 -:107C70008B000000BD000000F9000000280000009B -:107C80003B0000001F000000F8000000970000000B -:107C9000FF000000DE00000005000000980000006A -:107CA0000F000000EF0000002F0000001100000096 -:107CB0008B0000005A0000000A0000006D00000068 -:107CC0001F0000006D000000360000007E00000074 -:107CD000CF00000027000000CB00000009000000DA -:107CE000B70000004F000000460000003F00000009 -:107CF000660000009E0000005F000000EA00000037 -:107D00002D0000007500000027000000BA000000F0 -:107D1000C7000000EB000000E5000000F1000000DB -:107D20007B0000003D00000007000000390000005B -:107D3000F70000008A0000005200000092000000DE -:107D4000EA0000006B000000FB0000005F00000084 -:107D5000B10000001F0000008D0000005D00000069 -:107D60000800000056000000030000003000000082 -:107D700046000000FC0000007B0000006B000000DB -:107D8000AB000000F0000000CF000000BC000000CD -:107D9000200000009A000000F400000036000000FF -:107DA0001D000000A9000000E30000009100000099 -:107DB000610000005E000000E60000001B00000003 -:107DC0000800000065000000990000008500000028 -:107DD0005F00000014000000A00000006800000028 -:107DE000400000008D000000FF000000D8000000EF -:107DF000800000004D00000073000000270000001C -:107E00003100000006000000060000001500000020 -:107E100056000000CA00000073000000A800000027 -:107E2000C900000060000000E20000007B000000CC -:107E3000C00000008C0000006B0000000400000087 -:107E400007000000090000000000C93F0000F039F1 -:107E50000000DA370000A2330000842E0000502B0F -:107E60000000C2270000D0220000C41F0000C61B73 -:107E70000000441700000000000000000000304334 -:107E800000000000000030C36937AC3168212233A4 -:107E9000B40F14336821A2333863ED3EDA0F493F43 -:087EA0005E987B3FDA0FC93F39 -:087EA8003C72FF7F01000000A5 -:107EB000000100000000803F000000000000000002 -:107EC0000100DC05DC05DC05DC05DC05DC05DC058A -:107ED000DC05010000127A00000000000000000034 -:107EE0000102030406070809010303000000803FA4 -:107EF0000000803F0000803F010100000000803F43 -:107F0000000000000102030401020304060708093F -:107F1000020406080000000000000000000000004D -:107F2000010000000000000000000000030000004D -:107F3000000000000000000004000000000000003D -:107F40000000000003000000957E00080F270000DD -:107F5000FFFFFFFF00A24A0483690108B97101080D -:107F6000C5710108CB710108D3710108DB710108EB -:107F7000DE710108E67101086B790108000000005C -:107F800000000000000000000000000000000000F1 -:107F9000000000000000000000000000EA6A010884 -:107FA00000000000000000000000000000000000D1 -:107FB00000000000000000000000000000000000C1 -:107FC00000000000000000000000000000000000B1 -:107FD000000000000000000000000000CC000020B5 -:047FE000010000009C +:10000000A3FA01464FF07E50FEF74CFE8549FEF7FD +:1000100053FF02F0CBF96F688146D4F86C02FEF70B +:10002000F7FE3946FEF748FF8046D4F86002C0EB81 +:100030000900FEF7EDFE394681464FF07E50FEF78F +:1000400031FE01464846FEF737FF01464046FEF7BF +:100050002BFE02F0ABF9B4F97072B4F97232002FD2 +:10006000B8BF7F42002BB8BF5B429F42B8BF1F465C +:10007000DFF8C4813FB2FA2F8246D8F8000014DCC2 +:10008000FEF7C6FE81463846FEF7C2FE01466648C8 +:10009000FEF708FE01464846FEF70EFF6249FEF7EE +:1000A000BFFFFFF7CFF8074601E04FF0FF377B1E99 +:1000B000C62BC8F8007006D8C7EB0A03C4F8743220 +:1000C000C4F86C722EE0D4F87432002FDFF844913B +:1000D000C3EB0A0A02DCC9F86CA223E0C7F59670EC +:1000E000FEF796FE5149FEF79BFF80463846FEF725 +:1000F0008FFE4146FEF7E0FE07465046FEF788FEBB +:10010000414682464FF07E50FEF7CCFD01465046F8 +:10011000FEF7D2FE01463846FEF7C6FDFFF792F81D +:10012000C9F86C02424B18680193FEF76DFE414915 +:100130000746FEF7C1FE8246D4F88002FEF768FE4D +:100140008046D4F88402FEF763FE01464046FEF77F +:1001500067FFD4F888120490FEF7AEFE3946FEF72A +:10016000ABFE4FF07C51D4F86482D5F80C90D4F8F3 +:100170006C720290FEF7A0FE5146FEF79DFE5146BE +:10018000024640460392FEF797FE039A0146104648 +:10019000FEF78AFDD4F86812FEF786FD4946FEF7A1 +:1001A0008BFE82463846FEF733FE494602464FF044 +:1001B0007E500392FEF776FD039A01461046FEF745 +:1001C0007BFE01465046FEF76FFDDDF808C0C4F81F +:1001D0006802814661464046FEF766FD0022C4F88B +:1001E0006402C4F87822C4F87C22C4F88022C4F8DF +:1001F0008422019B80461A60074B1B88002B40F02D +:1002000016810D4B1B68013BC62B17D80149C1F85D +:10021000247119E038010020C427002080E6C5477A +:10022000B1DC423ED048874A000061440000C84229 +:10023000C8270020BD378635A40000204846FFF7B8 +:1002400001F8A54AC2F82401D4F88C02381AFEF746 +:10025000DFFDA249FEF730FE81465846FEF7D4FD89 +:1002600001464846FEF7DCFEFEF7ECFF40F2DC53A9 +:100270009B4A9842A8BF18469042B8BF10460A2130 +:10028000C4F88C72F9F70CF9AD68814629464046EE +:10029000FEF712FE07464846FEF7BAFD294680469D +:1002A0004FF07E50FEF7FEFC01464046FEF704FE8E +:1002B00001463846FEF7F8FCC4F8640202F076F80E +:1002C00005218046F9F7ECF8B4F8702240F23E635D +:1002D00002F21F3292B29A42C4F89002D4F8947299 +:1002E0000AD87D4AB2F8720200F21F3080B29842FA +:1002F0008CBF0020012000E0002000286AD094F884 +:100300009832754D13BBD5F82021D5F824317548A6 +:10031000D31AB3F5FA7FA8BF4FF4FA738342A8BF8C +:1003200018460A21F9F7BCF8D5F89C328022DB7810 +:10033000584390FBF2F3B3F5967FA8BF4FF4967342 +:10034000A2F5D6729342B8BF134601E0664B1B6814 +:10035000D4F89C22C8EB0303517A20205943D57C62 +:1003600091FBF0F1D4F83401B1F5967FA8BF4FF4BA +:10037000967103FB05005D4BB0F5C81FA8BF4FF495 +:10038000C8109842B8BF18464FF40055C4F834015D +:1003900090FBF5F0564DA942ACBF45184519507F6A +:1003A000FEF736FD394680460498FEF77DFC01468F +:1003B0004046FEF781FD4FF06C51FEF77DFDFEF7E4 +:1003C00041FF6FF095039628A8BF96209842B8BFCA +:1003D0001846281A049BC4F83801C4F8943226E061 +:1003E000B3681D0623D5F3F7A9F920E0D4F814214A +:1003F000394BD0061BD53F4AD3F8A01212683C31C6 +:100400008A4214D3C3F8A022D3F8A8723A4A3B4DCB +:10041000C3F8A4223B880B202B61F5F709FA3B882F +:100420006B6104E0B368990301D5FBF718FCD4F8BD +:100430003C31052B03DD284B0022C3F83C21F5F7A6 +:1004400029F92F4B1860B3892BB1D4F8AC22821A4A +:10045000002AC0F2D68618441F4D7379C4F8AC0246 +:10046000059305F53170D4F8B832D4F8B0729847D6 +:1004700005F53170014694F8CA22F4F747FF214B85 +:100480001B88002B00F0B880D5F8CC324FF0000963 +:100490001B7805F534750493C8461A4BB3F800A0D1 +:1004A000194BBAF57A7F03D1002243F809202A615B +:1004B000164A32F9080053F80920024443F809208B +:1004C000FEF7A6FC2A690132012A2A6120D1002305 +:1004D00068602860AB6046E0380100200024744961 +:1004E00024FAFFFF0CFEFFFFD02700200000E7FFEB +:1004F000D4FEFFFF2C200020A4000020000C0140AF +:10050000C0270020CC27002044040020FC0300204A +:10051000D5F800C003926146CDF808C00190FEF7FF +:10052000C1FB039A83461046FEF772FC014658460B +:10053000FEF776FDDDF808C001466046FEF7B4FB25 +:10054000019B02461146686018460392FEF7AAFB1B +:1005500001465846FEF7B0FCA968FEF7A5FB039AD2 +:10056000E8602A60A860684A002302F1540BBAF1DF +:10057000010F28F8023028F80B30DFF89CA12CD1AD +:100580002869012807DD0138FEF742FC0146E868CA +:10059000FEF746FD00E0002002F05EF903460498F5 +:1005A00058B10193FEF734FC019B01461846FEF753 +:1005B0003FFE10B14FF47A731CE0544B4FF47A7243 +:1005C00059F803300A2003F5FA7393FBF2F32BF882 +:1005D00008300F210122F5F747F908F10208B8F1B8 +:1005E000060F09F1040905F114057FF456AFBAF8B6 +:1005F0000030013BAAF800300023454D05F531726B +:1006000005F54671985A595A411A99520233062BE8 +:10061000F3D1D5F8143113F0020300F00583D5F8B7 +:10062000243305F54B70984705F54B70014695F856 +:100630003223F4F76BFEB5F8343305F54B78002B15 +:1006400045D00022D5F838031346314D38F902C0A1 +:10065000B5F8341305F54F7EB1F5C87F04BF00210E +:100660004EF803105EF80310294D61444EF8031054 +:10067000043300210C2B28F80210815202F10202EF +:10068000E3D1B5F83433012B1CD1D5F83C334FF40A +:10069000C872C83393FBF2F30380D5F84033C833F4 +:1006A00093FBF2F34380D5F84433C83393FBF2F263 +:1006B000184B1B88D21A8280A7F85410A7F856103E +:1006C000FBF778F8B4F83433013BA4F83433B3685B +:1006D0005A0740F18480B4F848230D4B322A1DD1CB +:1006E000D3F838231188A3F84A1351889288A3F8C5 +:1006F0004C13A3F84E23B7F85420A3F85023B7F8AF +:100700005620A3F852230BE0FC03002044040020F1 +:100710003801002000000020CC270020002A3CD017 +:100720000021D4F838530A46914838F901E0B0F86E +:10073000483300F55576322B04BF0023B350B05830 +:100740008B4B7044B050043200200C2A28F8010072 +:10075000685201F10201E7D1B3F84823012A17D109 +:1007600083F86123052283F86223B3F84A2383F8D0 +:1007700060032A80B3F84C236A80B3F84E23AA8022 +:10078000B3F85023B3F85233A7F85420A7F85630E3 +:10079000B4F84833013BA4F8483394F86323744B0E +:1007A000EAB1D3F85453D3F838133220002295FB22 +:1007B000F0F583F863230D80D3F8585395FBF0F5DB +:1007C0004D80D3F85C3393FBF0F06A4B1B88C01A62 +:1007D0008880A7F85420A7F85620FAF7EBFFD4F842 +:1007E0003833B4F82C131A8800268A1AA4F82C235C +:1007F000B4F82E135A88B1468A1AA4F82E239B887F +:10080000B4F83023D31AA4F83033F4F743FFD4F804 +:1008100064330546C31A18460493FEF7F5FAD4F874 +:1008200068130690FEF748FBD4F86C83C4F8645351 +:1008300098F800A0079035464F4F785FFEF7E8FA2A +:100840000799FEF739FB09A98851BAF1000F2DD09D +:100850005046FEF7DDFA01464FF07E50FEF7E0FB12 +:100860000246114607F1AC0B4FF07E500392FEF7A3 +:1008700019FA56F80B10FEF71FFB07F168018446C2 +:10088000485FCDF808C0FEF7C3FA039AB83711469F +:10089000FEF712FBDDF808C001466046FEF704FAD9 +:1008A0004BF80600FEF7CEFC785304E007F1B802DF +:1008B0006837E95BA952314F0436EA5F0235062DED +:1008C00002FB0299B8D12B4D4FF0640A2A880AFB2B +:1008D00009F3524393FBF2FAAAF1490A07F108001F +:1008E00009A91FFA8AFAF5F7B5F9BAF13B0FD8F85A +:1008F000046011D9B4F99003FEF78AFAD4F88C6336 +:1009000001463046FEF794FC194F94F84A3100280E +:1009100038D043F0080337E04FF07E513046FEF701 +:10092000C3F901464FF07E50FEF77AFB4FF0000B03 +:100930008246134B304653F81B100193FEF7BCFA66 +:10094000024637F90B000392FEF762FA039A01465A +:100950001046FEF7A9F95146FEF7AEFA019B43F89F +:100960001B000BF1020BBBF1060FE2D1C2E700BF87 +:100970003801002000000020FC030020B404002007 +:10098000BC04002023F008033146D4F8880387F81C +:100990004A3101F0D7FD0746C4F89403D4F8840324 +:1009A000D4F88CB300F10046D4F888030146FEF772 +:1009B00083FA594682465846FEF77EFA014650466B +:1009C000FEF772F901F048FF0146304601F0BAFD2A +:1009D000A6490646C4F898033846FEF76DFA01F0BA +:1009E000E5FCA249A4F870023046FEF765FA01F072 +:1009F000DDFCD4F81431A4F872021B0739D59C48E9 +:100A000009A9F5F727F9D8F808904FF07E51484624 +:100A1000FEF74AF901464FF07E50FEF701FB4FF01A +:100A2000000B8246934D484605F5677353F81B103B +:100A30000193FEF741FA05F5A271024631F90B0068 +:100A40000392FEF7E5F9039A01461046FEF72CF9EA +:100A50005146FEF731FA019B43F81B000BF1020BE4 +:100A6000BBF1060FDED11846F8F780FBA5F8A80306 +:100A700041E0DFF814A209A90AF10400F5F7EAF849 +:100A80006868D5F808B00146FEF716FAD5F80C905C +:100A9000594605465846FEF70FFA01462846FEF726 +:100AA00003F9494605464846FEF706FA0146284638 +:100AB000FEF7FAF801F0D0FE00210546FEF790FBA4 +:100AC000A0B9DAF804002946FEF7AAFA2946CAF8BE +:100AD0000400DAF80800FEF7A3FA2946CAF808006D +:100AE000DAF80C00FEF79CFACAF80C006248F8F736 +:100AF0003DFBA4F8A80361490698FEF7DDF907F16C +:100B00000047814606F10046B4F9A8030C970D96FC +:100B1000FEF77EF95A4900F10040FEF7CDF90E903C +:100B2000B4F97C03FEF774F90F90B4F97E03FEF775 +:100B30006FF91090B4F98003FEF76AF90CA91190CF +:100B40000FA8F5F787F898F801304A4D012B19D115 +:100B50004C4B1B785E070ED4D5F8AC33402093FB8A +:100B6000F0F0181AFEF754F91199FEF79DF8FEF708 +:100B700069FBC5F8AC033F4BD3F8AC03402390FBB3 +:100B8000F3F001E0404B1888FEF742F90146119856 +:100B9000FEF788F8D4F8B41311904846FEF784F8AD +:100BA00001464846FEF73CFAD4F8B05306462946BB +:100BB0001198FEF777F801463046FEF77DF90146B9 +:100BC0002846FEF771F80646C4F8B0030F98D4F82B +:100BD000787201F0EBFBD4F8B8532978F8F760FC91 +:100BE0003844C4F878021098D4F87C7201F0DEFB27 +:100BF0002978F8F755FC3844C4F87C023046D4F81C +:100C0000807201F0D3FB6978F8F74AFC1F4B049D12 +:100C10001A6838442A441A60D4F88432C4F880022E +:100C20000133C4F8843205E0A5F82C33A5F82E333F +:100C3000A5F830330F4DB5F8C432A5F8BC33B5F87C +:100C4000C632A5F8BE33059B012B21D1B5F9C223CD +:100C5000B5F9C83203EB4203032293FBF2F39BB2D4 +:100C6000A5F8C033A5F8C23316E000BF4C3D0F44D1 +:100C7000D40400203801002004000020BD37863550 +:100C800035FA8E3CD527002000000020C827002020 +:100C9000B5F8C832A5F8C033F4F7FCFCC14B012706 +:100CA0001860D5F8C833C5F8C803C31AA5F8C4330B +:100CB000F1F73EFED5F81831BB4E13F4801385F8DA +:100CC000107100F08D80B6F81C31180600F1D48048 +:100CD000B64B1B78590770D596F8CC23B44B12B19C +:100CE00096F8CD233AB10022C5F8D02301221A7418 +:100CF000002285F8CD231B7CD5F8B062032B96F833 +:100D00000090A94F06F1040885F8CC3306D140467F +:100D100007F575714C2201F0DBF844E0012B07D197 +:100D200007F5757041464C2201F0D2F8002302E02D +:100D3000022B02D1012387F82034012384F82134C7 +:100D400084F822340023C4F82434C4F82834994A9F +:100D500094F82034C4F82C8413441B7C964A1E4417 +:100D600084F83134C4F8D023307984F83094FEF715 +:100D70004FF89249FEF754F9C4F83404B07BFEF7FB +:100D800047F88F49FEF74CF9C4F83804307EFEF777 +:100D90003FF88C49FEF790F8C4F83C04FEF778FA67 +:100DA00000233076B373B5F81C3143F08003A5F807 +:100DB0001C31012385F840345EE04FF00008D6F87E +:100DC000D0034146FEF70CFA8146002854D1FAF7C9 +:100DD000F1FC774BC6F8D08386F8CC931F744BE0B8 +:100DE000B6F81CA11AF0800F3BD096F8CC23DFF8A0 +:100DF000C081511E012924D87149D6F83804FEF764 +:100E00005BF8FEF745FAD6F82C7496F831946E49E3 +:100E1000B94489F80A00D6F83C04FEF74DF8FEF70D +:100E200037FA89F814003878FDF7F2FF0146FDF72C +:100E30003BFFFEF72DFABB7AB8703B733B7DBB7569 +:100E400006E0032A04D186F8CC3388F8107004E059 +:100E500098F81030013388F810302AF0800AA5F88D +:100E60001CA1524B1B785A0706D495F840341BB18D +:100E70004D4B012283F8CD23D5F814914A4A19F03D +:100E8000080F524F38D0B2F82E1101F145039BB232 +:100E90008A2B2DD8B2F81C315B0729D5B2F8A803EC +:100EA000B2F8423495F84A61C21A92B293B218B2BB +:100EB000B330BCBF02F5B4739BB21AB2B32AC4BF3D +:100EC000A3F5B4739BB2360797F8EC00364A13D5F6 +:100ED00040B240424343D2F8B0021BB2007B4343CE +:100EE0006FF01D0093FBF0F31944A2F82E1103E0FC +:100EF000B5F8A833A5F8423419F0140F00F0988023 +:100F0000B5F81C21284B02F40272002A00F09080F0 +:100F100093F84A2102F0100202F0FF0052B1B3F838 +:100F20002C1197F92701D3F8382100FB0212A3F8FE +:100F30002C217DE0D3F84424D1789278002947D041 +:100F4000B3F830E1B3F928110FFA8EF6C1EB060CB5 +:100F5000BCF1000FB8BFCCF1000C94450FDD8E4200 +:100F6000C8BF52421FFA8EFEC8BF92B2C3F8340106 +:100F70007244012083F84804A5F8302158E093F822 +:100F800048242AB1D3F8242183F84804C3F8202147 +:100F9000D5F83831D5F84C24194413885288994231 +:100FA0003FE000BFC027002038010020D5270020E7 +:100FB00000000020504501080000A0410000204131 +:100FC00000007A445555553F9A99993F30200020AA +:100FD000B3F92801B3F93061361A86EAE67EAEEB42 +:100FE000E67E96450ADD022296FBF2F6764A166008 +:100FF000012283F8982283F848240AE093F84824D1 +:101000003AB1D3F8242183F89812C3F8202183F849 +:101010004814D5F84C14D5F838210B880244498877 +:101020009A4203DB8A42B4BF13460B46A5F830311F +:10103000D5F8B082654E98F864A1BAF1000F5BD084 +:10104000B6F81C31980757D0D6F88403B6F830218B +:10105000D6F888C30146D6F88CB30492CDF808C000 +:10106000FDF72AFFDDF808C002466146604603929C +:10107000FDF722FF039A01461046FDF715FE59467B +:10108000024658460392FDF717FF039A01461046A1 +:10109000FDF70AFE01F0E0FB01465846FDF7C0FFF0 +:1010A0004B490190FEF7B0F8019BF8B9184601F0E2 +:1010B000F9F9D6F85014FDF7FFFE01F077F9B0F515 +:1010C000617FA8BF4FF46170FDF7A2FE4149FDF7B3 +:1010D000A7FF01F0A9F906465046FDF799FE3146F3 +:1010E000FDF7EAFE01F062F980B200E00020DDF8D1 +:1010F00010B08344A5F830B119F0200F0BD0B5F82B +:101100001C3103F0300333B1304B93F84A31D90727 +:1011100001D5F3F7ABFE304B08F104001E68D5F89B +:10112000541408F15403B7F8F620B047FCF7CCFA92 +:10113000D5F85834002B5AD0244B93F85C34013B3B +:10114000142B4FD8DFE803F00B4E4E27514E4E1FA5 +:101150004E4E4E4E4E2F4E4E4E4E4E272F00D5F831 +:1011600060345B782BB11D4B0020998BF8F7C7FBDF +:101170003DE01B4B1B7803F0040303F0FF00002B42 +:10118000F1D10146F2E7154D0020298BF8F7B7FBA6 +:101190000120698BEAE7114D0020698BF8F7AFFB5E +:1011A0000120A98BE2E70D4D0020298BF8F7A7FB62 +:1011B0000120698BF8F7A3FB0220A98BF8F79FFBAE +:1011C0000320E98BD2E700BFD027002038010020A0 +:1011D0008FC2753CEFB6B0449C0000200000002098 +:1011E000D5270020BB689A0601D5F4F725FDFCF74A +:1011F0001BFAC94B1B7823B9BB681B0301D5FBF74E +:1012000095FAC54BC54D1B78C54E002B40F0D883D1 +:10121000B3685F0540F1D48395F86434002B00F087 +:10122000CF83F8F755F9002800F0CA8395F86534A4 +:10123000002B00F0C583D5F868341B78002B40F0F4 +:101240002E82D5F86C04F4F76BFB002840F027825F +:10125000DFF8E892D5F87024D9F800309A1A7C2A81 +:1012600040F21D82C5F8703495F87434804601331D +:1012700085F8743408F12400A84FC0B2F4F77AFC62 +:1012800007F55F7333F91800FDF7C2FDA54B8246E1 +:101290001888FDF7BDFD01465046FDF7C1FEA24985 +:1012A000FDF70AFEFDF7CEFF08F1010800B2F4F7E2 +:1012B0008DFCB8F1030FDDD13020F4F75BFCB7F9FA +:1012C0009002F4F783FCF4F763FC97F87434980702 +:1012D00030D1D7F8703441F2883293421BD91020B4 +:1012E000F4F748FCD7F86C024FF0640890FBF8F074 +:1012F00000B2F4F76BFC2120F4F73CFCD7F86C3219 +:1013000093FBF8F008FB103888EAE870A0EBE8706F +:1013100000B2F4F75BFC1420F4F72CFCB5F9A80339 +:10132000F4F754FC1C20F4F725FC0020F4F74EFCE5 +:10133000F4F72EFC95F87434784F590740F0898102 +:101340000220F4F717FCD7F884316422323393FB80 +:10135000F2F000B2F4F73AFC0320F4F70BFC734B05 +:101360001B7813F0040F4FF0050304D0B7F93001D8 +:1013700090FBF3F005E0D7F878245289B2FBF3F044 +:1013800000B2F4F723FCB3689A076AD5684F94F863 +:101390007C243B7840F63401B2FBF3F24A432A2125 +:1013A000B2FBF1F2B4F87E14062091FBF3F803FBD4 +:1013B00018184FEA08181FFA88F848EA02281FFA96 +:1013C00088F8C2F3032248EA0208F4F7D3FB0FFAC5 +:1013D00088F0F4F7FBFBB4F87E243B78013292B23C +:1013E00092FBF3F103FB1123A4F87E3494F87C34D0 +:1013F0006E275F43152397FBF3F73A204FF0640AFB +:10140000F4F7B8FBB7FBFAF84046F4F7DFFB3B20F4 +:10141000F4F7B0FB0AFB187080B24FF00A080530F1 +:1014200090FBF8F000B2F4F7D1FB2820F4F7A2FB10 +:10143000D4F8800490FBF8F000B2F4F7C7FB042066 +:10144000F4F798FBD4F878345B8913B1F3F7C0FC58 +:1014500004E0324BD3F8840480F3100000B2F4F7B8 +:10146000B5FBD5F814312D4C9B0640F1868094F8DD +:101470004A319F071AD51120F4F77CFBB4F8880491 +:10148000FDF7FCF822A3D3E90023FDF75DF9002264 +:10149000284BFCF7A7FFFDF769FB00B2F4F796FBBA +:1014A0001920F4F767FB0020F4F790FB95F84A3118 +:1014B000B5F88A4413F0020F08BF00240120F4F7A6 +:1014C00059FB20B2F4F782FB0920F4F753FB00200C +:1014D000F4F77CFB184B95F88C441B88B3F5967F8A +:1014E0000BD90E4A92F8742402F00F02072A04D88E +:1014F00042F20F74A342B8BF1C460520F4F73AFB32 +:10150000D5F890345B7BDBB920B234E0AFF30080D8 +:101510007B14AE47E17A843FD427002038010020B5 +:10152000302000200000002000007A44D527002051 +:10153000980000200000E03FA00000202C200020A8 +:10154000A4F12000FDF79AF8C1A3D3E90023FDF729 +:1015500025FAFDF753FB00210446FDF74BFE10B1C1 +:101560004FF03F4101E04FF07C512046FDF79CFBDE +:10157000FDF768FE00B2F4F729FBD5F814319806A0 +:101580000ED4B54B0021D3F890446068FDF728FED7 +:1015900000285CD1A0680021FDF722FE002856D16A +:1015A00095F84A21AC4B910703D493F89424012A6F +:1015B00007D10123D5F89874D5F89C4485F8943464 +:1015C0000FE0D3F89044A5496068FDF775FCFDF77E +:1015D00039FEA2490746A068FDF76EFCFDF732FE12 +:1015E00004460FA93846F7F79BFF1320F4F7C2FA19 +:1015F000BDF93C00F4F7EAFA1B20F4F7BBFABDF999 +:101600003E00F4F7E3FA2320F4F7B4FA002FACBF5E +:101610004E205320F4F7DAFA0FA92046F7F780FF9F +:101620001220F4F7A7FABDF93C00F4F7CFFA1A201C +:10163000F4F7A0FABDF93E00F4F7C8FA2220F4F757 +:1016400099FA002CACBF45205720F4F7BFFAF4F705 +:101650009FFA95F87434282B21D17F4B0022D9F8BA +:10166000004083F874244FF47A73B4FBF3F8172026 +:101670003C24F4F77FFAB8FBF4F7B7FBF4F004FB73 +:101680001070000200B2F4F7A1FA1820F4F772FA11 +:1016900004FB178000B2F4F799FAF4F779FAD5F859 +:1016A00068341B78012B01D1F6F739FFD5F868347F +:1016B000694C1B78022B1BD1D4F8A034C3B1C4F8F9 +:1016C000A4341B68664AC4F8A834D4F8AC34134474 +:1016D000987CF8F7D3F9D4F8A4349879F4F737F96B +:1016E000D4F8AC340133092B88BF0023C4F8AC34E0 +:1016F000F7F740FF002800F0638195F8B034013B14 +:10170000012B00F25D81D5F8B404F4F709F9524CCD +:10171000544FD8B1D4F8B404F4F7FDF894F8B824D1 +:101720003B687E2A0FD102221B2884F8B024C4F81B +:10173000BC3405D00D2803D0342801D0672802D14D +:10174000012385F8C03485F8B804DCE73B68D4F899 +:10175000BC2441F658319A1A8A4203D9032384F8EB +:10176000B0342DE1D4F8C4249B1A042B40F2288114 +:1017700094F8C034002B00F0238194F8C8243A4B2D +:1017800033F8120018B984F8C8044FF4036095F8D0 +:10179000C834B0F5C06F03F10103DBB22E4C85F8FD +:1017A000C83450D01CD8B0F5007F46D009D8B0F569 +:1017B000807F45D0B0F5887F40F00281D4F8901248 +:1017C000F9E0B0F5806F7ED0B0F5826F00F0C38095 +:1017D000B0F5047F40F0F48094F87C345321E9E0C4 +:1017E000B0F5006F42D00CD8B0F5E26F62D0B0F522 +:1017F000E46F65D0B0F5E06F40F0E280B4F97C139F +:101800005AE0B0F5036F07D0B0F5046F4ED0B0F5D5 +:10181000026F40F0D580C1E0D4F814319A0640F14F +:10182000CF8094F84A319B0740F1CA80B4F88834DD +:1018300024215943642312313FE0D4F88014BAE0E4 +:10184000D4F86C12B7E0D4F88414B4E0AFF300809D +:10185000CDCCCCCCCCCCFC3F380100208096184BB2 +:10186000504501082C20002074610108D4F814218F +:10187000970640F1A58094F84A21900740F1A08096 +:10188000D90709D5D4F89C140029BCBF494241F0BE +:10189000804141F0004106E0D4F898140029BCBF13 +:1018A000494241F080414FF400606BE0B4F9A83345 +:1018B00064217FE0B4F97E132C2391FBF3F17AE0ED +:1018C000B4F98013F8E794F8C93442F21071013387 +:1018D000DBB2032B84F8C93484BF012384F8C934F4 +:1018E00095F8C9345943AE4B1B78DA0748BF01312C +:1018F0009F0748BF02315C07B5F81C3148BF04316F +:10190000D80748BF0A319A0748BF14311F0648BF9D +:101910002831DC0548BF2831580748BF64311A0711 +:1019200048BFC8319F0548BF01F5C8719C0648BF34 +:1019300001F57A71D80648BF01F5FA615A0648BF29 +:1019400001F57A614FF48060F3F7F8F9954B0022C6 +:1019500083F8C02434E0D4F8141111F0200717D014 +:1019600094F84A3113F0020F0CBF00214FF47A7142 +:1019700013F0010F0CBF00234FF4FA63194495F8DC +:101980008C341944F3F7DAF9002385F8C03417E0F2 +:101990003946F3F7D3F984F8C07411E0D4F8143160 +:1019A0009B060DD594F84A319F0709D5B4F88A34BF +:1019B0004FF47A715943F3F7C1F9002384F8C03426 +:1019C000B368DC037EF551A895F8CA34754C002B3A +:1019D0003EF44BA8744B1B78002B7EF446A8F3F71B +:1019E00059FED4F8CC340746C31A6FEA0308D4F87A +:1019F000D0344FEAD878C31A6FEA030AD4F8D43443 +:101A00004FEADA7AC3EB00096FEA09094FEAD9799C +:101A1000B9F1000F06D1BAF1000F03D1B8F1000FF0 +:101A20003EF423A84FF0000B95F85C355FFA8BF479 +:101A30009C42DFF870C147D25C49DCF8D834A20080 +:101A4000096813446244C2F8DC145988C8050BD4F1 +:101A50008B0536D5524B1B785C0754BF544B554B06 +:101A60001B68C2F8DC342CE01946534A2046019327 +:101A7000CDF808C0FBF762FADDF808C0019BBCF89E +:101A80001C2112F0400F03D0204619464B4A16E0A5 +:101A9000500703D520461946494A10E0110703D5DF +:101AA00020461946474A0AE0900703D520461946C2 +:101AB000454A04E0D10704D5444A20461946FBF7BD +:101AC0003DFA0BF1010BAFE79C000023A3421FD0AE +:101AD000D5F8D82433491A445288520516D501F254 +:101AE000DC42D0580890B1F964057821A0F57A70ED +:101AF00048434FF47A7190FBF1F000F22B1040F262 +:101B0000671190FBF1FE01FB1E0199520433DDE7E2 +:101B1000B9F1000F2BD007F5C333A033C5F8D43487 +:101B200095F882351F4C13BB84F88335B3689E0744 +:101B300005D5F3F7A3FC10B1012384F88335D5F85C +:101B40008435184C1B689B68984728B194F88335F6 +:101B500043F0020384F88335114B1B7813F0050F13 +:101B600005D195F8833543F0040385F8833595F85E +:101B7000832522B90B4B93F88235002B66D095F85C +:101B8000821511F0010FA1F10C0033D103291FD8E8 +:101B9000064B074C12F0040F18BF234619E000BF94 +:101BA000D527002038010020CE27002070610108D1 +:101BB000504501085C4501086C4501087245010863 +:101BC000784501087E450108844501088A450108D9 +:101BD000B84B0439072904D8B74912F0010F18BFD0 +:101BE0000B46C0B2032810D8B44912F0020F18BF38 +:101BF0000B460AE0C0B2032806D8AE4BB04912F03B +:101C0000020F18BF0B4600E0AA4B002195F85C05B7 +:101C1000CCB2A042AB4E0CD9D6F8D804A4002044D4 +:101C20004088000603D518683444C4F8DC04013148 +:101C3000ECE7B9F1000F13D05AB195F88225A14B0A +:101C40000132D2B2142A09D1002207E0B9F1000F03 +:101C500006D095F88235002BEFD101E083F882257C +:101C6000BAF1000F23D0B5F92C31B5F92A21322170 +:101C7000002AB8BF5242002BB8BF5B4293FBF1F37E +:101C800092FBF1F1DBB2C9B28B4238BF0B468E4AF0 +:101C90000BB192FBF3F23A44C5F8D02495F88825AD +:101CA000884B0AB9012200E0002283F8882595F8C4 +:101CB0008825844B22B9854AC3F88C25002009E089 +:101CC0007C4AF9E7D3F8D81494000E197688760682 +:101CD00007D4013095F85C15C2B29142794BF1D826 +:101CE00099E0B3F92A61192E21DD11F822E093F869 +:101CF00090C50EF00F09E145D3F88C6508DC93F828 +:101D000091C5BCEB1E1F03DC23443468C3F8DC44DC +:101D100011F8224095F892E504F00F0CF445694B58 +:101D20002DDB93F891E5BEEB141F28DC22E0193679 +:101D300025DA11F822E093F890C50EF00F09E1457D +:101D4000D3F88C6508DC93F893C5BCEB1E1F03DB4E +:101D500023443468C3F8DC4411F8224095F892E536 +:101D600004F00F0CF445574B09DB93F893E5BEEBF9 +:101D7000141F04DB346803EB8203C3F8DC44B5F9B9 +:101D80002C41504B192C1BDD11F822E093F8906583 +:101D90000EF00F0CB445D3F88C450ADC93F891C5CE +:101DA000BCEB1E1F05DCD4F800E003EB8203C3F894 +:101DB000DCE411F8223003F00F01B1421EDD88E7A8 +:101DC000193486DA11F822E093F892650EF00F0CC0 +:101DD000B445D3F88C450ADB93F891C5BCEB1E1FC4 +:101DE00005DCD4F800E003EB8203C3F8DCE411F86F +:101DF000223003F00F01B142FFF66BAF95F8931557 +:101E0000B1EB131FFFF665AF2E4B03EB8202236885 +:101E1000C2F8DC345DE7B8F1000F1CD093F89525CB +:101E200093F8941507F543478818013890FBF2F4AE +:101E300002FB140083F89715013183F8960591FB96 +:101E4000F2F002FB10125037D2B2C3F8CC7483F810 +:101E5000982583F89425F2F721FEFDF706BECB0600 +:101E60007EF5EDAAD4F81821164B910207D4B3F8E9 +:101E70001C2122F40072A3F81C21FEF7E0BAB3F88B +:101E80001C1101F4007292B2002A7EF4D8AA41F427 +:101E90000071A3F81C11D3F82411C3F83421C3F83E +:101EA0002011B3F83011C3F83821A3F82811FEF738 +:101EB000C6BA00BF706101085445010858450108C1 +:101EC0005C45010838010020400D030090450108E1 +:101ED00010B50023934203D0CC5CC4540133F9E71E +:101EE00010BD02440346934202D003F8011BFAE7F7 +:101EF000704700000D4B70B51D680022845C2B19E3 +:101F00005B7803F00303012B8B5C08BF2034EE18D1 +:101F1000767806F00306012E08BF2033E41A02D1BA +:101F20000132002BEAD1204670BD00BFCC0000205A +:101F300010B50446224613780134002BFAD1CC5C4C +:101F4000D4540133002CFAD110BDC9B2024610F8A6 +:101F5000013B1BB18B42F9D1104670470029FBD0E1 +:101F600018467047034613F8012B002AFBD1181AB4 +:101F7000013870470F4BF0B51E680023934215D00F +:101F8000C55C7419647804F00304012CCC5C08BFB0 +:101F9000203537197F7807F00307012F08BF203459 +:101FA0002D1B04D10133002CE8D100E00025284688 +:101FB000F0BD00BFCC00002010B5034632B111F8CF +:101FC000014B013A03F8014B002CF7D11A4493421C +:101FD00003D0002103F8011BF9E710BD30B50378E9 +:101FE0000BB1044604E00B78002B18BF002030BD75 +:101FF00022461078013438B10023C85C28B1D55C82 +:102000008542F5D10133F8E730BD104630BD0021DF +:102010000A2200F001B92DE9F04E82468B461F4698 +:10202000144612B90020BDE8F08E002BFAD000262D +:10203000A642F7D2A5196D0807FB05B950464946D7 +:10204000089B9847002802DB03D06E1C25462C46CF +:10205000EEE74846BDE8F08E174B2DE9F0411D68CC +:102060000646AC6D0F46FCB9502000F0E3F8A865B9 +:102070008460AB6D046044601C61DC60AB6D9C618E +:102080005C61AB6DDC629C62AB6D5C631C63AB6DD1 +:10209000DC639C63AB6D5C641C64AB6DDC649C6452 +:1020A000AB6D1C77AB6D5C6230463946AA6D01237F +:1020B000BDE8F04100F002B830010020F0B508B9E9 +:1020C000106828B3044614F8015B0F4617F8016B3B +:1020D0003EB1B542FAD10BB12046F3E7146003706C +:1020E000F0BD4DB915602846F0BD17F8016BAE4242 +:1020F00007D0002EF9D11C46234613F8015B0F468A +:10210000F3E715B10021217000E02B461360F0BD0C +:10211000F0BD000084463F482DE9F04FD0F8008024 +:102120000E46344614F8015B08EB0500407800F0D9 +:10213000080000F0FF0708B12646F2E72D2D03D175 +:10214000B41C7578012703E02B2D04BF7578B41CEF +:1021500033F010000DD1302D08D1207800F0DF00D1 +:10216000582851D165781023023402E0002B08BFB3 +:102170000A23002F0CBF6FF0004A4FF0004ABAFB51 +:10218000F3F903FB19AA0026304608EB050B9BF870 +:1021900001B01BF0040F01D0303D0BE01BF0030B2E +:1021A0001BD0BBF1010F14BF4FF0570B4FF0370B93 +:1021B000CBEB05059D4210DAB6F1FF3F0AD048454A +:1021C00006D801D1554503DC03FB0050012601E090 +:1021D0004FF0FF3614F8015BD7E7731C0CD1002FCA +:1021E0004FF022030CBF6FF000404FF00040CCF8DE +:1021F00000302AB9BDE8F08F07B1404242B106B1C4 +:10220000611E1160BDE8F08F002B08BF0823B0E706 +:10221000BDE8F08FCC00002030B51346044A0546D7 +:102220000C46106829462246BDE83040FFF772BFD1 +:1022300030010020024B0146186800F003B800BFCF +:102240003001002070B5CD1C25F0030508350C2D9C +:1022500038BF0C25002D06463FDB8D423DD3214B78 +:102260001C6818462146A1B10B685B1B0ED40B2BD2 +:1022700003D90B60CC18CD501FE08C4202D16268AC +:1022800002601AE04B6863600C4616E00C46496831 +:10229000E9E7154C23681BB9304600F027F82060A9 +:1022A0002946304600F022F8431C014615D0C41CD4 +:1022B00024F0030484420AD1256004F10B00231D9D +:1022C00020F00700C31A0BD05A42E25070BD3046CE +:1022D000611A00F00BF80130EED10C2333600020BE +:1022E00070BD00BFE8270020E427002038B5064C69 +:1022F000002305460846236000F008F8431C02D17D +:10230000236803B12B6038BDF0270020094A136809 +:1023100063B118446946884202D810601846704775 +:10232000054B0C221A604FF0FF307047034B1360CF +:10233000EFE700BFEC270020F0270020F427002063 +:1023400000B5194A20F00043934283B0014617DDDF +:10235000B3F1FF4F04DBFCF7A5FC03B05DF804FB11 +:10236000694601F03BF800F00302012A0098019948 +:1023700011D0022A0AD09AB1012201F0F3FDECE754 +:10238000002101F0F3F903B05DF804FB01F0EEF970 +:1023900000F10040E1E701F0E5FD00F10040DCE77D +:1023A00001F0E4F9D9E700BFD80F493F30B5C0F3D9 +:1023B000C754A4F17F031E2B83B0014620DC581CB8 +:1023C0001BDB162B4FEAD17509DDC1F3160040F473 +:1023D0000000963CA04005B1404203B030BD114B17 +:1023E00053F825402046FCF75FFC019001982146F8 +:1023F000FCF758FC20F0004333B9002003B030BD97 +:10240000FCF720FF03B030BDC0F31604C0F3C75083 +:1024100044F40004C0F1960024FA00F0002DDCD052 +:10242000DAE700BF807B010800B51D4A20F00043B9 +:10243000934283B0014618DDB3F1FF4F04DBFCF794 +:1024400031FC03B05DF804FB694600F0C7FF00F003 +:102450000300012818D002280ED0D0B100980199AD +:1024600001F084F900F10040EBE70021002201F0C7 +:1024700079FD03B05DF804FB00980199012201F099 +:1024800071FD00F10040DCE70098019901F06EF960 +:10249000D7E700980199012201F064FDD1E700BF60 +:1024A000D80F493F70B58AB0054600F023FA224C98 +:1024B000064694F90030013303D0284601F0C4FFEA +:1024C00010B930460AB070BD284601F06BFF4FF0DE +:1024D0007E51FCF7ADFE0028F3D0184901220023FD +:1024E0002846009208930191FCF7DAF802460B4661 +:1024F0001348CDE90423CDE9022301F0ABFD94F9A3 +:102500000030CDE90601022B0BD0684601F0A0FD9A +:1025100038B1089B53B9DDE90601FCF76FFB0AB03F +:1025200070BD02F00FF821230360F2E702F00AF811 +:10253000089B0360EFE700BF34010020887B01089F +:10254000947B010800F03EBB2DE9F0418AB00746BC +:102550000C4600F0C7FB9B4E054696F90030013350 +:1025600003D0204601F070FF18B928460AB0BDE834 +:10257000F081384601F068FF8046002832D12046BD +:102580000021FCF72DFE0028EFD08F4A01233846AA +:1025900001920093CDF82080FCF782F8CDE902018A +:1025A0002046FCF77DF8894B96F900400022CDE9E2 +:1025B0000623631CCDE904010DD0022C0BD0684624 +:1025C00001F046FD002800F09A80089B1BB101F045 +:1025D000B9FF089B0360DDE90601FCF70FFB0AB0B9 +:1025E000BDE8F08138460021FCF7FAFD18B320461B +:1025F0000021FCF7F5FD8046002855D072490122E4 +:1026000000233846009208930191FCF749F8CDE980 +:1026100002012046FCF744F896F90040002200230E +:10262000CDE90401CDE90623002CC8D0674B002278 +:10263000CDE90623CFE7284601F0B8FE8046002802 +:1026400062D028460021FCF7CBFD00288DD038460B +:1026500001F0ACFE002888D0204601F0A7FE00283B +:1026600083D05949042200233846009208930191EF +:10267000FCF716F8CDE902012046FCF711F896F9AF +:10268000004000220023022CCDE90401CDE90623FD +:1026900000F08880684601F0DBFC002800F08280B2 +:1026A000089B002B97D092E7204601F07FFE002880 +:1026B0003FF45BAF20460021FCF79CFD00283FF46F +:1026C00054AF414A0123384601920093CDF820804F +:1026D000FBF7E6FFCDE902012046FBF7E1FF347886 +:1026E000CDE904010022002C30D0394B022CCDE979 +:1026F00006232ED101F026FF21230360D0E701F04D +:1027000021FF2123036060E7384601F04FFE0028D7 +:1027100097D0204601F04AFE002892D0284601F0CA +:1027200093FE0346D8B928490122384608930092FF +:102730000191FBF7B5FFCDE902012046FBF7B0FFA1 +:102740003478CDE90401002C31D100220023CDE9F9 +:102750000623684601F07CFC0028A1D1CAE71A4A8A +:102760000323384600930192CDF82080FBF798FFB1 +:10277000CDE902012046FBF793FF96F90030CDE941 +:102780000401384643BB134B4FF060420021CDE9B2 +:102790000623FCF72FFD00283FD196F90030022BCD +:1027A0007FF478AF01F0CEFE2223036078E70020AB +:1027B000002102460B46FCF7F1F8022CCDE9060198 +:1027C00098D0C6E734010020907B01080000F03F5C +:1027D0000000F0FFFFFFEF471C4B00220021CDE976 +:1027E0000623FCF707FD0028D7D020464FF07C5188 +:1027F000FCF762FBFBF754FF04460D4601F030FC8A +:1028000002460B4620462946FDF79EF80028C4D113 +:102810000F4B0022CDE90623BFE720464FF07C5145 +:10282000FCF74AFBFBF73CFF04460D4601F018FCA1 +:1028300002460B4620462946FDF786F80028ACD113 +:10284000044B4FF06042CDE90623A6E70000F07F7D +:102850000000F0FFFFFFEFC770B58AB0054600F03B +:1028600031FF224C064694F90030013308D0284647 +:1028700001F0EAFD20B128460021FCF7BBFC10B9AD +:1028800030460AB070BD1A49012200232846019142 +:1028900000920893FBF704FF2478CDE90401CDE909 +:1028A00002017CB900220023CDE90623684601F02D +:1028B000CFFB88B1089BA3B9DDE90601FCF79EF9BF +:1028C0000AB070BD0020002102460B46FCF766F8F6 +:1028D000022CCDE90601E9D101F034FE2123036089 +:1028E000E8E701F02FFE089B0360E5E734010020D4 +:1028F000987B0108F8B520F00043B3F17E5F0446F1 +:1029000010D008DCB3F17C5F11DAB3F10C5F00F397 +:1029100084809D48F8BD0146FCF7C4F90146FCF7E8 +:102920007FFBF8BD002840F3CD800020F8BD0028D3 +:10293000C0F2CA8001464FF07E50FCF7B3F94FF069 +:102940007C51FCF7B9FA044600F0BCFE8F490646FC +:102950002046FCF7B1FA8E49FCF7A6F92146FCF7B0 +:10296000ABFA8C49FCF79EF92146FCF7A5FA8A4997 +:10297000FCF79AF92146FCF79FFA8849FCF792F98F +:102980002146FCF799FA8649FCF78EF92146FCF7B7 +:1029900093FA844905462046FCF78EFA8249FCF7F3 +:1029A00081F92146FCF788FA8049FCF77DF9214638 +:1029B000FCF782FA7E49FCF775F92146FCF77CFAB0 +:1029C0004FF07E51FCF770F901462846FCF728FBD2 +:1029D0003146FCF771FA26F47F6525F00F050746AE +:1029E00029462846FCF768FA01462046FCF75AF9C2 +:1029F000294604463046FCF757F901462046FCF7C5 +:102A00000FFB01463846FCF74FF901462846FCF714 +:102A10004BF90146FCF748F9F8BD0146FCF74CFAC2 +:102A20005A490546FCF748FA5949FCF73DF9294649 +:102A3000FCF742FA5749FCF735F92946FCF73CFA0E +:102A40005549FCF731F92946FCF736FA5349FCF7AA +:102A500029F92946FCF730FA5149FCF725F92946AE +:102A6000FCF72AFA4F4906462846FCF725FA4E4954 +:102A7000FCF718F92946FCF71FFA4C49FCF714F942 +:102A80002946FCF719FA4A49FCF70CF92946FCF7E4 +:102A900013FA4FF07E51FCF707F901463046FCF778 +:102AA000BFFA01462046FCF707FA01464148FCF709 +:102AB000F9F801462046FCF7F5F801463E48FCF7D8 +:102AC000F1F8F8BD3D48F8BD4FF07E51FCF7ECF849 +:102AD0004FF07C51FCF7F0F92C490446FCF7ECF977 +:102AE0002B49FCF7E1F82146FCF7E6F92949FCF708 +:102AF000D9F82146FCF7E0F92749FCF7D5F821463B +:102B0000FCF7DAF92549FCF7CDF82146FCF7D4F9B2 +:102B10002349FCF7C9F82146FCF7CEF906462046C2 +:102B200000F0D0FD1F4905462046FCF7C5F91E49B7 +:102B3000FCF7B8F82146FCF7BFF91C49FCF7B4F8DC +:102B40002146FCF7B9F91A49FCF7ACF82146FCF725 +:102B5000B3F94FF07E51FCF7A7F801463046FCF779 +:102B60005FFA2946FCF7A8F91249FCF79BF80146E1 +:102B70002846FCF799F80146FCF796F801461048FC +:102B8000FCF790F8F8BD00BFDB0FC93F08EF113824 +:102B9000047F4F3A4611243DA80A4E3E90B0A63E0F +:102BA000ABAA2A3E2EC69D3D6133303F2D570140D2 +:102BB00039D119406821A233DA0FC93FDB0F4940F0 +:102BC000DA0F494021F00042B2F1FF4FF8B5044658 +:102BD00014DC20F00045B5F1FF4F06460EDCB1F1E4 +:102BE0007E5F3AD08F1707F0020747EAD07755B9D2 +:102BF000022F2FD0032F2FD13148F8BD0846214690 +:102C0000FCF752F8F8BDFAB1B2F1FF4F29D0B5F197 +:102C1000FF4F19D0AA1AD2153C2A19DC002938DB3B +:102C20002046FCF7FDF901F0BDFB01F0A5FA012FEC +:102C30002CD0022F22D0002F2FD02249FCF734F8BD +:102C40002149FCF72FF8F8BD002E15DB1F48F8BD11 +:102C50001E48ECE71C48F8BDF8BDBDE8F84001F09F +:102C60008BBAB5F1FF4F19D0022FF3D0032FC3D089 +:102C7000012F1BD00020F8BD1548F8BD1149FCF705 +:102C800013F801461048FCF70DF8F8BD00F10040BC +:102C9000F8BD3C32C4DA0020C9E7F8BD022F0CD0E1 +:102CA000032F08D0012F04D00A48F8BD4FF0004090 +:102CB000F8BD0948F8BD0948F8BD0948F8BD00BF8E +:102CC000DB0F49C02EBDBB33DB0F4940DB0FC93FD3 +:102CD000DB0FC9BFDB0F493FDB0F49BFE4CB16C099 +:102CE000E4CB16402DE9F04F31F0004987B00D4696 +:102CF0000C46074611D020F0004ABAF1FF4F80463B +:102D000005DD514807B0BDE8F04F01F0B7BBB9F1A0 +:102D1000FF4F07DDBAF17E5FF3D14FF07E5007B071 +:102D2000BDE8F08F002840DB0026B9F1FF4F34D01A +:102D3000B9F17E5F4CD0B4F1804F384655D0B4F134 +:102D40007C5F1BD001F02EFB0146BAF1000F1DD0B5 +:102D500028F04043B3F17E5F18D04FEAD87808F1ED +:102D6000FF3856EA080166D0B9F19A4F74DD374B47 +:102D70009A4533DC002C37DB0020D0E7B8F1000F98 +:102D8000E0DB07B0BDE8F04F00F09CBC002C41DB5D +:102D9000B8F1000F32DB0846C1E7BAF17E5FBCD064 +:102DA00027DD002CE8DB2846B9E7B9F1974F13DAA5 +:102DB000B9F17E5F0ADB4FEAE953C3F1960349FAA2 +:102DC00003F202FA03F34B4500F044820026AFE71A +:102DD000002C25DB3846A2E70226A6E71C4B9A45C5 +:102DE00040F39D82002CC7DD1A480146FCF764F8C9 +:102DF00095E7002CC0DA05F1004090E7AAF17E5A71 +:102E000056EA0A0A12D10846FBF74CFF0146FCF7C6 +:102E100007F984E74FF07E50FCF702F90146B7E767 +:102E200039464FF07E50FCF7FBF878E7012EB2D11F +:102E300001F1004073E739463846FBF733FF01469E +:102E4000FCF7EEF86BE700BF947B0108F7FF7F3FCC +:102E50000700803FCAF24971BAF5000F80F2028282 +:102E60004FF09741FCF728F86FF017028246B34BFA +:102E70004FEAEA51CAF3160A7F399A4501EB020C70 +:102E80004AF07E5740F3EB81AD4B9A4540F34282C6 +:102E900000220CF1010CA7F5000705920599A94B3A +:102EA000384653F82130CDF804C0194603920493F4 +:102EB000FBF7F8FE049981463846FBF7F5FE01461C +:102EC0004FF07E50FCF7ACF8034619464846029393 +:102ED000FBF7F2FF7910039A41F00051BB4601F570 +:102EE000802120F47F6727F00F070A4482461146AD +:102EF00038460392FBF7E0FF01464846FBF7D2FE57 +:102F0000039A814604991046FBF7CCFE01465846C9 +:102F1000FBF7C8FE01463846FBF7CEFF01464846A0 +:102F2000FBF7C0FE029B1946FBF7C6FF51468346DE +:102F30005046FBF7C1FF01468146FBF7BDFF8249C2 +:102F4000034648460293FBF7B7FF8049FBF7ACFE08 +:102F50004946FBF7B1FF7E49FBF7A6FE4946FBF762 +:102F6000ABFF7C49FBF7A0FE4946FBF7A5FF7A497A +:102F7000FBF79AFE4946FBF79FFF7849FBF794FE63 +:102F8000029B01461846FBF797FF3946814650469B +:102F9000FBF78AFE5946FBF78FFF4946FBF784FE95 +:102FA000394604903846FBF787FF6D490390FBF7DD +:102FB0007BFE0499FBF778FE20F47F6929F00F0966 +:102FC00049463846FBF778FF494607465846FBF71F +:102FD00073FF634983464846FBF764FE039A114634 +:102FE000FBF760FE01460498FBF75CFE5146FBF7D9 +:102FF00063FF01465846FBF757FE8346594638465D +:10300000FBF752FE20F47F6A2AF00F0A504655491A +:10301000FBF752FF544981465046FBF74DFF3946B6 +:10302000034650460293FBF73DFE01465846FBF728 +:1030300039FE4E49FBF740FF029B01461846FBF75D +:1030400033FE4B4B059A53F82210FBF72DFEDDF8AB +:1030500004C007466046FBF7DBFE464B059A04902A +:1030600053F822B039464846FBF71EFE5946FBF797 +:103070001BFE0499FBF718FE20F47F6A2AF00F0A62 +:1030800004995046FBF70EFE5946FBF70BFE4946E6 +:10309000FBF708FE01463846FBF704FE24F47F6484 +:1030A00024F00F04013E56EA0806814621462846D0 +:1030B0000CBF314F4FF07E57FBF7F4FD5146FBF745 +:1030C000FBFE494606462846FBF7F6FE014630461B +:1030D000FBF7EAFD214606465046FBF7EDFE0546A6 +:1030E00001463046FBF7E0FD00288146044620F00B +:1030F0000048AA4640F3F880B8F1864F00F3C2803A +:1031000000F0B280B8F17C5F00F3C4804FF000099A +:10311000C84624F47F6424F00F0420461749FBF7C7 +:10312000CBFE514605462046FBF7BCFD0146304626 +:10313000FBF7B8FD1249FBF7BFFE23E071C41C008A +:10314000D6B35D00B07B010842F1533E55326C3E70 +:1031500005A38B3EABAAAA3EB76DDB3E9A99193FF9 +:10316000000040400038763FA0C39D364F38763F80 +:10317000A87B0108A07B0108000080BF0072313FDE +:103180001872313F864906462046FBF795FE0146F8 +:103190003046FBF789FD064631462846FBF784FD9D +:1031A00029460446FBF77EFD01463046FBF77AFDD3 +:1031B000214606462046FBF77FFE7A490546FBF787 +:1031C0007BFE7949FBF76EFD2946FBF775FE7749D3 +:1031D000FBF76AFD2946FBF76FFE7549FBF762FDB9 +:1031E0002946FBF769FE7349FBF75EFD2946FBF7AD +:1031F00063FE01462046FBF755FD0546294620465D +:10320000FBF75AFE4FF0804182462846FBF74AFD05 +:1032100001465046FBF704FF314605462046FBF7C2 +:103220004BFE3146FBF740FD01462846FBF73AFDD1 +:103230002146FBF737FD01464FF07E50FBF732FD8C +:103240008144B9F5000FC0F2A58049463846FBF726 +:1032500033FE64E502F00102C2F1020668E50022D5 +:1032600005921BE6002202E653493046FBF71CFD9F +:10327000294682464846FBF715FD01465046FBF7B6 +:10328000D7FF38B138464D49FBF716FE4B49FBF7DF +:1032900013FE44E54FEAE858A8F17E084FF4000316 +:1032A00043FA08F32344C3F3C7524548C3F316084F +:1032B000A2F17F0140FA01F1C2F1960248F4000840 +:1032C00048FA02F8002C23EA01012846B8BFC8F1E9 +:1032D0000008FBF7E7FC824651463046FBF7E4FC6A +:1032E0004FEAC859044614E7364B98450ADC7FF488 +:1032F00009AF2946FBF7D6FC01463046FBF784FFB1 +:103300000028C7D038463049FBF7D6FD2E49FBF7D9 +:10331000D3FD04E501234FF400120593BEE54FF001 +:103320007E51FBF7BFFC29490746FBF7C5FD28493D +:1033300081463846FBF7C0FD394682463846FBF7E2 +:10334000BBFD4FF07A5183463846FBF7B5FD014689 +:103350002048FBF7A7FC3946FBF7AEFD01464FF0CE +:103360007C50FBF79FFC01465846FBF7A5FD1A4928 +:10337000FBF7A2FD01465046FBF794FC0746394691 +:103380004846FBF791FC20F47F6A2AF00F0A494671 +:1033900050467DE6414601F075F8014656E700BF0C +:1033A0008CBEBF354CBB31330EEADD3555B38A38A0 +:1033B000610B363BABAA2A3E3CAA3833CAF24971AC +:1033C000FFFF7F00000016436042A20D00AAB83F35 +:1033D00070A5EC36ABAAAA3E3BAAB83F2DE9F04F48 +:1033E000AB4A20F00044944289B006460D4664DDA5 +:1033F000A84A94421CDC0028A74940F3EC80FBF764 +:1034000051FCA64B24F00F049C42064664D0A4490C +:10341000FBF748FC014628603046FBF743FCA04917 +:10342000FBF740FC01236860184609B0BDE8F08F47 +:103430009C4A944262DDB4F1FF4F46DAE715863FBD +:10344000A4EBC7542046FBF7FDFEFBF7E1FC034667 +:10345000014620460593FBF725FC4FF08741FBF71B +:103460002BFD8046FBF7EEFEFBF7D2FC014604463F +:1034700040460694FBF716FC4FF08741FBF71CFD16 +:1034800000210790FBF7ACFE002800F0C580204625 +:103490000021FBF7A5FE002814BF01230223824868 +:1034A0000221019000913A4605A8294600F022FA2F +:1034B000002EC0F2A780034603E00022286000230C +:1034C0004A60184609B0BDE8F08F0146FBF7EAFBF9 +:1034D000002368602860F4E77449FBF7E3FB744954 +:1034E0000446FBF7DFFB014628602046FBF7DAFBCA +:1034F0006F49FBF7D7FB01236860E2E700F052FF5A +:103500006C490746FBF7D8FC4FF07C51FBF7CCFB2E +:10351000FBF798FE8246FBF77BFC5F498346FBF78F +:10352000CBFC01463846FBF7BDFB5D49804658465B +:10353000FBF7C2FCBAF11F0F81464946404618DC32 +:103540005D4B0AF1FF3253F8223024F0FF029A4219 +:103550000FD0FBF7A7FB07462F6039464046FBF725 +:10356000A1FB4946FBF79EFB002E686056DB5346E5 +:10357000A7E7FBF797FBE315C0F3C7529A1A082A8F +:103580000746E9DD494958460393FBF795FC074692 +:1035900039464046FBF786FB044621464046FBF78A +:1035A00081FB3946FBF77EFB414907465846FBF74E +:1035B00083FC3946FBF776FB814649462046FBF7FC +:1035C00071FB039BC0F3C7529B1A192B074641DCC2 +:1035D0002860A046C1E7FBF767FB304B24F00F04DF +:1035E0009C42064623D02E49FBF75EFB014628602D +:1035F0003046FBF757FB2A49FBF756FB4FF0FF33EA +:1036000068605EE795E80C0003F1004102F10042BA +:1036100043422A60696054E7032340E707F100470B +:1036200000F100402F606860CAF1000349E71F49BC +:10363000FBF73AFB1E490446FBF736FB01462860C0 +:103640002046FBF72FFB1A49FBF72EFB4FF0FF3309 +:10365000686036E719495846FBF72EFC074639469D +:103660002046FBF71FFB804641462046FBF71AFB2E +:103670003946FBF717FB124904465846FBF71CFC7A +:103680002146FBF70FFB81464946404661E700BFF4 +:10369000D80F493FE3CB1640800FC93FD00FC93F39 +:1036A00043443537800F4943387C0108004435379F +:1036B00008A3852E84F9223FB87B010800A3852E3C +:1036C00032318D2420F00042B2F1FF4FF8B50446AC +:1036D00003462DD25AB300283DDBB2F5000F4FEA66 +:1036E000E0502CD37F38C3F31603C20743F4000322 +:1036F00048BF5B00002740105B003E4619244FF096 +:103700008072B5189D4202DC5B1BAE181744013C69 +:103710004FEA43034FEA5202F3D113B107F001031A +:103720001F447F1007F17C5707EBC050F8BDF8BD70 +:103730000146FBF7C1FB2146FBF7B6FAF8BD14F4CE +:1037400000020FD15B00190202F10102FAD5C2F1A9 +:1037500001021044C6E70146FBF7A4FA0146FBF755 +:103760005FFCF8BD01221044BCE700BF2DE9F8431F +:1037700020F00046B6F1485F05460F4649DAFBF7F0 +:1037800061FD002800F09D8029462846FBF794FB48 +:103790004E490446FBF790FB4D49FBF785FA21465D +:1037A000FBF78AFB4B49FBF77DFA2146FBF784FBCD +:1037B0004949FBF779FA2146FBF77EFB4749FBF7BE +:1037C00071FA2146FBF778FB4549FBF76DFA214674 +:1037D000FBF772FB804620464FF07C51FBF76CFBF9 +:1037E000414606462046FBF767FB39460446284615 +:1037F000FBF762FB01462046FBF754FA01463046D0 +:10380000FBF750FA01464FF07E50FBF74BFABDE84C +:10381000F8830146FBF750FB2C490446FBF74CFBB1 +:103820002B49FBF741FA2146FBF746FB2949FBF7F9 +:1038300039FA2146FBF740FB2749FBF735FA2146C9 +:10384000FBF73AFB2549FBF72DFA2146FBF734FB42 +:103850002349FBF729FA2146FBF72EFB214B804633 +:103860009E42B8DD204B9E4227DC06F17F46314662 +:103870004FF07E50FBF716FA814620464FF07C5100 +:10388000FBF71AFB3146FBF70DFA41460646204688 +:10389000FBF712FB394604462846FBF70DFB0146B1 +:1038A0002046FBF7FFF901463046FBF7FBF90146DE +:1038B0004846FBF7F7F9BDE8F883DFF834900B4E84 +:1038C000DBE74FF07E50BDE8F88300BF4ED747AD31 +:1038D000F6740F317CF29334010DD037610BB63A98 +:1038E000ABAA2A3D9999993E0000483F0000903EBE +:1038F0000000383F2DE9F04FDFB00B93013B0293FE +:10390000D31E48BF131DB84C06466898DB1054F808 +:10391000204023EAE3730C93DB4302EBC3030894D8 +:103920000693089C029B0C9A1D190991C3EB020790 +:103930001DD4699C3D4404EB870901354FF0000814 +:1039400022AC0AE059F80800FBF762FA0137AF42EF +:1039500044F8080008F1040809D0002FF2DA013712 +:103960000020AF4244F8080008F10408F5D1089A95 +:10397000002AC0F2DF82089A0B9B02F101089C002A +:1039800022AF4FEA880827440025029A002AC0F295 +:10399000F28105EB070B4FF000094FF0000A56F8D3 +:1039A00009005BF8041DFBF787FA01465046FBF758 +:1039B0007BF909F10409A1458246F0D14AA840F8F3 +:1039C00005A004354545E0D1089A0EAB03EB820310 +:1039D0000D9391464FEA89030793079A5EAB134410 +:1039E000B9F1000F53F850AC23DD0DF134084AAFA4 +:1039F000174490440DAD4FF06E515046FBF75CFA02 +:103A0000FBF720FCFBF704FA4FF087418346FBF7F6 +:103A100053FA01465046FBF745F9FBF713FC5946AC +:103A200045F8040F57F8040DFBF73EF9454582466B +:103A3000E1D15046069900F025FD4FF0785105463A +:103A4000FBF73AFA00F0BAFC4FF08241FBF734FA88 +:103A500001462846FBF726F90546FBF7F3FB8246AD +:103A6000FBF7D6F901462846FBF71CF9069A804673 +:103A7000002A40F3678109F1FF310EA850F8213088 +:103A8000C2F1080043FA00F202FA00F01B1A06988D +:103A90009244C0F1070743FA07F70EA840F8213017 +:103AA000002F32DDB9F1000F0AF1010A40F37581F0 +:103AB0000EAB079A19461144002507E0C2F5807045 +:103AC00012B143F8040C01258B420BD053F8042BA0 +:103AD000002DF3D0C2F1FF028B4243F8042C4FF0CB +:103AE0000105F3D1069B002B0DDD012B00F0328187 +:103AF000022B08D109F1FF330EA951F8232002F05F +:103B00003F0241F82320022F70D040460021FBF7EE +:103B100067FB002800F08380089A09F1FF35AA426C +:103B20000DDC079A0EAB0D981344002253F8041DC8 +:103B3000834242EA0102F9D1002A40F0E481089B65 +:103B40000EA85A1E50F82230002B40F0F18100EBF5 +:103B50008202012352F8041D01330029FAD04B449C +:103B600099450A933DDADDF82CA022AACA44DDF873 +:103B7000308002EB8A02C844C9EB0309131D03928B +:103B80000593699A079B4FEA89094AAF02EB8808B7 +:103B9000CDF810901F44002558F8040FFBF738F9B2 +:103BA000029B039A002B50514FF0000B13DBDDF802 +:103BB00014A04FF00009AA4456F809005AF8041D51 +:103BC000FBF77AF901465846FBF76EF809F104094C +:103BD000A1458346F0D1049A0435954247F804BFC5 +:103BE000DAD1DDF82890F5E6507F010841464FF024 +:103BF0007E50FBF757F88046002D86D006994FF08F +:103C00007E5000F03FFC01464046FBF74BF88046F3 +:103C100040460021FBF7E4FA00287FF47DAF069BC5 +:103C200040465942CDF808A000F02CFC4FF08741E7 +:103C30000446FBF7F3FA002800F07F814FF06E5145 +:103C40002046FBF739F9FBF7FDFAFBF7E1F84FF0F7 +:103C500087410546FBF730F901462046FBF722F87D +:103C6000FBF7F0FA0EAB43F829002846FBF7EAFA17 +:103C7000069C09F1010508340EA9069441F82500B7 +:103C800006994FF07E5000F0FDFB002D04464FDBFF +:103C90006E1C4FEA8508C6EB867A0DF138094AABEF +:103CA000C1444FEA8A0A98444FF0000B59F80B00C0 +:103CB000FBF7AEF82146FBF7FFF84FF06E5148F8DE +:103CC0000B002046FBF7F8F8ABF1040BD345044694 +:103CD000ECD1DFF88C92DDF820A00024B3460395E8 +:103CE0000497BAF1000FB8BF002515DB0026374650 +:103CF000002501E0A7420FDC58F8061059F806002D +:103D0000FBF7DAF801462846FAF7CEFF0137BA4545 +:103D1000054606F10406EDDA5EA800EB84030134E3 +:103D2000A345A8F1040843F8A05CDAD1039D049FE1 +:103D3000689C032C00F29880DFE814F0CB009C0014 +:103D40009C00310010D109F1FF330EA951F8237006 +:103D50003F12A5E609F1FF330EA850F8232002F028 +:103D60007F0240F82320CEE64FF07C51FBF756FA55 +:103D700058B90746C9E64FF0000A4AA840F805A01E +:103D8000043545457FF401AE1EE6B9F1000F4FF052 +:103D900002070AF1010A3FF78BAE0025A2E6002DCB +:103DA00040F3DC804FEA850B5EAB36AE05F1FF3A9F +:103DB0005B4406EB8A0A53F8A08C54465B4635AA4E +:103DC000BB462F4600E0C84654F8045941462846F1 +:103DD00001920093FAF768FF814649462846FAF7B0 +:103DE00061FF4146FAF760FF019AC4F804909442DB +:103DF000A060009BE7D13D46012D5F469B4640F306 +:103E0000AD805EAB9B445BF8A04C00E044465AF8A2 +:103E1000049921464846FAF747FF804641464846FE +:103E2000FAF740FF2146FAF73FFF5645CAF80480EB +:103E3000CAF80800EAD16C1C06EB8404002008369E +:103E400054F8041DFAF730FFB442F9D1002F7ED0A8 +:103E5000369A379B099C00F1004002F1004203F1C1 +:103E60000043A06022606360029A02F007005FB026 +:103E7000BDE8F08F002DB8BF00200ADB36AE6C1C09 +:103E8000002006EB840454F8041DFAF70DFFB44239 +:103E9000F9D1002F35D000F10043099C0146236081 +:103EA0003698FAF7FFFE002D08DD36AC04EB8505E9 +:103EB00054F8041FFAF7F8FEAC42F9D10FB100F143 +:103EC0000040099A5060029A02F007005FB0BDE816 +:103ED000F08F002D39DB6C1C36AE002006EB84041D +:103EE00054F8041DFAF7E0FEB442F9D10FB100F125 +:103EF0000040099A1060029A02F007005FB0BDE826 +:103F0000F08F0346C9E7069A0EAC54F82530083AFC +:103F1000CDF808A00692002B7FF4B2AE04EB850327 +:103F200053F8041D013D083A0029F9D00692A7E68E +:103F3000012314E60B9B9C0046E52046FBF782F923 +:103F40000EAA4D4642F829009AE60020CEE7099CC9 +:103F5000369A379BA0602260636085E7002075E792 +:103F60005C7F01082DE9F84320F00043B3F1485F7E +:103F700004460F46904603DAFBF764F9002857D051 +:103F800021462046FAF798FF21460546FAF794FFA6 +:103F9000294906462846FAF78FFF2849FAF782FE94 +:103FA0002946FAF789FF2649FAF77EFE2946FAF7ED +:103FB00083FF2449FAF776FE2946FAF77DFF224966 +:103FC000FAF772FE8146B8F1000F22D038464FF062 +:103FD0007C51FAF771FF494680463046FAF76CFF8C +:103FE00001464046FAF75EFE2946FAF765FF394674 +:103FF000FAF758FE154905463046FAF75DFF0146C7 +:104000002846FAF751FE01462046FAF74BFEBDE876 +:10401000F88349462846FAF74FFF0C49FAF742FE63 +:104020003146FAF749FF2146FAF73EFEBDE8F8832C +:104030002046BDE8F88300BFD3C92E2F342FD732D6 +:104040001BEF3836010D50398988083CABAA2A3E4F +:104050000020704700200149704700BF0000F87F32 +:104060002DE9F043C1F30A5CACF2FF37132F83B0A4 +:1040700002460B460D46894680464FEAD17630DC33 +:10408000002F4CDB3A49394101EA030010432DD09F +:10409000490801EA030858EA02080CD04FF48023CB +:1040A0003B41132F25EA010141EA030914BF4FF0F8 +:1040B00000084FF000482F494B4601EBC606D6E9F1 +:1040C0000045424620462946FAF78CF9CDE9000121 +:1040D000DDE9000122462B46FAF782F903B0BDE87C +:1040E000F083332F07DDB7F5806F3ED010461946B9 +:1040F00003B0BDE8F083ACF2134C4FF0FF3121FA6E +:104100000CF10142F2D049080142D4D04FF080486E +:1041100048FA0CFC20EA010141EA0C08CBE721F047 +:1041200000410143E2D0C3F3130101434C420C436D +:104130001048590C240B490404F4002444EA0103F8 +:1041400000EBC601D1E9004520462946FAF74AF9B5 +:10415000CDE90001DDE900012B462246FAF740F9DE +:1041600021F0004343EAC671C2E7FAF73BF9BFE723 +:10417000FFFF0F00887F01082DE9F04120F0004586 +:10418000B5F1A14F0446064608DBB5F1FF4F6FDCE1 +:10419000002840F3A0806F48BDE8F0816E4B9D423F +:1041A00077DCB5F1445F68DB4FF0FF3721462046EE +:1041B000FAF782FE01468046FAF77EFE6749054619 +:1041C000FAF77AFE6649FAF76FFD2946FAF774FEA8 +:1041D0006449FAF769FD2946FAF76EFE6249FAF773 +:1041E00063FD2946FAF768FE6049FAF75DFD294646 +:1041F000FAF762FE5E49FAF757FD4146FAF75CFEB0 +:104200005C4980462846FAF757FE5B49FAF74AFDB3 +:104210002946FAF751FE5949FAF744FD2946FAF7BB +:104220004BFE5749FAF73EFD2946FAF745FE554938 +:10423000FAF738FD2946FAF73FFE7B1C0146404657 +:104240004CD0FAF731FD2146FAF736FE4E4B4F4D72 +:1042500053F82710FAF726FD2146FAF723FD014609 +:1042600055F82700FAF71EFD002E30DBBDE8F0817F +:104270000146FAF719FDBDE8F0814549FAF714FD4A +:104280004FF07E51FAF7D4FF00288DD02046BDE8CC +:10429000F08100F087F83F4B04469D4229DCA3F5EE +:1042A000D0039D4244DC0146FAF7FEFC4FF07E51FC +:1042B000FAF7F8FC4FF0804105462046FAF7F4FC87 +:1042C00001462846FAF7ACFE002704466EE700F1E7 +:1042D0000040BDE8F0813048BDE8F081FAF7E4FC29 +:1042E0002146FAF7E9FD01462046FAF7DBFCBDE876 +:1042F000F0812A4B9D4214DC4FF07F51FAF7D2FC3B +:104300004FF07F5105462046FAF7D6FD4FF07E511B +:10431000FAF7CAFC01462846FAF782FE022704464D +:1043200044E701461E48FAF77BFE032704463DE7B3 +:104330004FF07E51FAF7B6FC4FF07E51054620460D +:10434000FAF7B2FC01462846FAF76AFE012704464E +:104350002CE700BFDB0FC93FFFFFDF3ED769853C7D +:1043600059DA4B3D356B883D6E2EBA3D2549123EDC +:10437000ABAAAA3E21A215BD6BF16E3D95879D3D6E +:10438000388EE33DCDCC4C3E987F0108A87F0108D4 +:10439000CAF24971FFFF973FDB0FC9BFFFFF1B4008 +:1043A000000080BF20F00040704700BF20F00040B8 +:1043B000B0F1FF4FACBF0020012070472DE9F04164 +:1043C00020F00047FD0D7F3D162D064613DC002D25 +:1043D00080461BDB194F2F41074214D01849FAF7CA +:1043E00063FC0021FAF724FF68B1002E1BDB28EAEA +:1043F0000700BDE8F081B7F1FF4F04D30146FAF79B +:1044000053FCBDE8F0813046BDE8F0810C49FAF775 +:104410004BFC0021FAF70CFF0028F4D0002E08DB3B +:104420000020BDE8F0814FF4000343FA05F5A844ED +:10443000DDE7002FE7D00348BDE8F081FFFF7F00F4 +:10444000CAF24971000080BF30F0004001D1022063 +:104450007047A0F50003B3F1FE4F01D2042070476E +:10446000054B421E9A4201D803207047B0F1FF432A +:1044700058425841704700BFFEFF7F000048704718 +:104480000000C07F38B530F00044024603460D46B8 +:1044900014D0B4F1FF4F0DD2B4F5000F0FD3E40DDB +:1044A0002C44FE2C2EDC002C1DDD23F0FF4343EAC0 +:1044B000C45038BD0146FAF7F7FB38BD38BD4FF0A0 +:1044C0009841FAF7F9FC194B02469D4207DBC0F30D +:1044D000C7540346193CE3E7154800F02DF814498A +:1044E000FAF7EAFC38BD14F1160F13DA4CF2503328 +:1044F0009D421146F0DD0F4800F01EF80D49FAF715 +:10450000DBFC38BD11460B4800F016F80949FAF7F4 +:10451000D3FC38BD04F1190023F0FF4343EAC05037 +:104520004FF04C51FAF7C8FC38BD00BFB03CFFFF5C +:104530006042A20DCAF2497101F0004120F0004032 +:1045400008437047014B1868704700BF30010020D6 +:10455000780000FF000000FF3C0000FFF00000FFBB +:104560000001746564666D6A69736C67010B020D06 +:104570000A03050B030D0A03070B030D0A03090BBE +:10458000020D0A030A0B040D0A03080B040D0A03AB +:104590001E0000FF4A0100FF2C0100FF0E0100FF7A +:1045A000D20000FFB40000FF960000FF5A0000FF99 +:1045B0000000FFFF70610108B04501085445010883 +:1045C0009045010858450108AC45010850450108CF +:1045D000A8450108A4450108A04501085C4501085B +:1045E0009C45010898450108944501080800000011 +:1045F00000200000000C014010000000002000001E +:1046000000100140000C014008001002000C0140A5 +:1046100010001002000C0140040014020000000011 +:104620000000000003010000204C0108040000000D +:10463000E04B010804000000A04B0108020100004B +:10464000804B01080001000000000000060000008F +:10465000204B010806000000C04A010801010000CB +:104660000000000004000000804A0108060000006D +:10467000204A010808000000A049010808000000C5 +:104680002049010808000000A048010801010000BD +:104690000000000000010000000000000001000018 +:1046A000000000000400000060480108060000004F +:1046B00000480108000100000000000002010000A5 +:1046C000E0470108010100000000000000000000B8 +:1046D00000000000C2470108AA4701088C470108F2 +:1046E00074470108FD8C0008B98C0008958C0008FF +:1046F0006D8C00085D8C0008DDE20008E98C000884 +:104700000D8C0008DD8C0008CF8C00080000000034 +:1047100000C20100746201089762010801000000F4 +:1047200000E10000AC620108CE6201080200000056 +:1047300000960000E2620108046301080300000023 +:10474000004B0000186301083A63010804000000F0 +:1047500080250000096701080967010800010002BF +:104760000002000009170000010002000200000022 +:10477000010700000001080309030A040B040C04EC +:104780000D040404050406040704FFFF00020102EF +:1047900002020302040205020602070208030903DB +:1047A0000A040B040C040D04FFFF000108030903B5 +:1047B0000A030B030C030D0304030503060307039D +:1047C000FFFF0002010202020302040205020602C8 +:1047D0000702080309030A030B030C030D03FFFF81 +:1047E0000000803F0000000000000000000080BFCB +:1047F0000000803F00000000000000000000803F3B +:104800000000803F000080BF0000803F000080BFAC +:104810000000803F000080BF000080BF0000803F9C +:104820000000803F0000803F0000803F0000803F8C +:104830000000803F0000803F000080BF000080BF7C +:104840000000803F000000000000000000000000A9 +:104850000000803F00000000000000000000000099 +:104860000000803F000000000000803F0000803F0B +:104870000000803F000080BF000080BF00000000FB +:104880000000803F000000000000803F000080BF6B +:104890000000803F0000803F000080BF00000080DB +:1048A0000000803F0000803F000000BF0000803F0C +:1048B0000000803F000000BF000080BF0000803F7C +:1048C0000000803F000080BF0000003F0000803FEC +:1048D0000000803F0000003F0000803F0000803F5C +:1048E0000000803F0000003F000080BF000080BF4C +:1048F0000000803F000080BF000000BF000080BFBC +:104900000000803F000000BF0000803F000080BF2B +:104910000000803F0000803F0000003F000080BF9B +:104920000000803FF704353FF70435BF0000803FAB +:104930000000803FF70435BFF70435BF0000803F1B +:104940000000803FF70435BFF704353F0000803F8B +:104950000000803FF704353FF704353F0000803FFB +:104960000000803F00000000000080BF000080BF0A +:104970000000803F000080BF00000000000080BFFA +:104980000000803F000000000000803F000080BF6A +:104990000000803F0000803F00000000000080BF5A +:1049A0000000803F000080BF0000803F000080BF0B +:1049B0000000803F000080BF000080BF0000803FFB +:1049C0000000803F0000803F0000803F0000803FEB +:1049D0000000803F0000803F000080BF000080BFDB +:1049E0000000803F000080BF0000803F0000803F4B +:1049F0000000803F000080BF000080BF000080BF3B +:104A00000000803F0000803F0000803F000080BF2A +:104A10000000803F0000803F000080BF0000803F1A +:104A20000000803F000000BFD0B35D3F0000803F2A +:104A30000000803F000000BFD0B35DBF0000803F9A +:104A40000000803F0000003FD0B35D3F000080BF0A +:104A50000000803F0000003FD0B35DBF000080BF7A +:104A60000000803F000080BF00000000000080BF09 +:104A70000000803F0000803F000000000000803FF9 +:104A80000000803F000000000000803F000080BF69 +:104A90000000803F000080BF000080BF00000000D9 +:104AA0000000803F000000000000803F0000803FC9 +:104AB0000000803F0000803F000080BF0000000039 +:104AC0000000803FD0B35DBF0000003F0000803F8A +:104AD0000000803FD0B35DBF000000BF000080BF7A +:104AE0000000803FD0B35D3F0000003F0000803FEA +:104AF0000000803FD0B35D3F000000BF000080BFDA +:104B00000000803F00000000000080BF0000803FE8 +:104B10000000803F000000000000803F000080BFD8 +:104B20000000803F00000000A8AAAA3F0000803FCC +:104B30000000803F000080BFB0AA2ABF000080BFF5 +:104B40000000803F0000803FB0AA2ABF000080BF65 +:104B50000000803F00000000A8AAAA3F000080BF1C +:104B60000000803F000080BFB0AA2ABF0000803F45 +:104B70000000803F0000803FB0AA2ABF0000803FB5 +:104B80000000803F0000803F0000000000000000A7 +:104B90000000803F000080BF000000000000000017 +:104BA0000000803F000080BF0000803F000080BF09 +:104BB0000000803F000080BF000080BF0000803FF9 +:104BC0000000803F0000803F0000803F0000803FE9 +:104BD0000000803F0000803F000080BF000080BFD9 +:104BE0000000803F000000000000803F000080BF08 +:104BF0000000803F000080BF000000000000803FF8 +:104C00000000803F0000803F000000000000803F67 +:104C10000000803F00000000000080BF000080BF57 +:104C20000000803F00000000A8AAAA3F000000008A +:104C30000000803F000080BFB0AA2ABF0000000033 +:104C40000000803F0000803FB0AA2ABF00000000A3 +:104C50001000000000200000001001400040000093 +:104C600000100140010001020001030001040001E5 +:104C70000500010600010700010800010900010A02 +:104C800000010B00010C0103000000004E6301084D +:104C90000000000001000000536301080100000053 +:104CA000020000005A630108020000000300000037 +:104CB0006363010803000000040000006963010849 +:104CC00005000000050000006E63010806000000FA +:104CD00006000000786301080700000007000000DC +:104CE0008163010808000000080000008A630108D1 +:104CF0000900000009000000936301080A00000099 +:104D00000A0000009D6301080B0000000B0000007A +:104D1000A76301080C0000000C000000B16301084B +:104D20000D0000000D000000B96301080E00000036 +:104D30000E000000C16301080F0000000F0000001A +:104D4000C96301081000000010000000D2630108D0 +:104D50001100000011000000D963010812000000DA +:104D600012000000E36301081300000013000000BC +:104D7000EB6301081400000014000000F663010852 +:104D80001500000015000000006401081600000076 +:104D90001600000000000000FF000000B5620601E0 +:104DA0000300F00500FF19B56206010300F00300DF +:104DB000FD15B56206010300F00100FB11B56206A6 +:104DC000010300F00000FA0FB56206010300F002D3 +:104DD00000FC13B56206010300F00400FE17B56283 +:104DE000060103000102010E47B56206010300013E +:104DF00003010F49B56206010300010601124FB518 +:104E000062060103000112011E67B5620608060072 +:104E1000C80001000100DE6A00B562061608000342 +:104E20000703000000000031E501B5620616080026 +:104E300003070300510800008A4102B56206160804 +:104E4000000307030004E00400199D03B562061681 +:104E50000800030703000002020035EF04B56206F4 +:104E60001608000307030080010000B2E80090016B +:104E7000C800C800C800C800C800C800C800C800F2 +:104E800064000000C800C800C800C800320000016B +:104E90001E1E646464646464220046022100820170 +:104EA00020004302100001010000490201008801B6 +:104EB00002004C02120084011100900111009001C7 +:104EC0001100A0011100A00100540040000C01409D +:104ED000400080001F20000000002000005800401B +:104EE000000C0140000400082122000000004000E6 +:104EF000778D0008958D0008B18D0008858A00081F +:104F0000DD8D0008E98D000802000000802500000A +:104F100000C2010000000000200000008025000009 +:104F200000C20100010000004000000080250000D8 +:104F300000C2010000000000010000008025000008 +:104F400000C20100000000001000000080250000E9 +:104F500000C20100000300000400000080250000E2 +:104F6000004B0000000000000800000000E100000D +:104F700000E10000000400008000000000C2010009 +:104F800000C2010000000000524F4C4C3B504954FD +:104F900043483B5941573B414C543B506F733B5046 +:104FA0006F73523B4E6176523B4C4556454C3B4DE0 +:104FB00041473B56454C3B00C6670108BD670108A9 +:104FC000B167010840008000000100020004495759 +:104FD0004641540102040810204E45535755442CB5 +:104FE0003A3A0000E9840008458D0008138D000856 +:104FF000EDAA0008618D0008E9AA0008B66A010858 +:10500000BA6A0108C06A0108C66A0108C96A0108CB +:10501000D06A0108D36A0108D86A0108E46A010865 +:10502000E76A0108ED6A0108F46A0108FE6A0108EE +:10503000086B0108116B01081F6B01082B6B01083D +:10504000326B0108386B0108456B0108506B010891 +:105050005D6B010800000000FA690108016A01089F +:10506000066A0108176A0108216A01082C6A01080A +:10507000376A0108426A0108466A01084F6A010856 +:10508000556A01085F6A01086D6A0108706A0108C3 +:10509000806A0108876A0108906A01089A6A010813 +:1050A000A26A0108AD6A01080000000000000000CB +:1050B0000000004F00000007000700147F147F1459 +:1050C000242A7F2A1223130864623649552250008D +:1050D00005030000001C2241000041221C001408AE +:1050E0003E081408083E0808005030000008080870 +:1050F0000808006060000020100804023E51494585 +:105100003E00427F400042615149462141454B31BA +:105110001814127F1027454545393C4A494930014A +:10512000710905033649494936064949291E0036A1 +:1051300036000000563600000814224100141414F2 +:105140001414004122140802015109063249794120 +:105150003E7E1111117E7F494949363E414141222F +:105160007F4141221C7F494949417F090909013E8C +:105170004149497A7F0808087F00417F410020406B +:10518000413F017F081422417F404040407F020C94 +:10519000027F7F0408107F3E4141413E7F0909099B +:1051A000063E4151215E7F09192946464949493148 +:1051B00001017F01013F4040403F1F2040201F3F31 +:1051C0004038403F631408146307087008076151B2 +:1051D000494543007F41410002040810200041413D +:1051E0007F000402010204404040404001020400EC +:1051F0000020545454787F48444438384444442070 +:10520000384444487F3854545418087E0901020633 +:105210004949493F7F0804047800447D400020400C +:10522000443D007F1028440000417F40007C04186A +:10523000047C7C0804047838444444387C141414F6 +:1052400008081414187C7C0804040848545454209A +:10525000043F4440203C4040207C1C2040201C3C1B +:105260004030403C44281028440C5050503C44648A +:10527000544C44000836410000007F0000004136D5 +:10528000080002010204023E5555412200000000C0 +:105290000000007900001824742E24487E49424002 +:1052A0005D2222225D15167C161500007700000A8B +:1052B000555555280001000100000A0D0A04081484 +:1052C0002A1422040404041C000808080001010137 +:1052D0000101000205020044445F4444000004024E +:1052E000017E2020103E060F7F007F00181800006E +:1052F0000040502000000A0D0A0022142A1408174A +:1053000008342A7D1708046A593048454020420075 +:105310004200427E420042007E7E0042007E7E7E4F +:1053200042007E7E7E7E007E7E7E7E7E05040203BF +:10533000AB6C0108B46C0108D5450008D86C0108B5 +:10534000DC6C010809470008F26C0108F76C0108E1 +:10535000456300080B6D0108116D0108C960000864 +:1053600020670108226D0108B57800083F6D01082B +:10537000446D01089DB30008736D010809670108B9 +:10538000196C0008786D0108806D01088999000882 +:10539000946D0108986D0108BDA60008AB6D010869 +:1053A000BA6D010885C00008D46D010809670108BD +:1053B000C5A50008D96D0108DD6D010841AE0008E2 +:1053C000EC6D0108F06D0108B5A80008056D010835 +:1053D0000C6E01088D5F00081F6E0108256E010824 +:1053E000296000082E780108406E010851B30008BA +:1053F0004F6E0108406E0108B18200085B6E010823 +:10540000606E0108456C0008E3650108706E0108D4 +:105410001DA700089E6E0108926E010811D00008B9 +:10542000F47501080967010895A500084820507225 +:105430006F647563743A426C61636B626F78206667 +:105440006C696768742064617461207265636F724F +:10545000646572206279204E6963686F6C617320A5 +:10546000536865726C6F636B0A4820426C61636BB2 +:10547000626F782076657273696F6E3A310A4820E0 +:10548000446174612076657273696F6E3A310A0007 +:105490004D6F010887700108D27001082071010862 +:1054A0006D710108BB710108426F010806720108A5 +:1054B000F26A0108067201084B6F010806720108C2 +:1054C00048204669656C642047206E616D653A47E7 +:1054D00050535F6E756D5361742C4750535F636F0B +:1054E0006F72645B305D2C4750535F636F6F726403 +:1054F0005B315D2C4750535F616C746974756465F2 +:105500002C4750535F73706565640A48204669658F +:105510006C642047207369676E65643A302C312CC7 +:10552000312C302C300A48204669656C64204720B5 +:10553000707265646963746F723A302C372C372C43 +:10554000302C300A48204669656C64204720656E1F +:10555000636F64696E673A312C302C302C312C31FA +:105560000A48204669656C642048206E616D653A82 +:105570004750535F686F6D655B305D2C4750535FDC +:10558000686F6D655B315D0A48204669656C642013 +:1055900048207369676E65643A312C310A482046A9 +:1055A00069656C64204820707265646963746F7209 +:1055B0003A302C300A48204669656C6420482065E2 +:1055C0006E636F64696E673A302C300A0000020225 +:1055D0000308050A0B080A0A0B0C0E0E0F00000048 +:1055E000E8720108ED720108F1720108FA7201080F +:1055F0004F6A0108426A0108F672010800000000C3 +:1056000009670108A4720108AC720108B4720108AC +:10561000BC720108C3720108CE720108D67201087B +:10562000DE720108E37201080000000000000000C3 +:105630008025000000C201000600000001000000FB +:105640008025000000C201000700000003000000E8 +:1056500080250000004B000009000000040000004D +:1056600080250000004B000009000000FE720108C8 +:10567000440000003C20002000000000282300001F +:1056800007730108410000003E20002000000000D8 +:105690000100000015730108440000004A210020A9 +:1056A000B0040000A40600001C73010844000000C0 +:1056B0004C21002000000000D007000026730108E4 +:1056C000440000004E21002000000000D007000030 +:1056D000307301084200000050210020000000004B +:1056E000120000003D73010842000000512100201B +:1056F00001000000FF0000004873010842000000A4 +:105700005221002000000000010000005D7301082C +:10571000440000000021002000000000D00700002D +:105720006A7301084400000002210020000000000C +:10573000D007000077730108440000000421002016 +:1057400000000000D007000083730108440000003F +:105750000621002000000000D0070000937301081C +:10576000440000000821002000000000D0070000D5 +:10577000A4730108440000000A210020000000007A +:10578000D0070000AF730108440000000C21002086 +:1057900000000000D0070000C473010844000000AE +:1057A0000E21002032000000007D0000D3730108AC +:1057B000440000001021002032000000F20100002F +:1057C000E2730108410000005321002000000000A6 +:1057D00001000000EF730108410000005421002087 +:1057E00000000000010000000274010841000000F8 +:1057F0005521002000000000B40000000E740108D4 +:10580000410000005621002000000000640000005C +:105810001A7401084200000057210020FFFFFFFF1B +:105820000100000030740108410000005C210020EC +:10583000000000000B000000477401084100000058 +:105840005D210020000000000B0000005E740108D4 +:10585000410000005E210020000000000B0000005D +:1058600075740108410000005F2100200000000065 +:105870000B0000008C740108410000007021002022 +:10588000300000007E0000009D7401085000000000 +:1058900060210020B004000000C20100AA740108C9 +:1058A0005000000064210020B004000000C201008C +:1058B000B7740108500000006821002000000000BB +:1058C00000C20100C4740108500000006C210020D7 +:1058D000B004000000C20100DD74010841000000B6 +:1058E000582100200000000001000000EA740108B7 +:1058F00041000000592100200000000004000000C9 +:10590000F8740108410000005A2100200000000046 +:105910000100000008750108810000004C220020F1 +:1059200000000000C800000012750108810000009E +:105930005622002000000000C80000001C7501086D +:10594000810000006022002000000000C80000006C +:1059500026750108810000004D2200200000000093 +:10596000C8000000317501088100000057220020A6 +:1059700000000000C80000003C7501088100000024 +:105980006122002000000000C800000047750108E7 +:10599000810000004E22002000000000C80000002E +:1059A000517501088100000058220020000000000D +:1059B000C80000005B750108810000006222002021 +:1059C00000000000C80000006575010884000000A8 +:1059D000F623002000000000D007000073750108C6 +:1059E00081000000FA2300200000000001000000F8 +:1059F0008875010884000000FC2300200A000000D4 +:105A0000D00700009675010884000000FE230020E6 +:105A10000A000000D0070000A47501088100000002 +:105A2000F92300200000000064000000B2750108A6 +:105A30004100000048210020000000000300000099 +:105A4000C47501084100000074210020000000001E +:105A500003000000D77501084100000075210020F7 +:105A60000000000001000000E8750108410000008E +:105A7000762100200000000001000000FC750108F4 +:105A80006000000078210020A6FFFFFF5A00000000 +:105A900014760108600000007C2100204CFFFFFF0D +:105AA000B40000002C760108410000008021002095 +:105AB00000000000010000004576010841000000E0 +:105AC0008121002000000000010000005076010844 +:105AD000440000003E21002000000000204E000095 +:105AE0006176010841000000342100200000000020 +:105AF000FF0000006C760108410000003521002005 +:105B00000A00000032000000827601084100000017 +:105B1000362100200A0000003200000098760108BB +:105B20004400000038210020010000001027000080 +:105B3000AC760108440000003A210020000000007B +:105B400072060000C1760108410000003C210020DF +:105B50000000000001000000DF76010841000000A5 +:105B6000122100200000000008000000EA76010871 +:105B70004100000013210020000000000800000088 +:105B8000F47601084100000014210020000000000C +:105B900008000000FE7601084800000016210020E1 +:105BA0004CFFFFFF680100000F770108480000006C +:105BB000182100204CFFFFFF680100002177010839 +:105BC000480000001A2100204CFFFFFF6801000080 +:105BD0003177010844000000262100206400000005 +:105BE0008403000047770108440000001E210020C4 +:105BF0000000000000010000507701084100000093 +:105C000024210020000000008000000060770108CF +:105C1000440000002021002064000000E803000090 +:105C20007177010844000000222100206400000078 +:105C3000E80300008377010881000000A32300200F +:105C400001000000FA0000009577010881000000C3 +:105C5000A423002000000000010000008C77010850 +:105C600081000000A12300200000000020000000AF +:105C7000AA77010881000000A22300200000000094 +:105C800064000000B777010881000000A82300200D +:105C90000000000096000000D17701088400000099 +:105CA000A62300200100000084030000EB77010818 +:105CB000420000001C210020FFFFFFFF0100000048 +:105CC0000178010882000000F2230020FFFFFFFF9F +:105CD000010000000F78010882000000F32300207B +:105CE0000000000001000000217801088100000090 +:105CF0009422002000000000020000003678010815 +:105D0000010100008627002000000000FA000000CA +:105D10003E780108010100008727002000000000F4 +:105D20006400000046780108010100008827002077 +:105D300000000000640000004E780108010100002E +:105D40008927002000000000640000005778010847 +:105D5000010100008A27002000000000640000000C +:105D600067780108010100008B2700200000000077 +:105D70006400000070780108010100008C270020F9 +:105D800000000000640000007978010804010000B0 +:105D90008E270020E8030000D00700008878010863 +:105DA00081000000EA23002000000000C80000007D +:105DB0009778010881000000EB230020000000001C +:105DC000C8000000AA78010884000000EC2300202D +:105DD000E8030000D0070000BC7801088400000040 +:105DE000EE23002064000000D0070000CE780108F8 +:105DF00084000000F023002064000000B80B0000C5 +:105E0000E078010881000000F42300200000000079 +:105E1000FF000000ED780108410000001D21002076 +:105E20000000000009000000FA780108810000006D +:105E30009C22002000000000FA00000009790108FF +:105E400081000000A4220020000000006400000087 +:105E50001879010881000000A52200200000000040 +:105E60006400000026790108A0000000A0220020A4 +:105E700001000000140000003679010881000000D4 +:105E8000B822002000000000010000004579010850 +:105E9000880000009A220020D4FEFFFF2C010000A1 +:105EA000547901088800000098220020D4FEFFFFEA +:105EB0002C0100006279010881000000A822002066 +:105EC000000000003000000070790108A000000010 +:105ED000AC22002000000000010000007F790108D2 +:105EE000A0000000B022002000000000010000001F +:105EF0008B790108A0000000B422002000000000FF +:105F00000100000097790108880000009622002017 +:105F1000B0B9FFFF50460000A779010881000000DA +:105F2000442200200000000002000000B6790108B1 +:105F3000810000004922002000000000C80000008D +:105F4000BE790108810000005322002000000000FB +:105F5000C800000019770108810000005D220020C0 +:105F600000000000C8000000C679010881000000A0 +:105F70004822002000000000C8000000CD79010880 +:105F8000810000005222002000000000C800000034 +:105F900008770108810000005C220020000000005A +:105FA000C8000000D4790108810000004A220020C6 +:105FB00000000000C8000000DA790108810000003C +:105FC0005422002000000000C80000002B770108C8 +:105FD000810000005E22002000000000C8000000D8 +:105FE000E0790108A00000006C2200200000000001 +:105FF00064000000E9790108A00000007822002078 +:106000000000000064000000F2790108A000000018 +:10601000842200200000000064000000FB790108D9 +:10602000A0000000682200200000000064000000C2 +:10603000037A0108A0000000742200200000000084 +:10604000640000000B7A0108A000000080220020FC +:106050000000000064000000137A0108A0000000A6 +:106060007022002000000000640000001A7A01087D +:10607000A00000007C22002000000000640000005E +:10608000217A0108A0000000882200200000000002 +:1060900064000000287A0108A0000000902200207F +:1060A000000000000A000000367A0108A00000008D +:1060B0008C220020000000000A000000427A010843 +:1060C000810000004B22002000000000C8000000FA +:1060D000487A0108810000005522002000000000DD +:1060E000C80000004E7A0108810000005F220020F5 +:1060F00000000000C8000000547A01088100000080 +:106100004F22002000000000C80000005C7A010857 +:10611000810000005922002000000000C80000009B +:10612000647A010881000000632200200000000062 +:10613000C80000006C7A0108810000005122002094 +:1061400000000000C8000000727A01088100000011 +:106150005B22002000000000C8000000787A0108DF +:10616000810000006522002000000000C80000003F +:1061700000000000300810020002000100060008C4 +:106180000008100140080007100720070004100451 +:10619000200800000000004000080140010000004D +:1061A000001C002800000040000801400200000020 +:1061B000041C00280000004000080140040000000A +:1061C000081C0028000000400008014008000000F2 +:1061D0000C1C0028000400400008014040000000A2 +:1061E000001D00280004004000080140800000005D +:1061F000041D002800040040000C014001000000C4 +:10620000081D002800040040000C014002000000AE +:106210000C1D0028002C0140000801400001000076 +:10622000001B0128002C014000080140000800006C +:106230000C1B012800080040000C01404000000039 +:10624000001E002800080040000C014080000000F3 +:10625000041E002800080040000C0140000100005E +:10626000081E002800080040000C01400002000049 +:106270000C1E002824505542582C34312C312C301F +:106280003030332C303030312C3131353230302C0D +:10629000302A31450D0A0024504D544B3235312CF3 +:1062A0003131353230302A31460D0A002450554202 +:1062B000582C34312C312C303030332C30303031BC +:1062C0002C35373630302C302A32440D0A00245019 +:1062D0004D544B3235312C35373630302A32430D60 +:1062E0000A0024505542582C34312C312C30303097 +:1062F000332C303030312C33383430302C302A329B +:10630000360D0A0024504D544B3235312C3338347D +:1063100030302A32370D0A0024505542582C34317F +:106320002C312C303030332C303030312C3139326C +:1063300030302C302A32330D0A0024504D544B3269 +:1063400035312C31393230302A32320D0A00415287 +:106350004D3B00414E474C453B00484F52495A4F38 +:106360004E3B004241524F3B004D41473B004845A8 +:106370004144465245453B004845414441444A3B1F +:106380000043414D535441423B0043414D54524917 +:10639000473B0047505320484F4D453B0047505323 +:1063A00020484F4C443B0050415353544852553BB6 +:1063B000004245455045523B004C45444D41583BF9 +:1063C000004C45444C4F573B004C4C4947485453B4 +:1063D0003B0043414C49423B00474F5645524E4FCC +:1063E000523B004F53442053573B0054454C454DBE +:1063F000455452593B004155544F54554E453B006E +:10640000534F4E41523B0061646A72616E67652072 +:1064100025752025752025752025752025752025B5 +:10642000752025750D0A0061757820257520257564 +:106430002025752025752025750D0A00004F201098 +:1064400004430240010880C343757272656E742074 +:106450006D697865723A2025730D0A00417661698D +:106460006C61626C65206D69786572733A200025F5 +:10647000732000496E76616C6964206D697865727D +:1064800020747970650D0A004D6978657220736516 +:106490007420746F2025730D0A0055736167653A87 +:1064A0000D0A6D6F746F7220696E646578205B767B +:1064B000616C75655D202D2073686F77205B6F724E +:1064C000207365745D206D6F746F722076616C75DA +:1064D000650D0A004E6F2073756368206D6F746FD1 +:1064E000722C207573652061206E756D6265722057 +:1064F0005B302C2025645D0D0A004D6F746F722097 +:106500002564206973207365742061742025640DEF +:106510000A00496E76616C6964206D6F746F722039 +:1065200076616C75652C20313030302E2E32303053 +:10653000300D0A0053657474696E67206D6F746F57 +:106540007220256420746F2025640D0A00636F6C2F +:106550006F722025752025642C25752C25750D0A54 +:1065600000496E76616C696420636F6C6F7220699C +:106570006E6465783A206D757374206265203C20E6 +:1065800025750D0A005061727365206572726F7215 +:106590000D0A002E004E4709004F4B09004375734A +:1065A000746F6D206D697865723A200D0A4D6F74B5 +:1065B0006F720954687209526F6C6C095069746388 +:1065C00068095961770D0A002325643A090025738B +:1065D000090053616E69747920636865636B3A09D9 +:1065E000007265736574006C6F6164004C6F616468 +:1065F0006564202573206D69780D0A0057726F6EEF +:1066000067206E756D626572206F662061726775B6 +:106610006D656E74732C206E656564732069647893 +:106620002074687220726F6C6C20706974636820CB +:106630007961770D0A004D6F746F72206E756D620F +:106640006572206D7573742062652062657477656C +:10665000656E203120616E642025640D0A000D0AEC +:106660005265626F6F74696E67000D0A4C656176E2 +:10667000696E6720434C49206D6F64652C20756EF0 +:106680007361766564206368616E676573206C6F03 +:1066900073742E0D0A00536176696E67000D0A450A +:1066A0006E746572696E6720434C49204D6F646556 +:1066B0002C20747970652027657869742720746FA1 +:1066C0002072657475726E2C206F72202768656C5D +:1066D00070270D0A000D0A2320000D1B5B4B001BC9 +:1066E0005B324A1B5B313B314800556E6B6E6F77F6 +:1066F0006E20636F6D6D616E642C2074727920273B +:1067000068656C70270008200800414554523132FA +:10671000333400526573657474696E6720746F203A +:1067200064656661756C7473007261746570726F14 +:1067300066696C652025640D0A00303132333435CA +:10674000363738394142434445464748494A4B4C1D +:106750004D4E4F505152535455565758595A004563 +:106760006E61626C65642066656174757265733A0A +:106770002000417661696C61626C652066656174B8 +:10678000757265733A2000496E76616C69642066A3 +:10679000656174757265206E616D650D0A004469EE +:1067A0007361626C65642000456E61626C65642093 +:1067B0000044656320313020323031340031353AC5 +:1067C00033303A3430006534393261613600414645 +:1067D0004E4100436C65616E666C696768742F2575 +:1067E00073202573202F202573202825732900412D +:1067F0007661696C61626C6520636F6D6D616E645A +:10680000733A0D0A0025730925730D0A00202564CB +:1068100020256400556E6B6E6F776E20766172690D +:1068200061626C65206E616D650D0A004375727260 +:10683000656E742073657474696E67733A200D0A0F +:106840000025732073657420746F200056616C7589 +:10685000652061737369676E6D656E74206F757402 +:10686000206F662072616E67650D0A004D75737446 +:1068700020626520616E79206F72646572206F6698 +:106880002041455452313233340D0A00437572723F +:10689000656E742061737369676E6D656E743A20FE +:1068A00000736574202573203D200025752C257507 +:1068B0003A25733A2573006C65642025752025738D +:1068C0000D0A00496E76616C6964206C656420690C +:1068D0006E6465783A206D757374206265203C2083 +:1068E00025750D0A006D61737465720072617465BF +:1068F00073000D0A232076657273696F6E0D0A00AE +:106900000D0A232064756D70206D61737465720DBE +:106910000A000D0A23206D697865720D0A006D6901 +:106920007865722025730D0A00636D6978202564EF +:1069300000636D69782025642030203020302030BD +:106940000D0A000D0A0D0A232066656174757265D3 +:106950000D0A0066656174757265202D25730D0A38 +:1069600000666561747572652025730D0A000D0A55 +:106970000D0A23206D61700D0A006D617020257372 +:106980000D0A000D0A0D0A23206C65640D0A000D26 +:106990000A0D0A2320636F6C6F720D0A000D0A2323 +:1069A0002064756D702070726F66696C650D0A00E9 +:1069B0000D0A232070726F66696C650D0A000D0A5E +:1069C00023206175780D0A000D0A232061646A7224 +:1069D000616E67650D0A000D0A232064756D7020D5 +:1069E00072617465730D0A000D0A2320726174656B +:1069F00070726F66696C650D0A0052585F50504D99 +:106A0000005642415400494E464C494748545F4164 +:106A100043435F43414C0052585F53455249414CF8 +:106A2000004D4F544F525F53544F500053455256F0 +:106A30004F5F54494C5400534F46545345524941BB +:106A40004C00475053004641494C53414645005382 +:106A50004F4E41520054454C454D45545259004308 +:106A6000555252454E545F4D4554455200334400F3 +:106A700052585F504152414C4C454C5F50574D006D +:106A800052585F4D535000525353495F41444300A5 +:106A90004C45445F535452495000444953504C4173 +:106AA00059004F4E4553484F5431323500424C4106 +:106AB000434B424F580054524900515541445000F5 +:106AC00051554144580042490047494D42414C000C +:106AD0005936004845583600464C59494E475F578D +:106AE000494E47005934004845583658004F4354E2 +:106AF0004F5838004F43544F464C415450004F4379 +:106B0000544F464C41545800414952504C414E4517 +:106B10000048454C495F3132305F4343504D004897 +:106B2000454C495F39305F44454700565441494C14 +:106B3000340048455836480050504D5F544F5F531D +:106B40004552564F004455414C434F505445520016 +:106B500053494E474C45434F5054455200435553BB +:106B6000544F4D0041455254313233343536373865 +:106B70006162636465666768005265763A202573D2 +:106B8000005461726765743A20257300566F6C7407 +:106B9000733A2025642E2531642043656C6C733A6A +:106BA00020256400416D70733A2025642E253264DF +:106BB000206D41683A2025640020202020202020DC +:106BC000205820202020205920202020205A004119 +:106BD000203D202535642025356420253564004777 +:106BE000203D202535642025356420253564004D61 +:106BF000203D20253564202535642025356400504E +:106C0000726F66696C653A20256400526174652074 +:106C100070726F66696C653A2025640052432045A6 +:106C200078706F3A20256400524320526174653AAF +:106C30002025640052265020526174653A20256454 +:106C40000059617720526174653A202564007C2FD9 +:106C50002D5C00434C45414E464C49474854004149 +:106C6000524D454400424154544552590053454EFB +:106C7000534F52530052580050524F46494C450012 +:106C80004E415A45004572726F723A20456E6162FC +:106C90006C6520616E6420706C756720696E20479A +:106CA00050532066697273740D0A0061646A7261E0 +:106CB0006E67650073686F772F7365742061646A0F +:106CC0007573746D656E742072616E676573207381 +:106CD000657474696E6773006175780073686F77A7 +:106CE0002F736574206175782073657474696E679D +:106CF0007300636D69780064657369676E206375FE +:106D000073746F6D206D6978657200636F6C6F725C +:106D100000636F6E66696775726520636F6C6F7272 +:106D20007300726573657420746F206465666175A5 +:106D30006C747320616E64207265626F6F7400649E +:106D4000756D70007072696E7420636F6E6669672E +:106D5000757261626C652073657474696E67732007 +:106D6000696E2061207061737461626C6520666F6A +:106D7000726D00657869740066656174757265008E +:106D80006C697374206F72202D76616C206F722095 +:106D900076616C006765740067657420766172695E +:106DA00061626C652076616C7565006770737061F7 +:106DB00073737468726F7567680070617373746859 +:106DC000726F7567682067707320746F20736572C7 +:106DD00069616C0068656C70006C656400636F6E5F +:106DE000666967757265206C656473006D6170001B +:106DF0006D617070696E67206F66207263206368D2 +:106E0000616E6E656C206F72646572006D69786585 +:106E100072206E616D65206F72206C697374006DF5 +:106E20006F746F72006765742F736574206D6F7473 +:106E30006F72206F75747075742076616C75650063 +:106E4000696E64657820283020746F2032290072C2 +:106E500061746570726F66696C6500736176650058 +:106E60007361766520616E64207265626F6F740075 +:106E70006E616D653D76616C7565206F7220626C28 +:106E8000616E6B206F72202A20666F72206C6973AE +:106E9000740073686F772073797374656D207374F1 +:106EA000617475730048204669726D776172652060 +:106EB000747970653A436C65616E666C6967687475 +:106EC0000A0048204669726D7761726520726576A6 +:106ED0006973696F6E3A25730A0048204669726DBE +:106EE0007761726520646174653A25732025730AA1 +:106EF0000048207263526174653A25640A00482094 +:106F00006D696E7468726F74746C653A25640A00FA +:106F100048206D61787468726F74746C653A25648A +:106F20000A0048206779726F2E7363616C653A308E +:106F30007825780A0048206163635F31473A2575F8 +:106F40000A00736572766F5B355D0031004820463C +:106F500069656C642049206E616D653A6C6F6F7075 +:106F6000497465726174696F6E2C74696D652C610A +:106F7000786973505B305D2C61786973505B315D6B +:106F80002C61786973505B325D2C61786973495B61 +:106F9000305D2C61786973495B315D2C6178697370 +:106FA000495B325D2C61786973445B305D2C61789C +:106FB0006973445B315D2C61786973445B325D2C8D +:106FC0007263436F6D6D616E645B305D2C72634301 +:106FD0006F6D6D616E645B315D2C7263436F6D6DBF +:106FE000616E645B325D2C7263436F6D6D616E64C4 +:106FF0005B335D2C6779726F446174615B305D2C2B +:107000006779726F446174615B315D2C6779726F6F +:10701000446174615B325D2C616363536D6F6F74A7 +:10702000685B305D2C616363536D6F6F74685B31B7 +:107030005D2C616363536D6F6F74685B325D2C6DA3 +:107040006F746F725B305D2C6D6F746F725B315D4E +:107050002C6D6F746F725B325D2C6D6F746F725B31 +:10706000335D2C6D6F746F725B345D2C6D6F746F5C +:10707000725B355D2C6D6F746F725B365D2C6D6F5E +:10708000746F725B375D0048204669656C64204907 +:10709000207369676E65643A302C302C312C312CAA +:1070A000312C312C312C312C312C312C312C312CF8 +:1070B000312C312C302C312C312C312C312C312CE9 +:1070C000312C302C302C302C302C302C302C302CDF +:1070D000300048204669656C642049207072656400 +:1070E0006963746F723A302C302C302C302C302C79 +:1070F000302C302C302C302C302C302C302C302CB0 +:10710000302C342C302C302C302C302C302C302C9B +:10711000342C352C352C352C352C352C352C350094 +:1071200048204669656C64204920656E636F646918 +:107130006E673A312C312C302C302C302C302C30E6 +:107140002C302C302C302C302C302C302C302C315E +:107150002C302C302C302C302C302C302C312C304E +:107160002C302C302C302C302C302C300048204649 +:1071700069656C64205020707265646963746F7215 +:107180003A362C322C312C312C312C312C312C3103 +:107190002C312C312C312C312C312C312C312C3305 +:1071A0002C332C332C332C332C332C332C332C33E7 +:1071B0002C332C332C332C332C3300482046696578 +:1071C0006C64205020656E636F64696E673A302C82 +:1071D000302C302C302C302C372C372C372C302CBA +:1071E000302C302C382C382C382C382C302C302C9F +:1071F000302C302C302C302C302C302C302C302CAF +:10720000302C302C302C300053797374656D205540 +:107210007074696D653A202564207365636F6E64D0 +:10722000732C20566F6C746167653A202564202AA0 +:1072300020302E31562028256453206261747465F5 +:107240007279290D0A004350552025644D487A2C47 +:107250002064657465637465642073656E736F7212 +:10726000733A200041434348573A202573002E25A6 +:1072700063004379636C652054696D653A20256429 +:107280002C20493243204572726F72733A20256474 +:107290002C20636F6E6669672073697A653A2025D2 +:1072A000640D0A004144584C333435004D50553676 +:1072B000303530004D4D413834357800424D413243 +:1072C0003830004C534D333033444C4843004D501C +:1072D0005536303030004D5055363530300046414F +:1072E0004B45004E6F6E65004759524F0041434376 +:1072F000004241524F004750532B4D4147006C6FA5 +:107300006F7074696D6500656D665F61766F696445 +:10731000616E6365006D69645F7263006D696E5FC5 +:10732000636865636B006D61785F636865636B00BC +:10733000727373695F6368616E6E656C00727373FC +:10734000695F7363616C6500696E7075745F66690F +:107350006C746572696E675F6D6F6465006D696EF0 +:107360005F7468726F74746C65006D61785F7468C7 +:10737000726F74746C65006D696E5F636F6D6D61C3 +:107380006E640033645F6465616462616E645F6C47 +:107390006F770033645F6465616462616E645F6827 +:1073A0006967680033645F6E65757472616C003381 +:1073B000645F6465616462616E645F7468726F7457 +:1073C000746C65006D6F746F725F70776D5F726162 +:1073D000746500736572766F5F70776D5F7261744C +:1073E000650072657461726465645F61726D0064EA +:1073F000697361726D5F6B696C6C5F7377697463DD +:107400006800736D616C6C5F616E676C6500666CC3 +:107410006170735F73706565640066697865647731 +:10742000696E675F616C74686F6C645F6469720039 +:1074300073657269616C5F706F72745F315F7363E3 +:10744000656E6172696F0073657269616C5F706F00 +:1074500072745F325F7363656E6172696F0073652A +:107460007269616C5F706F72745F335F7363656EB6 +:107470006172696F0073657269616C5F706F7274BD +:107480005F345F7363656E6172696F007265626F0E +:107490006F745F636861726163746572006D7370AD +:1074A0005F626175647261746500636C695F6261DB +:1074B000756472617465006770735F626175647290 +:1074C000617465006770735F706173737468726F65 +:1074D0007567685F62617564726174650067707377 +:1074E0005F70726F7669646572006770735F736254 +:1074F00061735F6D6F6465006770735F6175746F52 +:107500005F636F6E666967006770735F706F735F4C +:1075100070006770735F706F735F69006770735F8F +:10752000706F735F64006770735F706F73725F700A +:10753000006770735F706F73725F69006770735F6D +:10754000706F73725F64006770735F6E61765F70F7 +:10755000006770735F6E61765F69006770735F6E5E +:1075600061765F64006770735F77705F72616469F2 +:107570007573006E61765F636F6E74726F6C735FAC +:1075800068656164696E67006E61765F73706565DA +:10759000645F6D696E006E61765F73706565645FD0 +:1075A0006D6178006E61765F736C65775F72617490 +:1075B000650073657269616C72785F70726F76696D +:1075C0006465720074656C656D657472795F707264 +:1075D0006F76696465720074656C656D6574727947 +:1075E0005F7377697463680074656C656D65747248 +:1075F000795F696E76657273696F6E006672736B20 +:10760000795F64656661756C745F6C6174746974CC +:10761000756465006672736B795F64656661756C2D +:10762000745F6C6F6E676974756465006672736B06 +:10763000795F636F6F7264696E617465735F666FA3 +:10764000726D6174006672736B795F756E69740038 +:10765000626174746572795F636170616369747982 +:1076600000766261745F7363616C65007662617459 +:107670005F6D61785F63656C6C5F766F6C7461677A +:107680006500766261745F6D696E5F63656C6C5FE7 +:10769000766F6C746167650063757272656E745F96 +:1076A0006D657465725F7363616C6500637572729A +:1076B000656E745F6D657465725F6F666673657421 +:1076C000006D756C74697769695F63757272656E58 +:1076D000745F6D657465725F6F7574707574006149 +:1076E0006C69676E5F6779726F00616C69676E5F66 +:1076F00061636300616C69676E5F6D616700616CF7 +:1077000069676E5F626F6172645F726F6C6C00615B +:107710006C69676E5F626F6172645F7069746368E1 +:1077200000616C69676E5F626F6172645F79617737 +:10773000006D61785F616E676C655F696E636C692F +:107740006E6174696F6E006779726F5F6C7066004E +:107750006D6F726F6E5F7468726573686F6C6400D2 +:107760006779726F5F636D70665F666163746F7275 +:10777000006779726F5F636D70666D5F66616374D9 +:107780006F7200616C745F686F6C645F64656164E4 +:1077900062616E6400616C745F686F6C645F6661E7 +:1077A00073745F6368616E6765007961775F6465B4 +:1077B000616462616E64007468726F74746C655F9A +:1077C000636F7272656374696F6E5F76616C756505 +:1077D000007468726F74746C655F636F7272656356 +:1077E00074696F6E5F616E676C65007961775F6366 +:1077F0006F6E74726F6C5F646972656374696F6ECB +:10780000007961775F646972656374696F6E007493 +:1078100072695F756E61726D65645F736572766FB4 +:107820000064656661756C745F726174655F707227 +:107830006F66696C650072635F7261746500726384 +:107840005F6578706F007468725F6D69640074685A +:10785000725F6578706F00726F6C6C5F70697463D3 +:10786000685F72617465007961775F726174650049 +:107870007470615F72617465007470615F627265DB +:10788000616B706F696E74006661696C73616665C7 +:107890005F64656C6179006661696C736166655FE0 +:1078A0006F66665F64656C6179006661696C7361BF +:1078B00066655F7468726F74746C65006661696C8C +:1078C000736166655F6D696E5F75736563006661A0 +:1078D000696C736166655F6D61785F757365630080 +:1078E00067696D62616C5F666C6167730061636399 +:1078F0005F6861726477617265006163635F6C7079 +:10790000665F666163746F720061636378795F6458 +:1079100065616462616E64006163637A5F6465617E +:107920006462616E64006163637A5F6C70665F635A +:1079300075746F6666006163635F756E61726D6515 +:107940006463616C006163635F7472696D5F706929 +:10795000746368006163635F7472696D5F726F6CFA +:107960006C006261726F5F7461625F73697A650057 +:107970006261726F5F6E6F6973655F6C70660062E3 +:1079800061726F5F63665F76656C006261726F5FE4 +:1079900063665F616C74006D61675F6465636C69E9 +:1079A0006E6174696F6E007069645F636F6E74728C +:1079B0006F6C6C657200705F706974636800695FFA +:1079C000706974636800705F726F6C6C00695F72DD +:1079D0006F6C6C00705F79617700695F7961770027 +:1079E000705F70697463686600695F70697463686A +:1079F0006600645F70697463686600705F726F6CC4 +:107A00006C6600695F726F6C6C6600645F726F6CAD +:107A10006C6600705F7961776600695F796177668F +:107A200000645F79617766006C6576656C5F686F8E +:107A300072697A6F6E006C6576656C5F616E676CFB +:107A40006500705F616C7400695F616C7400645FF5 +:107A5000616C7400705F6C6576656C00695F6C6565 +:107A600076656C00645F6C6576656C00705F76654A +:107A70006C00695F76656C00645F76656C00002061 +:107A800020202020202020202828282828202020CE +:107A9000202020202020202020202020202020887E +:107AA00010101010101010101010101010101004E2 +:107AB0000404040404040404041010101010101032 +:107AC0004141414141410101010101010101010126 +:107AD000010101010101010101011010101010103C +:107AE00042424242424202020202020202020202F6 +:107AF0000202020202020202020210101010200012 +:107B00000000000000000000000000000000000075 +:107B10000000000000000000000000000000000065 +:107B20000000000000000000000000000000000055 +:107B30000000000000000000000000000000000045 +:107B40000000000000000000000000000000000035 +:107B50000000000000000000000000000000000025 +:107B60000000000000000000000000000000000015 +:107B70000000000000000000000000000000000005 +:107B80000000004B000000CB61636F7366000000D3 +:107B9000706F7766000000007371727466000000F9 +:107BA0000000000000C0153F00000000DCCFD13510 +:107BB0000000803F0000C03F000FC93F000F494058 +:107BC00000CB9640000FC9400053FB4000CB16414C +:107BD00000ED2F41000F49410031624100537B41CC +:107BE000003A8A4100CB9641005CA34100EDAF41D1 +:107BF000007EBC41000FC94100A0D5410031E241E7 +:107C000000C2EE410053FB4100F20342003A0A4237 +:107C10000083104200CB164200141D42005C234238 +:107C200000A5294200ED2F4200363642007E3C423C +:107C300000C74242000F4942A2000000F9000000C4 +:107C4000830000006E0000004E00000044000000B1 +:107C50001500000029000000FC00000027000000C3 +:107C600057000000D1000000F500000034000000C3 +:107C7000DD000000C0000000DB000000620000002A +:107C800095000000990000003C0000004300000047 +:107C90009000000041000000FE00000051000000C4 +:107CA00063000000AB000000DE000000BB0000002D +:107CB000C500000061000000B700000024000000C3 +:107CC0006E0000003A000000420000004D0000007D +:107CD000D2000000E00000000600000049000000A3 +:107CE0002E000000EA00000009000000D1000000A2 +:107CF000920000001C000000FE0000001D000000BB +:107D0000EB0000001C000000B10000002900000092 +:107D1000A70000003E000000E80000008200000014 +:107D200035000000F50000002E000000BB00000040 +:107D30004400000084000000E90000009C000000F6 +:107D40007000000026000000B40000005F0000008A +:107D50007E0000004100000039000000910000009A +:107D6000D60000003900000083000000530000002E +:107D700039000000F40000009C00000084000000B6 +:107D80005F0000008B000000BD000000F900000053 +:107D9000280000003B0000001F000000F800000069 +:107DA00097000000FF000000DE000000050000005A +:107DB000980000000F000000EF0000002F000000FE +:107DC000110000008B0000005A0000000A000000B3 +:107DD0006D0000001F0000006D0000003600000074 +:107DE0007E000000CF00000027000000CB00000054 +:107DF00009000000B70000004F000000460000002E +:107E00003F000000660000009E0000005F000000D0 +:107E1000EA0000002D0000007500000027000000AF +:107E2000BA000000C7000000EB000000E500000001 +:107E3000F10000007B0000003D0000000700000092 +:107E400039000000F70000008A0000005200000026 +:107E500092000000EA0000006B000000FB00000040 +:107E60005F000000B10000001F0000008D00000056 +:107E70005D00000008000000560000000300000044 +:107E80003000000046000000FC0000007B00000005 +:107E90006B000000AB000000F0000000CF0000000D +:107EA000BC000000200000009A000000F400000068 +:107EB000360000001D000000A9000000E3000000E3 +:107EC00091000000610000005E000000E60000007C +:107ED0001B00000008000000650000009900000081 +:107EE000850000005F00000014000000A0000000FA +:107EF00068000000400000008D000000FF0000004E +:107F0000D8000000800000004D0000007300000059 +:107F100027000000310000000600000006000000FD +:107F20001500000056000000CA00000073000000A9 +:107F3000A8000000C900000060000000E20000008E +:107F40007B000000C00000008C0000006B000000FF +:107F50000400000007000000090000000000C93F05 +:107F60000000F0390000DA370000A2330000842E50 +:107F70000000502B0000C2270000D0220000C41FC8 +:107F80000000C61B00004417000000000000304342 +:107F900000000000000030C36937AC316821223393 +:107FA000B40F14336821A2333863ED3EDA0F493F32 +:087FB0005E987B3FDA0FC93F28 +:087FB800B473FF7F010000001B +:107FC000000100000000803F0000000000000000F1 +:107FD0000100DC05DC05DC05DC05DC05DC05DC0579 +:107FE000DC05000000127A00000000000000000024 +:107FF0000102030406070809010303000000803F93 +:108000000000803F0000803F010100000000803F31 +:10801000000000000102030401020304060708092E +:10802000020406080100000000000000000000003B +:10803000000000000100000000000000000000003F +:108040000300000000000000000000000400000029 +:10805000000000000000000003000000056E0008A2 +:108060000F270000FFFFFFFF00A24A04CE670108B0 +:10807000536C01085F6C0108656C01086D6C0108A8 +:10808000756C0108786C0108806C01087E7A010823 +:1080900000000000000000000000000000000000E0 +:1080A00000000000000000000000000000000000D0 +:1080B000EF72010800000000000000000000000056 +:1080C00000000000000000000000000000000000B0 +:1080D00000000000000000000000000000000000A0 +:1080E0000000000000000000000000000000000090 +:0880F000D00000200100000097 :0400000508000000EF :00000001FF From ce5d64f653eabd663ee8d29ea8ca3991bd0ae0f0 Mon Sep 17 00:00:00 2001 From: Nicholas Sherlock Date: Wed, 17 Dec 2014 17:16:17 +1300 Subject: [PATCH 05/24] Firmware version 0.1.4 Add ability to reduce recorded data rate Update struct names to conform to code style guidelines --- obj/cleanflight_NAZE.hex | 11269 +++++++++++++++--------------- src/main/blackbox/blackbox.c | 72 +- src/main/blackbox/blackbox.h | 4 +- src/main/config/config.c | 5 + src/main/config/config_master.h | 2 + src/main/io/serial_cli.c | 3 + 6 files changed, 5709 insertions(+), 5646 deletions(-) diff --git a/obj/cleanflight_NAZE.hex b/obj/cleanflight_NAZE.hex index 21712cb525..9d67adbbef 100644 --- a/obj/cleanflight_NAZE.hex +++ b/obj/cleanflight_NAZE.hex @@ -1,24 +1,24 @@ :020000040800F2 -:1000000000500020ADF9000859FA0008A9E30008E3 -:1000100059FA000859FA000859FA000800000000CF -:1000200000000000000000000000000059FA000875 -:1000300059FA00080000000059FA000899E3000886 -:1000400059FA000859FA000859FA000859FA000844 -:1000500059FA000859FA000859FA0008EDE10008B9 -:1000600059FA000859FA000859FA000859FA000824 -:1000700059FA000859FA0008ADE1000859FA0008D9 -:10008000F1E1000859FA000859FA000859FA000885 -:1000900059FA000859FA000859FA0008E9E100087D -:1000A00059FA0008C1E0000859FA0008D1E0000838 -:1000B000B1E00008A1E0000891E000082DE200088E -:1000C00025E2000829E2000821E2000859FA0008A8 -:1000D00059FA000869E10008E1E0000859FA00084F -:1000E00031E2000859FA000859FA0008000000003F +:10000000005000208DFB000839FC000889E500083D +:1000100039FC000839FC000839FC00080000000029 +:1000200000000000000000000000000039FC000893 +:1000300039FC00080000000039FC000879E50008E0 +:1000400039FC000839FC000839FC000839FC0008BC +:1000500039FC000839FC000839FC0008CDE3000831 +:1000600039FC000839FC000839FC000839FC00089C +:1000700039FC000839FC00088DE3000839FC000851 +:10008000D1E3000839FC000839FC000839FC0008FD +:1000900039FC000839FC000839FC0008C9E30008F5 +:1000A00039FC0008A1E2000839FC0008B1E20008B0 +:1000B00091E2000881E2000871E200080DE4000806 +:1000C00005E4000809E4000801E4000839FC000820 +:1000D00039FC000849E30008C1E2000839FC0008C7 +:1000E00011E4000839FC000839FC00080000000099 :1000F0000000000000000000000000000000000000 :0C01000000000000000000005FF808F1A3 :100110002DE9F04F734B744D9FB02B6000236B6043 -:100120000BF0C3FB18B907F0EBF90BF0E1FB0DF096 -:10013000EDFD002308936D4C09930A934FF4E013EF +:100120000CF079FF18B908F051F90CF097FF0DF0B9 +:10013000DDFE002308936D4C09930A934FF4E013FE :100140000B9323686A4943F480338A7B2360A36955 :10015000894643F01003A361236803F40033099335 :10016000089B01330893099B1BB9089BB3F5A06F4B @@ -45,34 +45,34 @@ :1002B00005E0526812F4003F3A6818BF52085143F3 :1002C00019606268C2F303123A4492F804B01A68E3 :1002D00022FA0BFB0A4AC3F800B03B68934217D1DD -:1002E000012219E0955A0008D406002000100240AF -:1002F0003020002000200240240000200410014093 +:1002E000012219E0956A0008B007002000100240C2 +:1002F000342000200020024024000020041001408F :1003000000127A00001BB700A800002000093D0081 :10031000B24A934202D10222B14B1A70DFF800A315 :10032000B04B1EAECAF80C30A3694FF0000843F082 :100330000103A361636AAC4843F080736362A369FD :1003400043F01C03A3614FF6FF7326F82C3D3146A2 -:100350008DF84E8009F0DEFAA448314609F0DAFA49 -:100360003146A34809F0D6FAA24B30465A6842F00B -:1003700000725A6006F08AFA139B9F4A6420B3FB0E +:100350008DF84E8005F094F8A448314605F090F8E9 +:100360003146A34805F08CF8A24B30465A6842F05B +:1003700000725A6007F0F0F9139B9F4A6420B3FBA8 :10038000F2F34FF47A72AB60BBFBF2FB9B4B0BF1C9 :10039000FF325A60F0228AF823200722C3F808802F -:1003A0001A6005F050FA96484146A02211F099FDD6 +:1003A0001A6006F050FA96484146A02211F025FE48 :1003B000E36943F00703E361A36943F4006343F097 :1003C0000C03A3618F4B002103F10C0208F802100B :1003D00008F10108B8F10E0FF4D1FF229A76DA760F :1003E0001A775A77884B0FCB86E80F00A36908224B :1003F00043F00803A361A369139843F00803A361C2 -:100400007A4B14A91A6110221A6109F083FA15981F -:1004100016A909F07FFA724B73481A789846012A98 +:100400007A4B14A91A6110221A6105F039F815986F +:1004100016A905F035F8724B73481A789846012AE8 :100420008CBF102314238DF84E304FF002038DF84B :100430004F30A3694FF4805243F00403ADF84C20D1 -:100440008CBF4FF0010A4FF0000AA361314609F05A -:1004500061FA6E4BBAF1000F01D06D4A00E06D4AAF -:1004600000201A6005F0F9F96B4B93E80300A369CB -:1004700086E8030043F0080314A9A361139809F068 -:1004800049FA0BF041F99F238DF8383032200023D0 -:100490008DF839308DF83A308DF83B3005F0D3F9CE +:100440008CBF4FF0010A4FF0000AA361314605F05E +:1004500017F86E4BBAF1000F01D06D4A00E06D4AFB +:1004600000201A6006F0F9F96B4B93E80300A369CA +:1004700086E8030043F0080314A9A361139804F06D +:10048000FFFF0BF00BFA9F238DF83830322000234A +:100490008DF839308DF83A308DF83B3006F0D3F9CD :1004A000524B4FF480525A61A3F554430EAA9B89D4 :1004B00005204FF47A7331469246013823D01AB1A1 :1004C00092F800E0013208E04FF0FF0E05E003F182 @@ -82,12 +82,12 @@ :1005000001339BB2EB83DFF8E4B04FF48053CBF8B8 :1005100010309DF84E109DF84D20090241EA02412D :100520009DF84F2011433D4A914214D0CBF814302E -:10053000F52002930CF042FFFF200CF03FFF029BDE +:10053000F520029309F0AAFCFF2009F0A7FC029B1A :100540007028CBF8103006D198F80030022B02D179 :10055000234B03221A7098F800B0BBF1030F02D0AE -:10056000012007F0D1F9D9F80820DFF8988002F4CB +:10056000012008F03BF9D9F80820DFF8988002F460 :1005700000434FF0100C02F4006204920021624626 -:1005800008F120000293CDF80CC011F0AAFC002263 +:1005800008F120000293CDF80CC011F036FD0022D6 :100590008DF83B200422DDF80CC0072085F82020D0 :1005A0000122022185F8230093458DF83A10ADF819 :1005B00038C085F82220029B36D94FF0300EADF8B6 @@ -95,21 +95,21 @@ :1005D0002A2088F82B00884627E000BF001BB700C0 :1005E000D62700200005FA0500080140000C014054 :1005F000001001400000014040420F0010E000E008 -:10060000D01E0020D406002004460108D827002070 -:10061000E1500008F550000814460108152020009C +:10060000D41E0020B0070020EC480108DC270020A1 +:100610008560000899600008FC480108152020004A :1006200000ED00E00038004090469BB1BDF8383046 :1006300085F8258043F00203ADF83830012308EB3C :10064000030285F8243085F82630072385F8273003 -:100650005FFA82F88548514604F063FD049BABB114 -:10066000022383485146ADF8383004F05AFD09237F +:100650005FFA82F88548514605F035FD049BABB141 +:10066000022383485146ADF8383005F02CFD0923AC :10067000012285F82C3085F82E2008F1010307228D :1006800085F82D8085F82F205FFA83F86369794813 :1006900043F001036361A369764D43F40073A361E2 -:1006A00004F0BCFD744B00241393744BB8F1010F9C +:1006A00005F08EFD744B00241393744BB8F1010FC9 :1006B00014930CBF2346802318934FF4807319932F :1006C0004FF480631A93202331461B9328464FF43E -:1006D00000531C931594CDF8588017941D9404F082 -:1006E0007FFD2B68B8F1010F43F001032B60644BD1 +:1006D00000531C931594CDF8588017941D9405F081 +:1006E00051FD2B68B8F1010F43F001032B60644BFF :1006F00098BF00215A6888BF012122F4702222F499 :10070000807242EA01225A6099685E4A20460A4095 :1007100042F4602242F002029A60D96A08F1FF3284 @@ -134,40 +134,40 @@ :1008400013F00403FAD19168B9F8E60041F4A0016D :1008500091600E4AE8B9B2F9E830CBB9B2F9EA30A2 :10086000D3F1010338BF002313E000BF00080140AB -:10087000000C0140080002404C2401400407002005 -:1008800000240140FDF7F1FFF40600203020002095 +:10087000000C0140080002404C240140E007002029 +:1008800000240140FDF7F1FFD007002034200020B4 :10089000034613F0010340F081803B7500B20EF077 -:1008A000B7FAAB490EF008FBAA4C0646B4F9E800CB -:1008B0000EF0AEFAA6490EF0FFFA0546B4F9EA00CA -:1008C0000EF0A6FAA2490EF0F7FA0446304611F0EF -:1008D00037FD0746304611F0A7FD8046284611F047 -:1008E0002FFD0646284611F09FFD0546204611F0D3 -:1008F00027FD8246204611F097FD39468146504635 -:100900000EF0DAFA3946834648460EF0D5FA5146DB -:10091000049040460EF0D0FA4946059040460EF04D -:10092000CBFA3146079050460EF0C6FA8A4C49463B -:10093000A06306F100400EF0BFFA2946E06325648B -:1009400005980EF0B9FA014604980EF0ADF9294663 -:10095000606407980EF0B0FA014658460EF0A2F90E -:100960003146A06408F100400EF0A6FA2946E06482 -:1009700058460EF0A1FA014607980EF093F9294661 -:10098000206504980EF098FA014605980EF08CF94F -:100990003946606530460EF08FFAA0656D4B6E4D9E -:1009A0009A6812F4003F18D0C8206A4C04F04BFF3C -:1009B0000BF0E3F8C82004F046FF04F5887300212B -:1009C0000C2205F16000EB6511F08BFA0BF047F992 -:1009D00004F060FE614B0344AB66614B00211A6872 +:1008A000A7FBAB490EF0F8FBAA4C0646B4F9E800EA +:1008B0000EF09EFBA6490EF0EFFB0546B4F9EA00E8 +:1008C0000EF096FBA2490EF0E7FB0446304611F00D +:1008D000C3FD0746304611F033FE8046284611F02E +:1008E000BBFD0646284611F02BFE0546204611F0BA +:1008F000B3FD8246204611F023FE3946814650461C +:100900000EF0CAFB3946834648460EF0C5FB5146F9 +:10091000049040460EF0C0FB4946059040460EF05C +:10092000BBFB3146079050460EF0B6FB8A4C494659 +:10093000A06306F100400EF0AFFB2946E06325649A +:1009400005980EF0A9FB014604980EF09DFA294681 +:10095000606407980EF0A0FB014658460EF092FA2C +:100960003146A06408F100400EF096FB2946E06491 +:1009700058460EF091FB014607980EF083FA29467F +:10098000206504980EF088FB014605980EF07CFA6D +:100990003946606530460EF07FFBA0656D4B6E4DAD +:1009A0009A6812F4003F18D0C8206A4C05F04BFF3B +:1009B0000CF099FCC82005F046FF04F5887300216F +:1009C0000C2205F16000EB6511F017FB0CF0FDFC4B +:1009D00005F058FE614B0344AB66614B00211A6879 :1009E000994642F00E021A605E4A5F4B12685948FF :1009F000B2F85220B0F8EE6005925C4A90F8ED70C3 :100A000011705B4903F10C0291F800A0594CBAF146 -:100A1000010F88BF1346EB6607F0E8FADFF8848120 +:100A1000010F88BF1346EB6608F052FADFF88481B5 :100A20008346DFF884C108B3534BBB2EC8F80030AF :100A3000524BC8F80CC0C8F8043001D901230EE0AD :100A4000612E01D902230AE0292E01D9032306E0F1 :100A5000132E01D9042302E0092E05D90523434AA8 :100A60006375012313702CE00623F8E71920CDF8F5 -:100A70000CC004F0E8FE682015215A4607F03EF845 -:100A8000DDF80CC0002801F010823D4A622EC8F843 +:100A70000CC005F0E8FE682015215A4607F0A8FFD3 +:100A8000DDF80CC0002801F00E823D4A622EC8F845 :100A900000203C4AC8F80CC0C8F804203A4AC8F8FC :100AA000082000F0ED8240F2E482BC2E00F0E682E5 :100AB000B6F5807F40F0E78284F816B02B4801231A @@ -176,41 +176,41 @@ :100AE000110011003200B900DA00F200F200F20049 :100AF000F2000A00D9F8003023F00203C9F80030F0 :100B0000E0E0BAF1010F20D84FF000081EAB03F867 -:100B10002C2D53204146012207F04AF990B19DF84F +:100B10002C2D53204146012208F0B4F890B19DF8E5 :100B20004C30E52B0ED11A4B1A4A85F870801A60AA :100B3000194A5A60042301223370184B97421A70E5 :100B400000F0C080BAF1010F30D9154B2FE000BF83 -:100B500035FA8E3C30200020D4060020404B4C005B -:100B60004C020020E8030020EC45010802040020AC -:100B7000D627002024000020ED7B0008AF7F00086E -:100B8000557C000849800008178000086A0400208E -:100B900058040020597D000823810008D727002031 -:100BA000F8450108EC03002090C1793D8B4BDFF83C -:100BB0005882EB6607F01AFA00284AD0062113ABD8 -:100BC00068200A4607F0F4F89DF84F309DF851B0C0 +:100B500035FA8E3C34200020B0070020404B4C007A +:100B6000080200203C030020D4480108560300205E +:100B7000D627002024000020C18A0008838E0008A8 +:100B8000298B00081D8F0008EB8E0008BE03002093 +:100B9000AC0300202D8C0008F78F0008DA27002016 +:100BA000E04801084003002090C1793D8B4BDFF8FD +:100BB0005882EB6608F084F900284AD0062113AB6E +:100BC00068200A4608F05EF89DF84F309DF851B055 :100BD00003F001035B000BF0010B43EA8B0B9DF864 :100BE0004D3003F001035BEA030B08D0BBF1010FAA :100BF00001D1002317E0BBF1020F0BD112E00EABC5 -:100C000068200C21012207F0D3F89DF8383013F04A -:100C10000F0302D1052001F049B9042B02D188F855 +:100C000068200C21012208F03DF89DF8383013F0DF +:100C10000F0302D1052001F047B9042B02D188F857 :100C200071B002E0012388F871306D4B6D4A1A6093 :100C30006D4A5A6095F87120002A14BF6E226F2207 :100C40001A726A4B02221A7097424FF001033370F6 :100C500038D0BAF1010F1DD800221EAB03F82C2D9D -:100C60001C200D21012207F0A3F898B19DF84C300B +:100C60001C200D21012208F00DF898B19DF84C30A0 :100C70002A2B01D01A2B0DD1594A5D4985F87230C3 :100C800011605C490223516033700322574B974235 :100C90001A7017D000211EAB03F82C1D182001225A -:100CA00007F086F870B19DF84C30FB2B0AD14C4B05 +:100CA00007F0F0FF70B19DF84C30FB2B0AD14C4B94 :100CB000514A1A60514A5A604C4B04221A70504BE8 :100CC00001221A70494B1B7843B90FB11F46FEE64B :100CD000D9F8003023F00203C9F80030BAF1010F4F -:100CE00005D107F0C9FA474B4FF400525A610A2068 -:100CF00004F0A9FD7720A02101220EAB07F058F8DF +:100CE00005D108F033FA474B4FF400525A610A20FD +:100CF00005F0A9FD7720A02101220EAB07F0C2FF6D :100D000038B995F884A0404EBAF1000F00F08A80FF -:100D100055E11E210122772006F0F0FE4FF42F60EE -:100D200004F086FD0026A6F160010027C9B2022268 -:100D300013AB77208DF84C708DF84D7007F038F8B4 +:100D100055E11E210122772007F05AFE4FF42F6083 +:100D200005F086FD0026A6F160010027C9B2022267 +:100D300013AB77208DF84C708DF84D7007F0A2FF43 :100D40009DF84D309DF84C1043EA01212E4B03F1E4 :100D50007402B1520236102EE5D1B3F882E00121BF :100D60000EF00F060EF47F4EA3F882E03A463B46A3 @@ -220,23 +220,23 @@ :100DA000F7D10132102AE3D146EA0E0EA5F882E00F :100DB0000029A6D1C3F303339E42A2D1134B42F2C2 :100DC00010721A805A80124A5A60124A9A60124A65 -:100DD000DA60124A1A61124A5BE100BFEC45010871 -:100DE00058040020D1780008717F0008D727002020 -:100DF000A57C000887800008357D0008DF8000089A -:100E00006A04002000100140D4060020A002002047 -:100E1000AD7B0008C97E0008A57B0008D97E0008CC -:100E2000398F00089C4F07F027FA4FF480450EA930 +:100DD000DA60124A1A61124A5BE100BFD448010886 +:100DE000AC030020A5870008458E0008DA27002004 +:100DF000798B00085B8F0008098C0008B38F00080E +:100E0000BE03002000100140B00700203C0200207B +:100E1000818A00089D8D0008798A0008AD8D000840 +:100E2000814800089C4F08F091F94FF480450EA9C5 :100E300004233846ADF838508DF83A304FF4005856 -:100E400008F068FD954BC7F810805A6913A822F482 +:100E400004F01EFB954BC7F810805A6913A822F4D2 :100E500070625A615A694FF0030942F400725A6194 :100E60000823139501258DF851308DF850A08DF889 -:100E7000525009F0C5FE28230DA88DF834308DF8A6 -:100E800035908DF836A08DF8375009F099FE142072 -:100E900004F0D9FC0EAB7720D0212A4606F088FF5B +:100E700052500BF03FF928230DA88DF834308DF82F +:100E800035908DF836A08DF837500BF013F91420FB +:100E900005F0D9FC0EAB7720D0212A4607F0F2FEF0 :100EA0009DF83830A6F8A890552B86F89F307FD152 -:100EB000D1212A460EAB772006F07AFF9DF8383014 +:100EB000D1212A460EAB772007F0E4FE9DF83830AA :100EC000772003F00F021B0986F8A02086F8A130D6 -:100ED000162213ABAA2106F06BFF9DF84C209DF85B +:100ED000162213ABAA2107F0D5FE9DF84C209DF8F1 :100EE0004D3043EA0223A6F888309DF84E209DF845 :100EF0004F3043EA0223A6F88A309DF850209DF82F :100F0000513043EA0223A6F88C309DF852209DF818 @@ -252,266 +252,266 @@ :100FA000414A9A60414ADA60414A1A61414A70E016 :100FB000414BC7F814801A6822F004021A601EAA76 :100FC000002302F82C3D04921E200A210122049BDA -:100FD00006F0EEFE384F38B19DF84C30482B03D167 +:100FD00007F058FE384F38B19DF84C30482B03D1FC :100FE000364B03221A7003E03B6823F008033B6092 :100FF000334D95F8E2300BB1324A137095F8E33077 :101000000BB1314A137095F8E4300BB12B4A1370D1 :101010003B68990702D52D4B1B689847DFF8BC80C9 :101020002B4ED8F8003098473B6813F0080F1CD0BF :10103000059B4FF0640A0FFA83F898FBFAF94846CB -:101040000DF0E6FE83460AFB198000B20DF0E0FECB -:1010500020490DF031FF014658460DF025FE1E498E -:101060000DF02AFFC6F8AC003AE00023C6F8AC3019 +:101040000DF0D6FF83460AFB198000B20DF0D0FFE9 +:1010500020490EF021F8014658460DF015FF1E49B3 +:101060000EF01AF8C6F8AC003AE00023C6F8AC302F :1010700036E00A2E0BD0142E07D004E0012300E046 :101080000223A3751AE50323FBE70423F9E70523ED :10109000F7E75A6193E700BF0010014000000140EC -:1010A000A0020020D97B0008397F0008B57B00082A -:1010B000E97E0008919000084C020020CF27002014 -:1010C00030200020020400206A0400205804002080 -:1010D000D40600208988883C00002041EC030020D1 +:1010A0003C020020AD8A00080D8E0008898A0008E5 +:1010B000BD8D0008D949000808020020E027002063 +:1010C0003420002056030020BE030020AC03002083 +:1010D000B00700208988883C0000204140030020A0 :1010E000844B10225A6108221A614FF00A0ADFF875 :1010F00004921920D9F80C300AF1FF3A83F010035A :10110000C9F80C30D9F80C3083F00803C9F80C305A -:1011100004F099FB012004F0A0FB192004F093FBDC -:10112000002004F09AFB1AF0FF0AE0D10823C9F866 -:1011300010301023C9F810306F4BDFF8FC911B689A -:1011400093F90C000DF064FE6C490DF0B5FE11F042 -:10115000F7F88246B9F800000DF05AFE51460DF03E -:10116000ABFE11F023F9664B1880B9F800000DF0C2 -:101170004FFE014663480DF053FF63490DF050FFE9 -:10118000624B63491860C8685C490DF095FE61497F -:101190000DF092FE604B6A791860604B60491A70DE -:1011A000604B01EBC20292F83120C6F8B0305E4BC2 +:1011100005F099FB012005F0A0FB192005F093FBD9 +:10112000002005F09AFB1AF0FF0AE0D10823C9F865 +:1011300010301023C9F810306F4BDFF8F8911B689E +:1011400093F90C000DF054FF6C490DF0A5FF11F060 +:1011500083F98246B9F800000DF04AFF51460DF0C0 +:101160009BFF11F0AFF9664B1880B9F800000DF045 +:101170003FFF014663480EF043F863490EF040F824 +:101180006249C6F8B000C8685C490DF085FF604947 +:101190000DF082FF5F4B6A7918605F4B5F491A70F0 +:1011A0005F4B01EBC20292F83120C6F8B4305D4BC0 :1011B0001A60AA68920644BF01221A603B681B07A6 -:1011C00040F1FF804B4B10225A61584A4FF0000803 -:1011D00012784FF00A0A012A554A8CBF4FF0100EC0 +:1011C00040F1FE804B4B10225A61574A4FF0000805 +:1011D00012784FF00A0A012A544A8CBF4FF0100EC1 :1011E0004FF0080E90698CBF4FF480414FF480514E -:1011F0004EEA000090614F484FF0020298BF184637 +:1011F0004EEA000090614E484FF0020298BF184638 :10120000ADF838108DF83B200EA904228DF83A2055 -:1012100008F080FB322004F016FB002111221E2072 -:1012200006F06CFC012160221E2006F067FC6420A1 -:1012300004F009FB049806F0F9FDC146C3460221FB -:1012400001221E2006F05AFC322004F0FCFA049819 -:1012500006F0ECFDBDF94C20BDF94E10BDF9503043 +:1012100004F036F9322005F016FB002111221E20C1 +:1012200007F0D6FB012160221E2007F0D1FB6420CD +:1012300005F009FB049807F063FDC146C34602218F +:1012400001221E2007F0C4FB322005F0FCFA0498AE +:1012500007F056FDBDF94C20BDF94E10BDF95030D8 :1012600093449142B8BF0A4698449A42B8BF134685 :1012700013F5805F89440ADD1E4BBAF1010ADA6872 :1012800082F01002DA60DAD14FF0010A01E04FF08B -:10129000000A1E200021122206F030FC0A2302213F -:1012A00001221E20029306F029FC322004F0CBFA22 -:1012B000049806F0BBFDBDF94C10BDF94E00BDF918 +:10129000000A1E200021122207F09AFB0A230221D5 +:1012A00001221E20029307F093FB322005F0CBFAB7 +:1012B000049807F025FDBDF94C10BDF94E00BDF9AD :1012C0005020C1EB0B0B8842B8BF0146C2EB0808A7 :1012D0009142B8BF0A4612F5805FC0EB0909029B34 -:1012E0002CDD044A013BD16881F01001D160D6D1D8 -:1012F00026E000BF000C0140A404002035FA8E3C1B -:10130000C80400200AE81C4100401C46C00300201D -:10131000EC030020BD378635A00400209405002092 -:10132000EC4501084020002090050020D627002031 -:101330000010024000100140000000204FF0000AA1 -:10134000AF4B584602930DF063FD0146AD480DF0DA -:1013500067FE20F00040A06148460DF059FD0146AF -:10136000A8480DF05DFE20F00040E06140460DF021 -:101370004FFD0146A4480DF053FE20F000402062CE -:10138000002170221E2006F0B9FB012120221E2020 -:1013900006F0B4FB022100221E2006F0AFFB642001 -:1013A00004F051FA029BBAF1000F04D14FF07E52C3 -:1013B0009A61DA611A62954B10221A61944B0122EC -:1013C0001A700AF0F1FE0EA80021142210F089FD17 -:1013D0006B790E2B01D0082B02D101238DF84330FD -:1013E0008C4A8C4C9368B4F8E000C3F380418DF8CC -:1013F0003E108949C3F3400209688DF83D20C3F3CC -:10140000801200318DF83F20C3F3403218BF012114 -:101410008DF83820C3F3C0328DF83A208DF8411092 -:10142000C3F3C0227D498DF83B20C3F300428DF801 -:101430004020096803F001028DF8392091F8B011BD -:10144000ADF84600C1F380014FF47A708DF8421078 -:10145000B4F8DE10ADF84800D804ADF8441003D558 -:10146000B4F8DA30ADF84830B1F5FA7F84BF002324 -:10147000ADF84830B5F81A3195F82211ADF84A3078 -:10148000674B83F8B410002183F8B51083F8B610C9 -:101490009DF843308B4214BF02230B4602B1013347 -:1014A000604A4FF0000A02EB8303D3F8E830CDF82E -:1014B00014A00793079C4FF6FF7234F80A809045FA -:1014C0005FFA88F30DD1564C94F8B53084F8B730F4 -:1014D000554B93F80090B9F1160F40F07581002636 -:1014E00064E1524A9DF83C104FEA031B02EB0B04E7 -:1014F00019B1991E012940F243819DF83F1029B18D -:1015000052F80B104A48814200F03A819DF8401091 -:1015100029B152F80B104648814200F031819DF804 -:101520003A1011B1012B00F02B814FEA1828B8F1C5 -:10153000020F06D19DF83810002908BF4FF00008AF -:1015400004E0B8F1010F08BF9DF839809DF8411003 -:1015500041B19DF8431029B9A3F10801012998BFB1 -:101560004FF004089DF8421031B19DF8431019B9AD -:10157000043B032B40F2EB80B8F1010F60D1FF2355 -:10158000E17B86F8FC3086F8FD30A3684FF0000957 -:10159000606886F80091C6F80C41ADF84C308DF8C3 -:1015A0004E10022304998DF84F3086F8B890C6F893 -:1015B000BC90C6F8C090C6F8C490C6F8F89086F8FB -:1015C000FE9086F8FF90039208F0A4F9039A217B1D -:1015D00052F80B004A4605F00FF9204649464246AC -:1015E0000AF0B0FA134B1449C6F81031134BC6F881 -:1015F0001891C6F8143120460A1D09F0ADF9BFE074 +:1012E0002ADD044A013BD16881F01001D160D6D1DA +:1012F00024E000BF000C0140F803002035FA8E3CCA +:101300001C0400200AE81C4100401C464003002049 +:10131000BD378635F403002004050020D4480108B9 +:101320004420002000050020D627002000100240A5 +:1013300000100140000000204FF0000AB04B58465A +:1013400002930DF055FE0146AE480DF059FF20F016 +:101350000040A06148460DF04BFE0146A9480DF043 +:101360004FFF20F00040E06140460DF041FE014695 +:10137000A5480DF045FF20F00040206200217022BA +:101380001E2007F025FB012120221E2007F020FB54 +:10139000022100221E2007F01BFB642005F053FAF7 +:1013A000029BBAF1000F04D14FF07E529A61DA61CC +:1013B0001A62964B10221A61954B012283F8B820CD +:1013C0000CF0A8FA0EA80021142210F016FE6B797A +:1013D0000E2B01D0082B02D101238DF843308D4A0A +:1013E0008C4C9368B4F8E000C3F380418DF83E1054 +:1013F0008949C3F3400209688DF83D20C3F3801288 +:1014000000318DF83F20C3F3403218BF01218DF821 +:101410003820C3F3C0328DF83A208DF84110C3F361 +:10142000C0227E498DF83B20C3F300428DF8402056 +:10143000096803F001028DF8392091F8B011ADF878 +:101440004600C1F380014FF47A708DF84210B4F871 +:10145000DE10ADF84800D804ADF8441003D5B4F858 +:10146000DA30ADF84830B1F5FA7F84BF0023ADF82B +:101470004830B5F81A3195F82211ADF84A30644B6E +:1014800083F8B910002183F8BA1083F8BB109DF8D7 +:1014900043308B4214BF02230B4602B10133604A32 +:1014A0004FF0000A02EB8303D3F8E830CDF814A024 +:1014B0000793079C4FF6FF7234F80A8090455FFA55 +:1014C00088F30DD1524C94F8BA3084F8BC30554BA7 +:1014D00093F80090B9F1160F40F07481002663E193 +:1014E000514A9DF83C104FEA031B02EB0B0419B163 +:1014F000991E012940F242819DF83F1029B152F80E +:101500000B104A48814200F039819DF8401029B102 +:1015100052F80B104548814200F030819DF83A1096 +:1015200011B1012B00F02A814FEA1828B8F1020FFF +:1015300006D19DF83810002908BF4FF0000804E0DC +:10154000B8F1010F08BF9DF839809DF8411041B1F5 +:101550009DF8431029B9A3F10801012998BF4FF064 +:1015600004089DF8421031B19DF8431019B9043BAD +:10157000032B40F2EA80B8F1010F5FD1FF23E17B3A +:1015800086F8043186F80531A3684FF000096068D9 +:1015900086F80891C6F81441ADF84C308DF84E101D +:1015A000022304998DF84F3086F8C090C6F8C49095 +:1015B000C6F8C890C6F8CC90C6F8009186F8069197 +:1015C00086F80791039203F05BFF039A217B52F8A0 +:1015D0000B004A4606F076F82046494642460BF094 +:1015E00067FE134B1349C6F81831134BC6F8209108 +:1015F000C6F81C3120460A1D0AF028FCBEE000BFD8 :101600002400002000406F4601C05E46000C0140EF -:10161000940200203020002090050020E8030020E4 -:10162000D4060020EC4501089405002094610108CF -:1016300000040040198E0008E4070020F58E000821 -:10164000B8F1020F43D10599B448CBB21C215943DC -:101650004FF0000300EB010989F8023089F80A30E5 -:10166000059B94F80FE089F8013001234354A168E9 -:101670006068C9F80C40ADF84C1004998DF84EE044 -:10168000029303928DF84F8008F044F9039A217B6E -:1016900052F80B00002205F0AFF8029B20461A46D4 -:1016A00000210AF04FFA9E4B0020C9F810309D4BE4 -:1016B000C9F81800C9F81430204609F1100109F1E1 -:1016C000140209F049F9059C0134059458E0B8F179 -:1016D000030F39D19DF83E30DFF85C8233B198F8C2 -:1016E000B690204608214FF6FF721CE0BDF844304A -:1016F00098F8B690B3F5FA7F0FD98B4A2046B2FB23 -:10170000F3F20821BDF8483092B20BF00BFD08EB64 -:101710008903C3F8E001854B0EE0854A2046B2FB01 -:10172000F3F2012192B2BDF848300BF0FBFC08EB5C -:101730008903C3F8E0017F4BC3607F4B93F8B62069 -:10174000013283F8B6201BE0B8F1040F18D1BDF8C0 -:101750004630774ADFF8E08192FBF3F22046BDF88D -:101760004A30012192B298F8B5900BF0DBFC08EBFF -:101770008903C3F8100298F8B530013388F8B53002 -:101780000AF1020ABAF11C0F7FF494AE9BE66B4B90 -:1017900006EB030E98E80F008EE80F00684B10363A -:1017A0001A78C02E02F101021A7009D0D4F8B030B4 -:1017B0000021985903EB06080DF012FD0028E6D031 -:1017C000AB68DB0420D419E05E4B5D4A03EBC90330 -:1017D00093F830C0D3F8348082F800C0B8F1000F1D -:1017E000EED000266645EBDA544A330103EB020ED5 -:1017F00043440FCB01368EE80F00F3E7B9F1080F31 -:10180000DFF86C8128D12AE04D4B93F800A0BAF1A3 -:10181000010FF3D94C4E4FF00008D04506F11006E9 -:10182000ECDA56F8100C4FF07C510DF045FB4FF000 -:101830007C5146F8100C56F8140C0DF03DFB4FF09F -:101840007C5146F8140C56F80C0C0DF035FB08F1E1 -:10185000010846F80C0CE0E7B9F10E0F04D198F836 -:10186000003043F0100303E098F8003023F0100339 -:1018700088F800300BF0BCFE3449354B3548364A09 -:10188000C4F8F43201600023B5F81A01C4F8F0126C -:10189000A4F8FA3284F8FC32C4F80023C4F8042314 -:1018A0002E4958520233242BFAD12D4B1A60AB68C3 -:1018B0001E0740F1AE802B4B002293F81831042B09 -:1018C00000F2A180DFE803F00303567C8B00012BBC -:1018D0004FF0030208D184F80823072284F80A3362 -:1018E00084F809230C2308E0022384F8083300233A -:1018F00084F80A3384F80923072384F80B33002380 -:1019000000931020012318494FF4E13209F092FEB0 -:10191000164BC4F81003C4F8143370E0D407002049 -:1019200035680008ED8D000800127A00158F000858 -:1019300040420F00058F0008D40600200409002053 -:10194000E1270020EC4501080C090020402100207F -:10195000E44601083C010020C8090020960600204A -:101960004002002030200020C9560008E94F00083E -:10197000820200200123574A574900931020052373 -:1019800009F058FEC4F818030646B5F81A010DF020 -:101990003FFA52490DF090FA51490DF083F90DF0DC -:1019A00077FC00234F4A98500433402BFAD14E4B1A -:1019B000301CC4F814334FF0100384F80B331FE0CD -:1019C00000920123102049494FF4E13209F032FE20 -:1019D000474BC4F81C03C4F8143310230DE00092E5 -:1019E0000123102043494FF4E13209F023FE424B1A -:1019F000C4F82003C4F81433082384F80B330030F0 -:101A000018BF012028B9082007F059FD0023C4F8A9 -:101A10001433AB68580405D5082284F80B23374AE1 -:101A2000C4F8142342F201021A4003F0010103F446 -:101A300000505AB1324AC4F8142318B1314A082070 -:101A400082F80B0311B10C2284F80B2394F80B23BA -:101A50001906A2F1040284F80C2369D5294B2A4AFD -:101A6000D5F83811C3F824230023284A02EB0310C9 -:101A7000D0F824011646884204D00133DBB2042B8F -:101A8000F3D9002384F82933214B0020C4F84433D0 -:101A900003F090F91F4B94F829231B680021C4F828 -:101AA000303395F8283106EB02128B42C4F82C1320 -:101AB0004FF020000091D2F824210CBF0123032312 -:101AC00009F0B8FDC4F8480330BB802007F0F7FCEC -:101AD00025E000BFA0860100D5570008CDCCCC3F43 -:101AE0000000B0445C0100209D50000861570008D0 -:101AF0008D5000081557000879500008C95000089B -:101B0000D5500008D40600205C210020EC450108D7 -:101B1000582100202C200020012003F04BF98C4B91 -:101B2000186800F5D9730430C4F84C3307F000FE90 -:101B3000AB689A050CD59E044CBF8648864809F0D0 -:101B40009BFF3B68002243F010033B60834B1A600D -:101B5000834B8449D4F800230B608033C4F850339E -:101B6000814B824E1A60AB680027D803377040F172 -:101B7000B380DFF824B2DFF824A207F015FD07F0E8 -:101B80004FFD07F029FD40F22A334FF001091A46B4 -:101B90005846394686F80090029310F0A2F9DAF818 -:101BA0001820734842F00402CAF818204022ADF809 -:101BB000302018228DF833200CA903228DF8322012 -:101BC00003F0AFFADAF81C206A4E42F00202CAF8BB -:101BD0001C20694AAAF6947A1168684AB1FBF2F1AE -:101BE0003288013922F45C721204120C328089B2FC -:101BF0001D22B2853185A6F81490328C22F00102A4 -:101C00001204120C3284328CB088318B22F0020222 -:101C100021F0730109041204090C120C41F0600157 -:101C200080B242EA0902B0803183B7863284328BB7 -:101C300022F008021204120C42F008023283B6F8B5 -:101C400044206FEA42426FEA524292B2A6F8442020 -:101C5000DAF8A82F42EA0902CAF8A82F504603F082 -:101C6000DDFA474A029B1392802218924FF4807249 -:101C7000CDF850B019924FF0100B4FF4005250466F -:101C800004991C92CDF854B0169317971A971B9786 -:101C90001D9703F0A5FAB2890DA892B242F4007222 -:101CA000B281DAF8002042F00202CAF800208DF872 -:101CB00034B08DF835908DF836708DF8379008F087 -:101CC0007FFF304B1A68304BFA500437802FF8D121 -:101CD00002F0E4FE02F0E2FEAB68590540F19180AB -:101CE00007F048FC08B1082000E00420012106F0BC -:101CF00060FFAB6884F87E0613F4806F234E01D139 -:101D000000201DE033681B78032B05D133681B7856 -:101D1000032B0BD0012013E0042006F0BAFE01468D -:101D2000042006F085FD0028F0D1E9E7082006F040 -:101D3000B0FE0146082006F07BFD003018BF0120F0 -:101D4000134B36681870337853BB124B1E604CE04F -:101D5000E80300205C47010868470108A400002050 -:101D60008421002010060020BC060020020600206E -:101D70000008014000040040A800002000366E0169 -:101D800034040040B045010814060020A0050020DE -:101D90009C050020C8050020280A002000100240F1 -:101DA000012B22D100212C224348C4F8806610F078 -:101DB00098F88E234FF07C0984F885367D27E02340 -:101DC0003E4800212C2284F8873684F8849684F8D3 -:101DD000AF7610F086F88A2384F8B136A02384F811 -:101DE000B09684F8B33684F8DB763378022B08BFDC -:101DF000C4F8DC6607F0BEFB08B1C4F8E0660AF080 -:101E000085FAAB6813F4002300D0012384F8E6368A -:101E100003F040FC2A4B18606B79052B03D1294B4A -:101E20004FF4C8721A80284B4FF47A721A80274BED -:101E3000C8221A8098F8003043F0080388F8003070 -:101E4000234B1A7822F002021A70AB689A071ED54B -:101E5000204B214A1D461A6003F026FB282003F080 -:101E6000F2FC069901390691F6D129681B4B487896 -:101E70001E7802460123964203D30133082B024405 -:101E8000F9D1174A13708A785343A4F8E436154BF6 -:101E90009B689B030CD594F8633043F0010384F8EE -:101EA0006330032384F8643002E0032003F002FD72 -:101EB0001FB0BDE8F08F00BF580D0020840D00203A -:101EC000000500206C040020CC270020C42700203F -:101ED000D5270020B005002034210020B4050020C3 -:101EE0009800002030200020A14A2DE9F04F13680F +:10161000B007002034200020000500203C030020FB +:10162000D448010804050020446601080004004075 +:1016300061470008C80800203D480008B8F1020FC3 +:1016400043D10599B448CBB21C2159434FF0000354 +:1016500000EB010989F8023089F80A30059B94F8FB +:101660000FE089F8013001234354A1686068C9F88C +:101670000C40ADF84C1004998DF84EE002930392A3 +:101680008DF84F8003F0FCFE039A217B52F80B008B +:10169000002206F017F8029B20461A4600210BF0A4 +:1016A00007FE9E4B0020C9F810309D4BC9F818006A +:1016B000C9F81430204609F1100109F114020AF0AA +:1016C000C5FB059C0134059458E0B8F1030F39D1EE +:1016D0009DF83E30DFF85C8233B198F8BB9020462D +:1016E00008214FF6FF721CE0BDF8443098F8BB901B +:1016F000B3F5FA7F0FD98B4A2046B2FBF3F20821EB +:10170000BDF8483092B208F075FA08EB8903C3F8C7 +:10171000E801854B0EE0854A2046B2FBF3F2012139 +:1017200092B2BDF8483008F065FA08EB8903C3F8B7 +:10173000E8017F4BC3607F4B93F8BB20013283F8F5 +:10174000BB201BE0B8F1040F18D1BDF84630774A32 +:10175000DFF8E08192FBF3F22046BDF84A30012128 +:1017600092B298F8BA9008F045FA08EB8903C3F8EA +:10177000180298F8BA30013388F8BA300AF1020A30 +:10178000BAF11C0F7FF495AE9CE66B4B06EB030E93 +:1017900098E80F008EE80F00684B10361A78C02EBC +:1017A00002F101021A7009D0D4F8B430002198591E +:1017B00003EB06080DF004FE0028E6D0AB68DB045E +:1017C00020D419E05E4B5D4A03EBC90393F830C0A7 +:1017D000D3F8348082F800C0B8F1000FEED00026B4 +:1017E0006645EBDA544A330103EB020E43440FCB58 +:1017F00001368EE80F00F3E7B9F1080FDFF86C81CE +:1018000028D12AE04D4B93F800A0BAF1010FF3D98B +:101810004C4E4FF00008D04506F11006ECDA56F8B1 +:10182000100C4FF07C510DF037FC4FF07C5146F816 +:10183000100C56F8140C0DF02FFC4FF07C5146F8AC +:10184000140C56F80C0C0DF027FC08F1010846F8B2 +:101850000C0CE0E7B9F10E0F04D198F8003043F01A +:10186000100303E098F8003023F0100388F80030EC +:101870000AF068FF3449354B3548364AC4F8FC3223 +:1018800001600023B5F81A01C4F8F812A4F8023375 +:1018900084F80433C4F80823C4F80C232E495852A2 +:1018A0000233242BFAD12D4B1A60AB681E0740F18E +:1018B000AE802B4B002293F81831042B00F2A1804C +:1018C000DFE803F00303567C8B00012B4FF003028B +:1018D00008D184F81023072284F8123384F81123E6 +:1018E0000C2308E0022384F81033002384F8123319 +:1018F00084F81123072384F8133300230093102066 +:10190000012318494FF4E13209F05EFF164BC4F889 +:101910001803C4F81C3370E0B808002001770008F1 +:101920003547000800127A005D48000840420F0069 +:101930004D480008B0070020E8090020E7270020F4 +:10194000D4480108F009002044210020CC490108B6 +:101950003C010020AC0A002072070020FC0100209E +:1019600034200020B9660008895F00081E040020AA +:101970000123574A574900931020052309F024FFFB +:10198000C4F820030646B5F81A010DF031FB5249A0 +:101990000DF082FB51490DF075FA0DF069FD002341 +:1019A0004F4A98500433402BFAD14E4B301CC4F8A8 +:1019B0001C334FF0100384F813331FE0009201230F +:1019C000102049494FF4E13209F0FEFE474BC4F8BC +:1019D0002403C4F81C3310230DE0009201231020CF +:1019E00043494FF4E13209F0EFFE424BC4F82803BB +:1019F000C4F81C33082384F81333003018BF0120C7 +:101A000028B9082003F0B7FA0023C4F81C33AB68E8 +:101A1000580405D5082284F81323374AC4F81C2338 +:101A200042F201021A4003F0010103F400505AB1DE +:101A3000324AC4F81C2318B1314A082082F8130333 +:101A400011B10C2284F8132394F813231906A2F180 +:101A5000040284F8142369D5294B2A4AD5F8381191 +:101A6000C3F82C230023284A02EB0310D0F82401EA +:101A70001646884204D00133DBB2042BF3D900238D +:101A800084F83133214B0020C4F84C3304F062F960 +:101A90001F4B94F831231B680021C4F8383395F8A4 +:101AA000283106EB02128B42C4F834134FF02000A9 +:101AB0000091D2F824210CBF0123032309F084FEF6 +:101AC000C4F8500330BB802003F055FA25E000BF76 +:101AD000A0860100D1670008CDCCCC3F0000B04407 +:101AE0005C010020416000085D6700082D6000086F +:101AF0000D670008196000086D6000087960000833 +:101B0000B007002060210020D44801085C2100209B +:101B100030200020012004F01DF98C4B186800F5DE +:101B2000D9730430C4F8543303F0B8FBAB689A059A +:101B30000CD59E044CBF864886480BF053FB3B688F +:101B4000002243F010033B60834B1A60834B8449AF +:101B5000D4F808230B608033C4F85833814B824E8D +:101B60001A60AB680027D803377040F1B380DFF804 +:101B700024B2DFF824A203F0CDFA03F007FB03F050 +:101B8000E1FA40F22A334FF001091A465846394625 +:101B900086F80090029310F030FADAF818207348B3 +:101BA00042F00402CAF818204022ADF83020182272 +:101BB0008DF833200CA903228DF8322004F083FA2B +:101BC000DAF81C206A4E42F00202CAF81C20694A68 +:101BD000AAF6947A1168684AB1FBF2F132880139A9 +:101BE00022F45C721204120C328089B21D22B2857A +:101BF0003185A6F81490328C22F001021204120CE6 +:101C00003284328CB088318B22F0020221F07301D1 +:101C100009041204090C120C41F0600180B242EA7E +:101C20000902B0803183B7863284328B22F00802F9 +:101C30001204120C42F008023283B6F844206FEA14 +:101C400042426FEA524292B2A6F84420DAF8A82F34 +:101C500042EA0902CAF8A82F504604F0B1FA474AEE +:101C6000029B1392802218924FF48072CDF850B0EC +:101C700019924FF0100B4FF40052504604991C92E9 +:101C8000CDF854B0169317971A971B971D9704F029 +:101C900079FAB2890DA892B242F40072B281DAF8F0 +:101CA000002042F00202CAF800208DF834B08DF80E +:101CB00035908DF836708DF837900AF0FBF9304B7F +:101CC0001A68304BFA500437802FF8D103F0B6FE73 +:101CD00003F0B4FEAB68590540F1918003F000FABF +:101CE00008B1082000E00420012107F0CCFEAB6819 +:101CF00084F8860613F4806F234E01D100201DE086 +:101D000033681B78032B05D133681B78032B0BD06A +:101D1000012013E0042007F026FE0146042007F00E +:101D2000F1FC0028F0D1E9E7082007F01CFE01468D +:101D3000082007F0E7FC003018BF0120134B36687D +:101D40001870337853BB124B1E604CE03C030020EC +:101D5000444A0108504A0108A400002088210020BC +:101D6000EC06002098070020DC0600200008014057 +:101D700000040040A800002000366E01340400403A +:101D80008C480108F0060020840600208006002010 +:101D9000AC0600200C0B002000100240012B22D1C9 +:101DA00000212C224348C4F8886610F026F98E23BF +:101DB0004FF07C0984F88D367D27E0233E480021D2 +:101DC0002C2284F88F3684F88C9684F8B77610F03D +:101DD00014F98A2384F8B936A02384F8B89684F8D5 +:101DE000BB3684F8E3763378022B08BFC4F8E46688 +:101DF00003F076F908B1C4F8E8660BF03DFEAB6875 +:101E00002E4A13F4002300D00123137004F03AFC8F +:101E10002B4B18606B79052B03D12A4B4FF4C872FA +:101E20001A80294B4FF47A721A80284BC8221A80E4 +:101E300098F8003043F0080388F80030244B1A78F3 +:101E400022F002021A70AB689A071ED5214B224A73 +:101E50001D461A6004F0FAFA282004F0F4FC0699F2 +:101E600001390691F6D129681C4B48781E78024644 +:101E70000123964203D30133082B0244F9D1184AB7 +:101E800013708A785343A4F8EC36164B9B689B0377 +:101E90000CD594F8633043F0010384F863300323D6 +:101EA00084F8643002E0032004F004FD1FB0BDE8B4 +:101EB000F08F00BF3C0E0020680E00200C050020B3 +:101EC0006C040020C0030020CC270020D82700206D +:101ED000D527002098060020382100209C060020ED +:101EE0009800002034200020A14A2DE9F04F13680B :101EF000A04903F59C43A04D20330B60AB6885B02F :101F000013F4807F174604D09C4B1B681B681B6929 :101F10009847AB6842F201041C405CB9984E337894 -:101F200073B1964B1B681B681B6898470BF06AFAE5 -:101F3000347005E0934B1A7801321A700BF062FA94 +:101F200073B1964B1B681B681B6898470AF01CFB33 +:101F3000347005E0934B1A7801321A700AF014FBE2 :101F4000AB68DA0405D5904B1B68DB0701D40CF0B5 -:101F500083F98E4B3C681868037CCBB18C4A013BFB +:101F500073FA8E4B3C681868037CCBB18C4A013B0A :101F600032F91300A0F57A70B0F57A7FA8BF4FF46C -:101F70007A7020EAE0700CF04BFF86490DF050F8C3 -:101F800085490CF099FF0DF083F97E4B588039E0BC +:101F70007A7020EAE0700DF03BF886490DF040F9E8 +:101F800085490DF089F80DF073FA7E4B588039E0E1 :101F9000AA68160436D57B4A5168611A002931DBDC :101FA00004F59C41203151607C494E797C4931F8DF :101FB0001660417CB6B296FBF1F0117A013101F066 :101FC0000F0111720A44507218466E4E06F1090252 :101FD0009A5C01331044102B80B2F6D100B290FB12 :101FE000F3F000B26428A8BF642020EAE0700CF08F -:101FF0000FFF6C490DF014F867490CF05DFF0DF010 -:1020000047F97080AB68D80510D5674B9C42674C88 +:101FF000FFFF6C490DF004F967490DF04DF80DF045 +:1020000037FA7080AB68D80510D5674B9C42674C97 :1020100008D923681B681B6A984718B923681B688E :102020005B6A984723681B685B699847AA68DFF872 :1020300060A112F4805F504BB5F8DC10BAF90620AD @@ -523,28 +523,28 @@ :102090003C4C617E994204D1A17EF92903D80131DB :1020A00000E00021A1766376414B374F1978A1B942 :1020B0003B68D90707D582B93E4B1B78DB070CD5A7 -:1020C0000AF0A4FA09E03B4B1B785E0705D510B176 -:1020D0000CF0C2F801E0002AFAD0A37E294A142BA2 +:1020C0000BF05AFE09E03B4B1B785E0705D510B1BB +:1020D0000CF0B2F901E0002AFAD0A37E294A142BB1 :1020E000354E40F09980334B18F100081B7818BF2B :1020F0004FF0010803F0040303F0FF0093B12C49F3 :102100000B78002B00F08880537E5F2B01D10CF000 -:10211000A3F8B8F1000F7FD0637E7D2B7CD10CF04B -:102120009BF879E0537E572B0BD1244B4FF47A72F6 +:1021100093F9B8F1000F7FD0637E7D2B7CD10CF05A +:102120008BF979E0537E572B0BD1244B4FF47A7205 :102130001A80234B1B6813F008036DD1214A1380CA :102140006AE0A968490745D55A2B43D11E4B197837 :1021500019B1187001221D4B4DE0D17E1C4B81F04E :102160000101D17609B1042245E0062243E000BF17 -:10217000C027002044020020302000204002002020 -:1021800038010020BC0D0020500200203C0100203E -:102190009606002000007A4400C07F44F406002028 -:1021A000040700200000C842404B4C00D409002026 -:1021B00048000020D5270020E8030020CC2700207D -:1021C0004C020020E0040020990400209B04002021 -:1021D0009A0400205D2B00F01E835B2B00F01D8312 +:10217000C42700200002002034200020FC010020A1 +:1021800038010020A00E00200C0200203C0100209D +:102190007207002000007A4400C07F44D00700206E +:1021A000E00700200000C842404B4C00B80A002065 +:1021B00048000020D52700203C030020CC27002029 +:1021C000080200203E040020ED030020EF03002061 +:1021D000EE0300205D2B00F01E835B2B00F01D83BF :1021E0005E2B0AD1032219E3A72B40F05D83AA4B93 :1021F0001A7842F004021A700EE0562B01D109F051 -:10220000D9FAA64A1378002B00F01E83637E6F2B49 -:1022100040F014830AF0FAF9AB685B0731D5E37E2E +:10220000A3FBA64A1378002B00F01E83637E6F2B7E +:1022100040F014830BF0B0FDAB685B0731D5E37E73 :102220009BB19F4B1B7858070FD59E4BBAF90620E0 :10223000B3F81C319A4208DD3B6813F0010304D166 :10224000994A32211180994AD3763B68D9030AD53D @@ -553,13 +553,13 @@ :1022700002F0040202F0FF011AB919708E4B01221C :102280001A70D6F80090002309F1750B3B6009F134 :10229000770698460BF1020303EB080113F80820B8 -:1022A0004B7816F8010C9A420AD2314602F0BAFD78 +:1022A0004B7816F8010C9A420AD2314603F08AFDA7 :1022B00030B116F8023C01229A403B6813433B6060 :1022C00008F10408B8F1A00F06F10406E2D17B4B37 :1022D0001B7843B13B68DFF8FC8113F0020F784EA6 :1022E00040F09A818FE109F21512019209F58B767F :1022F0009846019A16F8010C531C03EB080113F8D9 -:1023000008204B789A4228D2314602F08BFD20B348 +:1023000008204B789A4228D2314603F05BFD20B377 :10231000B0786C4B013800EB400096F804B01844DC :102320004FF00C0CF3780CFB0BFC00935F4B03F1AC :102330001C0909EB0C014A6882420ED0009A09F888 @@ -580,15 +580,15 @@ :10242000DFE801F0060F1B28315C6E80929CA6004D :1024300032781344FA2BA8BFFA2323EAE3733370EC :1024400007E072781344642BA8BF642323EAE37384 -:102450007370304603F0F6F8C4E0F2783046134467 -:10246000642BA8BF642323EAE373F370216D03F0A8 -:10247000A5F8B7E032791344642BA8BF642323EA9C +:102450007370304604F0EEF8C4E0F278304613446E +:10246000642BA8BF642323EAE373F370216D04F0A7 +:102470009DF8B7E032791344642BA8BF642323EAA4 :10248000E3733371AEE072791344642BA8BF642305 -:1024900023EAE3737371A5E0820200204800002064 -:1024A000D52700203020002080040020BC0D002013 -:1024B00098040020990400209B040020D4270020C9 -:1024C00054020020644C01088C0500202C200020C0 -:1024D0009A0400204C020020DC0D0020616D4A7837 +:1024900023EAE3737371A5E01E04002048000020C6 +:1024A000D527002034200020D4030020A00E0020D7 +:1024B000EC030020ED030020EF030020D4270020D0 +:1024C000100200204C4F0108FC04002030200020A6 +:1024D000EE03002008020020C00E0020616D4A7843 :1024E0001A44C82AA8BFC82222EAE2724A700A78AF :1024F0001344C82BA8BFC82323EAE3730B7071E011 :10250000616DCA7A1A44C82AA8BFC82222EAE272B8 @@ -605,7 +605,7 @@ :1025B00092FBF3F3DBB2A94A581C0C29107011D11D :1025C00094F858209A420DD0A54A042B28BF022324 :1025D0000A2184F8583001FB0323A24A0633136012 -:1025E00003F04AF8012303FA09F394F84C2013434B +:1025E00004F042F8012303FA09F394F84C20134352 :1025F00084F84C3009F10109B9F1040F08F10C0815 :102600007FF4BBAE66E6AB68D80514D5964B1B6865 :102610001B689B68984770B1D8F800309B070AD5B3 @@ -624,40 +624,40 @@ :1026E0007DD5674A1278042A79D913F4007C3288A0 :1026F00012D002F010039BB2002B77D15B4922F07D :10270000200242F010025F480A805F4A011D5370A8 -:1027100006F048F8022367E022F0100189B258055C +:1027100006F0B2FF022367E022F0100189B25805EB :1027200031802ED5594B1B685889594BB3F900801D :10273000B8F1000FB8BFC8F10008804509DAB3F955 :102740000230002BB8BF5B428342ACBF00230123A1 :1027500000E06346DB0714D502F0200292B2002AA3 :1027600044D1494B4B485A704B4B41F020011A68F9 -:102770005B683180011DA367626706F013F80123CF +:102770005B683180011DE366A26606F07DFF0123E0 :1027800032E022F0300232803F4A537873BB01219D :1027900051701A46414C424900205052211D04F10B :1027A000080C5052002143F80C109C441053CCF8F4 :1027B0000400CCF80810023204F1300C583443F80D :1027C0000C1019519C441C44042ACCF80400CCF889 :1027D00008106060A16003F11403DBD106E03388C8 -:1027E00023F030033380002384F870303B6813F407 +:1027E00023F030033380002384F866303B6813F411 :1027F000006F338814BF43F4807323F480733380F5 :102800006B79082B02D00E2B40F08D80338823F09B :102810004003338087E0012200E002225FFA82F861 -:1028200008F1FF3385F8543709F062F80BF06EFABF -:1028300002202821424603F017F8EDE4B8F1000F1A +:1028200008F1FF3385F854370AF018FC0BF05EFB13 +:1028300002202821424604F017F8EDE4B8F1000F19 :1028400002D07E2B3FF4E6AC637E972B7FF4CCACBA -:10285000144B4FF4C8721A80DEE400BF9A040020C3 -:10286000802700208C050020D4090020540200207D -:10287000000C0140E00400207A05002082020020C4 -:10288000C4050020240E002048000020200A00205B -:1028900062020020300E0020D0050020380E0020FB -:1028A000DC2700206C0400200022BB2B039201D106 +:10285000144B4FF4C8721A80DEE400BFEE03002070 +:1028600084270020FC040020B80A00201002002069 +:10287000000C01403E040020E60400201E0400205D +:10288000740600205806002048000020040B002099 +:102890001E020020080F002078060020100F0020E4 +:1028A000E2270020C00300200022BB2B039201D1AD :1028B000022303E0B72B04D14FF6FE73ADF80E30C0 :1028C0000AE0BE2B01D1022304E0BD2B7FF4A4ACAF :1028D0004FF6FE73ADF80C303368BDF80C10B3F84A :1028E00054200A44A3F85420BDF80E10B3F8562023 -:1028F0000A44A3F8562008F05DFF0023A3768BE47A -:102900000A4B00220021DA651A66C3F8FC20C3F8DE -:102910000021C3F80421C3F80811C3F80C11C3F84F -:102920001011FFF79CBB05B0BDE8F08FBC0D002077 +:1028F0000A44A3F8562009F027F80023A3768BE4B6 +:102900000A4B00220021DA651A66C3F8F020C3F8EA +:10291000F420C3F8F820C3F8FC10C3F80011C3F882 +:102920000411FFF79CBB05B0BDE8F08FA00E00209E :10293000664B2DE9F04FB3F90600654B87B01D6873 :102940002B8998420EDBB0F5FA6FAF7907DAC21A1D :102950005743A3F5FA6397FBF3F7643703E0C7F136 @@ -683,32 +683,32 @@ :102A9000049B9E45DFF84CE004DA3EF801305B42CF :102AA0002EF801300132032A01F1020104F1010480 :102AB0007FF467AF074EB6F81C31984216DBB0F5CD -:102AC000FA6FA8BF4FF4FA6011E000BF960600202D -:102AD0008C05002030200020E80300200CFEFFFFC2 -:102AE000D00E002062020020DE0E00201846C01A20 +:102AC000FA6FA8BF4FF4FA6011E000BF7207002050 +:102AD000FC040020342000203C0300200CFEFFFFFB +:102AE000A80F00201E020020B60F00201846C01AB2 :102AF0004FF47A725043C3F5FA63B0FBF3F36427E3 :102B0000A34C93FBF7F204EB42016FF0630000FB70 :102B10000233098B04EB4202B2F91A000AB2821A9C :102B2000534393FBF7F739449A4F9B4D3B88AEF8DC :102B300006105A063DD5994B1888994B1B88C01A28 -:102B400000B20CF065F997490CF0B6F980460FF029 -:102B5000F7FB814640460FF067FC8046B5F902005E -:102B60000CF056F98246B5F900000CF051F94946CF -:102B700083460CF0A1F941460346504602930CF0FF -:102B80009BF9029B014618460CF08CF80CF05AFB9E -:102B90004946288050460CF08FF9414681465846F8 -:102BA0000CF08AF9014648460CF07EF80CF04AFB1E +:102B400000B20CF055FA97490CF0A6FA80460FF047 +:102B500083FC814640460FF0F3FC8046B5F9020045 +:102B60000CF046FA8246B5F900000CF041FA4946ED +:102B700083460CF091FA41460346504602930CF00E +:102B80008BFA029B014618460CF07CF90CF04AFCCB +:102B90004946288050460CF07FFA41468146584607 +:102BA0000CF07AFA014648460CF06EF90CF03AFC4B :102BB0006880B26840F602031340002B53D07A4B72 :102BC00006211D88236B1D4494F83430256301339E :102BD000DBB2B3FBF1F084F8343001FB103313F0B7 -:102BE000FF0F40D1930706D502F05EFC02F046FCD1 +:102BE000FF0F40D1930706D503F030FC03F018FC2B :102BF000674B83F83500B368180532D56B4BA16B72 :102C00005A7B6B4B33F81200082391FBF3F280B22E :102C10008A1A0244A26392FBF3F292B240F6E443B2 :102C20005A43644B40F6FF71B2FBF1F219684FF45E :102C30007A73C8888988121A5A4392FBF1F2554375 :102C40005D4995FBF3F30A60D4E91001C01841EB2C -:102C5000E371C4E910010023584A0CF039FB584BCA +:102C5000E371C4E910010023584A0CF029FC584BD9 :102C60001860002323635749494A0B6894F835805C :102C700013F4805318BF012382F84830B3688A46A2 :102C800013F4807F504D2CD0DFF850912878D9F87C @@ -721,18 +721,18 @@ :102CF000C06F05D0364B1B789B0701D4012300E041 :102D0000002384F84A3094F84920214B022A02D14A :102D10004C204E211EE0012A06D153204D214C2289 -:102D20000B4601F0BDFF2BE093F84A20012A03D1A6 +:102D20000B4602F08DFF2BE093F84A20012A03D1D5 :102D3000532001464E2206E093F84820012A04D190 :102D40005320014602464D23EBE7B8F1000F04D0B3 :102D500053204D210A464423E3E73A88170603D55A :102D600053204D210246DBE71A4A12781AB1192086 -:102D700001F06AFF04E0404683F84B8002F06DFDED +:102D700002F03AFF04E0404683F84B8003F06DFD1B :102D80002B7858072CD5144B08225A6183E000BFDA -:102D9000D00E00205402002062020020E004002037 -:102DA000200E002035FA8E3CFC040020F4060020A2 -:102DB00004070020B0050020B8050020407E050073 -:102DC000BC05002050020020D52700204C02002026 -:102DD000820200209A040020000C0140D809002043 +:102D9000A80F0020100200201E0200203E04002088 +:102DA000040F002035FA8E3C68040020D007002074 +:102DB000E007002098060020A0060020407E0500C5 +:102DC000A40600200C020020D527002008020020C5 +:102DD0001E040020EE030020000C0140BC0A00206D :102DE000DAF80020D10703D4B74943F001030B7090 :102DF000B6490B6813F0020302D0B5490988A1B99E :102E0000B449098801B12BB9B34B1B88003318BFF3 @@ -744,14 +744,14 @@ :102E600041B9A14903F5F42303F59073CB649B4B5F :102E700008215961E36C12686BB1D21A002A0ADB8F :102E8000964A03F5F423D16803F5907381F00801A5 -:102E9000D160954AD36409F039FA944B1B7813B189 -:102EA00004F026FAF9E3012005F094FE002800F072 +:102E9000D160954AD3640AF0EFFD944B1B7813B1CF +:102EA00005F08CF9F9E3012006F0FEFD002800F0A2 :102EB000F483DFF8589299F84A30012B40F0E78309 :102EC0008B4A8C4BD9F80010C2F8009019609246DA -:102ED000884A106802F024FD002800F0D283854B58 -:102EE000186802F018FDDAF8003093F84820DAB9D3 +:102ED000884A106803F024FD002800F0D283854B57 +:102EE000186803F018FDDAF8003093F84820DAB9D2 :102EF000B0F124014A424A4183F84820002AE7D130 -:102F00002B785B07E4D4232802D104F0F1F9DFE742 +:102F00002B785B07E4D4232802D105F057F9DFE7DB :102F1000D4F8E8301B7D8342DAD1774A774B1A60C8 :102F2000774A784BDA60D3E7012A04D14D2814BFE1 :102F300000220222A2E3022A04D13C2814BF00226C @@ -760,133 +760,133 @@ :102F600006D19A7983F8490050409871052285E38B :102F7000052AADD159791A799142997906D94140FA :102F80009971511C197113441872A1E7814240F0E4 -:102F9000728393F8490006F071FD002840F06683C3 +:102F9000728393F8490007F0ABFB002840F066838A :102FA000DAF8003093F84930C82B00F0DD8043D8C0 :102FB0002D2B00F0F08224D8252B00F0CD8206D8EE :102FC000212B00F02382232B00F0688186E3292B3C :102FD00000F0CD822B2B00F0D682272B40F07E8391 -:102FE000002002F0E3FC02F0ADFA474FA7F8E6003C -:102FF00002F0A8FAA7F8E80002F0A4FAA7F8EA009D +:102FE000002003F0E3FC03F0A5FA474FA7F8E60042 +:102FF00003F0A0FAA7F8E80003F09CFAA7F8EA00AB :1030000031E3332B00F0DB820CD82F2B00F0ED8264 -:10301000312B40F063833C4FC02002F0C7FC07F126 +:10301000312B40F063833C4FC02003F0C7FC07F125 :103020008008F8E2412B00F0D282442B00F0158397 :10303000352B40F0538353E1D02B00F0F58169D854 :10304000CC2B00F07B8106D8C92B00F02782CA2B3D :1030500000F0A28042E3CE2B00F0128240F2EF811A -:1030600002F070FA02F06EFA274FDFF8A480A7F89A -:10307000D00002F067FAA7F8D20002F063FAD8F89D -:1030800000B0A7F8D40002F05DFAABF8A80102F096 -:1030900059FA02F061FAD8F8008002F053FA00EB16 -:1030A00080004000A8F8520002F042FA87F80401BC -:1030B00002F03EFA87F8060102F03AFA87F80501B5 -:1030C00002F036FACFE200BFD52700204C020020E4 -:1030D000C42700206C040020CC270020000C0140F5 -:1030E00082020020C0270020D00E0020D42700201C -:1030F000DC050020E0050020EFBEADDEF04F002033 -:103100000400FA0500ED00E030200020200F002030 -:10311000E8030020D42B00F0438108D8D22B10D034 -:1031200040F2E18102F00EFAC94B18809BE2EF2BCE +:1030600003F068FA03F066FA274FDFF8A480A7F8A8 +:10307000D00003F05FFAA7F8D20003F05BFAD8F8AB +:1030800000B0A7F8D40003F055FAABF8A80103F09C +:1030900051FA03F059FAD8F8008003F04BFA00EB2C +:1030A00080004000A8F8520003F03AFA87F80401C3 +:1030B00003F036FA87F8060103F032FA87F80501C3 +:1030C00003F02EFACFE200BFD5270020080200202F +:1030D000D8270020C0030020CC270020000C01408E +:1030E0001E040020C4270020A80F0020D4270020A1 +:1030F000B8060020BC060020EFBEADDEF04F002079 +:103100000400FA0500ED00E034200020F80F002054 +:103110003C030020D42B00F0438108D8D22B10D0E0 +:1031200040F2E18103F006FAC94B18809BE2EF2BD5 :1031300025D0FA2B00F0AE81D62B40F0CF820027AD :1031400026E12B7803F0040303F0FF07002B40F087 -:103150008A8202F0EDF9BF4B022883F8540740F24F -:10316000698183F8547765E1002702F0EBF9BA4BE7 +:103150008A8203F0E5F9BF4B022883F8540740F256 +:10316000698183F8547765E1002703F0E3F9BA4BEE :10317000D8530237102FF8D10122B84B88E1B84F4D -:10318000D7F8008002F0DEF9A8F856003F6802F098 -:10319000D9F9A7F8540066E2B14B00271A6898469F -:1031A0001278022A61D1D8F800B002F0C1F907F113 -:1031B00008020BEB820B0BF027FEAA490BF030FF45 -:1031C000CBF80400D8F800B002F0B2F907F10A0217 -:1031D0000BEB820B0BF018FEA3490BF021FFCBF891 -:1031E0000800D8F800B002F0A3F907F10E020BEBCB -:1031F000820B0BF009FE9D490BF012FF0137032FE4 -:10320000CBF80400CFD1072FD8F800B016D102F0C8 -:103210008FF90BF0F9FD93490BF002FFCBF8480052 -:10322000D8F800B002F084F90BF0EEFD8D490BF0F8 -:10323000F7FECBF84C0002F07BF912E002F078F9CF -:103240000BEB07031871D8F800B002F071F90BEB23 -:1032500007039873D8F800B002F06AF90BEB070384 -:10326000187601370A2FCED1FDE1D8F800B002F070 -:103270005FF90BEB07031871D8F800B002F058F9AA -:103280000BEB07039873D8F800B002F051F90BEB81 -:10329000070301370A2F1876E7D1E4E102F048F975 +:10318000D7F8008003F0D6F9A8F856003F6803F09E +:10319000D1F9A7F8540066E2B14B00271A689846A7 +:1031A0001278022A61D1D8F800B003F0B9F907F11A +:1031B00008020BEB820B0BF017FFAA490CF020F86A +:1031C000CBF80400D8F800B003F0AAF907F10A021E +:1031D0000BEB820B0BF008FFA3490CF011F8CBF8B6 +:1031E0000800D8F800B003F09BF907F10E020BEBD2 +:1031F000820B0BF0F9FE9D490CF002F80137032F0A +:10320000CBF80400CFD1072FD8F800B016D103F0C7 +:1032100087F90BF0E9FE93490BF0F2FFCBF8480079 +:10322000D8F800B003F07CF90BF0DEFE8D490BF00E +:10323000E7FFCBF84C0003F073F912E003F070F9EC +:103240000BEB07031871D8F800B003F069F90BEB2A +:1032500007039873D8F800B003F062F90BEB07038B +:10326000187601370A2FCED1FDE1D8F800B003F06F +:1032700057F90BEB07031871D8F800B003F050F9B9 +:103280000BEB07039873D8F800B003F049F90BEB88 +:10329000070301370A2F1876E7D1E4E103F040F97C :1032A000272821D86E4B00F11C081B6803EB880807 -:1032B00002F03EF96E4B08F1050703F58A72197AA0 +:1032B00003F036F96E4B08F1050703F58A72197AA7 :1032C000814203D00C339342F9D10DE01B7888F88A -:1032D000053002F02DF9787002F02AF9B87053E049 -:1032E00002F026F90B2804D90120002102F040FB4E +:1032D000053003F025F9787003F022F9B87053E057 +:1032E00003F01EF90B2804D90120002103F040FB54 :1032F000B9E14FF0060808FB00F0594B00F5887063 -:103300001B6803EB000802F013F90328ECD888F8D7 -:103310000A0002F00DF988F8050002F009F988F8B2 -:10332000060002F005F988F8070002F001F988F8B4 -:10333000080002F0FDF888F8090094E14D4FD7F835 -:10334000008002F0F5F888F80000D7F8008002F05D -:10335000EFF888F80100D7F8008002F0E9F888F863 -:103360000400D7F8008002F0E3F888F80500D7F8E9 -:10337000008002F0DDF888F80600D7F8008002F03F -:10338000D7F888F802003F6802F0D2F8F8706AE1D6 -:1033900002F0D8F8384BD8530237102FF8D162E139 -:1033A0004FF000082E4F08F12C0B3968029102F003 -:1033B000C9F802994FEACB021144C88039680192DA -:1033C000029102F0BFF8019A02991144088101921A -:1033D00002F0B8F80728019A02D839680A445073F5 +:103300001B6803EB000803F00BF90328ECD888F8DE +:103310000A0003F005F988F8050003F001F988F8C0 +:10332000060003F0FDF888F8070003F0F9F888F8C4 +:10333000080003F0F5F888F8090094E14D4FD7F83C +:10334000008003F0EDF888F80000D7F8008003F063 +:10335000E7F888F80100D7F8008003F0E1F888F872 +:103360000400D7F8008003F0DBF888F80500D7F8F0 +:10337000008003F0D5F888F80600D7F8008003F045 +:10338000CFF888F802003F6803F0CAF8F8706AE1E5 +:1033900003F0D0F8384BD8530237102FF8D162E140 +:1033A0004FF000082E4F08F12C0B3968029103F002 +:1033B000C1F802994FEACB021144C88039680192E2 +:1033C000029103F0B7F8019A029911440881019221 +:1033D00003F0B0F80728019A02D839680A445073FC :1033E000A0F57A7292B2B2F57A7F03D83A6802EB0E -:1033F000CB0250813F6802F09BF808F1010807EB0F +:1033F000CB0250813F6803F093F808F1010807EB16 :10340000CB03B8F1080F1873CCD12CE10027144B73 -:10341000D3F8008002F08CF808EBC7030137082FBF +:10341000D3F8008003F084F808EBC7030137082FC6 :1034200083F86D01F3D11EE12B785F0700F11B815A -:1034300004F066F808F05CFA0AF068FC13E12B78F7 +:1034300004F0CCFF09F012FE0AF058FD13E12B78DE :10344000580700F110810D4B4FF4C8721A800AE141 -:103450007A05002030200020960600203C02002043 -:10346000E8030020000020410000C84200007A4428 -:10347000884C01088C050020BC0F00206C04002043 +:10345000E60400203420002072070020F80100203C +:103460003C030020000020410000C84200007A44D4 +:10347000704F0108FC04002094100020C0030020BD :103480002B78590700F1EF80984B1A7842F004022C -:103490001A70E8E02B785A07CCD51FE102F048F803 +:103490001A70E8E02B785A07CCD51FE103F040F80A :1034A000924B1A7810B142F0020201E022F00202BF -:1034B0001A7002F03DF88E4B8E4F187002F04CF8E7 -:1034C000386002F049F8786002F03CF88A4B1880C6 -:1034D00002F038F8894B188094F8043143F0020365 -:1034E00084F80431BFE002F023F8019002F034F8D0 -:1034F000029002F031F8804602F02EF8074602F002 -:1035000021F802F01FF802F013F8019A029B92B919 +:1034B0001A7003F035F88E4B8E4F187003F044F8F5 +:1034C000386003F041F8786003F034F88A4B1880D4 +:1034D00003F030F8894B188094F8043143F002036C +:1034E00084F80431BFE003F01BF8019003F02CF8DE +:1034F000029003F029F8804603F026F8074603F00F +:1035000019F803F017F803F00BF8019A029B92B92F :103510007B4A82E808017B4B1A8822F010021A804D :10352000724B1A7842F001021A70002F00F09B8053 :10353000754B1F6097E0102A40F09580734A82E82F :1035400008010FB1704B1F607048714B0222011DC2 -:103550001A7005F027F986E0002002F027FA002310 -:10356000B36001F0F9FFB3681843B0607BE000205E -:1035700002F01CFA01F0E6FFA6F8080101F0E2FFF4 -:10358000A6F80A016FE0002002F010FA01F0D0FF67 -:10359000604B587167E0002002F008FA01F0C8FFA4 -:1035A00086F8180101F0CEFFA6F81E0101F0CAFF4F -:1035B000A6F81A0101F0C6FFA6F81C0153E000208E -:1035C00002F0F4F901F0B4FF86F820014BE000208E -:1035D00002F0ECF9002701F0ABFF4E4B3B44013702 -:1035E000082F83F81001F6D13DE0002002F0DEF94B -:1035F000484F07F1400801F0A5FFA7F8D40101F0FA -:1036000097FF87F8D60101F093FF043787F8D301BD -:103610004745F0D127E001F095FF00F03F00A7F803 -:10362000560101F08FFFB7F85621800100F4F863CE -:103630001343A7F8563101F07BFF000187F85401CE -:1036400001F076FF97F8543100F00F00184387F827 -:10365000540104374745DED105E0002002F0A6F909 -:10366000012384F80531002002F0A0F9DAF80030D7 -:10367000987902F06CF9DAF80030002283F84820DB +:103550001A7006F091F886E0002003F027FA0023A5 +:10356000B36002F0F1FFB3681843B0607BE0002065 +:1035700003F01CFA02F0DEFFA6F8080102F0DAFF01 +:10358000A6F80A016FE0002003F010FA02F0C8FF6D +:10359000604B587167E0002003F008FA02F0C0FFAA +:1035A00086F8180102F0C6FFA6F81E0102F0C2FF5D +:1035B000A6F81A0102F0BEFFA6F81C0153E0002095 +:1035C00003F0F4F902F0ACFF86F820014BE0002094 +:1035D00003F0ECF9002702F0A3FF4E4B3B44013708 +:1035E000082F83F81001F6D13DE0002003F0DEF94A +:1035F000484F07F1400802F09DFFA7F8D40102F000 +:103600008FFF87F8D60102F08BFF043787F8D301CC +:103610004745F0D127E002F08DFF00F03F00A7F80A +:10362000560102F087FFB7F85621800100F4F863D5 +:103630001343A7F8563102F073FF000187F85401D5 +:1036400002F06EFF97F8543100F00F00184387F82E +:10365000540104374745DED105E0002003F0A6F908 +:10366000012384F80531002003F0A0F9DAF80030D6 +:10367000987903F06CF9DAF80030002283F84820DA :1036800026E494F8053113B1234A244BDA60244B25 :1036900009F14C0999457FF40EAC22490B689B0651 :1036A00016D5214BD4F808211B689A1A002A0FDB83 :1036B0000F4A1278042A0BD91C4A03F5123303F57A :1036C000F873C2F808311A4BDA6882F01002DA6037 :1036D000184B9B683BB11848984704E00120002133 -:1036E00002F046F9C2E707B0BDE8F08F8202002081 -:1036F000C4050020D0050020C2050020C005002020 -:10370000240E00205402002058020020300E002019 -:103710002C0E0020302000200400FA0500ED00E00F -:10372000B80F00204C020020C0270020D00E00203F -:10373000000C0140EC030020DC0F00202DE9F04FCD +:1036E00003F046F9C2E707B0BDE8F08F1E040020E2 +:1036F0007406002078060020AA060020A8060020F4 +:10370000580600201002002014020020080F00209C +:10371000060F0020342000200400FA0500ED00E030 +:103720009010002008020020C4270020A80F0020CD +:10373000000C014040030020B41000202DE9F04FA0 :10374000974B91B01B68BBB9964C2378013B042B77 :1037500000F2F086DFE813F00B060B060B06DE0620 -:10376000C406206802F0D7F88F4B04461B681B780C -:103770004BB1012B00F0ED80894C206802F0D0F8AD +:10376000C406206803F0D7F88F4B04461B681B780B +:103770004BB1012B00F0ED80894C206803F0D0F8AC :103780000028EED1E0E72428884D0CD006D80A287E :1037900000F08E800D2800F08B80C6E02A2806D02D :1037A0002C2804D0C1E02B706B70AB70CEE06A782F @@ -896,14 +896,14 @@ :1037E0006A79724B522A07D19A794D2A04D1DA7933 :1037F000432A04BF02229A74AB7C6C4F012B02D087 :10380000022B36D049E0B31E072B46D8DFE803F081 -:10381000040810141C27452C07F070FA68613CE07E +:10381000040810141C27452C08F0EAFC68613CE001 :10382000EA78624B532A38D15A6952425A6134E0DD -:1038300007F064FAA86130E0EA785C4B572A2CD193 +:1038300008F0DEFCA86130E0EA785C4B572A2CD116 :103840009A6952429A6128E0EB78302B584B1A78EB :103850008CBF42F0020222F002021A701DE000202A -:1038600007F0A6FA287718E0002007F0A1FAE8830D -:1038700013E0072E06D0082E0FD1012007F098FA8A -:1038800078840AE0012007F093FA41F21843584384 +:1038600008F020FD287718E0002008F01BFDE88311 +:1038700013E0072E06D0082E0FD1012008F012FD0C +:1038800078840AE0012008F00DFD41F21843584306 :103890004FF47A72B0FBF2F33B84013600232A2CFA :1038A000424A2E706B704CD1012182F824104DE0F9 :1038B00095F82430002B34D03C4BDB78402B04D9D6 @@ -921,9 +921,9 @@ :1039700001D1022207E083F82510B52C40F04A81DE :1039800093F82520013283F8252043E1032283F8B0 :10399000252083F8260083F8270083F8280039E1E2 -:1039A0001C0A0020FC090020180A0020E00F00205B -:1039B00082020020C00500203E180020D005002013 -:1039C000C4050020C2050020042283F8252093F8B6 +:1039A000000B0020E00A0020FC0A0020B8100020D4 +:1039B0001E040020A80600204A1A002078060020D5 +:1039C00074060020AA060020042283F8252093F81C :1039D000272093F828100244D2B283F827200A4403 :1039E00083F8282083F8290014E1052283F8252094 :1039F00093F8272093F828100244D2B283F82720A6 @@ -956,18 +956,18 @@ :103BA000045C184C155511F8035C174C155511F8A9 :103BB000015C164C15550D78154C15550132EAE788 :103BC00093F8F930054A2BB392F8FA3013B3002377 -:103BD00082F8F93082F8FA3001231CE0E00F00206F -:103BE0004418002010100020D0050020C20500203D -:103BF00082020020C4050020A0000020C005002093 -:103C00003E18002045180020551800206518002097 -:103C1000751800200023002B3FF4AEADA54BA64E37 +:103BD00082F8F93082F8FA3001231CE0B810002096 +:103BE000501A0020E810002078060020AA060020C5 +:103BF0001E04002074060020A0000020A80600205B +:103C00004A1A0020511A0020611A0020711A00205F +:103C1000811A00200023002B3FF4AEADA54BA64E29 :103C20009A68DA6032689A60A44B1A6842F02002FF :103C30001A60A34B1A78012A0CBF002201221A70C5 :103C4000A04B1A7891077FF597AD9F490978042911 :103C50007FF692AD9D49097801F0040101F0FF0063 :103C600011B922F001021A701B78964F13F0010F60 :103C7000974C984D11D180B19B070ED5964B286873 -:103C80006A6818605A6005F035FD944B1B88A4F8EB +:103C80006A6818605A6001F0EBFA944B1B88A4F83C :103C9000FC303B7843F001033B7094F8FE304FF06A :103CA0000509013393FBF9F909EB8909C9EB03090C :103CB0008B4B8C481B7884F8FE900593831D03EB97 @@ -981,53 +981,53 @@ :103D3000183201299850774608D1DDF810E0AEF12D :103D40000202B2F5797F9CBF069908600433082B04 :103D5000B9D1DFF87C813068D8F84C31C01A0BF04B -:103D600053F864490BF05CF933684FF07E51C8F8A2 -:103D70004C3181460BF03EFA10B94FF07E5000E016 +:103D600043F964490BF04CFA33684FF07E51C8F8C0 +:103D70004C3181460BF02EFB10B94FF07E5000E025 :103D800048460CAAC4F85001534B00920DAA019268 -:103D900097E803000CCB05F06BFC0C9B56496422A2 +:103D900097E803000CCB01F021FA0C9B56496422F2 :103DA000B3FBF2F30D980B80544B90FBF2F21A80A8 :103DB000444A474E127812F0010208BF1A8098F860 :103DC000543108BF0A80002B3AD0D6F850114FF07A -:103DD0007E500BF025F9D6F8583181462868C01A74 -:103DE0000BF016F849460BF067F80BF02BFAD6F8F3 +:103DD0007E500BF015FAD6F8583181462868C01A83 +:103DE0000BF006F949460BF057F90BF01BFBD6F820 :103DF0005C211FFA80FA68680FFA8AFA801A0BF0C1 -:103E000007F83F4B19680BF057F849460BF054F888 -:103E10000BF018FAB6F9623100B2C218B6F9603187 +:103E0000F7F83F4B19680BF047F949460BF044F9B6 +:103E10000BF008FBB6F9623100B2C218B6F9603196 :103E20000221534492FBF1F293FBF1F392B29BB265 :103E3000A6F86621A6F86431A6F86221A6F86031DA :103E4000012388F854312F4B79681B88386803F0B8 :103E500030031F4E1F4DC8F85C11C8F85801002BE5 :103E60003FF48AAC06F5B873009306F5BA73019374 -:103E7000D6F86821D6F86C3105F0FAFB6B68D6F8F5 -:103E80006C01C01A0AF0C4FF1D4B19680BF014F83E -:103E90000BF0D8F9D6F868312A68C6F87C019B1A6D +:103E7000D6F86821D6F86C3101F0B0F96B68D6F845 +:103E80006C01C01A0BF0B4F81D4B19680BF004F963 +:103E90000BF0C8FAD6F868312A68C6F87C019B1A7C :103EA000C6F878310E4B1B78012B2DD0022B00F079 -:103EB000F58061E4FC0900202C2000204C02002049 -:103EC000D40F002082020020C4050020D527002046 -:103ED000E00F0020D0050020240E0020E004002088 -:103EE0002C0E0020DE1000200C110020809698007F -:103EF000806967FF00007A444018002042180020C3 -:103F00004C00002054020020D6F89C41D6F8903195 +:103EB000F58061E4E00A00203020002008020020A4 +:103EC000AC1000201E04002074060020D52700201E +:103ED000B810002078060020580600203E0400207C +:103EE000060F0020B6110020E411002080969800F3 +:103EF000806967FF00007A444C1A00204E1A0020A7 +:103F00004C00002010020020D6F89C41D6F89031D9 :103F1000D6F88021D6F8947104F1004005930492FC -:103F200007970BF08FF9074620460BF08BF98C4B67 +:103F200007970BF07FFA074620460BF07BFA8C4B85 :103F3000D6F850511B68D6F898618A4C08900696BE :103F400009934FF0000ADFF83C9259F81A60A9F182 -:103F5000140230463AF802800AF05AFF04990AF037 -:103F6000ABFF0BF06FF9C8EB000080B209F1280934 -:103F70002AF809000FFA80F948460AF049FF059926 -:103F80000AF09AFF0BF05EF91FFA80FB09EB0600BE -:103F90000AF03EFF07990AF08FFF29460AF08CFFCE -:103FA00021680AF081FE0BF04DF9B84204DB089A53 -:103FB0009042A8BF104600E038460AF029FF206072 -:103FC0000BF040F958441FFA80FB606808F1310893 -:103FD000301A0AF01DFF29460BF022F8099B2061D8 -:103FE00002469878D4F8089003920AF00DFF5E49D3 -:103FF0000AF062FF01464FF07E500BF011F829469F -:104000000AF052FE014628460BF00AF8039A84464D -:1040100049461046CDF80CC00AF044FEDDF80CC04D -:10402000014660460AF048FF014648460AF03CFE59 +:103F5000140230463AF802800BF04AF804990BF04C +:103F60009BF80BF05FFAC8EB000080B209F128095A +:103F70002AF809000FFA80F948460BF039F805993C +:103F80000BF08AF80BF04EFA1FFA80FB09EB0600E3 +:103F90000BF02EF807990BF07FF829460BF07CF810 +:103FA00021680AF071FF0BF03DFAB84204DB089A71 +:103FB0009042A8BF104600E038460BF019F8206088 +:103FC0000BF030FA58441FFA80FB606808F13108A2 +:103FD000301A0BF00DF829460BF012F9099B2061FD +:103FE00002469878D4F8089003920AF0FDFF5E49E3 +:103FF0000BF052F801464FF07E500BF001F92946C4 +:104000000AF042FF014628460BF0FAF8039A84466C +:1040100049461046CDF80CC00AF034FFDDF80CC05C +:10402000014660460BF038F8014648460AF02CFF7E :104030001FFA88F8B8F1620F014620616660A0603F -:104040000ED906980AF038FF0BF0FCF8474AB0F595 +:104040000ED906980BF028F80BF0ECF9474AB0F5BA :10405000FA6FA8BF4FF4FA609042B8BF104600E074 :104060000020834440F6B8320FFA8BFB9345A8BF7B :1040700093463F4A0A219345B8BF934601FB0AF194 @@ -1035,5131 +1035,5154 @@ :10409000BAF1040F88503FF46FAB54E7304BD6F8B9 :1040A00070911F68B6F8A451B7F808A04FEA5903F9 :1040B0009A4528BF9A462BB29A4502DC1FFA8AFA23 -:1040C0000BE02E49D6F850010AF0F6FE0BF0BAF8D4 +:1040C0000BE02E49D6F850010AF0E6FF0BF0AAF9F2 :1040D00028441FFA80FAA6F8A4A1D8F87451D8F899 -:1040E000A861AE1B304605F073FB0028D8BF4042E4 +:1040E000A861AE1B304601F029F90028D8BF404234 :1040F00041F293139842CCBF00200120002843D006 -:1041000030460AF085FE1E490AF0D6FE0EF08CF904 -:10411000064648460AF078FE014630460AF0CCFED4 -:104120000BF090F880B240F6B83203B29342A8BFC9 +:1041000030460AF075FF1E490AF0C6FF0EF018FA95 +:10411000064648460AF068FF014630460AF0BCFFF2 +:104120000BF080F980B240F6B83203B29342A8BFD8 :1041300013460F4AA8F8AC019342ACBFEB18AB187A :1041400048F6A042934203DDA3F50C43A03B04E0F4 :10415000002BBCBF03F50C43A033C8F8B03115E009 -:10416000200A0020680E0020DB0FC94030F8FFFF56 -:1041700048F4FFFF3C0E0020900E00200000C842D3 -:10418000D302373958110020C8F8B051D4F8B02103 -:10419000C2F50C50283004920AF03AFEAA490AF0FF -:1041A0008BFE05460EF0CCF80F9028460EF03CF939 +:10416000040B0020400F0020DB0FC94030F8FFFF98 +:1041700048F4FFFF140F0020680F00200000C84221 +:10418000D302373930120020C8F8B051D4F8B0212A +:10419000C2F50C50283004920AF02AFFAA490AF00E +:1041A0007BFF05460EF058F90F9028460EF0C8F92F :1041B000D4F8C051D4F8B431D4F8B8210E9005F138 -:1041C000004007930A920BF03DF8059028460BF04B -:1041D00039F8D4F85081D4F8BC410B9009949B4C29 -:1041E000002550460AF014FE0EAB53F815100AF0E5 -:1041F00063FEDFF894B206463BF905000AF008FEBC -:10420000014630460AF04EFD0BF01CF8904B06B20A +:1041C000004007930A920BF02DF9059028460BF05A +:1041D00029F9D4F85081D4F8BC410B9009949B4C38 +:1041E000002550460AF004FF0EAB53F815100AF0F4 +:1041F00053FFDFF894B206463BF905000AF0F8FEDB +:10420000014630460AF03EFE0BF00CF9904B06B228 :10421000B6F57A7FA8BF4FF47A769E42B8BF1E46A5 -:10422000B0B20BF13C0B25F80B0000B20AF0F0FD28 -:10423000079983460AF040FE0BF004F880B208901C -:104240000A9958460AF038FE41460AF035FE2168C0 -:104250000AF02AFD0AF0F6FF059B984204DB0B9A50 -:104260009042A8BF104600E005980AF0D1FD8346B1 -:10427000206060681434301A0AF0CAFD41460AF022 -:10428000CFFE54F80C3C44F8040C0246B878069370 -:1042900003920AF0B9FD6F490AF00EFE01464FF095 -:1042A0007E500AF0BDFE41460AF0FEFC0146404643 -:1042B0000AF0B6FE039A844606991046CDF80CC063 -:1042C0000AF0F0FCDDF80CC0014660460AF0F4FD8F -:1042D000014606980AF0E8FC44F8106C014644F8E0 -:1042E000040C44F80C0C09980AF0E6FD0AF0AAFF49 -:1042F000089E064458460AF0A5FF304440F6B832FE +:10422000B0B20BF13C0B25F80B0000B20AF0E0FE37 +:10423000079983460AF030FF0BF0F4F880B208903B +:104240000A9958460AF028FF41460AF025FF2168DE +:104250000AF01AFE0BF0E6F8059B984204DB0B9A75 +:104260009042A8BF104600E005980AF0C1FE8346C0 +:10427000206060681434301A0AF0BAFE41460AF031 +:10428000BFFF54F80C3C44F8040C0246B87806937F +:1042900003920AF0A9FE6F490AF0FEFE01464FF0B4 +:1042A0007E500AF0ADFF41460AF0EEFD0146404661 +:1042B0000AF0A6FF039A844606991046CDF80CC072 +:1042C0000AF0E0FDDDF80CC0014660460AF0E4FEAD +:1042D000014606980AF0D8FD44F8106C014644F8EF +:1042E000040C44F80C0C09980AF0D6FE0BF09AF86E +:1042F000089E064458460BF095F8304440F6B83214 :1043000000B29042A8BF1046534A0A219042B8BF5B :1043100010466943514AA852514A0235042D41F8CA :1043200002B07FF45EAF3B792BB1049B642293FB18 :10433000F2F24C4B1A803B884B4C99450ED9D4F87D -:10434000A831D4F87401C01A05F042FA42F2107391 +:10434000A831D4F87401C01A00F0F8FF42F21073DB :104350000028B8BF404298427FF70EAA434B012283 :104360001A70B4F8FC203F4B1A80FFF705BA404A98 :10437000116890460F7817B1012F0DD0ADE0012BD9 :1043800000F2AB8062783B4B03EB02133A4A596868 -:10439000106801F0BBFA9DE0374E306801F0B1FAC9 +:10439000106802F0BBFA9DE0374E306802F0B1FAC7 :1043A000B146002800F099802378344D022B29D0A3 :1043B000032B31D0012B40F09080314B1F686B698B :1043C000FB1A632B40F289802B69042B18D8DFF885 -:1043D000A480306808EB0313596801F097FA6B78F2 +:1043D000A480306808EB0313596802F097FA6B78F1 :1043E000366808EB03139D6815F8011B19B13046B8 -:1043F00001F0A8FAF8E723696761013323616CE0F3 +:1043F00002F0A8FAF8E723696761013323616CE0F2 :10440000022068E06A781B4B306803EB021359689E -:1044100001F07CFA03205EE02B7E03B92F76227E2A +:1044100002F07CFA03205EE02B7E03B92F76227E29 :10442000164B012A36D11A697B2A2FD8D8F80030CA -:104430009B782BB9134BD9F80000995C01F082FAF4 -:1044400023690133236125E0D3023739900E002020 -:1044500018FCFFFFDB0FC94048F4FFFF3C0E0020B3 -:10446000680E00207A050020E00F00202C0E0020AE -:10447000180A00200C4701081C0A0020FC09002033 -:104480002C2000209C4D01084411002000221A61BC +:104430009B782BB9134BD9F80000995C02F082FAF3 +:1044400023690133236125E0D3023739680F002047 +:1044500018FCFFFFDB0FC94048F4FFFF140F0020DA +:10446000400F0020E6040020B8100020060F0020B6 +:10447000FC0A0020F4490108000B0020E00A00209B +:1044800030200020845001081C12002000221A61F4 :1044900002221A76227E294B022A18D11A690F2A83 :1044A00013D8D8F80030997859B95B78244903EBD0 -:1044B00003130B441A44D9F8000092F87D1001F060 +:1044B00003130B441A44D9F8000092F87D1002F05F :1044C00041FA23690133236101E003221A76237E36 -:1044D000022B02D9042000F06DFC0023636029E068 +:1044D000022B02D9042001F03DFC0023636029E097 :1044E0006368052201336360637801200133DBB226 :1044F000B3FBF2F202EB82029B1A6370114B0022B3 :104500001B68A360104B1A70104B1A7822F002023D :104510001A700DE00B4B1A68A368D21A40F6C41348 :104520009A4207D90A4B05201A6822F020021A6025 -:1045300000F040FC11B0BDE8F08F00BFFC09002086 -:104540009C4D01082C200020C40500208202002080 -:104550004C02002070B50E46202115460DF0F5FCEA -:104560000446B8B1441C20460DF051FDB0F5617F02 -:1045700005DB40F634039842A8BF184601E04FF42B -:1045800061701923A0F5617090FBF3F030702B7807 -:1045900001332B70204620210DF0D7FC0446B8B122 -:1045A000441C20460DF033FDB0F5617F05DB40F67D -:1045B00034039842A8BF184601E04FF461701923F4 -:1045C000A0F5617090FBF3F070702B7801332B70C5 -:1045D000204670BD70B586B005460DF0C3FCC0B274 -:1045E00008BB044606236343444A03F588731268F4 -:1045F00019201344591D4D789A7A454305F5617584 -:104600005B7900958D78684300F561700190C878FA -:10461000029009793A4803912146013401F098FC4F -:104620000C2CDFD168E028460DF0F1FC0B285FDC94 -:1046300006267043314B00F588701E682021064421 -:104640000023681C8DF817300DF07FFC741D0546A3 -:1046500058B1451C28460DF0DAFC032805D89DF812 -:104660001730607101338DF81730284620210DF086 -:104670006CFC054658B1451C28460DF0C8FC0D28B9 -:1046800005D870719DF8173001338DF81730284622 -:10469000611C0DF11702FFF75DFF20210DF055FCA5 -:1046A000054658B1451C28460DF0B1FC0C2805D82C -:1046B0009DF81730E07001338DF81730284620211F -:1046C0000DF043FC50B101300DF0A1FC0D2805D8D0 -:1046D0009DF81730207101338DF817309DF8173091 -:1046E000062B09D02046002106220DF0FAFB03E03C -:1046F00004480C2101F02CFC06B070BDE80300203A -:1047000007640108CF680108F0B585B007460DF0D1 -:1047100029FCC0B2E0B90446324B04F11C021B680C -:10472000192003EB8203591D8D785A79454305F50D -:1047300061759B790095C978484300F561700190D7 -:1047400021462948013401F003FC282CE4D146E03D -:1047500038460DF05CFC27283DDC224B00F11C069E -:104760001B68781C03EB8606202100238DF80F3090 -:104770000DF0EBFB751D044658B1441C20460DF0AE -:1047800046FC152805D870719DF80F3001338DF85F -:104790000F30204620210DF0D8FB044658B1441CB0 -:1047A00020460DF034FC0D2805D89DF80F306870B8 -:1047B00001338DF80F302046A91C0DF10F02FFF7D1 -:1047C000C9FE9DF80F30042B09D028460021042291 -:1047D0000DF087FB03E00548282101F0B9FB05B087 -:1047E000F0BD00BFE803002027640108CF6801087E -:1047F000F0B5884C884A23689D8AADB2E9B211F0C1 -:10480000010F32D0198821F400610904090C1980C4 -:10481000198889B241F480611980002111707F49A3 -:1048200008787F49A8B1507818B97E480078FF28E9 -:104830000FD1012050707C480078022804D11888DC -:1048400080B240F400601880097841F001011982BB -:1048500002E1097801F0FE011982724B1B78FF2BEF -:1048600000F0FA80FF231370F6E08F073CD5BFF30A -:104870005F8F6D490878C0B2012814D1674D2D783B -:104880008DB155787DB1198821F480610904090C36 -:104890001980BFF35F8F198B1988907089B241F42A -:1048A000007119801BE0188BBFF35F8F0878022816 -:1048B0000BD15A48007840B1507830B1198821F4B2 -:1048C00080610904090C1980C0E00978032906D128 -:1048D0005249097819B15178002940F0B780998878 -:1048E00089B241F48061B6E04E075BD50121917039 -:1048F0004A49097800293AD05178002937D04A49E5 -:1049000010780978494D022919881ED921F480614F -:104910000904090C19801F8A2E68C1B2FFB240B287 -:104920003754188880B240F4007018808B1C1370C4 -:10493000236828681D8A013149B2EDB2455499882F -:1049400089B241F48061998027E089B241F4007115 -:1049500019801E8A2D68C1B2F6B240B22E541B8A4D -:10496000481C40B2DBB203312B54117015E0517872 -:1049700011B92F49097841B1198889B241F4007100 -:10498000198013780133137007E0198889B241F454 -:1049900080711980204B0121597021680B88D8053E -:1049A000FCD459E001F0400101F0FF061E48F1B1CE -:1049B0001E49B3F810C00F6811785FFA8CFCCDB2B5 -:1049C0006E1C49B2F6B207F801C01670077876B2CD -:1049D000F11C8F4205D1998821F480610904090CEA -:1049E00099800378B34237D10235157034E0290637 -:1049F00032D511784DB26F1C1ED00E4E0131366883 -:104A0000C9B2755D1170EDB21D82007849B288425D -:104A100022D11BE030130020A41100203813002005 -:104A200035130020361300204413002040130020CB -:104A3000371300203C130020134916700978C9B2BF -:104A400019821249097809B9017829B9998821F49C -:104A500080610904090C99800D4B92F900101878B7 -:104A60000C4B421C91420DD100225A709B7833B1FD -:104A70002268938823F440731B041B0C9380064B1D -:104A800000221A70F0BD00BF36130020381300203A -:104A900044130020A4110020451300202DE9F04FFD -:104AA000624C63686249581C0A78894602F0FF0C20 -:104AB0000AB10346F6E7277B667BA57B2169636025 -:104AC000E0461FFA88F213B21F2B00F39380594976 -:104AD00001EB8300C278807831F82310C0F1FF0029 -:104AE00080B2002861D0C0F1FF0050433C23B1FBED -:104AF000F3FA0012BAF1050F5AD8DFE80AF0030BF7 -:104B00001A283846161A4E43C5B2B6FBF3F62E44A1 -:104B1000F6B248E0B1FBF3F703FB1717BFB2C5B21B -:104B2000C7F13C07101A4743B7FBF3F72F4416466B -:104B300029E0B1FBF3F503FB1515C7B2ADB2101AAE -:104B40004543B5FBF3F53D44EDB2164630E0B1FB0D -:104B5000F3F603FB1616B6B2C7B2C6F13C06101A3E -:104B60004643B6FBF3F63E441546F6B220E0B1FBF1 -:104B7000F3F703FB1717C6B2BFB2101A4743B7FBD0 -:104B8000F3F737441546FFB212E0B1FBF3F503FB30 -:104B90001515ADB2C6B2C5F13C05101A4543B5FBBB -:104BA000F3F53544EDB2174602E0154616461746B2 -:104BB0004FEA072A4AEA064A4AEA050A1723012168 -:104BC00099400CF1170211EA0A0FC3EB02021A49CD -:104BD0000CBF0920112092B213F1FF338854EED29A -:104BE0000CF1180C08F101081FFA8CFC1FFA88F868 -:104BF000124966E7012389F80030114B628140F2C7 -:104C00002A3227736673A5732161A4F808C05A601D -:104C10000C4A00219184118889B241F00101118070 -:104C20001A6842F001021A60BDE8F08FA41100205A -:104C3000CE27002014060020280A0020B0110020F2 -:104C40006C0002400004004038B5114B114D1A7839 -:104C5000114C29688AB162690244914217D300203D -:104C6000187000F0FAFD2B6863610C4B1A780AB1DA -:104C7000013A1A700123237638BD6269C832914225 -:104C800005D30120187000F0E8FD2B68636138BD82 -:104C90001B0F00202C200020A41100209A040020CB -:104CA00037B5214D8DF807306B7E8DF8062002AAAE -:104CB0008DF804008DF805101A4412F8042C443ABB -:104CC000D2B20F2A29D81949022B31F8124003D841 -:104CD00014B12046FFF7B8FF6B7E134A022B09D9A7 -:104CE000134B19685369091B8B4203D20023537677 -:104CF000104A13702B7E012B00D09CB96B7E022BC7 -:104D000002D8094A013353760B4B002028761870DD -:104D100003B0BDE8304000F0A0BD022B4FF0C80446 -:104D2000D7D9D9E703B030BDA41100206E4E0108D9 -:104D30002C2000209A0400201B0F002030B585B0E5 -:104D400004AC002524F8025D0091ADF80600214670 -:104D5000102000F0F1FE9DF80600214600F0ECFE68 -:104D60009DF80700214600F0E7FE9DF8000021466F -:104D700000F0E2FE9DF80100214600F0DDFE9DF806 -:104D80000200214600F0D8FE9DF80300214600F005 -:104D9000D3FE9DF80E002946C043C0B200F0CCFE01 -:104DA000024B1A68024B1A6005B030BD2C2000205F -:104DB000FC0500200449054B0968002218701A619F -:104DC00059611A76704700BF2C200020FC09002092 -:104DD000114B70B51B685E89104B186880F310008A -:104DE000301A09F04BFC00220D4B09F0ADFC0446D3 -:104DF00030460D4609F042FC02460B462046294645 -:104E000009F0CCFD09F0B2FE6428A8BF642020EAB6 -:104E1000E070C0B270BD00BFB0050020BC0500202E -:104E200000005940104B043033F91030B3F5617F66 -:104E300005DB40F633029342A8BF134601E04FF46E -:104E4000617308781922504300F28330984208DADF -:104E50004878504300F283309842B4BF00200120CC -:104E600070470020704700BF960600204D4B2DE98B -:104E7000F74FB3F9000009F0CBFF4B490AF01CF8DB -:104E800004460DF0D1FA074620460DF059FA474B7B -:104E900006461B68DFF8208193F80390444DB9F172 -:104EA000000F4CD0DFF814A1B8F90200BAF80230B4 -:104EB000C9F100041FFA83FB1BB2C01A04F088FC7E -:104EC000A04203DB4845A8BF484600E02046BAF8A8 -:104ED00000308344B8F900009AB21BB21FFA8BFB72 -:104EE000C01A0192AAF802B004F072FCA042019A22 -:104EF00003DB4845B4BF04464C461444A4B20FFA41 -:104F00008BF0AAF8004009F083FF804620B209F038 -:104F10007FFF31460446404609F0CEFF39468146C0 -:104F2000204609F0C9FF0146484609F0BBFE214969 -:104F30000AF076F80AF086F9288040461DE0B8F9B4 -:104F4000020009F065FF8146B8F9000009F060FF32 -:104F500031460446484609F0AFFF394680462046B0 -:104F600009F0AAFF0146404609F09CFE11490AF0EB -:104F700057F80AF067F928804846394609F09CFF3F -:104F800031460746204609F097FF0146384609F0AA -:104F90008BFE08490AF044F80AF054F9688003B01F -:104FA000BDE8F08FE004002035FA8E3C200A002096 -:104FB000DC270020000020413C0E0020380E00209D -:104FC000084BDA68D10709D4DA68520708D4DB68DD -:104FD00013F0100F0CBF042003207047012070470E -:104FE00002207047002002401E4B2DE9F0431A7842 -:104FF0001D460AB31C4B07781E781C4B93F800C063 -:1050000002231B4A03F10108D45C344104F00F046D -:10501000BC420CD20B2C0AD812F8039012F808806C -:1050200002EB840209EA0C0408EB04241461023345 -:10503000102BE6D100232B7003788B420FD90C4B39 -:1050400093F8400060B10B4A890012780B4418694C -:1050500002B1400800F5777080B2BDE8F08300200F -:10506000BDE8F08340010020DC090020DD090020BC -:10507000C0110020DE09002007299ABF024B33F837 -:1050800021000020704700BF1C020020024B53F893 -:105090002100C0F3CF007047C401002008B5074BC2 -:1050A00053F8210009F0B0FE054909F005FF054954 -:1050B00009F0FAFD0AF0ECF880B208BD5C010020AE -:1050C0000000203F00005C44014B33F811007047A2 -:1050D00096060020014B33F811007047441200205F -:1050E000034B4FF4805208B11A6170475A61704700 -:1050F00000080140034B4FF4805208B15A617047D9 -:105100001A6170470008014038B50C680546204612 -:105110000CF028FF214602462868BDE838400CF014 -:1051200029BFCB78F0B5DA0648BF8A78098803F042 -:105130000F0548BF154311F0FF0F1DD00468002272 -:105140000127974007EA0106BE4211D197004FF0B0 -:105150000F0C0CFA07FC05FA07F724EA0C04282BBD -:1051600044EA070401D1466102E0482B08BF06610A -:105170000132082AE4D10460FF291FD944680022C3 -:1051800002F108060127B74007EA0106BE4211D125 -:1051900097004FF00F0C0CFA07FC05FA07F724EA0A -:1051A0000C04282B44EA070401D1466102E0482B95 -:1051B00008BF06610132082AE2D14460F0BD10B593 -:1051C0000446FFF7FDFE012806D11CB1FFF7F8FEEB -:1051D000013CF8E7052010BD002C08BF052010BDDC -:1051E0008A6810B50C6A036814430A6923F4FF4304 -:1051F00014434A6923F0700314438A691443CA694B -:1052000014434A6A14438A6A224313430360CB68F7 -:1052100043600B6883604B68C36010BD02684FF643 -:10522000FE73134003600023036043608360C36028 -:105230002A4B984222D02A4B984229D0294B984297 -:1052400030D0294B984237D0284B98423ED0284B3B -:10525000984206D153F8682C42F4700243F8682C47 -:105260007047244B984206D153F87C2C42F0706270 -:1052700043F87C2C7047204B984206D153F8042CFD -:1052800042F00F0243F8042C70471C4B984206D1A1 -:1052900053F8182C42F0F00243F8182C7047184BC2 -:1052A000984206D153F82C2C42F4706243F82C2C0F -:1052B0007047144B984206D153F8402C42F4704288 -:1052C00043F8402C7047104B984205D153F8542CAA -:1052D00042F4702243F8542C704700BF080002408B -:1052E0001C000240300002404400024058000240CE -:1052F0006C00024080000240080402401C0402408E -:105300003004024044040240580402402DE9F843AE -:10531000574B0C460168013AC3F842108188A3F844 -:105320004610072A42D8DFE802F0040A10182229A2 -:105330002F35B3F842202280B3F8442013E0B3F8AD -:1053400044202280B3F8422005E0B3F842205242C4 -:105350002280B3F84420524205E0B3F84420524280 -:105360002280B3F842206280B3F846301DE0B3F8E3 -:10537000422052422280B3F8442012E0B3F8442085 -:105380002280B3F842200CE0B3F842202280B3F828 -:10539000442005E0B3F8442052422280B3F8422072 -:1053A00052426280B3F846305B42A380314B1B7897 -:1053B000002B5AD1B4F9000009F02AFD8046B4F957 -:1053C000020009F025FD0746B4F9040009F020FDAC -:1053D000294D06462968404609F06EFDE968814678 -:1053E000384609F069FD0146484609F05DFCA969A7 -:1053F0008146304609F060FD0146484609F054FCFC -:105400000CF0D4FF69682080404609F055FD2969F9 -:105410008146384609F050FD0146484609F044FCF3 -:10542000E9698146304609F047FD0146484609F0E2 -:105430003BFC0CF0BBFFA9686080404609F03CFDD6 -:1054400069698046384609F037FD0146404609F053 -:105450002BFC296A0746304609F02EFD01463846E6 -:1054600009F022FC0CF0A2FFA080BDE8F88300BF89 -:10547000C0110020380000200C070020074B084A0C -:105480001B7812889A4207D3064A1268907898428D -:105490008CBF00200120704700207047B405002019 -:1054A000B80D0020B005002010B5194B93F8482026 -:1054B000511C83F84810174902F007024878164932 -:1054C00003EB420331F81010A3F84A1000231846EA -:1054D000124A9A5A02331044102B80B2F8D1C008F5 -:1054E00009F096FC0E4909F0E7FC0E4909F098FD19 -:1054F0000D4B04461B68187809F08AFC01462046CB -:1055000009F0DAFC09F0C4FE084B187010BD00BFAA -:10551000C0110020F4060020040700200A12002019 -:105520003333534000F07F45B0050020B405002020 -:10553000034B1B68DA79511CD9711344187A7047F0 -:10554000DC05002010B5FFF7F3FF0446FFF7F0FF7E -:1055500004EB002080B210BD10B5FFF7F3FF044646 -:10556000FFF7F0FF04EB004010BD0B4AA2F130033F -:10557000197A81420BD00C339342F9D1074B197A37 -:10558000014004D10C339342F9D1084603E0184698 -:105590000BB15868704770479800002068000020E1 -:1055A00000230549DAB2595C814203D001330C2B48 -:1055B000F7D11A46104670473C6401082DE9F047C0 -:1055C0008278C6781E4BC2F1640802EB820C54420A -:1055D0005FFA88F84FEA4C0CC6F16409A4B203F1F3 -:1055E0001807A5B228B2002804DC002D14BF154608 -:1055F000012500E0454600FB00FA6D430AFB06FA70 -:105600009AFBF5F54D4468434FF00A0A90FBFAF017 -:10561000604480B258800D88B1F802A000B2C5EB9A -:105620000A0A00FB0AF04FF47A7A90FBFAF005447C -:1056300023F8025F0A34BB42A4B2D2D1BDE8F0879E -:10564000E60E002010B544780078002303FB03F138 -:105650001939614301F6C4115943414340F6C4125C -:1056600091FBF2F1034A22F813100133072BEDD11D -:1056700010BD00BFD00E002010B5044C2068FFF70D -:10568000E1FF20680249BDE8104097E78C05002043 -:105690000021002010B5094A094913688C68126876 -:1056A0009342F8D1074A106811684FF47A72504358 -:1056B000001BB0FBF1F002FB030010BD2C2000200A -:1056C00010E000E0DC06002038B5104C0123054650 -:1056D00084F84030FFF7DEFFE36D41F28832C31AF1 -:1056E0009342236684BF002384F8643094F86430C6 -:1056F000EDB20F2BE065E55403D1054B01221A7082 -:1057000038BD024A013382F8643038BDC011002030 -:105710004001002010B50446FFF7BCFF0D4B41F2DD -:1057200088319A6E9866821A8A42DA6684BF0022AD -:1057300083F8702093F87030074A142BD45403D1A7 -:10574000064B01221A7010BD024A013382F87030F4 -:1057500010BD00BFC011002005020020040200207F -:1057600010B50446FFF796FF164A536F5067C31AE9 -:10577000B3F57A6F84BF002382F8783092F87830DE -:1057800023B9A82C1CD110490B7006E0022B02D1C2 -:105790000E490C7001E0242B01D80D49CC54013383 -:1057A000DBB282F87830094A12785200053293420F -:1057B00006D1044B002283F87820034B01221A7093 -:1057C00010BD00BFC01100209C010020C2010020BC -:1057D0009D01002038B50446FFF75CFF114B40F6F1 -:1057E000C411DA6FD867821A8A4284BF002283F814 -:1057F000802093F880200AB90F2C11D10A4800218B -:10580000017052B1094D182A154405F8014C04D114 -:10581000012283F88010027038BD013283F88020A5 -:1058200038BD00BFC011002041010020420100200E -:1058300038B50446FFF72EFF0546FFF72BFF401B48 -:10584000A042FAD338BD10B504462CB14FF47A709B -:10585000FFF7EEFF013CF8E710BD08B5014B1B68F0 -:10586000984708BDD82700202DE9F04106460F468D -:1058700090460025EBB2434518D20024E3B2B34270 -:105880000FD20B4B0120DA68013482F00802DA6093 -:10589000FFF7E3FF3846FFF7D6FF0020FFF7DDFFF5 -:1058A000ECE73C20FFF7CFFF0135E3E7BDE8F081EF -:1058B000000C014040F2DB14604308B50D4B102290 -:1058C0005A6108221A61841E0A4B2046DA6882F067 -:1058D0001002DA60DA6882F00802DA60FFF7B3FFDC -:1058E0000120FFF7BAFF1920FFF7ADFF0020FFF7F7 -:1058F000B4FFE9E7000C014008B503685B6998470D -:1059000008BD08B503681B69984708BD08B503685A -:10591000DB68984708BD08B503689B68984708BDD1 -:1059200008B503685B68984708BD10B5044C20684B -:10593000FFF7F6FF18B12068FFF7EDFFF6E710BD9F -:10594000E41B002008B503681B68984708BD064B98 -:1059500010B5044621461868FFF7F4FF034B1B6897 -:105960009A7954409C7110BDE0050020DC050020B0 -:1059700038B5044624200D46FFF7E9FF4D20FFF718 -:10598000E6FF002C084C0CBF3E202120FFF7DFFF74 -:105990002368002228469A71FFF7D9FF236893F8FD -:1059A0004900BDE83840D2E7DC0500200146002070 -:1059B000DEE7F8B50E4E0F4C0F4DC1B2074630680A -:1059C00084F88110FFF7BEFF2B6894F881109A7954 -:1059D00030684A409A71C7F3072184F88110FFF7B5 -:1059E000B1FF2B6894F881109A794A409A71F8BDFA -:1059F000E0050020C0110020DC050020F8B51B4D9B -:105A00001B4C1C4F0646C1B2286884F88210FFF771 -:105A100099FF3B6894F882109A7928684A409A71F5 -:105A2000C6F3072184F88210FFF78CFF3B6894F8D7 -:105A300082109A7928684A409A71C6F3074184F81F -:105A40008210FFF77FFF3B6894F882109A792868EC -:105A50004A409A71310E84F88210FFF773FF3B6859 -:105A600094F882109A794A409A71F8BDE0050020B6 -:105A7000C0110020DC05002010B5441E14F8011FE1 -:105A800021B1034B1868FFF75DFFF7E710BD00BFBA -:105A9000D81B0020014B186854E700BF2C130020CE -:105AA000014B014618684DE71C20002010B5044644 -:105AB0007F2C06D964F07F00C0B2FFF7F1FFE40944 -:105AC000F6E7E0B2BDE81040EAE7430083EAE070A1 -:105AD000ECE770B5104E114C114D4720FFF7E0FF79 -:105AE0003078FFF7E3FF23682868C01AFFF7EDFF5F -:105AF00063686868C01AFFF7E8FF0A4B1888FFF769 -:105B0000D5FF094B1888FFF7D1FF337823742B6832 -:105B1000A3606B68E36070BDC4050020141C002006 -:105B2000D0050020C2050020C0050020014B1868E8 -:105B300008E700BF1C200020A0F17D03012B70B5F9 -:105B400004460D460A4E05D830687D21FFF7FAFE5F -:105B500084F0200430682146FFF7F4FE35B12B882D -:105B60001C4404EB142404F0FF042C8070BD00BF1F -:105B7000EC05002038B5054C05465E212068FFF78E -:105B8000E1FE20682946BDE83840DBE6A405002098 -:105B9000014B5E211868D5E6A405002010B50A4C1B -:105BA0005E280146206805D15D21FFF7CBFE206805 -:105BB0003E2105E05D2903D1FFF7C4FE20683D21A9 -:105BC000BDE81040BEE600BFA405002010B50446A5 -:105BD000C0B2FFF7E3FFC4F30720BDE81040FFF7B2 -:105BE000DDBF064B1B6803EBC00090F9063019427D -:105BF0000CBF01204FF0FF30704700BFA81E0020EF -:105C00000A4B1A6802EBC002D379FF2B07D0084970 -:105C10000978994203D9074A32F8130004E00728AB -:105C2000D4BF908840F2DC5000B27047A81E00201C -:105C3000DF0900209606002010B5054C00202188C1 -:105C400003F05DFE61880120BDE8104003F057BEFF -:105C5000120000202DE9F04F0C68836889B0D0F85D -:105C600000A0D0F804800646204603938B460CF033 -:105C700067FB074620460CF0D7FBDBF80440814663 -:105C800020460CF05DFB054620460CF0CDFBDBF812 -:105C900008200446104601920CF052FB019A8346FC -:105CA00010460CF0C1FB39460290584609F004F941 -:105CB00039460490029809F0FFF859460590484685 -:105CC00009F0FAF802990690484609F0F5F82946D5 -:105CD0000790584609F0F0F80146504609F0ECF8F4 -:105CE00021468346069809F0E7F80146059808F032 -:105CF000DBFF0146404609F0DFF80146584608F050 -:105D0000D3FF21468346049809F0D6F80146079848 -:105D100008F0C8FF0146039809F0CEF8014658463E -:105D200008F0C2FF3060029905F1004009F0C4F8A4 -:105D30000146504609F0C0F821468346079809F00D -:105D4000BBF80146049808F0ADFF0146404609F053 -:105D5000B3F80146584608F0A7FF21468346059848 -:105D600009F0AAF80146069808F09EFF014603983C -:105D700009F0A2F80146584608F096FF21467060E7 -:105D8000504609F099F82946044609F1004009F007 -:105D900093F80146404609F08FF80146204608F086 -:105DA00083FF39460446284609F086F801460398E1 -:105DB00009F082F80146204608F076FFB06009B08D -:105DC000BDE8F08F2DE9F04F064689B00F46154625 -:105DD0009B462978002900F0B880252902D001359A -:105DE0003046B0E06C78302C03D002354FF000091B -:105DF00003E0AC784FF001090335A4F13003092B1F -:105E00004FF000081AD8A4F13003DAB2092A07D8F3 -:105E10000A2B13DC0A2202FB083815F8014BF2E7C3 -:105E2000A4F16103052B02D8A4F15703F0E7A4F114 -:105E30004103052B02D8A4F13703E9E76C2C03BF1B -:105E40002C78012201350022632C66D006D8252C3F -:105E500077D0582C3FD0002C77D0BAE7732C63D082 -:105E600002D8642C11D0B4E7752C02D0782C32D033 -:105E7000AFE70BF1040A05ACDBF800000A2112B110 -:105E80000022234613E0234620E00BF1040A05AC70 -:105E9000DBF8000072B1002806DA2D238DF81430EB -:105EA00040420DF1150300E023460A21002203F0D1 -:105EB00097FA0DE0002806DA2D238DF814304042C1 -:105EC0000DF1150300E023460A21002203F060FAD9 -:105ED000D34600941AE00BF1040303930DF1140A66 -:105EE000DBF80000102132B1583C62426241534657 -:105EF00003F076FA06E0B4F158035A425A41534689 -:105F000003F046FADDF80CB0CDF800A03046394673 -:105F100042464B4603F0A0FA5BE730469BF8001080 -:105F20000BF10404B8470AE0DBF800303046009378 -:105F30003946424600230BF1040403F08DFAA346D0 -:105F400047E730462146B84743E709B0BDE8F08F40 -:105F50000FB407B50A4904AB08680A4953F8042B83 -:105F600009680193FFF72EFF074B1868FFF7C9FC7C -:105F70000028F9D003B05DF804EB04B0704700BF0F -:105F8000D8060020D40600202C130020F8B50746C0 -:105F90000BF0E8FF044638B9194B1A485A791A4BE6 -:105FA000013A53F8221028E03846184922460BF0EF -:105FB000E1FF60B91648FFF75FFD164C54F8041F67 -:105FC00019B11548FFF7C4FFF8E7144805E00025AC -:105FD0000D4B53F8256026B91148BDE8F840FFF78E -:105FE0004BBD3846314622460BF0C4FF0135002830 -:105FF000EED1034B0B485D713146BDE8F840A7E791 -:106000003020002048640108FC4F01081A6E010886 -:106010005C640108F84F01086F6401083E680108DC -:10602000736401088864010870B504460BF09AFF98 -:1060300008B91E482EE020461D490CF00DF800243A -:106040002646254678B12CB1012C06D10BF0DFFF96 -:10605000064602E00BF0DBFF05461549002001343F -:106060000BF0FAFFEEE70B2D04D9BDE870401148A4 -:106070000C216DE7012C07DC0F4B294633F9152065 -:106080000E48BDE8704063E7A6F57A73B3F57A7FF2 -:1060900003D90B48BDE870405AE70A482946324602 -:1060A000FFF756FF044B23F8156070BD9A64010892 -:1060B000D8660108D4640108BC0F0020FA64010806 -:1060C00012650108346501082DE9F74304460BF019 -:1060D00049FFC0B290B9304C054694F8D711B4F8D6 -:1060E000D42194F8D6312D48009129460135FFF787 -:1060F0002FFF102D04F10404EFD14AE020460BF0ED -:1061000086FF0F28054636DC204620210BF01DFFB8 -:10611000234FEDB2D7F80090441CAD000026204676 -:106120000BF075FF5FFA86F8B8F1010F83B208D063 -:10613000B8F1020F0BD0B3F5B47F1ED23A685353B7 -:106140000AE0FF2B19D83B682B44987004E0FF2B22 -:1061500013D83B682B44D87020462C210BF0F5FE59 -:10616000044608B1441C02E0B8F1020F05D1013623 -:10617000032ED4D10DE00B4806E009EB0500002109 -:1061800004220BF0AEFE0848102103B0BDE8F04336 -:10619000DEE603B0BDE8F083302000204D65010845 -:1061A000240A00206165010885650108F0B5002317 -:1061B0001946CEB200220C2505FB02F70D48D4B2D9 -:1061C0003F5CB74203D00132042AF4D10BE0FF2C2C -:1061D00009D0094A05FB04001A4492F82C21074C07 -:1061E0000133A25C02720131052901D0032BE0D9F1 -:1061F000F0BD00BF68000020302000203C64010892 -:1062000010B54F20FFF7CCF90C4C84F82C0100207E -:10621000FFF7C6F94FF4E133C4F83031C4F8343134 -:10622000C4F83831C4F83C31522384F82D0184F885 -:106230002E0184F82F0184F8403110BD3020002059 -:1062400070B50546441E14F8011F61B1064E304674 -:106250000BF07BFE0028F6D0861B0448631B3044FD -:1062600080F81031EFE770BD646B0108302000202A -:1062700030B587B005460C4603A800210C220BF070 -:1062800030FE2846002108F0D3FF20B128462A49D5 -:1062900008F00AFD03E02846274908F003FD2749D6 -:1062A00008F00AFE08F0CEFF054685EAE570A0EB8F -:1062B000E57069460A2203F0BBF800239D42037093 -:1062C000ACBF20232D2368468DF80C300BF04AFE1E -:1062D000012807D130238DF80D308DF80E308DF860 -:1062E0000F300CE0022805D130238DF80D308DF8E9 -:1062F0000E3004E0032804BF30238DF80D306946CA -:1063000003A80BF015FE03A80BF02CFE0338C5B252 -:106310002A4603A920460BF04FFE00236355204672 -:1063200007490BF005FE03A9204629440BF000FEA7 -:10633000204607B030BD00BF6F12033A00007A4418 -:10634000936501082DE9F04389B004460BF00AFE7D -:10635000C6B2002E6CD18B48FFF78EFB8A4C2069A9 -:10636000002108F03DFF40BB013688483146FFF769 -:10637000EFFD206904A9FFF77BFF01468448FFF782 -:10638000E7FD606904A9FFF773FF01468048FFF746 -:10639000DFFDA06904A9FFF76BFF01467C48FFF70A -:1063A000D7FDE06904A9FFF763FF01467948FFF7CD -:1063B000CFFD0C2E04F11004D1D10025764C2F46D0 -:1063C0002B464FF00008B04504F1100415DA1846CA -:1063D00054F8101C08F068FC54F80C1C8146284640 -:1063E00008F062FC54F8081C0546384608F05CFCCE -:1063F00008F101084B460746E5E768480193029516 -:106400000397FFF739FB002401ABE058644920F003 -:10641000004008F00DFF634B634A0434002814BFAA -:1064200010461846FFF728FB0C2CEDD15F4891E091 -:1064300020465F4905220BF09DFD38B9524B0022E2 -:1064400003441030C0281A61F8D197E0204659491A -:1064500004220BF08FFD06462046002E40D120215D -:106460000BF073FD002800F08980451C28460BF0D6 -:1064700079FD34468046504B53F824600EB94F489E -:1064800068E0284631465FFA88F20BF073FD671C1E -:1064900020BB3D4B0021C2181030C02811619C4622 -:1064A000F7D1474B002403EBC702D2F804E098462B -:1064B000BEF1000F04D143483146FFF749FD55E0D6 -:1064C00018F837309C42F6DA23010CEB030510353F -:1064D00073440FCB013485E80F00F1E73C46CAE76F -:1064E0000BF095FD461E0B2E074643DC204620216F -:1064F0000BF02BFD054640B1451C284602F0B2FECC -:10650000214B3F01D851012400E0044628462021B8 -:106510000BF01BFD054640B1451C284602F0A2FECB -:10652000194B013403EB06135861284620210BF068 -:106530000CFD054640B1451C284602F093FE124B67 -:10654000013403EB06139861284620210BF0FDFC73 -:1065500018B91D48FFF790FA10E0013002F082FEF2 -:10656000094B032C03EB0616F061F2D11748FFF735 -:10657000E9FE03E016480C21FFF7EAFC09B0BDE88C -:10658000F08300BF9D65010830200020C865010828 -:10659000CE6501080868010844200020D265010882 -:1065A0000AD7233C99650108956501083E680108F2 -:1065B000E1650108E7650108FC4F01087364010803 -:1065C0001C460108EC650108FC6501080967010823 -:1065D000366601080A88F0B54B888F880E89CD8809 -:1065E000002A3AD1048C834A24F001042404240CA8 -:1065F0000484018B048C89B221F0F30141EA061670 -:10660000B6B29042A4B246EA070743F0010315D0A0 -:1066100002F50062904211D0B0F1804F0ED0A2F589 -:10662000983290420AD002F58062904206D002F57C -:106630008062904218BF24F00A0401D124F00204C1 -:10664000234307830384038B23F00C031B041B0CDD -:106650000383038B9BB21D4344E0042A44D1048C82 -:10666000644A24F010042404240C0484018B048C58 -:1066700021F440710905090D41EA063189B241EA68 -:1066800007279042A4B2BFB212D002F50062904236 -:106690000ED0B0F1804F0BD0A2F59832904207D0C7 -:1066A00002F58062904203D002F58062904207D1E9 -:1066B00024F0200444EA03139BB243F0100304E0E7 -:1066C00024F0A00443F01003234307830384038BC7 -:1066D00023F440631B041B0C0383038B9BB243EA2C -:1066E0000525ADB20583F0BD082A018C3ED121F409 -:1066F00080710904090C0184818B3E4A89B221F022 -:10670000F301048C41EA0616B6B29042A4B246EAFE -:10671000070712D002F5006290420ED0B0F1804F10 -:106720000BD0A2F59832904207D002F580629042D9 -:1067300003D002F58062904207D124F4007444EA49 -:1067400003239BB243F4807304E024F4206443F4F5 -:106750008073234387830384838B23F00C031B0400 -:106760001B0C8383838B9BB21D4341E021F480513A -:106770000904090C0184828B048C22F440721205F6 -:10678000120D42EA072242EA06361A4AA4B29042A1 -:10679000B6B212D002F5006290420ED0B0F1804F36 -:1067A0000BD0A2F59832904207D002F58062904259 -:1067B00003D002F58062904207D124F4005242EAED -:1067C000033292B242F4805205E047F6FF52224073 -:1067D00043F480531A4386830284838B23F44063FB -:1067E0001B041B0C8383838B9BB243EA0525ADB24C -:1067F0008583F0BD002C01401FB50123ADF80830A2 -:106800000023ADF80C30ADF80A30094BADF8041098 -:106810001B7801A9012B08BF0323ADF8062008BF90 -:10682000ADF80C30FFF7D6FE05B05DF804FB00BFF5 -:106830008807002038B510F80E2C044650F8043CA8 -:1068400052B9012200F80E2C20F80C1C197B186894 -:106850000222BDE83840CFE730F80C2C20F80A1CA3 -:10686000891A89B220F8081C074A10F80F0C002575 -:1068700022F8101004F80E5C1868197B2A46FFF7FE -:10688000BBFF04F8065C38BD441200201F4B10B556 -:106890005A6802F00C02042A03D0082A04D01C4AC9 -:1068A00014E01C4A126811E05A685968C2F3834226 -:1068B000C90302F1020201D4174906E0596811F434 -:1068C000003F1449096818BF49084A4302605968E3 -:1068D000124AC1F30311545C0168E14041605C68F5 -:1068E000C4F30224145D21FA04F484605C68C4F3E8 -:1068F000C224145DE140C1605B68C3F381331A4474 -:10690000137CB1FBF3F1016110BD00BF0010024028 -:1069100000127A002400002000093D0050000020F1 -:10692000024B1A6922EA0000186170470010024009 -:10693000954B2DE9F74F1B78013B012B00F220818D -:10694000924B1E78864240F01B81914B1B78022BA4 -:1069500000F016818F4B904D13F806808F4B83F813 -:1069600000808F4B1A7801921AB18E4B33F91600C2 -:1069700007E08C4A2B6832F9160003F100432B60C4 -:10698000404208F045FA884908F04AFBDFF838A28F -:106990000446DAF800B00021584608F021FC002730 -:1069A000DFF82C92002859D0D9F800B0204659467B -:1069B00008F03EFC68B17D4B2A687B491A60C9F833 -:1069C0000040204608F078FA08F03CFC784BD8806C -:1069D000BDE05846394608F02BFC002800F0B7808F -:1069E000744B1A78002A31D12046296808F05AF9E8 -:1069F0004FF07E5108F0FEFB6F4C28B160686F4984 -:106A000008F05AFA60600FE06D49606808F054FAC7 -:106A1000DFF8CCA18346514608F0ECFB10B9C4F86E -:106A200004B001E0C4F804A0624A01231370654B6E -:106A300000221B68C9F8007043449A72019A82F0E0 -:106A40000103574A1370604B1F6080E05F4BCAF828 -:106A500000401A68554BFA325A6078E02046594691 -:106A600008F0C8FB48B1584A4F491460204608F066 -:106A700023FA08F0E7FB4E4BD880534BD9F800902F -:106A8000D3F800A04846514608F00CF94F4B834616 -:106A90001968464B5A688A1A002A0BDA4FF07E5161 -:106AA00008F0C6FB002852D02046514608F0C0FB33 -:106AB00000284CD03D4A4846116808F0B9FB3E4CCE -:106AC00038B120683E4908F0F7F93C492060A068D9 -:106AD00007E058464FF0804108F0AAFB28B1A068B3 -:106AE000374908F0E9F9A06004E02068334908F06C -:106AF000E3F92060334B2C492068D3F8009008F06C -:106B0000DBF908F0C5FB09F80800A06808F0C0FB35 -:106B1000019AC84482F00103214A88F814001370D6 -:106B2000294B1F602A4B1F60224B1A780132D2B2C8 -:106B3000032A01D01A700AE000221A701E4B254960 -:106B4000586808F0B9F908F0A3FB88F80A001EB9E4 -:106B5000174B1A8864321A80114A13780BB11E4BF6 -:106B600000E01E4B2B600F4B33F9160008F050F974 -:106B70000D4908F055FA0146286808F093F800E03E -:106B8000084603B0BDE8F08F04050020580500203A -:106B900068050020604501080805002069050020FF -:106BA00059050020A8030020000020415C120020AD -:106BB000861800205A0500206C0500200AD7833F64 -:106BC000EC51783F640500205C0500202C2000205B -:106BD0006005002000007A440000A0410000A0C130 -:106BE0006F12833A10B50848FEF746FF074B1C6842 -:106BF0002046FEF786FE18B90A20FEF724FEF7E7C6 -:106C0000034A044BDA6010BD5E660108D81B002001 -:106C10000400FA0500ED00E008B50748FEF72CFF78 -:106C2000064A002313729363054A137006F0E0FCD2 -:106C3000BDE80840FFF7D6BF6A6601085C12002075 -:106C4000D427002008B50448FEF716FF04F050FED4 -:106C5000BDE80840FFF7C6BF966601082DE9F04F72 -:106C6000002487B007460491924605938046254646 -:106C7000022DDFF888914FEA450607D10498437941 -:106C8000B9F904001B3343435B1148E0524B39F917 -:106C9000151033F9153003EB4101CAF10003994295 -:106CA00003DB5145B4BF0B4653464C49059A31F9B5 -:106CB00006B0915FCBEB030303EB010B02F0C0FACC -:106CC00098B1474B58465B5D039308F0A1F84549DE -:106CD00008F0A6F9039B01461846FFF729FE414933 -:106CE00008F0EAF808F0AEFA83463F4B1988C80767 -:106CF00011D404988A07037939F9060003F11B03BC -:106D000000FB03F34FEA231309D57A7C02FB0BFB4C -:106D100003EB2B2303E0FB7903FB0BF31B11334A3B -:106D200098F80AB0905F042290FBF2F0181A7B5D8D -:106D30002F4A4343DB1101932E4B01351988A35889 -:106D400001FB00FC4FEAEC2C0BFB0C33DFF8B0C06E -:106D5000B3F5001FA8BF4FF400136345B8BF6346E7 -:106D6000A3504FEA633C244B0909E258E050821AD1 -:106D70004FF6FF70B0FBF1F14A4303F10C0003F151 -:106D8000180B215854F80B90921189442250CDF8D9 -:106D90000890914498F8142044F80B1002FB09F174 -:106DA00001980912084403F12402604490530198A9 -:106DB00003F12C02A050032D03F1380203F1440328 -:106DC00044F802C0E15008F1010804F104047FF422 -:106DD0004FAF07B0BDE8F08FDC270020A8030020EC -:106DE0008E4E01080000204154020020F4040020CF -:106DF000B80E0020FC04002098120020620200203F -:106E00000000E0FF2DE9F04F89B00793994B0692FF -:106E1000B3F90220B3F90030002AB8BF5242002B68 -:106E2000B8BF5B4200249A42B8BF1A46039005924D -:106E30002646A04627460494A3462546DFF86092DE -:106E4000B9F8003099075AD0022D58D0894BDDF897 -:106E500018C0F25E884BF35E03EB4202CCF10003F4 -:106E60009A4203DB63469A42B8BF1346834ADDF871 -:106E70001CC036F902A03CF90620CAEB030303EB61 -:106E8000020A02F0DDF990B17D4B504615F803B0CF -:106E900007F0BEFF7B4908F0C3F801465846FFF7EC -:106EA00047FD784908F008F808F0CCF982460398C5 -:106EB0006423C2796FF0040102FB0AF292FBF3F241 -:106EC000C37E01FB03FB5A4505DB03EB83039A42B8 -:106ED000B4BF93469B466C4A42F21071A358534488 -:106EE0008B42A8BF0B4669498B42B8BF0B4603993A -:106EF000A35091F811A00AFB03F31B130493B9F8F4 -:106F0000003003F00302012A01D1022D3DD1594A7C -:106F10005F49B75E895F039A81EAE170A0EBE17097 -:106F200012F805C05B4AB0F5206F54F802801DDCF2 -:106F3000022D15D05020784390FBFCFC042091FBDF -:106F4000F0F1C1EB0C0CE0445348B8F57A5FA8BFF0 -:106F50004FF47A588045ACBF42F80480105107E0E6 -:106F600087EAE770A0EBE7706428E3DD00211151A8 -:106F7000484AA1587D2291FBF2F8039A2A44927A5A -:106F800002FB08F8402298FBF2F89A0716D5022D6A -:106F900014D0059BDDF814C0C3F5FA720CFB08F0A1 -:106FA0007B43DDF810C002FB0B3302FB0C024FF4F5 -:106FB000FA7193FBF1F392FBF1F208E0DB0701D5E4 -:106FC000022D02D142463B4601E0049A5B4630491D -:106FD000DFF8D0A0715A4FF0040C0FFA81F915F8C0 -:106FE0000AA099FBFCF00AFB00F06FF04F0A90FB3F -:106FF000FAF01844294B019036F903A0F152CAEB7C -:10700000090999FBFCF903F1140A03F1080C54F87F -:107010000C0054F80A1044F80C90DFF88CC00144BE -:1070200015F80CC0494402910CFB01F14FF0200C03 -:1070300091FBFCF144F80A000198C1EB0209A3F1AD -:107040002C0C814426F80C900135A3F1240C44F853 -:107050000C004942A3F11800032DA3F10C032250A8 -:10706000E15006F1020604F104047FF4E7AE09B032 -:10707000BDE8F08F62020020DC270020A80300207A -:107080008E4E010800002041180E0020F0D8FFFFAE -:10709000F4040020B80E002080C1FFFFE812002099 -:1070A00054020020DE0E0020E40E00202DE9F04FF7 -:1070B00089B007937A4B814618880491059207F0AE -:1070C000A3FE784907F0F8FE002403904F462546BA -:1070D0002646022EDFF80CA20BD10499BAF904005F -:1070E0004B790A33584307F093FE6F4907F098FF36 -:1070F00044E06E4B3AF90520EB5E05991A444B4289 -:107100009A4203DB0B469A42B8BF1346684AAA5E0E -:107110009B1A079A505F184407F07AFE654907F0FA -:107120007FFF804602F08CF828B1634B4146985DA2 -:10713000FFF7FEFB8046614B1A88D10705D5404614 -:10714000D9F8441007F0B8FE18E004993AF90500A0 -:107150000B7901921433584307F05AFE524907F055 -:107160005FFF019A8346930709D5D9F84810404636 -:1071700007F0A2FE0146584607F096FD8346504AA6 -:10718000505F07F045FE4F4AD16807F095FE8246F2 -:107190005146584607F086FD396A804607F08CFE56 -:1071A000DFF844B106900399404607F085FEF96A7E -:1071B00007F082FE54F80B1007F076FD4249804636 -:1071C00008F018F838B94046404908F031F820B1C5 -:1071D000DFF8F88001E0DFF8F0804BF80480DFF89A -:1071E0000CB1504654F80B1007F05CFD44F80BA0AE -:1071F000034603994FF07E50029307F011FF029B64 -:107200000146184607F058FE0BF10C03E2580BF14B -:10721000180B54F80B10824610460192029307F0A7 -:1072200043FD514607F040FD019A029B44F80B20B4 -:1072300044F803A0264907F0F3FEB96B07F03CFEC3 -:107240002449824607F0D6FF38B95046224907F054 -:10725000EFFF20B1DFF880A001E0DFF878A006980A -:10726000414607F021FD514607F01CFD0BF09EF84A -:107270001A4BB0F57A7FA8BF4FF47A709842B8BF26 -:1072800018460136164B032EE85204F1040405F1AA -:10729000020507F104077FF41CAF09B0BDE8F08FC9 -:1072A000FC040020BD37863500004842DC27002062 -:1072B000A8030020000020418E4E01085402002047 -:1072C000F4040020EC03002000007AC300007A439D -:1072D00000004040000096C30000964318FCFFFFEA -:1072E000BC12002062020020C40E002008130020FF -:1072F0002DE9F047734A86B013789146DFF8D881BC -:10730000C3B90122D8F8001089F800206E4A1A4447 -:107310005068884203D00C33302BF7D1002202236F -:1073200053726A4B6A48C3F8D010FEF7A5FB694850 -:10733000FEF7A2FBD8F80000FEF7F2FA002800F0F2 -:10734000BE80654B614C1868FEF7E5FA09280146D6 -:1073500001D03F284FD14FF0000AA56B5F4F564632 -:107360002DB15F4839682A460AF004FE10B9BA46C2 -:1073700006B93E465B4B0C379F42F1D3CEB137681E -:10738000DAF800E02B46F85C1EF80310814201D0C9 -:10739000A3630EE05A1C41B92D2B06D8A2632344E7 -:1073A000202022441872117203E04D4958541346AC -:1073B000E9E7A36B0BB1564512D04B48FEF75CFBD7 -:1073C000564509D856F80C0BFEF756FBD8F80000C6 -:1073D0000921FEF7B7FAF3E73E48FEF74DFB00251B -:1073E000A36B9D42A6D23E4BD8F80000595DFEF734 -:1073F000A9FA0135F4E7A36B33B904283BD104F1B2 -:107400000800FFF709FC5AE00C2801D137488CE747 -:107410000A2901D00D2949D13548FEF72DFBA36B70 -:10742000E21800231372227A232A17D00493314BD7 -:107430002B4E009303A8294915220C2303960AF02A -:10744000EAFD054638B100680AF08CFD0130AB68F2 -:107450003044984702E02848FEF70EFB2048002100 -:1074600030220AF03EFD0023A36399F80030002B80 -:107470007FF45DAF23E00C28C8D07F2903D159E702 -:107480002F2B3FF657AFA1F12002D2B25E2A3FF672 -:1074900051AF13B920293FF44DAF5A1CA263D8F85D -:1074A00000001C442172FEF74DFA43E77F29E7D123 -:1074B000013BA363002223441A72104838E706B048 -:1074C000BDE8F087D4270020680000205C1200206F -:1074D0009D660108D5660108D81B002030530108BD -:1074E000641200202C540108DA660108DF660108E6 -:1074F0003E68010809510008EA66010806670108AC -:107500002DE9F04FD84AD94C85B01068516802ABCC -:1075100003C3DFF8908300214FF4EF6220460AF0A6 -:10752000E0FC04F50573C8F80030D14B0025DFF806 -:1075300078A31D7004F25673CAF8003003236371F8 -:107540000223A36040F24C404FF41673A4F8F030CD -:10755000A4F81C01FA2340F26C70A4F8F230A4F8ED -:107560001E012A231920A4F8EE3084F825014FF4D7 -:10757000FA7340F27E40A4F8F630A4F8D00020233D -:1075800040F23A7084F8F430A4F8D2006E234FF43D -:107590007A7084F80431A4F8D4002B2340F27E5092 -:1075A00084F80531A4F8D600212340F2EA500126E0 -:1075B000552240F2DC514FF01E0B4FF0320984F897 -:1075C0000631A4F8D8004FF4C87340F2B4502270CA -:1075D000A4F80831A4F81A11A4F8DA00A4F8DE30EF -:1075E00084F8EC6084F821B184F8246184F8276180 -:1075F000A4F8DC90A4F8E0908DE80600FEF700FE09 -:1076000040F6AC53A381D8F8003028271720A57383 -:1076100018761F7183F80EB05F7183F80FB058763B -:107620001D700B20019A1872142058721875502082 -:1076300098776420D8774FF0080E782083F813E00D -:107640005873DFF868C28B484FF00E0E9A7183F8BA -:107650000AE02D224FF05A0E4FF00A0B1A745A7797 -:1076600083F80BE01F73DA7583F821609D7683F849 -:1076700007905D74DD769D741D7783F815B0C3F8AF -:1076800024C0D86318644FF08240D8624FF07C5019 -:1076900098637948C3F828C05864784A7848DFF876 -:1076A00010C200991A635A639864C3F84CC084F8F6 -:1076B00056E74FF0410EA4F85E1784F857E784F8B8 -:1076C0005A5784F85B5784F8589784F8595784F8C8 -:1076D0005C579A666B4A0421DA666B4A83F8581045 -:1076E0001521D86583F8607083F861701A6783F894 -:1076F0007460A3F85450A3F85650A3F8525083F87E -:1077000064106248FEF79CFDD8F800304FF44872D0 -:10771000A3F86221C82283F8A7214FF49662A3F848 -:10772000A82140F2D932A3F8AA2140F6430283F8F7 -:107730005F7183F86061A3F8AC2183F85D5183F831 -:107740005E5183F8645183F8A6B11A4647465646FF -:107750004FF47F71A2F866114FF4FA61A2F8681134 -:1077600002A840F2DC51A2F86A11415D013582F8AD -:107770006C11082D4FF0FF0182F86D1102F1080223 -:10778000E6D1012283F8AE2183F8AF2183F8B0213E -:10779000C82183F8B6216422A3F8B211A3F8B82156 -:1077A00014214FF4967283F8B411A3F8BA211E2164 -:1077B000282283F8B511A3F8BC210023E218103366 -:1077C0000021C02B1161F9D13148002140220AF07B -:1077D00088FB00232F49E218595804330868382BD6 -:1077E000C2F8D401F6D12C48002180220AF079FB9E -:1077F0002A4B294D03F1300E186859682A4603C2F6 -:10780000083373451546F7D1254D01F0CDFE01F043 -:1078100007FF01F0E1FE3F68284639464FF4E07269 -:107820000AF056FB394605F5E0704FF4E0720AF0B5 -:107830004FFB336805F563725968186803C21989EC -:1078400011801A68C5F896235A68C5F89A231B89CF -:10785000A5F89E33012384F82434022384F8E43508 -:1078600005B0BDE8F08F00BF904E01083020002029 -:10787000140E00208FC2753DCDCC4C3D9A99193F16 -:107880000000A040F6287C3F3D0A773F0A670108C8 -:1078900004220020B445010884210020984E0108EC -:1078A00004240020E80300208C0500200000204074 -:1078B0000000404008B50548FEF7DEF8FFF720FE5F -:1078C00004F016F8BDE80840FFF78CB9136701080B -:1078D00010B50A4C23681BB105F006FC0023236099 -:1078E000074B1B7813B1012B03D010BD4FF400627E -:1078F00001E04FF48052034B1A8010BD4007002076 -:1079000045070020000000202DE9F04F012828BF86 -:107910000120142101FB00F389B0DFF8BCB1019014 -:107920000BEB03025BF803706548019B654E076033 -:10793000F469037110691589B2F80A9020435468FC -:1079400049EA0508F0610222C4F8108020468DF84B -:107950000E1003A9ADF80C808DF80F2001F0DAFFAE -:107960004FF0080AA268154203D10A20FDF760FF14 -:10797000F8E70A206561FDF75BFF25610A20FDF746 -:1079800057FFBAF1010AEDD10A20C4F81490FDF7AF -:107990004FFF0A206561FDF74BFF0A202561FDF7C7 -:1079A00047FF0222C4F8109020468DF80F2003A94B -:1079B0001C228DF80E20ADF80C8001F0ABFF424A7E -:1079C0009742326905D142F4001232614FF400103F -:1079D00004E042F4800232614FF48000FEF7A0FF21 -:1079E000BA8803A822F440721204120CBA803A88B2 -:1079F000012592B242F001023A80BC88FEF746FFB0 -:107A000024F03F04059831492404B0FBF1F1240C23 -:107A10000C43A4B2BC803A88142322F00102120461 -:107A2000120C3A802A4A0024B0FBF2F24FF496700E -:107A3000414392B24FF47A70002A91FBF0F108BFF3 -:107A40000122013142F4004289B23984BA833A8872 -:107A500003A892B242F001023A803A8822F481628D -:107A600022F002021204120C3A804FF480423A8152 -:107A7000019A8DF80D4003FB02B77B7B8DF80E4019 -:107A80008DF80C308DF80F5003F09AF83B7B9DF881 -:107A90000F208DF80C308DF80D408DF80E401AB186 -:107AA00003A803F08DF807E0590903F01F039D4078 -:107AB000084A203142F8215009B0BDE8F08F00BFDC -:107AC00030130020001002400054004040420F00DC -:107AD000804F120000E100E0C84E010808B5054BD8 -:107AE0001A88013292B21A80034B1879FFF70CFF03 -:107AF000002008BD3C1800203013002013B51E4B99 -:107B00004000C0B2587102AC1868997104F8012D98 -:107B100000210122DA71DC6019721C611A755A7534 -:107B2000997538B38288920515D40288D4050DD48E -:107B300047F230520188890502D5013AFAD112E0A4 -:107B40008AB1028892B242F480720280828892B234 -:107B500042F44072828047F23052597D11B1013AAD -:107B6000FBD100E012B9FFF7B9FF03E0024B987DAB -:107B700080F0010002B010BD301300200246402109 -:107B80003C20BBE7024680213C20B7E708B55038CF -:107B9000C0B2FFF7F7FF0020FFF7F4FFBDE8084091 -:107BA0001020EFE7772048210122A7E7772058210E -:107BB0000122A3E7064B002193F82020054B9201F8 -:107BC000343219707720F42102F0FC0296E700BFEE -:107BD0005C07002018200020034B00221A70772039 -:107BE000F4212E228AE700BF1820002010B5174C80 -:107BF00023681BB105F078FA002323606B218022F3 -:107C00006820FFF77BFF6420FDF71DFE192100228D -:107C10006820FFF773FF6B2103226820FFF76EFFD8 -:107C2000372102226820FFF769FF094B1A211A78D1 -:107C30006820FFF763FF1B2118226820FFF75EFF13 -:107C4000BDE8104068201C21102257E740070020A3 -:107C50003900002008B51920FDF7F5FD6820152131 -:107C60000022FFF74BFF10B90320FDF723FE0C4B5A -:107C700016211A78682042F01802FFF73FFF1721FB -:107C800000226820FFF73AFF3D2101226820FFF71C -:107C900035FFBDE8084068203E2101222EE700BFE5 -:107CA0003A00002013B500222A211C20FFF726FFEE -:107CB0000E2102221C20FFF721FF0F2103221C208E -:107CC000FFF71CFF2B2112221C20FFF717FF164B7A -:107CD00002249A69154842F004029A612023ADF803 -:107CE000043004230DEB03018DF806308DF80740B6 -:107CF00001F010FE22462C211C20FFF7FFFE2D2153 -:107D000001221C20FFF7FAFE2E2100221C20FFF783 -:107D1000F5FE2A2105221C20FFF7F0FE044B4FF44C -:107D200080721A8002B010BD0010024000080140AD -:107D30000000002008B50F2108221820FFF7DEFE02 -:107D40000E2218201021FFF7D9FE024B4FF480526B -:107D50001A8008BD0000002008B5134B53201B7883 -:107D60002D2108227BB1FFF7C9FE31210A225320C1 -:107D7000FFF7C4FE2C210C225320FFF7BFFE532037 -:107D80003821902209E0FFF7B9FE31210A22532061 -:107D9000FFF7B4FE53202C210A22FFF7AFFE034B5E -:107DA00040F209121A8008BD44070020000000209C -:107DB00010B540001C4CC0B26071A17101200021BF -:107DC000E17120722275607520682361E360A175FE -:107DD00040B383889B0515D40388D9050DD447F299 -:107DE00030530288920502D5013BFAD112E08BB1E3 -:107DF00003889BB243F48073038083889BB243F46F -:107E00004073838047F23053627D12B1013BFBD156 -:107E100000E01BB9BDE81040FFF760BE024B987D43 -:107E200080F0010010BD00BF3013002037B50622DE -:107E3000044603216B461E20FFF7BAFF9DF8013070 -:107E40009DF80000154D43EA002000B206F0E0FF67 -:107E5000296807F031F807F0F5F99DF80330208024 -:107E60009DF8020043EA002000B206F0D1FFA968A5 -:107E700007F022F807F0E6F99DF80530A0809DF89C -:107E8000040043EA002000B206F0C2FF696807F070 -:107E900013F807F0D7F9608003B030BD3C00002034 -:107EA00007B5002101AB03227720FFF781FF9DF882 -:107EB00005009DF80430000240EA03409DF80630BA -:107EC000184303B05DF804FB08B5FFF7E9FF014B69 -:107ED000986108BD3013002008B5FFF7E1FF014BA2 -:107EE000D86108BD30130020104B13B51B78104C1F -:107EF00013B9238C0133238401ABF62103227720AD -:107F0000FFF756FF9DF805309DF804201B0243EA59 -:107F100002439DF806201343064AB2F92020C2F11D -:107F20000802D340636202B010BD00BF18200020D9 -:107F3000301300205C0700200B4B13B51B780B4C53 -:107F400013B9238C0133238401ABF621022277205D -:107F5000FFF72EFF9DF804209DF8053043EA022329 -:107F6000238502B010BD00BF182000203013002070 -:107F700013B5062204466B463B216820FFF718FF25 -:107F80009DF800209DF8013043EA022323809DF8EC -:107F900002209DF8033043EA022363809DF8042009 -:107FA0009DF8053043EA0223A38002B010BD13B54B -:107FB000062204466B4643216820FFF7F9FE9DF830 -:107FC00000209DF8013043EA022323809DF802201F -:107FD0009DF8033043EA022363809DF804209DF856 -:107FE000053043EA0223A38002B010BD07B5232069 -:107FF000FDF729FC6820752101220DF10703FFF729 -:10800000D7FE28B19DF80700B0F1680358425841E7 -:1080100003B05DF804FB13B50222044601AB1B213B -:108020006820FFF7C5FE9DF804209DF8053043EA5F -:10803000022303F54E534FF48C72103393FBF2F38B -:108040002333238002B010BD13B5062204466B46CD -:108050001D216820FFF7ACFE9DF800209DF801303F -:1080600043EA022323809DF802209DF8033043EA6F -:10807000022363809DF804209DF8053043EA022323 -:10808000A38002B010BD13B5062204466B46012141 -:108090001C20FFF78DFE9DF801309DF800209DF813 -:1080A000021043EA022242F38D02042392FBF3F210 -:1080B00022809DF8032042EA012242F38D0292FBC6 -:1080C000F3F262809DF804109DF8052042EA012237 -:1080D00042F38D0292FBF3F3A38002B010BD13B5FF -:1080E000062204466B4602211820FFF761FE9DF828 -:1080F00000309DF801209B0803EB022323809DF8AC -:1081000002309DF803209B0803EB022363809DF857 -:1081100004309DF805209B0803EB0223A38002B0E6 -:1081200010BD2F4B2DE9F3411B780546002B39D0AC -:10813000002426462746A04608226B4653203221BB -:10814000FFF736FE9DF801209DF80030013403EB67 -:1081500002231BB29DF8032098449DF80230E4B23C -:1081600003EB02231BB21F449DF805209DF8043049 -:10817000202C03EB02231BB21E449DF8073003F0B2 -:108180007F0301D0002BD7D1164B98FBF4F897FB57 -:10819000F4F796FBF4F6A5F800806F80AE8083F8C4 -:1081A0002A401AE006226B4653203221FFF700FED8 -:1081B0009DF801209DF8003003EB02232B809DF8F1 -:1081C00003209DF8023003EB02236B809DF805200D -:1081D0009DF8043003EB0223AB8002B0BDE8F081D0 -:1081E000440700203013002013B5224C23689A8ADC -:1081F00092B20192019A12F4706F1CBF0122A27513 -:10820000019A12F4E06F29D01A8B9A8822F48062C6 -:108210001204120C9A80019A91051FD41A889205B3 -:108220001CD41A88D0050ED51A88D105FCD41A881A -:1082300092B242F400721A801A889205FCD4207916 -:10824000FFF762FB0AE01A8892B242F400721A80C9 -:108250009A8822F440721204120C9A802268938A3F -:1082600023F470631B041B0C93820023637502B01C -:1082700010BD00BF301300200B4B07B59A690B48A7 -:1082800042F010029A614FF40053ADF8043002231B -:108290008DF8073001A910238DF8063001F03AFB64 -:1082A00003B05DF804FB00BF001002400010014065 -:1082B00010B50446204609F055FE10F0FF0F06D118 -:1082C0000C4B0D481978BDE81040FDF741BE204623 -:1082D00009F09DFE02280CD8064B0A221870074BA5 -:1082E000074C02FB0030074B06301860FDF7C4F95D -:1082F000E0E710BD140E0020296701088027002048 -:10830000096701088C0500201FB50123ADF808306E -:10831000ADF80410002301A9ADF80A30ADF80C3017 -:10832000ADF80620FEF756F905B05DF804FB10B570 -:10833000A0F5127494F83C22C2B9A36A616A99420A -:1083400029D0591CA069A162C05C2369C0B29942BE -:108350004FEA400343F40073A4F83E324FF00A039F -:1083600084F83D3228BFA262012312E094F93D3225 -:108370007BB1B4F83E1220464B08A4F83E3201F01F -:10838000010101F0ACFA94F83D32013B84F83D3232 -:1083900001E084F83C3294F83832002B4FD194F845 -:1083A00039320133DBB2092B84F8393204D120464B -:1083B000BDE8104001F07EBA0A2B40D194F83B3260 -:1083C0002BB9B4F8403243F00103A4F8403263798A -:1083D000D9071CD5B4F84002820501D4C30705D4DF -:1083E000B4F844320133A4F8443210E0E36AC0F335 -:1083F00047000BB198470AE0E3696269D054E2692B -:10840000E3680132B2FBF3F103FB1123E3610122C4 -:1084100084F8382294F83B220023012A84F8393268 -:108420000DD1A27984F83B32236B012A1868197B9D -:1084300014BF02220022BDE81040FFF765BF10BD47 -:1084400010B5A0F513746379DB074CD594F8383276 -:1084500013B3236B1868828DC2F34E02828494F8A2 -:108460003C2222B1B4F842220132A4F84222A2797D -:10847000197B012A0CBF02220022FFF745FF0123CE -:1084800084F83B32002384F8393284F83A3284F895 -:108490003832A4F8403210BD94F83B322046012B0C -:1084A00004BF94F8393284F83A3201F003FA94F8B0 -:1084B0003B12236BA27949B9012184F83B128A420D -:1084C0001868197B0CBF0222002208E0002184F802 -:1084D0003B12012A1868197B14BF02220022BDE852 -:1084E0001040FFF711BF10BD426A10B58469A15456 -:1084F000416A02690131B1FBF2F402FB14124262DB -:10850000426B32B11368DB0708D4BDE8104002F0BB -:10851000EFBA036DDA6842F08002DA6010BD2DE92F -:10852000F84FFDF7B7F88B4E8B4A33680546C31AF0 -:10853000934240F29580894B8949002209789A70CC -:108540001A71DA775A75874A9977197511680A226C -:1085500091FBF2F11977091259778349096891FB68 -:10856000F2F283F82020121283F821207F4B804AF8 -:108570001978804B91761B7813F0020F134602D1C5 -:108580002D23D3766BE004298CBF33223222DA7696 -:10859000794A7A4C1768DFF8089297FBF4FC09FBDC -:1085A0000C7A4FF0060808FB0AFA5068744A0CEB84 -:1085B0008C0C9AFBF2FB02FB1BAA0CEB8C0C4FFA07 -:1085C0008BFB0BEB8C0C1FFA8CFC90FBF4F483F808 -:1085D0000AC04FEA1C2C83F80BC009FB040C08FBF3 -:1085E0000CFCFF0F5F729CFBF2F702FB17C26421C9 -:1085F00092FBF1F25A7412129A74624AC00F1288F6 -:108600009873242042439AFBF1FA92FBF1F15E4AFF -:10861000D9711288C1F30721DA74120A1A755B4AFC -:10862000197211880A22B1FBF2F202F5FA7292B2C3 -:1086300004EB84045A75120A7FB204EB84049A7521 -:10864000534A07EB8404A4B2128883F80CA0DC73AD -:108650004FEA2A2A240A83F80DA01C741A77356081 -:108660003379DFF8F0804BB94A4C2068FDF758F9B0 -:10867000494B1B78002B44D1012848D8F068354C71 -:10868000002865D027793FB1236940F6B732EB1A4D -:1086900093420AD8BDE8F88F012323713D4B022194 -:1086A0001868FDF729F9277528E0637D394A43B931 -:1086B00010680121E3602371FDF71EF9FDF735F91C -:1086C0001CE0013BDBB26375217D94F816E03BB9F9 -:1086D0004B1C0EF1010E237584F816E010680BE0B8 -:1086E000034613F8017B0EF1010E39441068217521 -:1086F000E36084F816E03946FDF724F93561BDE8FA -:10870000F88F0028BAD02068FDF705F91DE002288F -:10871000224F03D0FDF709F9012303E03A781AB19B -:10872000C8F808503B70A9E7D8F80830EB1AB3F541 -:108730007A6FA3D3012320683B70FDF7ECF807465E -:108740002068FDF7E8F8802F98D103F071F995E7DC -:10875000BDE8F88F5C1300203F0D0300580D00208A -:10876000B4050020B8050020BC050020C405002089 -:10877000840D002082020020D00500208096980001 -:1087800040420F00C005002040180020C205002014 -:1087900042180020E41B0020F01B00206400002091 -:1087A000806967FFF7B50368174C184D23600B68A5 -:1087B000174E6360006800F09DFF95E80300154BBD -:1087C0000196009394E80C0000F052FF3668124BBB -:1087D00060681E606B68114FC01A06F019FB104BE1 -:1087E000196806F069FB06F02DFD22682B68786099 -:1087F000D31A3B600B4B1E600B4B1B68DA880B4B8C -:108800001A8003B0F0BD00BF48110020D005002041 -:108810005411002050110020901100205811002008 -:108820004C00002088110020200A00208411002024 -:108830002DE9F043142285B0814688461B4800216B -:1088400009F04FFB03261A4B0027B74224DA13F82E -:10885000042C0021C8B2013112B1501E0240F9E7C8 -:108860001C7AD1B2013214B1611E0C40F9E7421AF0 -:10887000002A0EDD01ACA3F10C0595E8070084E8A1 -:10888000070093E8070085E8070094E8070083E8FD -:10889000070001370C33D8E7013ED4D1034A4846DC -:1088A000414605B0BDE8F04304F044BE7413002017 -:1088B000740000200022064B13445968814203D003 -:1088C0000C32302AF7D1002300225A725A607047C6 -:1088D0006800002038B50E4D04462B68834207D14E -:1088E0000121FFF7E7FF284600214C2209F0F9FAA1 -:1088F000EB6CA3420AD120460121FFF7DBFFBDE864 -:108900003840044800214C2209F0EBBA38BD00BFC2 -:10891000200F00206C0F002010B50023054A1A44D8 -:108920005468844203D00C33302BF7D100225172AB -:1089300010BD00BF680000202DE9F34706461F4622 -:108940004FF41473734347489246C41880460EB9D7 -:10895000454A02E0012E04D1444A22631032C4F891 -:108960003421434A0025C250032363714FF48073BE -:108970004FF00109E3602361D4F8343184F83C52AC -:1089800084F8389284F8395284F84662586804F1C1 -:1089900034029B68626104F59C72A261E162256207 -:1089A000E561A5626562A4F84252A4F84452ADF8AC -:1089B00004300225102301A9C4F808A0A7718DF87E -:1089C00006308DF8075000F0A5FF236B01A9586809 -:1089D0009B688DF80750ADF8043048238DF80630B9 -:1089E00000F098FF4946204600F079FF3220FCF75E -:1089F0002AFF204BD4F834911B681D46B5FBFAF1D1 -:108A0000B1F5803F03D3012DF8D96D08F6E71A4A76 -:108A10004846B3FBF2F289B2D2B203F093F84FF4B6 -:108A200014735E43154B06F5127608EB060548F8FD -:108A3000063048462946002201F08EFF266B012FA2 -:108A400014BF022200223068317BFFF75DFC0C4B23 -:108A500030466B60291D002201F07EFF204602B0E7 -:108A6000BDE8F08788130020D4610108F461010893 -:108A7000F04E0108A800002040420F002F8300089C -:108A80004184000803460A4690F84602D96A9B7959 -:108A900052E7F8B5002207463749130101F11800E3 -:108AA000185CB84204D00132082AF5D10020F8BD84 -:108AB000324E0B44183306F2CC45082F0FCB344608 -:108AC00085E80F001BD009D8022F0ED0042F16D036 -:108AD000012F4FD12A4B1B685B6847E0202F42D003 -:108AE000402F06D0102F45D122E0254B1B689B68F4 -:108AF00002E0234B1B681B69C6F8D03436E0214BDB -:108B00001B681B7853B1013B012B0AD900F032FDE1 -:108B1000002814BF4FF46143002304E04FF41653C0 -:108B200001E04FF49643C4F8D034C4F8D43421E0C3 -:108B3000154B1B681B7A042B1CD8DFE803F00A0ACC -:108B4000030A0A00114BC6F8D034C6F8D434032304 -:108B500006E04FF4E133C6F8D034C6F8D43401232C -:108B600084F8D93406E0064B1B68DB68C6F8D434B9 -:108B70002846F8BD0648F8BDF04E01085C130020F9 -:108B8000B80F0020A00500203C010020A0860100B5 -:108B90002818002010B50446FFF77BFF0146204649 -:108BA000FFF746FE4368187A10F0010018BF5868B6 -:108BB00010BD38B505460C46FFF76BFF0146284649 -:108BC000FFF736FE28B143681B7A1C420CBF002019 -:108BD000012038BD38B50B4B05469B685A050ED5AC -:108BE00000F0C8FC044650B10820E9B2FFF7E1FFED -:108BF00030B1054B1C78231F5C425C4100E001242E -:108C0000204638BD30200020E8050020032810B59C -:108C10000F4B0DD80F4A126894888C4208D2D28824 -:108C20008A4205D9012202FA00F01A78104318701E -:108C30001B780F2B0BD1064B00221A70064B99881C -:108C400008B2142802DD1439998010BD9A8010BD35 -:108C50003818002028200020C8090020024B9A88DC -:108C600001329A80704700BFC8090020074B1A687C -:108C7000074B1178B3F9040053780B4403EB8303DB -:108C80009842D4BF00200120704700BF2820002058 -:108C9000C8090020064BB3F90400064B1B681B787B -:108CA00003EB83039842D4BF00200120704700BF2C -:108CB000C80900202820002010B50446FFF7EAFF6D -:108CC000002814BF2046002000F0010010BD024B18 -:108CD00001221A72704700BFC8090020014B187AA0 -:108CE000704700BFC8090020034BB3F90400D0F15E -:108CF000010038BF00207047C8090020014B002246 -:108D00009A807047C809002003685A1C02601970D5 -:108D10007047016B0346C26810B5406941B1196CD8 -:108D2000541A005D013918BF0A46C0B21A6410BD5A -:108D3000196A405C0131B1FBF2F402FB1412C0B2BB -:108D40001A6210BD026B03691AB15168013B026CD3 -:108D500002E0C169026A013B881A1840C0B270473C -:108D6000436B13B190F844007047826A436AD31A88 -:108D700058425841704743799B070AD5436A826934 -:108D8000D154426A03690132B2FBF3F103FB1123B0 -:108D900043627047437913F0010307D0C368C16988 -:108DA000026A013B881A1840C0B2704718467047E3 -:108DB000437910B513F0010304460DD0FFF7EAFF25 -:108DC00058B1226A6369985CE3680132B2FBF3F13F -:108DD00003FB1123236210BD184610BD426A806A4E -:108DE000131A5842584170474171704710F80A3CB5 -:108DF0000133DBB20A2B00F80A3C0AD910F8123C06 -:108E000023B910F8131C034A22F81130002300F88C -:108E10000A3C704744120020334A10B5136C906826 -:108E20001944081A40F68C2398429160D060516032 -:108E300013463CD9127893F945108A420BD1111F81 -:108E4000082908D893F84610182901D8013103E001 -:108E500083F8442002E0002183F8461093F944107F -:108E60008A421CD1204991F84710C1B1002191429A -:108E70001E4806DA03EB8104246920F81140013111 -:108E8000F5E7511E00EB41011630814203D000246A -:108E900021F8024FF9E7164908780130087083F885 -:108EA0004520002201211A7083F8471010BD92F866 -:108EB0004710B9B1A0F2EF2440F2DA518C4208D841 -:108EC00011780B2905D80B1D0131117042F82300D0 -:108ED00010BD002283F84720991804320020302A60 -:108EE0000861F9D110BD00BF8C070020441200209A -:108EF000281E0020024B1A6C01321144196470477D -:108F00008C070020024B53F820301B6819807047F3 -:108F1000B4080020074BA1F57A7153F820304FF4C4 -:108F20007A701A681B894B4393FBF0F39BB2138052 -:108F3000704700BFB40800202DE9F04F504A514E51 -:108F40001768738984463089A7EB032785B003919E -:108F500087FB0001B288CB111404C209F08842EAF1 -:108F6000416287FB000114EB020872884FF0000594 -:108F70004FEAC2344FEA1022B08945EB030942EAB6 -:108F800001620B1287FB000114EB020A4FEAD05278 -:108F900042EA41224FF0000545EB030B12F5FA605F -:108FA0004FEAE15343F10001CDE90001B0F5FA6F5A -:108FB00071F1000147DAA2FB024502FB03F105262D -:108FC00005EB4105A4FB060106FB05114D104FEA18 -:108FD0003004B8EB040869EB050984082A4844EA20 -:108FE00081748D104FF0FF31BAEB040A6BEB050B67 -:108FF000DDE9004584428D4125DA40F6AC50121877 -:109000004FF0000143EB010302FB03F1A2FB02233B -:109010006FF0060003EB4103544200FB0344A2FB44 -:10902000000118EB000821444FF00B0449EB010943 -:10903000A2FB040104FB031149104FEA3000BAEB14 -:10904000000A6BEB010B114B1A68A2FB0A0102FB31 -:109050000B11420D42EAC1224B15B2EB080263EB41 -:109060000903D00B40EA4340BCF1000F01D0CCF81B -:109070000000039808B10099016005B0BDE8F08FC9 -:10908000481300204807002024FAFFFF4C1300205B -:10909000324B2DE9F0411C88314B0A265A89B3F92D -:1090A0001250A41A1A89ED025443B3F91420E413A0 -:1090B000224495FBF2F22244DA615643A2F57A6229 -:1090C00002FB02F4B3F90480B3F902C0B3F90E70E5 -:1090D00002FB0CFC02FB08F2B3F90C80241367437B -:1090E00004FB08F4241404EB62320232DC88921090 -:1090F00002F50042B3F920506243B3F900304FEA61 -:10910000EC2404EBE72404EB8304AC40154B02345D -:109110001B68D20BA3EBA4044CF250332B416343E6 -:1091200055BF5B00B3FBF2F3B3FBF2F35B001A1223 -:10913000524340F6DE3462430B4C08365C43241441 -:1091400004EB224202F6CF62361103EB221300B188 -:10915000036001B10E60BDE8F08100BF581300202C -:109160005C0700205413002043E3FFFF2DE9F84F74 -:109170002E4E04463768384609F0E2F80546384670 -:1091800009F052F976688046304609F0D9F88346EE -:10919000304609F049F9D4F8049006462946484675 -:1091A00005F08AFEA76882464146384605F084FEEF -:1091B0000146504605F076FD21688246584605F086 -:1091C0007BFE41460446484605F076FE314605F0F2 -:1091D00073FE0146204605F067FD314604463846D9 -:1091E00005F06AFE294605F067FE0146204605F0B7 -:1091F0005BFD0146504609F0A5F90D4905F05CFEFE -:109200000C4905F00DFF0C4B196805F04DFD0B499D -:1092100005F006FF09F0CAF883B21A0444BF00F54E -:10922000B4739BB218B2BDE8F88F00BFCC04002025 -:109230000000E144DB0F494080070020000020418E -:10924000064B1B7803F0040303F0FF001BB1044B33 -:109250001888C0F3C01000F001007047D527002027 -:10926000540200202DE9F04102780346202A00F143 -:109270000100F9D0092AF7D02D2A02D10346414D29 -:1092800004E02B2A08BF03464FF07E551E460024FB -:10929000334616F8012BA2F13007F9B209290DD88F -:1092A0003949204605F008FE0446384605F0B0FD71 -:1092B0000146204605F0F8FC0446E9E72E2A17D1BE -:1092C000314F334616F8010B3038C2B2092A0FD895 -:1092D00005F09EFD394605F0A3FE0146204605F047 -:1092E000E3FC29490446384605F0E6FD0746E8E771 -:1092F0001A7802F0DF02452A38D15A782D2A02D195 -:109300000233012604E02B2A14BF01330233002666 -:10931000013B002713F8012F303AD1B2092903D8B5 -:109320000A2101FB0727F5E7B7F59A7F28BF4FF41D -:109330009A77B8464FF07E51B8F1070F07D9084623 -:10934000124905F0B9FDA8F108080146F4E707F055 -:10935000070737B108460C4905F0AEFD013F01464D -:10936000F7E72EB1204605F05BFE04E04FF07E519A -:10937000204605F0A1FD0146284605F09DFDBDE80B -:10938000F08100BF000080BF0000204120BCBE4C27 -:10939000F0B50124B0FBF4F58D4201D34C43F9E75D -:1093A0000026DCB1B0FBF4F504FB1500B4FBF1F4CE -:1093B0001EB9002D01DC002CF3D1092D03F10107AA -:1093C0005FFA85FC04DD002A0CBF5725372500E035 -:1093D000302565441D7001363B46E2E71C70F0BD48 -:1093E000F0B50124B0FBF4F58D4201D34C43F9E70D -:1093F0000026DCB1B0FBF4F504FB1500B4FBF1F47E -:109400001EB9002D01DC002CF3D1092D03F1010759 -:109410005FFA85FC04DD002A0CBF5725372500E0E4 -:10942000302565441D7001363B46E2E71C70F0BDF7 -:1094300070B50646B6FBF2F40846154614B1204650 -:10944000FFF7F6FF05FB1464024B1B5D00F8013BC0 -:1094500070BD00BF3A6701082DE9F041069C002B62 -:1094600006460F460CBF4FF020084FF03008234649 -:1094700013F8011B09B9154603E0002AFBDD013A88 -:10948000F6E7002D04DD30464146B847013DF8E7D8 -:1094900014F8011B11B13046B847F9E7BDE8F08177 -:1094A00080EAE073A3EBE0738B4206DB002801DD6A -:1094B000401A704702D00844704700207047034BA1 -:1094C0009A6822EA00009860704700BF30200020B0 -:1094D0000E4B1B78BBB10E4B1B681A78032A06D1C2 -:1094E0000C4B187802288CBF0020012070475B7855 -:1094F00023B1094B1868C0F3C0407047074B187878 -:10950000C0F3800070470120704700BF520D00205B -:10951000A0050020E805002050020020D5270020EB -:10952000114A30B50028B8BF4042104C90FBF2F30E -:1095300004FB03003C2568430D4D90FBF2F22D68BF -:109540002D7B25B903EB830303EB830301E0C3EB1E -:10955000031302EB830304FB02020B804FF47A73C4 -:1095600092FBF3F24A8030BD80969800806967FFD5 -:10957000C8050020034B1B681878C31E5842584189 -:10958000704700BFA005002008B5064808F0EAFCB7 -:10959000C0B2142805D8034A431C20211154D8B264 -:1095A000F7E708BDA91B0020094A0A48002310B5A7 -:1095B000116803701A46CC1864880CB9CC5C24B1CD -:1095C00004330132802BD2B2F5D1027010BD00BF3E -:1095D000100600209406002010B50B4B0B4819789C -:1095E0000B4B5A784B085C1E047001F001010948CE -:1095F0000B44037008495308581E087002F001021A -:10960000064913440B7010BDCD060020C80600208B -:1096100038180020CA060020CB060020C90600200A -:10962000F0B50F4A0F4816780F4A002317684370A9 -:109630001A4619460546D0B2B0420CD217F822009D -:10964000013204099C4200F00F00A8BF631C88424D -:10965000A8BF411CEFE76B70044B1970F0BD00BF51 -:10966000940600203818002010060020CD060020A7 -:10967000F8B5101A0C461F4605F0CAFB0546381B04 -:1096800005F0C6FB174B079E196805F015FC294627 -:109690000446284605F010FC21460746204605F002 -:1096A0000BFC0146384605F0FFFA09F0D5F80E49E3 -:1096B00005F002FC05F0ECFD069B2146186005F163 -:1096C000004008F03FFF094905F0F6FB084905F0A6 -:1096D000EBFA05F0B7FD0028BCBF00F50C40A03048 -:1096E0003060F8BD4C0000202C7D8E3FA00CB345AF -:1096F00000A00C4610B505F08BFB0021044605F0D8 -:1097000097FD08B1204601E004F10040054905F04D -:1097100087FC054905F0D0FB08F012FE034B1860EA -:1097200010BD00BF8096184B35FA8E3C4C000020CF -:1097300070B50446007905F067FB1E4905F070FC22 -:109740001D4D1E4E2860A07B05F05EFB194905F0FB -:1097500067FCEE606860607905F056FB184905F01B -:109760005FFC184D2860E07B05F04EFB114905F0C9 -:1097700057FC6860607E05F047FB134905F050FC1C -:10978000EE60A860A07905F03FFB0D4905F048FCAC -:109790000E4D2860207C05F037FB064905F040FCA3 -:1097A0006860A07E05F030FB074905F039FCEE60EB -:1097B000A86070BD0000C842601100200000FA449B -:1097C000000020417011002000007A449411002014 -:1097D00044F25063984203DDA0F50C40A038704776 -:1097E000034B9842BCBF00F50C40A030704700BF4F -:1097F000B0B9FFFF2DE9F041038A87890446BFB263 -:109800000D461F40002F36D0B7FA87F34FF00042C5 -:10981000DA40D24391B21B3B21821740042BF1D88E -:10982000DFE803F0221F1C1903006B6A33B103F158 -:10983000FF3800231FFA88F86B6203E0B4F82C802D -:109840001FFA88F82E6A002EDCD033683046414675 -:1098500098477668F7E72868A18E08E06868218F46 -:1098600005E0A868A18F02E0E868B4F8401003683A -:1098700089B29847C6E7BDE8F0810C4B800A984250 -:109880000CD003D8B0F5801F0ED00BE0084B9842E7 -:1098900006D04933984205D1002070470220704716 -:1098A00003207047FE207047012070470100100020 -:1098B0000200100090F83B3210B57BB990F83A32B4 -:1098C00090F83922934209D201219940B0F84042E0 -:1098D00001332143A0F84012DBB2F3E710BD8379D6 -:1098E000012B03D1D1F1010138BF0021D0F834316F -:1098F0005A681B8909B11361704753617047044B63 -:1099000053F820301BB107289CBF1B681980704793 -:10991000E40800202DE9F0410F88002347FA03F204 -:10992000D2072BD58A7803F0070512F0100F18BF65 -:1099300091F803C002F00F0618BF46EA0C06AD000E -:109940004FF00F0C0CFA05FC06FA05F5DC0850F890 -:109950002480282A28EA0C0C45EA0C0540F82450FB -:1099600005D101229A40C46824EA020205E0482A8F -:1099700004D101229A40C4682243C2600133102BF3 -:10998000CCD1BDE8F08100BF2DE9F047054608F0D5 -:10999000E9FA2E4B0446D3F808809A4690B92C4831 -:1099A000FCF76AF82B4B53F8241049B10123A3406C -:1099B00013EA080F02D02848FCF7CAFA0134F1E78D -:1099C000264821E028462649224608F0D3FA58B90D -:1099D0002448FCF751F8244C54F8041F0029EFD018 -:1099E0001D48FCF7B5FAF7E72B7800262D2B03BFAF -:1099F000013504F1FF344FF001094FF00009154B18 -:109A000053F8267027B91948BDE8F047FCF734B879 -:109A100028463946224608F0ADFAA8B90120B040E0 -:109A2000B9F1000F03D0FFF74AFD114804E040EA06 -:109A30000800CAF808000F48FCF71EF839460E481F -:109A4000BDE8F047FCF784BA0136D8E730200020A3 -:109A50005F670108585001086F6401083E680108FB -:109A60001A6E0108726701085450010887670108DF -:109A70009E670108A8670108086801082DE9F04FF2 -:109A8000692887B0044600F0A78200F296802E284D -:109A900000F0398562D8242800F009852BD82028C9 -:109AA00000F08282222800F0BE83012840F05C850D -:109AB0002C20FBF77BFF0020FBF749FF2046FBF73C -:109AC00046FF0020FBF743FF4320FBF740FF4C20FD -:109AD000FBF73DFF4620FBF73AFF4C20FBF737FF33 -:109AE0002046FBF734FF0020FBF731FF0020FBF797 -:109AF0002EFF0024F0E0282800F0E18412D8262868 -:109B000040F03285924C0320FBF750FFB4F9E60099 -:109B1000FBF74FFFB4F9E800FBF74BFFB4F9EA009D -:109B200000F034BC2A2800F0D5842C2840F01C8595 -:109B3000874C0720FBF73AFF94F81801FBF707FF63 -:109B4000B4F91E01FBF735FFB4F91A01FBF731FF39 -:109B5000B4F91C01FBF72DFF00F0C2BC642800F033 -:109B6000E3801AD8322800F0BB840AD8302840F0AD -:109B7000FB84774C8020FBF719FF04F1800500F08F -:109B8000D8BC342800F06F83402840F0ED840820D2 -:109B9000FBF70CFF002400F0ACBC662800F09C81B1 -:109BA000C0F0F080672800F0D081682840F0DC84A5 -:109BB0001020FBF7FBFE002406E2732800F0BA83B6 -:109BC00055D86D2800F01B8212D86B2800F0008455 -:109BD00040F2BB835F4C0620FBF7E8FEB4F90000BF -:109BE000FBF7E7FEB4F90200FBF7E3FE5A4B0EE287 -:109BF0006F2800F06782C0F00D82702800F081822B -:109C0000722840F0B184524C1620FBF7CFFE0020A2 -:109C1000FBF7CFFEB4F9D000FBF7CBFE4F4DB4F904 -:109C2000D200FBF7C6FEB4F9D400FBF7C2FE2B68E6 -:109C3000B3F9A801FBF7BDFE0020FBF7BAFE002038 -:109C4000FBF7DCFE2B68B3F952000A2390FBF3F01C -:109C5000FBF7AFFE94F80401FBF779FE94F80601D8 -:109C6000FBF775FE94F80501FBF771FEE5E3782834 -:109C700000F0778110D8752800F0C982C0F01483F5 -:109C8000762800F0B683772840F06E84344D0024A7 -:109C90002878FBF78BFE42E3A42800F0D08310D88D -:109CA000A02840F061840C20FBF780FE2D4B186843 -:109CB000FBF7A4FE2C4B1868FBF7A0FE2B4B186893 -:109CC000FAE3F02800F0E683FE2840F04D840820F7 -:109CD000FBF76CFE0024D5E3254B1B68185D0134AF -:109CE000FBF735FE042CF7D1224B00241878FBF744 -:109CF00060FE214B185D0134FBF729FE0B2CF8D1D7 -:109D000000241E4B185D0134FBF721FE082CF8D10E -:109D10000720FBF71CFE0024194B185D0134FBF7EC -:109D200016FE072CF8D188E30720094CFBF73EFE0E -:109D3000E620FBF70CFE6079FBF709FE0020FBF73D -:109D400006FE94F82631002B0CBF04200C20B3E350 -:109D500030200020A8030020E0040020E8030020B9 -:109D6000D61B0020E8F7FF1FECF7FF1FF0F7FF1FDF -:109D7000AC000020D6270020B1670108BD670108AC -:109D8000C66701080B20FBF711FEB64BB3F90000C4 -:109D9000FBF70FFEB44B188800B2FBF70AFEB34B7B -:109DA0001B68C3F3C000C3F38002800040EA420096 -:109DB000C3F340021043C3F3401240EAC20003F071 -:109DC00010031843FBF7F5FDA94B1A8812F0010F99 -:109DD0000CBF0020022012F0020F0CBF0021042152 -:109DE00012F0040F0CBF0023102312F0400F0CBF21 -:109DF00000242024019312F0100F9E4B02940CBFFC -:109E000000244FF4007412F0200F1B6803940CBF61 -:109E100000244FF4806412F4807F04940CBF00246B -:109E20004FF4006402F0080B03F4807A059403F405 -:109E3000805903F4005803F4004C03F4803E03F40B -:109E4000003703F4802603F4002503F4801403F0A4 -:109E5000C00343EA0B0343EA0A0343EA090343EA64 -:109E6000080343EA0C0343EA0E0E834B4EEA07074E -:109E70003E431B7835432C43C3F380032343034302 -:109E80000B430199029C0B4303992343049C0B430E -:109E90000599234312F4007F43EA01030CBF00221B -:109EA0004FF400121A43754B00201C780346A3425E -:109EB0000CD273495D5C012101FA05F5154218BF0A -:109EC000994003F1010318BF0843F0E7FBF796FD43 -:109ED0006C4B93F8540709E31220FBF767FD6A4BBC -:109EE0006A4C1B88B3F5806F22D90025605F082378 -:109EF00090FBF3F00235FBF75CFD062DF6D1644CC8 -:109F0000B4F90000FBF755FDB4F90200FBF751FD71 -:109F1000B4F904005F4CFBF74CFDB4F90000FBF70B -:109F200048FDB4F90200FBF744FDB4F904002DE24A -:109F3000B4F90000FBF73DFDB4F90200FBF739FD71 -:109F4000B4F90400FBF735FDD9E71020FBF72EFD2F -:109F50000024514B185D0134FBF7F9FC102CF8D1AB -:109F600016E23820FBF722FD00254C4E05F12C04AB -:109F70003368E4002344B3F90600FBF71AFD3368A5 -:109F800001352344B3F90800FBF713FD336823447C -:109F9000B3F90A00FBF70DFD33681C44207BFBF787 -:109FA000D6FC082DE1D1F3E10820FBF7FFFC0024EB -:109FB0003A4B1B6803EBC40393F86D010134FBF7C4 -:109FC000C6FC082CF4D1E3E1354B185D0134FBF7F6 -:109FD000BEFC102CF8D1DBE1324D00242878400083 -:109FE00000F0FE00FBF7E2FC2B789C4280F0D08171 -:109FF0002D4B33F91400FBF7DCFC0134F4E70620A9 -:10A00000FBF7D4FC294B1868FBF7F8FC284BB3F995 -:10A010000000BBE10720FBF7C9FC264B4FF6FF749D -:10A020001878FBF794FC244B1868A042A8BF204680 -:10A0300020EAE07000B2FBF7BCFC204BB3F9000053 -:10A04000FBF7B7FC0F4B93F80C211D4B1868002849 -:10A05000B8BF40420AB10A235843A042A8BF2046D5 -:10A0600000B293E1FC0400203C1800204C020020C8 -:10A070005402002050020020D5270020D61B0020CB -:10A08000C01B00203020002000000020B40400206D -:10A09000F40400207C02002012000020E8030020CD -:10A0A000A8270020DF090020960600205C0200207F -:10A0B000C8030020B4050020BC050020BE0D002010 -:10A0C000B8050020B34C0720FBF770FC2368187814 -:10A0D000FBF73DFC23685878FBF739FC23681879B7 -:10A0E000FBF735FC23685879FBF731FC2368987936 -:10A0F000FBF72DFC23689878FBF729FC2368D878B8 -:10A10000F4E1A54D1E20FBF751FC2B6800241B78C1 -:10A11000022B69D12B68A14903EB8403586A04F030 -:10A12000CBFE08F043F9FA28A8BFFA2020EAE07035 -:10A13000C0B2FBF70CFC2B68994903EB8403186B46 -:10A1400004F0BAFE08F032F9FA28A8BFFA2020EA93 -:10A15000E070C0B2FBF7FBFB2B68924903EB840372 -:10A16000D86B04F0A9FE08F021F96428A8BF642088 -:10A1700020EAE070C0B20134FBF7E9FB032CC9D13F -:10A18000072C2B681ED1986C844904F095FE08F0CA -:10A190000DF9FA28A8BFFA2020EAE070C0B2FBF758 -:10A1A000D6FB2B687D49D86C04F086FE08F0FEF8DB -:10A1B000FA28A8BFFA2020EAE070C0B2FBF7C7FB7C -:10A1C00000200BE023441879FBF7C1FB2B682344E4 -:10A1D000987BFBF7BCFB2B682344187E0134FBF70C -:10A1E000B6FB0A2CCCD1D3E02B6823441879FBF7BB -:10A1F000AEFB2B682344987BFBF7A9FB2B68234419 -:10A20000187E0134FBF7A3FB0A2CEDD1C0E02F2010 -:10A21000FBF7CCFB644C14F8010F002800F0B88069 -:10A22000FBF795FBF7E7A020FBF7C0FB00245A4B98 -:10A2300004F11C021B680C2103EB82035D1D5B4AC9 -:10A240005B79013401FB0323187AFBF780FB687804 -:10A25000FBF77DFBA878FBF77AFBE878FBF777FB49 -:10A26000282CE4D194E04820FBF7A0FB002506262B -:10A270006E43494B06F588761B6801351E44B07A5B -:10A28000FBF765FB7079FBF762FBB079FBF75FFBCF -:10A29000F079FBF75CFB307AFBF759FB707AFBF740 -:10A2A00056FB0C2DE3D173E0002701240025404B21 -:10A2B0001B789D4222DA3F4BE95C00233B4A03EBCB -:10A2C00002089A5C8A4204D00C33B3F58A7FF5D138 -:10A2D00012E0D8F8040007F045FE81460CB9264686 -:10A2E00001E0074408E04E4506DAD8F80430985DEE -:10A2F000FBF72DFB0136F6E70135D8E7002C47D0F8 -:10A30000F8B2FBF753FB0024D0E7284A99189A5C6F -:10A3100082420BD00C33B3F58A7FF6D101342B780F -:10A320009C4235D2234BE05C0023EEE7087AFBF732 -:10A330000EFBF3E70820FBF739FB0124E0B2013400 -:10A34000FBF705FB092CF9D122E01020FBF72EFBCF -:10A35000194B1A4C187800F00200FBF7F8FA184B6A -:10A360001878FBF7F4FA2068FBF748FB6068FBF706 -:10A3700045FB144BB3F90000FBF71BFB124BB3F981 -:10A380000000FBF716FB114BB3F90200FBF711FBC2 -:10A390000120EAE08C050020E803002000002041B5 -:10A3A0000000C84200007A44874F0108884C010829 -:10A3B000D61B0020C01B002082020020D0050020F8 -:10A3C000C4050020C2050020C00500203C18002064 -:10A3D000674C0520FBF7EAFAB4F90400FBF7E9FA49 -:10A3E000B4F90600FBF7E5FA624B187800F00100BB -:10A3F0007CE0FBF79DF806461220FBF7D7FA0EB972 -:10A400005D4B02E0102E03D15C4B1D685C6801E0DF -:10A41000002425463046FBF79AFA2846FBF7EEFA69 -:10A420002046FBF7EBFA564B1868FBF7E7FA0020DB -:10A43000FBF7BFFA0020FBF7BCFA002056E04C4DBA -:10A440000024287A2E4680000130C0B2FBF7AEFA15 -:10A45000287AFBF77CFA337A9C4299D2494D285DE1 -:10A46000FBF775FA05F11003185DFBF770FA05F1BB -:10A470002003185D3035FBF76AFA285DFBF767FAB1 -:10A480000134E8E7404B185F0234FBF792FA082CDE -:10A49000F8D17DE73D4C0420FBF788FA2368B3F937 -:10A4A0005600FBF786FA2368B3F954006EE70420E0 -:10A4B000FBF77CFA364B9868FBF7A0FA68E7344C58 -:10A4C0000420FBF773FAB4F90801FBF772FAB4F948 -:10A4D0000A015BE70120FBF769FA2D4B587905E08B -:10A4E0000120FBF763FA2A4B93F82001FBF72FFAC0 -:10A4F0004EE7274B234493F810010134FBF727FA6A -:10A50000082CF6D144E74020FBF750FA204C04F128 -:10A510004005B4F9D401FBF74CFA94F8D601FBF7E7 -:10A5200016FA043494F8D301FBF711FAAC42F0D1D7 -:10A530002EE7B4F85601043400F03F00FBF739FA77 -:10A54000B4F85201C0F38410FBF733FA94F85001C9 -:10A550000009FBF7FCF994F8500100F00F00FBF73D -:10A56000F6F9AC42E5D113E7002007B0BDE8F08F63 -:10A570003C180020D40F0020240E0020300E0020B4 -:10A58000580200204518002086180020E80300200B -:10A590003020002007B5064B06480093064B074ABB -:10A5A0001968074BFBF7D4FC03B05DF804FB00BF50 -:10A5B000C6670108D3670108C8000020B167010819 -:10A5C000BD67010810B50748FBF756FA0024064B93 -:10A5D0000648E218E15852680C34FBF7B9FCFC2C31 -:10A5E000F5D110BDEF670108305301080568010877 -:10A5F00037B582880446836810060D4606D529497A -:10A600004FF4E07091F8541700FB0133D10504D5E5 -:10A6100025490A20097800FB013302F03F02042A91 -:10A6200012D006D8012A0DD0022A2FD193F900109A -:10A630002DE0102A0AD0202A0AD0082A26D1B3F900 -:10A64000001024E0197822E0198820E019681EE043 -:10A6500069461868FBF70CFE01461448FBF778FCC6 -:10A66000F5B1E06804F0D4FB6946FBF701FE014652 -:10A670000F48FBF76DFC206904F0CAFB6946FBF745 -:10A68000F7FD01460A48FBF763FC09E00021094891 -:10A69000FBF75EFC25B10848E1682269FBF758FC2E -:10A6A00003B030BD30200020140E00206B72010872 -:10A6B0006A720108086C01080D6801082DE9F04173 -:10A6C000002407462546114B3946E65804EB03089B -:10A6D000304607F083FC58B10D483146FBF738FC93 -:10A6E00040460021FFF784FF0A48FBF731FC0135A3 -:10A6F000143440F604339C42E5D125B90648BDE840 -:10A70000F041FBF7B9B9BDE8F08100BF6C56010814 -:10A71000A56801083E680108146801082DE9F74F93 -:10A72000044607F01FFC054620B1012819D1237803 -:10A730002A2B16D15648FBF79FF90024554B564853 -:10A74000E618E158FBF704FC30462946FFF750FFB6 -:10A750005248FBF791F9143440F604339C42EDD192 -:10A7600092E020463D2107F0F0FB002800F08780B2 -:10A77000034613F8012C202A01D1013BF9E7451CBF -:10A780002846C4EB030A07F042FC83462846FEF73E -:10A7900069FD0026054614237343DFF8F89053F84B -:10A7A000097003EB0908384607F0DCFB03461A463C -:10A7B00020463946019307F0DDFB019B002855D167 -:10A7C0005FFA8AF29A4251D1D8F80C0004F020FBCB -:10A7D0000146284604F022FD002845D0D8F8100094 -:10A7E00004F016FB0146284604F00EFD00283BD07D -:10A7F000B8F804309B064FF0140303FB0696B288AA -:10A8000058BF5D4614062946B36806D524484FF460 -:10A81000E07490F8540704FB0033D00504D52148B8 -:10A820000A24007804FB003302F03F02042A0BD014 -:10A8300004D8013A012A0CD819700AE0102A05D070 -:10A84000202A05D0082A04D1198002E0196000E00E -:10A850001D6039461448FBF77BFB3046002103B0EE -:10A86000BDE8F04FFFF7C4BE104803E001368D2E5F -:10A8700091D10F4803B0BDE8F04FFBF7FDB820467B -:10A8800003B0BDE8F04F19E703B0BDE8F08F00BF9B -:10A890002C6801086C560108A56801083E6801088B -:10A8A00030200020140E0020416801084C68010887 -:10A8B000146801087FB5044607F054FB082824D12A -:10A8C00000231F49E25C09681144497801F0030143 -:10A8D000022908BF203AE2540133082BF1D10025A8 -:10A8E000665D1848314607F030FB28B10135601924 -:10A8F000314607F02AFB18B11348FBF7BDF81CE0FE -:10A90000082DEDD12046FBF79BFC1048FBF7B4F86F -:10A9100000230F4A04A91A4492F810210A44094955 -:10A92000595C0133082B02F80C1CF2D100230948B2 -:10A9300001A98DF80C30FBF70BFB04B070BD00BF14 -:10A94000CC000020646B01086C6801088C68010869 -:10A950003020002008680108F8B504680546204644 -:10A960000E461746FEF789FF032845D82B7B9B0828 -:10A970009AB246B94FF0020C0CFA03F3A18989B2DE -:10A9800021EA0303A3810A2101FB00211B4B43F8A9 -:10A990002160043143F8217046B12A7B02259208D8 -:10A9A00005FA02F2A1890A4392B2A281282202FB8F -:10A9B000003000F12002EFF31286502383F3128857 -:10A9C0000023C1180D6915B115600A6904320433FA -:10A9D000102BF6D100231360F3B283F31188036ABE -:10A9E00023B1A3899BB243F0010304E0A38923F0C0 -:10A9F00001031B041B0CA381F8BD00BFD01E002067 -:10AA000070B5046D4279A38902F0040123F4005368 -:10AA10001B041B0C0546866886B0A38101F0FF006D -:10AA200021B14FF480604FF4005100E0014612F074 -:10AA3000010F14BF0423002312F0020F1CBF43F0C8 -:10AA400008039BB212F0080F228A18BF0C2392B29F -:10AA500022F4405211432182A28992B222F4B052D0 -:10AA600022F00C02104303439BB2A381A38A01A8E6 -:10AA700023F440731B041B0CA382FBF707FF194947 -:10AA8000049A039B8C4208BF1346A289192159439B -:10AA900012B2002AB4BF7600B600B1FBF6F164230F -:10AAA000B1FBF3F21201100903FB1011A08900B2EF -:10AAB000002806DAC9003231B1FBF3F303F00703D3 -:10AAC00005E009013231B1FBF3F303F00F031A4340 -:10AAD00092B22B6D22819A8992B242F400529A81ED -:10AAE00006B070BD00380140417189E7816087E799 -:10AAF000826A8169436B1144D960416A914203D9EA -:10AB00008A1A5A60816204E001698A1A5A60002236 -:10AB10008262002280F844201A6842F001021A6022 -:10AB2000704738B5114B124C9968124B1A681D4684 -:10AB30005288114203D0FAF7ADFD206011E0FAF718 -:10AB4000A9FD236898420CD9C01A0B4B3B22B0FBDD -:10AB5000F2F01B68B0F5967FC8BF4FF0FF3003B12D -:10AB600018602B685A68054B5A6138BD000C0140CB -:10AB700090180020E0030020DC03002000040140C6 -:10AB800070B5064600240B4BE518AA8816420AD079 -:10AB9000E1580948FBF7DCF928460021FFF728FDBA -:10ABA0000648FAF769FF143440F604339C42EAD1B0 -:10ABB00070BD00BF6C560108A16801083E6801081D -:10ABC0000D4B0278D9684378C943C1F30221C1F122 -:10ABD000040103FA01F1094B0901C9B21A4482F8D0 -:10ABE000001302780120510902F01F0200FA02F25C -:10ABF00043F82120704700BF00ED00E000E100E0D5 -:10AC0000134B026810B51C68D1430C401C605C6893 -:10AC10002140596019680A431A6002689C68D14350 -:10AC20000C409C60DC682140D9604179102906D134 -:10AC3000996811439960D9680A43DA6010BD01F13F -:10AC4000804303F5823319680A431A6010BD00BFC0 -:10AC500000040140254B10B55343254A254C12688A -:10AC60000139B2FBF3F20388013AA04289B292B2F1 -:10AC70009BB212D004F50064A0420ED0B0F1804F18 -:10AC80000BD0A4F59834A04207D004F58064A0420C -:10AC900003D004F58064A04202D123F070039BB27C -:10ACA000154CA04206D004F58064A0421CBF23F4DA -:10ACB00040739BB203800F4B8185984202850FD071 -:10ACC00003F5006398420BD003F54063984207D028 -:10ACD00003F58063984203D003F58063984201D165 -:10ACE000002303860123838210BD00BF40420F0072 -:10ACF000A8000020002C014000100040284BF0B5B7 -:10AD00001D6800222748165C1418AB19597801F009 -:10AD1000040101F0FF0371B10132102AF2D10020C9 -:10AD2000F0BD1BB103EB83035B00DBB210F8012B1A -:10AD3000303A1344DBB2221A022AF2DC00218442A8 -:10AD40000AD919B101EB81014900C9B210F8012BF0 -:10AD5000303A1144C9B2F2E72E2E14D1601C002201 -:10AD60000424067802EB8202AF197F7852007F0735 -:10AD700092B203D5303A3244013092B2013C14F021 -:10AD8000FF04EED100E0002207480624414364207E -:10AD900000FB02120548B2FBF4F200FB0320F0BDF9 -:10ADA000CC000020E30F002040420F008096980066 -:10ADB00030B5002213460D495C5C9CB12E2C04D1A9 -:10ADC000013378B11C1800250D550A246243C95C73 -:10ADD000A1F13004092C9CBF303A52180E2B03D835 -:10ADE0000133E8E7104630BD002030BDE30F0020FE -:10ADF0000FB407B504AB53F8042B002004490193AA -:10AE0000FAF7E0FF03B05DF804EB04B0704700BF51 -:10AE10002D5B00080EB40FB505AB53F8042B019061 -:10AE2000064901A80393FAF7CDFF019B00221A708F -:10AE300004B05DF804EB03B0704700BF098D000853 -:10AE40002DE9F0438DB0054607F08CF8C0B200281C -:10AE500058D104467F4B00211E68142207A807F032 -:10AE600040F8A500002303A905A8039305937719CB -:10AE70000B7183801A46DFF8F0E1B7F802C03EF8A4 -:10AE8000138018EA0C0F0CD00EF10A0E0DF13008E9 -:10AE900013F80EE002F1010C424402F824EC5FFAD0 -:10AEA0008CF20133052BE6D100231A46DFF8C0E10E -:10AEB000B7F802C013F80E8018EA0C0F0CD00EF190 -:10AEC000060E0DF1300813F80EE002F1010C4244B9 -:10AED00002F81CEC5FFA8CF20133062BE6D1735DAD -:10AEE0008DE803001A0907A85B4903F00F03FFF779 -:10AEF00091FF2146594807AA0134FBF729F8202C75 -:10AF0000A8D1A3E0284607F082F81F28044600F3E2 -:10AF1000918028462021E4B207F017F81F2C01D9B0 -:10AF20004F4888E04B4B471C1B68002103EB84040F -:10AF30002046042206F0D5FF00254A4B07AE3046D6 -:10AF400000210A2215F803905FFA85F806F0C9FF80 -:10AF50000023FA5CF91832B10A2B04D04A4502D01A -:10AF6000F2540133F5E74A4501F1010767D1B8F121 -:10AF7000020F0DD0B8F1030F0CD0B8F1010F0BD0B8 -:10AF8000304607F044F82378C0B243EA00100AE0E4 -:10AF9000002219E0002226E0304607F038F8237836 -:10AFA00000F00F001843207038E00133062B0AD060 -:10AFB0002D4800F115069E5D8E42F6D10344D97BE3 -:10AFC00063880B43638001320CA9D3B20B4413F89E -:10AFD000141C19B30023EBE7412B1DD0542B08BFE1 -:10AFE00004230ED00132D3B20DF13008434413F8DC -:10AFF000143C9BB1492B01D1002302E0572B07D110 -:10B000000123194931F8131063880B436380E9E782 -:10B01000462BE1D10223F4E70323F2E70135042DA7 -:10B020008BD10124FEF7C0FAFEF7FAFAFEF7D4FA44 -:10B0300064B975E70D482021FAF78AFF06E020463B -:10B040000021042206F04DFF0024EBE70DB0BDE81F -:10B05000F08300BF10060020AB680108B768010844 -:10B0600085650108DF4F0108C44F0108C368010866 -:10B07000D34F01082DE9F0418CB01D469DF84830B2 -:10B080008846012B174608D1A84B984240F04681CC -:10B09000042203F548431A6165E0A54B98425ED14E -:10B0A000A448A54B87600360A44BA907436103F143 -:10B0B000C00383614FF0C003C36003619C4B036511 -:10B0C00003F104038364C36403F5484303F15403A9 -:10B0D0000363A3F11403D3F8D42F436342F48042F3 -:10B0E000C3F8D42FD3F8D02F42F00102C3F8D02FE9 -:10B0F0004FF002038DF803304FF40073ADF80030C9 -:10B100004FF018038DF8023003D58D486946FEF7DD -:10B1100001FC1C232A078DF8023003D588486946B4 -:10B12000FEF7F8FB4FF48063ADF8003048238DF84C -:10B130000230EB0703D582486946FEF7EBFB0E238E -:10B140008DF804300022012301A88DF805308DF818 -:10B1500006208DF80730774CFFF732FD55E0734B32 -:10B16000984240F0DF80774B734A9F601A60C0229C -:10B17000DA601A61744AAE075A6102F1C0029A613C -:10B180006A4A1A6502F104029A64DA646F4BDA695A -:10B1900042F40032DA615A6942F001025A614FF01A -:10B1A00002038DF803304FF00403ADF800304FF088 -:10B1B00018038DF8023003D561486946FEF7AAFBF3 -:10B1C0001C232C078DF8023003D55D486946FEF735 -:10B1D000A1FB0823ADF80030E8074FF048038DF8D5 -:10B1E000023003D556486946FEF794FB26238DF8B6 -:10B1F00004300022012301A88DF805308DF80620C7 -:10B200008DF80730FFF7DCFC4E4C0026012384F854 -:10B2100044302662E661A6626662C4F82C806571DD -:10B22000A760A6712046FFF7EBFB15F0090F31D0A0 -:10B23000206B002826D0E36C039601934FF48053D3 -:10B240000A9380230693E3680596049320230993C9 -:10B2500063690796029308960B96F9F7DFFF01A939 -:10B26000206BF9F7BDFF236B1A6842F001021A60E8 -:10B27000226D918A89B241F0400191825B689BB254 -:10B28000236407E0236D4FF6DF721A80DA6842F01C -:10B290002002DA6015F00A0F2CD0606B28B3A36C83 -:10B2A000002601934FF480530A9380230693236969 -:10B2B0000296049310230393059607960896099621 -:10B2C0000B96F9F7ABFF606B01A9F9F789FF636B88 -:10B2D0001A6842F002021A605E605E60236D9A8A0C -:10B2E00092B242F080029A8204E0236DDA6842F062 -:10B2F0008002DA60236D29079A8992B242F40052E3 -:10B300009A819A8A03D592B242F0080203E022F0B1 -:10B3100008021204120C9A82204604E0044B984260 -:10B320003FF4BEAE00200CB0BDE8F0810044004008 -:10B3300000380140C41F0020E44F01089418002089 -:10B3400000080140701F0020141A00200010024065 -:10B3500010B50446204606F005FE10F0FF0F07D199 -:10B360000B4B0C4893F85417BDE81040FAF7F0BDAA -:10B37000204606F04CFE022808D8054B064C83F800 -:10B38000540700F0B5FA02F0C1FCE3E710BD00BFBE -:10B39000302000202D670108096701082DE9F04FD2 -:10B3A000844985B0054606F0A5FD83490028284656 -:10B3B0000CBF0124072406F09DFD80490028284683 -:10B3C00008BF022406F096FD002808BF0424E10708 -:10B3D00040F1BE807A48FAF7BBFD0020FFF7DAF8AB -:10B3E000784F7948FAF7B4FD7848FAF7B1FD7A79E1 -:10B3F000774B784803EB82035969FAF7A9FD38695E -:10B40000002103F0EDFE00285CD13D460646D5F84C -:10B4100010800021404603F0E3FE00284ED10136A3 -:10B420006D483146D5F814B0D5F818A0D5F81C9061 -:10B43000FAF78EFD4046002103F0DCFE10B16748AC -:10B44000FAF786FD69464046FAF712FF014664485E -:10B45000FAF77EFD5846002103F0CCFE10B15F489C -:10B46000FAF776FD69465846FAF702FF01465C484E -:10B47000FAF76EFD5046002103F0BCFE10B15748AC -:10B48000FAF766FD69465046FAF7F2FE014654485F -:10B49000FAF75EFD4846002103F0ACFE10B14F48BC -:10B4A000FAF756FD69464846FAF7E2FE01464D486E -:10B4B000FAF74EFD0C2E05F11005A8D14A48711C73 -:10B4C000FAF746FD4948FAF743FD494DD7F8088099 -:10B4D00055F8041F19B14748FAF73AFDF8E70D4649 -:10B4E000454B53F8256056B10123AB4013EA080FD2 -:10B4F00003D042483146FAF72BFD0135F0E74048CA -:10B50000FAF726FD31467B1893F8103104AA13444C -:10B510003C4A8A5C0131082903F8102CF3D100233E -:10B52000694639488DF80830FAF712FD3748FAF7BE -:10B530000FFD3748FFF784FC3648FAF709FD344819 -:10B54000FAF7C2FD3448FAF703FD4020FFF718FB75 -:10B55000A2071AD53148FAF7FBFC3148FAF7F8FC94 -:10B560002B48FFF7F5FE2F48FAF7F2FC2848F9F7C9 -:10B57000CBF82D48FAF7ECFC2548F9F72BF82648CC -:10B58000FAF7E6FC8020FFF7FBFA63070FD52748A0 -:10B59000FAF7DEFC2648FAF7DBFC1D48FCF788FECC -:10B5A0001D48FAF7D5FC4FF48070FFF7E9FA05B0B3 -:10B5B000BDE8F08FE56801082E780108EC68010805 -:10B5C000F2680108302000200069010812690108B2 -:10B5D000E44F01081E69010829690108D8660108BD -:10B5E0006B720108086801083169010843690108A4 -:10B5F0005450010853690108585001086169010855 -:10B600006E690108646B01087A69010883690108A1 -:10B61000096701088F6901083E6801089D690108F2 -:10B62000B0690108BE690108C8690108D769010845 -:10B63000E86901082DE9F04F87B0984682460F4629 -:10B6400016469DF84040FDF724FA0DF1080E054618 -:10B65000034600F1100C18685968724603C208339B -:10B6600063459646F7D12B7B0BB90396049650465B -:10B6700002A9FDF7DDF8054640B14368586830B1CE -:10B68000504602A92A4601F055FFF4E733E0AB68C3 -:10B6900095F800B093F80090B9F1040F2BD8DFE8CB -:10B6A00009F003062A0F11000094144801E0144821 -:10B6B0000094394632464346FFF7DCFC04460BE073 -:10B6C000002000E00120394623463246FDF734F9D8 -:10B6D00041460446FAF710F964B10A4B84F8049025 -:10B6E00003EB8B03C3F800436B6820465C60514654 -:10B6F000FDF712F9204607B0BDE8F08F0038014091 -:10B700000044004094180020F7B5274C274DE3690A -:10B71000284643F48043E361236901A943F480434D -:10B72000236118238DF806304FF42043ADF8043020 -:10B7300003238DF80730FEF7EDF804234FF480461D -:10B740000DEB030128468DF806304FF48057ADF815 -:10B750000460FEF7DFF81023284601A98DF80630B3 -:10B76000ADF80470FEF7D6F82F61236930463343F5 -:10B770002361FBF7D5F80E4B1A8802F4415242F4CC -:10B78000457242F003021A809A8B22F4006212047E -:10B79000120C9A8307221A821A8892B242F040024F -:10B7A0001A8003B0F0BD00BF00100240000C014041 -:10B7B0000038004008B500F09BF802F0A7FABDE899 -:10B7C00008400F2014210122FAF74EB870B50A4E36 -:10B7D00000EB800006440024331913F8A00C074B3B -:10B7E00001341D786840FCF7C9F9052CF4D12846CE -:10B7F000BDE87040FCF7C2B9AC500108E02700205A -:10B80000642928BF6421F8B501FB00F7642497FB85 -:10B81000F4F40546E4B20026F3B2A34204D29F201A -:10B82000FFF7D4FF0136F7E7AC420BD2142097FBA9 -:10B83000F0F0C4EB84136638C4EB83031844C0B241 -:10B84000FFF7C4FF0134E4B2AC4238BF9A20F7D30B -:10B85000F8BD0F4B10B50446185CFFF7B7FF0D4B52 -:10B8600033F91430B3F57A7F05DBB3F5FA6FA8BF6F -:10B870004FF4FA6301E04FF47A73A3F57A730A2266 -:10B8800093FBF2F10920C9B2BDE81040FFF7B8BF41 -:10B89000646B01089606002010B5441E14F8010FD1 -:10B8A00010B1FFF793FFF9E710BD0F4B1A78552A37 -:10B8B00016D15A88B2F5EF6F12D11A79BE2A0FD17C -:10B8C00093F874270020EF2A0CD113F8012B504075 -:10B8D000064A9342F9D1D0F1010038BF00207047E9 -:10B8E00000207047704700BF00F8010878FF01088A -:10B8F0004A4B55222DE9F3411A704FF4EF625A80FA -:10B90000BE221A71EF2283F87427002283F875276C -:10B9100011461E46B35C0132B2F5EF6F81EA0301B6 -:10B92000F8D13E4B3E4A83F875173E4B04275A60C8 -:10B9300002F188325A600020013F17F0FF075DD006 -:10B94000384B3422384CDA60C4F309037BB1331925 -:10B9500003F17843A3F5FC33D3F800804FF4005093 -:10B9600000230193F9F72BFC0428E5D11BE04FF4E9 -:10B970003020F9F724FC0428DED12A4D4FF4302082 -:10B980002B6943F002032B616C612B6943F0400388 -:10B990002B61F9F714FC2A6941F6FD731340042862 -:10B9A0002B61D4D0C8E71F4D4FF400502B6943F0F2 -:10B9B00001032B611FFA88F32380F9F700FC0428A8 -:10B9C00012D1A31C0193019B4FEA1848A3F80080F1 -:10B9D0004FF40050F9F7F3FB2B6941F6FE721A4061 -:10B9E00004282A6106D0A7E72B6941F6FE721A40A7 -:10B9F0002A61A1E70D4B04349C42A5D1094B0428D0 -:10BA00001A6942F080021A6102D1FFF74EFF10B9A5 -:10BA10000A20F9F74FFF02B0BDE8F0813020002086 -:10BA2000230167450020024000F8010878FF010863 -:10BA30008A2802D08E2809D07047094B1B689B06C4 -:10BA40000DD5084B1B7853B9074A03E0054B1B780B -:10BA50002BB9064A064B1A60064B2D221A70704706 -:10BA60004C02002060130020840D0020580D00209F -:10BA700068130020711300207FB52B4B2B4C9A6963 -:10BA8000206042F001029A61294D03881026ADF82A -:10BA900004302846022301A98DF807308DF806608E -:10BAA000FDF738FF236828465B88ADF8043004238F -:10BAB0000DEB03018DF80630FDF72CFF22680F20F7 -:10BAC000137A03F003018900884003F0FC0303F1BB -:10BAD000804303F580339D6825EA0000012505FABF -:10BAE00001F198609868014399605368114A02A86F -:10BAF0005361029300238DF80C308DF80E508DF8B1 -:10BB00000D60FFF77DF823680B4A5B7A59B203F0AA -:10BB10001F039D404909094B42F821501A68084B00 -:10BB20003C3A1A6004B070BD00100240E0030020EF -:10BB3000000C01400004014000E100E02C20002046 -:10BB4000D803002013B504460068FFF783F8236884 -:10BB500001A81A8892B242F001021A80637B002287 -:10BB60008DF8043001238DF805308DF806208DF80E -:10BB70000730FFF725F802B010BD10B5AE20FCF776 -:10BB800001F8D420FBF7FEFF8020FBF7FBFFA82085 -:10BB9000FBF7F8FF3F20FBF7F5FFD320FBF7F2FFA1 -:10BBA0000020FBF7EFFF4020FBF7ECFF8D20FBF7B9 -:10BBB000E9FF1420FBF7E6FFA120FBF7E3FFC82015 -:10BBC000FBF7E0FFDA20FBF7DDFF1220FBF7DAFFDF -:10BBD0008120FBF7D7FFCF20FBF7D4FFD920FBF75D -:10BBE000D1FFF120FBF7CEFFDB20FBF7CBFF40209E -:10BBF000FBF7C8FFA420FBF7C5FFA620FBF7C2FF99 -:10BC0000AF20FBF7BFFFA620FBF7BCFFAE20FBF782 -:10BC1000B9FF2020FBF7B6FF0020FBF7B3FFB020F1 -:10BC2000FBF7B0FF4020FBF7ADFF0020FBF7AAFFBA -:10BC30001020FBF7A7FF4FF48064013C0020A4B262 -:10BC4000FBF79CFF002CF8D18120FBF79BFFC8205D -:10BC5000FBF798FFBDE81040AF20FBF793BF2DE93D -:10BC6000F341F9F717FDAB4D07462B68C31A002BBC -:10BC7000C0F2F08100F5C333A0332B60A64B2A79C4 -:10BC80001E78C6F38006B21A18BF01222E714EB17B -:10BC9000002A00F0DF81A14B5A789A7001225A7075 -:10BCA0001A7020E09D4B2AB1DA7842F00202DA7075 -:10BCB0009A785A70D9788A0705D4984A9068381AC1 -:10BCC000C043C00F00E00120944A187058B1CC075F -:10BCD00009D513799249013303F0030313710B441F -:10BCE00093F8803253708D4C23784BB3FFF745FFA8 -:10BCF000B020FBF747FF4020FBF744FF0020FBF795 -:10BD000041FF1020FBF73EFF4FF4806808F1FF3839 -:10BD100000201FFA88F8FBF731FFB8F1000FF5D1CA -:10BD20004046FBF733FF7F4B627853F82200FFF762 -:10BD3000B3FDE37823F00203E3707B4B3B44A36045 -:10BD40006378052B00F27381DFE813F008007101BE -:10BD50001B00770006001C010024D5E07349744ADB -:10BD60007448FFF757F80120FBF710FF7148FFF701 -:10BD700093FD714B6F4871491A68FFF74BF8022029 -:10BD800050E16F4B9A68984612F0020F2ED06D4C1E -:10BD90000A2321786C4FB1FBF3F203FB12133978BD -:10BDA000DBB2644800916949FFF734F8FDF7ECFB1A -:10BDB0000120FBF7EBFE5F48FFF76EFD644B3A781E -:10BDC000186824788378642102FB13444C4341783B -:10BDD0000220CB1A5A43B4FBF2F4E4B2FBF7D6FECE -:10BDE00021461520FFF70CFD032400E00124D8F8BC -:10BDF0000830180540F11B81564B57491F680968E8 -:10BE0000642397FBF3F203FB1273009149485349F3 -:10BE1000FFF700F8FDF7B8FB2046FBF7B7FE4548F3 -:10BE2000FFF73AFDF8F7D4FF0746601CFBF7AEFEBC -:10BE300015203946FFF7E4FCF9E00120484FFBF7F5 -:10BE4000A5FE4848FFF728FD3B68990715D54649E8 -:10BE50003848B1F90020B1F90230B1F904100324D7 -:10BE600000914249FEF7D6FFFDF78EFB0220FBF75B -:10BE70008DFE3048FFF710FD00E002243B68DA0732 -:10BE800018D53B492B48B1F90020B1F90230B1F97E -:10BE9000041004F1010800913649FEF7BBFFFDF7DD -:10BEA00073FB2046FBF772FE2248FFF7F5FC5FFAB2 -:10BEB00088F844463B681B0740F1B9802E491D486D -:10BEC000B1F90020B1F90230B1F9041000912B4909 -:10BED000FEF7A0FFFDF758FB2046A3E00E2C00F074 -:10BEE000A68060080130FBF751FE2046FFF7B1FC49 -:10BEF0003B78A34206D92020FFF768FC601CC0B243 -:10BF0000FFF7A7FC0234E4B21D4F3B78A342E5D80B -:10BF10008DE000BFA41B0020D5270020340700209F -:10BF2000AC500108B0000020404B4C00796B010878 -:10BF3000C6670108A91B0020C8000020816B01080A -:10BF400030200020B4050020980000208C6B0108F0 -:10BF5000B0050020B8050020BC050020A46B010836 -:10BF60004C020020B96B0108B4040020CF6B01081B -:10BF7000FC030020DF6B01087C020020EF6B01084E -:10BF8000DF090020354C364994F854273548FEF730 -:10BF900041FF0120FBF7FAFD3248FFF77DFC324BF1 -:10BFA00032491F782F483A46FEF734FF0220FBF74C -:10BFB000EDFD2C48FFF770FC0A2303FB07472C49D3 -:10BFC00097F857272748FEF725FFFDF7DDFA0320EE -:10BFD000FBF7DCFD2348FFF75FFC264997F856275F -:10BFE0002048FEF717FFFDF7CFFA0420FBF7CEFD40 -:10BFF0001C48FFF751FC204997F85A271948FEF7CB -:10C0000009FFFDF7C1FA0520FBF7C0FD1548FFF752 -:10C0100043FC1448194997F85B27FEF7FBFEFDF730 -:10C02000B3FA0620FBF7B2FD0E48FFF735FC8EB9D8 -:10C03000B020FBF7A7FD0820FBF7A4FD1720FBF7B6 -:10C04000A1FDEC7E0E4B185D013404F00304FFF7F4 -:10C05000BDFBEC7602B0BDE8F08100BF30200020CF -:10C06000FF6B0108A91B0020140E00200B6C0108B7 -:10C070001C6C0108286C0108346C0108416C010833 -:10C080004E6C01082DE9F3412D4B1B78042B50D148 -:10C090004020F9F76AFA044670B12046F9F731FCFE -:10C0A00018B90A20F9F7CFFBF7E7264B20461B68A3 -:10C0B0001969F9F72BFC0BE0224B21461B68009015 -:10C0C0001A6940200323FFF7B5FA0446002830D050 -:10C0D0001D4D286841798B0703D441F00201F9F71F -:10C0E0000BFC1A4B08221A6110221A612868F9F712 -:10C0F00017FC58B1144B154E082718687761F9F7EB -:10C100000AFC01462046F9F71DFC37612046F9F785 -:10C1100007FC0028EAD00D4E102777612046D5F89D -:10C120000080F9F7F8FB01464046F9F70BFC376150 -:10C13000DCE7074802B0BDE8F041F9F79DBC00BF5D -:10C14000FC090020F80900201C0A0020000C014016 -:10C15000856C01082DE9F743124C814604F19808DB -:10C1600094F84A60C6B9D9F804200025009501204A -:10C1700029460323FFF75EFA074620B97EB94FF43C -:10C1800096420126F1E7204629464C2205F0A9FEF9 -:10C190000123276084F84A304C344445E0D103B091 -:10C1A000BDE8F083200F0020F7B5524B524C2360BE -:10C1B000F9F7FCFF0120FCF70DFD002800F084805A -:10C1C0004E4BFF2118461622256805F08AFE0022F4 -:10C1D00002704B4A0121126803469707817504D506 -:10C1E00041700321817502218170560704D5997D24 -:10C1F000481C98750320585412F00A0F0CD09A7DF1 -:10C2000004219954511CC9B205205854D11C023242 -:10C210009975D2B2062199543A4FBA68900604D55E -:10C22000997D481C987507205854110608D5997DAA -:10C2300009205854881C01319875C9B20A205854F5 -:10C240007979082901D00E2904D1997D481C987567 -:10C250000B205854997D4FF00C0E481CC0B212F0C0 -:10C26000040F264E987503F801E003D00231B17532 -:10C2700010213154997D97F84571481CC0B24FF098 -:10C28000120E002F0CBF002702F001071B4E9875FD -:10C2900003F801E01FB10231B17513213154997DCA -:10C2A0001427481CC0B298755F549305134E03D5EC -:10C2B00002311523B175335413480021982205F03B -:10C2C00010FE2846FFF746FF0220FCF783FC70B102 -:10C2D0000220F9F74AF92568084C0146A06130B9F7 -:10C2E0000090AA6802200323FFF7A4F9A06103B01D -:10C2F000F0BD00BF5C210020B80F0020C01B002053 -:10C300004C02002030200020200F0020A44B2DE9FB -:10C31000F3411B78002B00F07381FDF7D9F8A14F92 -:10C3200006463B78834200F06B819F4D2B681B785B -:10C33000002800F0E88063BB0420F9F716F99B4C55 -:10C3400001462060DFF86C8290B143794FF41651BA -:10C3500088F81C308368C8F82030F9F7D7FA2068CD -:10C360000221F9F7C9FA20680421FCF7D5FA10E098 -:10C370008F4B04201B684FF416529B7800930223C6 -:10C38000FFF758F94379206088F81C308368C8F8B3 -:10C3900020302B6893F80080B8F1010F2BD10420D6 -:10C3A000F9F7E3F8834C0146606288B143794FF4B2 -:10C3B000964184F828308368E362F9F7A7FA606A47 -:10C3C0004146F9F799FA606A0421FCF7A5FA12E0F0 -:10C3D0000090434604204FF49642FFF72BF943792F -:10C3E000606284F828308368E3620379033B012BA1 -:10C3F00098BF84F830802B681D78022D41D104202D -:10C40000F9F7B3F86B4C0146606388B143794FF498 -:10C41000964184F838308368E363F9F777FA606B04 -:10C420002946F9F769FA606B0421FCF775FA0CE00C -:10C4300000902B4604204FF49642FFF7FBF8437917 -:10C44000606384F838308368E363656B5A4C94F812 -:10C450004A30022B09D094F89620022A00F0CE80B0 -:10C460001BB14C34002A18BF0024544B1C6044B14B -:10C47000204600214C2205F034FD0223256084F87B -:10C480004A30FDF777F8002800F0B6804C4D2B7845 -:10C49000002B40F0B1800820F9F767F8494C0146BD -:10C4A000206090B1434B42794FF4614183F84020C2 -:10C4B00082685A64F9F72AFA20680821F9F71CFA09 -:10C4C00020680821FCF728FA96E03F4B08201B68FB -:10C4D0004FF461429B7800930346FFF7ABF820606E -:10C4E00040B1012342792B70324B83F8402082689F -:10C4F0005A6481E0354B1B78002B7DD004232B70D0 -:10C50000FFF752FE78E083B9284CDFF8A880206856 -:10C5100098F81C10F9F7F0F92068D8F82010F9F70E -:10C52000F5F920680421FCF7C5F92B681B78012B6D -:10C530000DD1204C606A94F82810F9F7DDF9606A93 -:10C54000E16AF9F7E3F9606A0421FCF7B3F92B68B3 -:10C550001B78022B0DD1174C606B94F83810F9F74B -:10C56000CBF9606BE16BF9F7D1F9606B0421FCF753 -:10C57000A1F9FCF7FFFF00283ED0114D2B7813F0F6 -:10C58000FB0F39D0114B0F4C1B780BB320680821DF -:10C59000FCF790F904232B70FFF706FE2AE000BF9A -:10C5A0009C0500209D050020A0050020A40500207A -:10C5B000C8050020C01B0020200F0020D805002047 -:10C5C000E8050020EC050020B40D0020520D0020ED -:10C5D000DFF83480206898F84010F9F78DF920686A -:10C5E000D8F84410F9F792F920680821FCF762F9AD -:10C5F00004232B70002323603E7001E04C3434E7A9 -:10C6000002B0BDE8F08100BFC01B002037B53D4936 -:10C610000B7813F0010F03F0040268D0002A6FD1E9 -:10C62000980764D443F004030B70374B1A88374BD8 -:10C630001A80374B9A681C4612F4806F05D004208C -:10C64000FCF7A8FA08B1FCF745F9A3681B0357D516 -:10C650008020FCF79FFA08B1FCF73CF92D4D2B78B0 -:10C66000012B4DD18020F8F780FF2B4C0146206034 -:10C6700090B14279294B4FF4E1311A708268284B0E -:10C680001A60F9F743F920680221F9F735F92068B3 -:10C690008021FCF741F90EE000904FF4E132802058 -:10C6A0000223FEF7C7FF206028B142791B4B1A70A6 -:10C6B00082681B4B1A6023680BB92B7020E0194B62 -:10C6C000194C1B680021A36404F1540002231422B6 -:10C6D0002B70E164216505F004FC04F17403A3668A -:10C6E00004F1D803E36604F59E73236708E03AB9C2 -:10C6F0000220FF21012203B0BDE83040F9F7B4B8B1 -:10C7000003B030BDD5270020E0040020200E00201B -:10C7100030200020BA0D00201C2000202020002006 -:10C72000242000202C200020C01B00202DE9F04FE9 -:10C730008E4C8BB02378023B042B00F2EA83DFE8B7 -:10C7400013F007002B0005009900D60010267BE0AF -:10C75000874B1A68874B1B6864339A4240F2D9832F -:10C760001026854D854B2A689846985C2F4638B12F -:10C77000F9F796F92A68013E02F101022A60F0D128 -:10C780003B6818F80330002B40F0C383032222706B -:10C79000794A13607A4A6BE0774D7A4B2E6893F8AA -:10C7A0000080052E3FD8754FC8F1080807EB8603B7 -:10C7B000586E05F0D7FB002E14BF02230923704EDC -:10C7C00008FB1308346833680F33A34202DA444588 -:10C7D00027D10AE04445FADA2B6807EB83035B6E46 -:10C7E000185DF9F75DF90134EDE7674B5B79012BD3 -:10C7F00008D00A20F9F754F92B6801332B60002385 -:10C80000336086E32C20F9F74BF92B6807EB83079D -:10C81000FC6F013C14F8010F0028EAD0F9F740F949 -:10C82000F8E7346075E3584B9B681A064CBF042345 -:10C8300005232370002358E0F9F732F92A68013EF6 -:10C8400002F101022A6009D04B4D4C4B2A689846F0 -:10C850001A4492F894002F460028EDD13B684344D7 -:10C8600093F89430002B40F0548305222270424A02 -:10C8700013604EE3404D2B680B2B32D8DFE803F0FA -:10C8800006330A330D33131F24292D333F48FEF797 -:10C89000AFFA28E03E483F490EE03F483F49404A52 -:10C8A000FEF7A6FA1FE0384B0A2193F854273D48BB -:10C8B00001FB023393F85617FEF79AFA13E0324B56 -:10C8C0003948B3F8D010F7E72F4B3848B3F8D210F7 -:10C8D000F2E7374B3748D968EEE7374B37481988C6 -:10C8E000EAE7062323702B6801332B6011E3344DF4 -:10C8F000344B2C681B682360334B1A6862605A689B -:10C900009B68A260E360314B1A6822615A689B6899 -:10C910006261A3612E4B1A68E2615A689B682262C9 -:10C9200063622C4B1A8822855A8862859A88DB8834 -:10C93000A285E385284B1A8822865A889B886286BE -:10C94000A386264B1A88E2865A889B8822870D4A3E -:10C950006387117800238B4244DA214804EB4302B9 -:10C9600030F8130001339087F5E700BFBA0D0020BF -:10C970002C200020081C00200C1C00202C54010836 -:10C98000601D0020E127002030200020A56E010856 -:10C99000C26E0108C6670108DA6E0108B1670108B6 -:10C9A000BD670108F16E0108FE6E0108106F0108F5 -:10C9B000EC030020226F010800000020356F010801 -:10C9C000281C0020C0270020C4120020D012002004 -:10C9D000DC12002062020020F4040020B4040020D5 -:10C9E000A8270020B14B5B89A4F85E30B04BD3F888 -:10C9F0000090984619F01F02019240F0868049206D -:10CA0000F9F74EF8D8F80000F9F750F82068F9F770 -:10CA10004DF86068F9F759F8A068F9F756F8E0683A -:10CA2000F9F753F82069F9F750F86069F9F74DF80C -:10CA3000A069F9F74AF8E069F9F747F8206AF9F7C9 -:10CA400044F8606AF9F741F8B4F92800F9F73DF8BD -:10CA5000984FB4F92A00F9F738F8B4F92C00F9F72F -:10CA600034F8B7F8D030B4F92E000126C01AF9F71F -:10CA70001DF8B4F93000F9F728F8B4F93200F9F7E5 -:10CA800024F8B4F93400F9F720F8B4F93600F9F7CE -:10CA90001CF8B4F93800F9F718F8B4F93A00F9F7C6 -:10CAA00014F8B4F93C00B7F8D030C01AF8F7FEFF1C -:10CAB000814803789E420ADA04EB4603B3F93C004E -:10CAC000B4F93C300136C01AF8F7FFFFF0E77B7984 -:10CAD000012B06D12B68B3F95E00A0F2DC50F8F709 -:10CAE000F4FF2B68754A76496B60AB609B1A9B100C -:10CAF0004B430321013393FBF1F101EB41015B1A3D -:10CB0000642101FB03222A60FEE150206E68F8F7E1 -:10CB1000C7FFAA682B6810681B68002718446B6859 -:10CB20001B68A0EB4300F8F7D0FFE219F319506837 -:10CB30005B680437C01AF8F7C8FF0C2FF5D1002343 -:10CB4000E118F2180969126903F1080004338A1A1E -:10CB50000C2B69464250F3D10022134602A881589B -:10CB600001F120003F2820D801F108000F2806D845 -:10CB70000231032904D9002B08BF012300E002235E -:10CB800004320C2AEAD1012B029813D0022B1FD0B9 -:10CB9000039B00F0030003F003039B0043EA001033 -:10CBA000049B03F0030318431EE004AA01A84FF0FE -:10CBB000000A1DE000F00F0040F04000F8F770FFA1 -:10CBC000049B03F00F02039B42EA0310C0B20BE088 -:10CBD00000F03F0040F08000F8F762FF9DF80C0085 -:10CBE000F8F75EFF9DF81000F8F75AFF002769E09C -:10CBF00052F804194FEA8A0A01F18007FF2F10D971 -:10CC000001F50047B7F5803F02D24AF0010A08E07B -:10CC100001F50001B1F1807F34BF4AF0020A4AF009 -:10CC2000030A8242E4D16AF03F00C0B2F8F738FF4D -:10CC30004FF0000B0AF00301022910D003291BD08A -:10CC4000012903D002A911F80B0024E002AA52F82E -:10CC50000B70F8B2F8F724FFC7F307201BE002AB14 -:10CC600053F80B70F8B2F8F71BFFC7F30720F8F77B -:10CC700017FFC7F307400EE002A850F80B70F8B298 -:10CC8000F8F70EFFC7F30720F8F70AFFC7F30740CE -:10CC9000F8F706FF380E0BF1040BF8F701FFBBF1B4 -:10CCA0000C0F4FEAAA0AC5D1A0E700BF120000206E -:10CCB000101C002030200020E1270020341C002020 -:10CCC000295C8FC2E219F319D069DB690437C01AF5 -:10CCD000F8F7FBFE0C2FF5D10023E218B2F928106B -:10CCE000F218B2F928208A1A02A941F81320023357 -:10CCF000082BF2D1884B06AF03F1100E1868596863 -:10CD00003A4603C2083373451746F7D105AA01A86E -:10CD1000002352F804199B00DBB269B101F1080746 -:10CD20000F2F02D843F0010306E08031FF2994BFA2 -:10CD300043F0020343F003038242EAD10AA800EB66 -:10CD4000131203F00F03034412F8107C13F8103C85 -:10CD50004FF0000B43EA0717FFB23846F8F7A0FE82 -:10CD600007F00302022A15D0032A19D0012A25D17F -:10CD70000AA901EB8B0252F8200C52F81C1C00F09F -:10CD80000F0040EA0110C0B2F8F78AFE0BF1010B68 -:10CD9000BF0813E00AAB03EB8B0212F8200C0BE088 -:10CDA0000AA800EB8B0252F8202CD0B20092F8F7C0 -:10CDB00077FE009AC2F30720F8F772FE0BF1010B21 -:10CDC000BBF1030F4FEA9707CADD00272A6807F176 -:10CDD000180332F913006A68013732F91310AA6890 -:10CDE00032F9133002220B4493FBF2F3C01AF8F726 -:10CDF0006CFE032FEAD100272A6807F118035B00B5 -:10CE00001A44B2F906006A6801371A44B2F90610EA -:10CE1000AA681344B3F9063002220B4493FBF2F3E1 -:10CE2000C01AF8F752FE032FE6D100273B490B78D2 -:10CE30009F4217DA2A6807F11C035B001A44B2F913 -:10CE400004006A6801371A44B2F90410AA6813444E -:10CE5000B3F9043002220B4493FBF2F3C01AF8F743 -:10CE600034FEE3E72E4B5A791F46012A06D1B4F966 -:10CE70005E00B6F95E30C01AF8F727FE6B682A68C4 -:10CE8000AB60284B28496A60D21A92104A430321AA -:10CE9000013292FBF1F101EB4101521A642101FBD5 -:10CEA00002332B60BB681B062ED5204C204D226818 -:10CEB0002B689A4209D162686B689A4205D1019A3F -:10CEC0000F2A10D119F47E6F0DD14820F8F7E8FD34 -:10CED0002068F8F7FAFD6068F8F7F7FD23682B6023 -:10CEE00063686B600EE0134A114B11782A7C914203 -:10CEF00008D1114A99681068884203D15268DB68EA -:10CF00009A4201D0F8F7E5FDD8F800300133C8F8AF -:10CF100000300BB0BDE8F08FCD550108E1270020AF -:10CF200030200020341C0020295C8FC2240E0020F9 -:10CF3000141C0020C4050020D00500204B8810B52B -:10CF4000DC0607D52C4B14791B6853F824402B4B77 -:10CF500043F820404B889B0607D5274B54791B6824 -:10CF600053F82440254B43F820404B881C070DD52F -:10CF7000234B0C781B78B3EB141F07DB1E4BD478C4 -:10CF80001B6853F824401D4B43F820404B889B07F7 -:10CF90000DD51C4B0C781B78B3EB141F07DC164B1C -:10CFA00054781B6853F82440144B43F820404B88B6 -:10CFB000DC070ED5144B0C781B7804F00F049C4250 -:10CFC00007DC0D4B14781B6853F824400B4B43F8D7 -:10CFD00020404B885B070ED50C4B09781B7801F07D -:10CFE0000F01994207DB044B92781B6853F822200B -:10CFF000024B43F8202010BD240A00201406002014 -:10D00000CB060020C9060020C8060020CA06002062 -:10D01000234B70B519684FF47A73B1FBF3F1214BD0 -:10D0200021481A78214B224D1B78F8F791FF214BAC -:10D0300021481968214B2E68B1FBF3F1F8F788FFFE -:10D0400000241F4BE2B253F8221049B1012303FA26 -:10D0500002F2324202D01B48F8F77AFF0134F0E7BF -:10D060002A6892070DD5184A1848127803EB8203F4 -:10D07000196AF8F76DFF164B197A11B11548F8F7D0 -:10D0800067FF1548F8F7F8FCBDE87040134B1448EB -:10D090001A88144B92B219884FF4EF63F8F758BF0F -:10D0A0002C200020B4050020087201089800002000 -:10D0B0004C020020A80000204672010840420F00E8 -:10D0C000E05501086F640108D72700206472010849 -:10D0D000580400206E7201083E6801083C180020C8 -:10D0E00072720108FC0400200C4B07B51B6819681C -:10D0F00019B10B4A9069014391619A889868ADF81B -:10D10000042002228DF8072004220DEB02018DF885 -:10D110000620FCF7FFFB03B05DF804FB400700208E -:10D12000001002402DE9F74FA24E0C463778054615 -:10D130001146006891469B4622467B1C06F8043B3C -:10D14000FDF788FDAB686868ADF8043018238DF8EA -:10D15000063001A902238DF80730FCF7DBFB2B7B9F -:10D160003F0106EB070A2C680C2B00F2F280DFE887 -:10D1700013F00D00F000F000F0004D00F000F000A2 -:10D18000F0008200F000F000F000B600238C8A4826 -:10D1900023F001031B041B0C2384218CA288238B06 -:10D1A000844223F073034FEA03434FEA134389B2E7 -:10D1B00092B243F0700314D000F50060844210D0A6 -:10D1C00000F5406084420CD000F58060844208D0B5 -:10D1D00000F58060844204D021F0020141F0030197 -:10D1E00007E021F00E0122F4407241F0030142F405 -:10D1F0008072A2802383A4F834B02184238B23F08F -:10D2000008031B041B0C43F0080332E0238C6A481C -:10D2100023F010031B041B0C2384218CA288238B76 -:10D22000844223F4E6434FEA03434FEA134389B2AF -:10D2300092B243F4E04308D000F50060844204D089 -:10D2400021F0200141F0300107E021F0E00122F45B -:10D25000406241F0300142F48062A2802383A4F84E -:10D2600038B02184238B23F400631B041B0C43F48C -:10D27000006323836DE0238C4F4823F480731B04E9 -:10D280001B0C2384218CA288A38B844223F073037C -:10D290004FEA03434FEA134389B292B243F070035B -:10D2A00008D000F50060844204D021F4007141F4FC -:10D2B000407107E021F4606122F4405241F4407172 -:10D2C00042F48052A280A383A4F83CB02184A38BB3 -:10D2D00023F008031B041B0C43F0080338E0B4F8E8 -:10D2E00020C0354A2CF4805C4FEA0C4C4FEA1C4CB1 -:10D2F000A4F820C0B4F820C0A388B4F81C802CF493 -:10D30000005C28F4E6484FEA08484FEA0C4C4FEA24 -:10D3100018484FEA1C4C94429BB248F4E0484CF445 -:10D32000405C03D002F50062944203D123F48043B1 -:10D3300043F48043A380A4F81C80A4F840B0A4F870 -:10D3400020C0A38B23F400631B041B0C43F4006375 -:10D35000A383AB7B43B1B4F844306FEA43436FEA35 -:10D3600053439BB2A4F8443023889BB243F001039B -:10D3700023802B7B0C2B14D8DFE803F00713131347 -:10D380000A1313130D131313100004F1340307E0F1 -:10D3900004F1380304E004F13C0301E004F140032C -:10D3A000F3515046AAF80890CAF8044003B0BDE80B -:10D3B000F08F00BF641D0020002C014040F2E933D3 -:10D3C0000E4A1189890709D5908140F2E9330B4A49 -:10D3D0001189C9070DD59089C0B27047013B9BB236 -:10D3E000002BEDD1064BFF201A88013292B21A8031 -:10D3F0007047013B9BB2002BE9D1F3E700380040B6 -:10D40000F2060020434A2DE9F84F916840F20113DB -:10D410000B4040F201118B4293460CD13E4B93F8E6 -:10D42000C42093F8C59083F8C520B9EB020918BF52 -:10D430004FF0010901E04FF001094FF00008374BB0 -:10D440005FFA88F41B78A34261D9354B354E1B68CF -:10D45000354F23B93B685B8926F8143054E03A68AD -:10D46000072C94BF12F804A0A2462C4851469847B6 -:10D47000DBF808300546DB0509D5B9F1000F06D009 -:10D480002A4B50461B6829461B68DB699847A5F262 -:10D49000EE2240F2DC5392B29A4288BF3B68DBF83E -:10D4A000082088BF5D8942F20103134053B3204B2B -:10D4B0001978194B01F0030202EB840293F826015C -:10D4C00003EB4202A2F8C6501A4620B9032919D923 -:10D4D000012183F8261102EBC403B3F8C810B3F896 -:10D4E000C65002EB44020D44B3F8CA10B3F8CC3076 -:10D4F0000D441D44ADB2A2F8285104232DB295FB72 -:10D50000F3F5ADB226F8145008F1010897E7BDE82D -:10D51000F88F00BF30200020641D0020DF090020AC -:10D52000E8090020960600203C010020400200206F -:10D53000BC0D00202DE9F74F2A4B157C9B6801900C -:10D5400003F0400903F4007C03F40058032D45D890 -:10D550000C246C43244B0198E618377A0135384285 -:10D560003AD0E35C4BB1012B07D0032B04D0042B42 -:10D5700014BF0423032300E00223DFF870A01F017F -:10D580000AEB0704B9F1000F06D11AF807B0ABF1A6 -:10D59000030BBBF1010F1FD9BCF1000F06D0B8F18E -:10D5A000000F03D11AF80770042F15D04F7B94F8A1 -:10D5B0000CA007EA0A0ABA450ED14F686068874294 -:10D5C0000AD38F68A068874206D8137094605660AB -:10D5D000D1601574104602E0EDB2B7E7002003B049 -:10D5E000BDE8F08F30200020680000202C56010894 -:10D5F000094B30B59D68094B05F480551868084BF8 -:10D600001C6800230DB1828800E0A28805495A52A7 -:10D610000233182BF6D130BD30200020AC1E002084 -:10D62000B01E0020BC0F0020F8B50024204BE0B253 -:10D630001F78B8420CD21F4B33F810101E4B53F812 -:10D6400020301BB10B2801D8DB6898470134EDE787 -:10D650001A4B9B685B032AD50025194E2B46EAB26C -:10D66000BA4224D2726854689C4218D02046FCF713 -:10D6700004F9EFF31283502282F3128811494FF01C -:10D68000280CA28C0CFB001092B201324262A28ADA -:10D69000DBB292B242F00102A28283F3118856F803 -:10D6A000043F00221B6801351A802346D7E7F8BDE6 -:10D6B000E1270020A8270020B40800203020002007 -:10D6C000B0080020D01E00202DE9F04FAE4E85B0EE -:10D6D0003778032F14D9AD4BAD48B3F90410B0F926 -:10D6E00004200029B8BF49426FF063035B1A9A42D5 -:10D6F00004DB01F164039342A8BF134683801FE05B -:10D70000012F1DD8A34BA44C1B78013B142B00F216 -:10D71000E181DFE813F09100DF01DF0168009F0085 -:10D72000DF01DF012F01DF01DF01DF01DF01DF01A9 -:10D73000BD00DF01DF01DF01DF01DF01A101B80171 -:10D74000924B9649B3F806A0914B0968B3F8028052 -:10D75000B3F80090B3F904B0914C02910025BD429A -:10D7600004F11004CED20FFA8AF001F051FB54F804 -:10D77000101C01F0A1FB03460FFA88F0019301F0A1 -:10D7800047FB54F8081C01F097FB019B0146184623 -:10D7900001F08AFA03460FFA89F0019301F038FB91 -:10D7A00054F80C1C01F088FB019B0146184601F05F -:10D7B0007BFA029A034692F90000019340420BFB68 -:10D7C00000F001F025FB54F8041C01F075FB019BEF -:10D7D0000146184601F068FA01F034FD714B23F858 -:10D7E00015000135BBE702210420F8F7FAF9684D6E -:10D7F0000121AF8878431FFA80F80420F8F7F1F987 -:10D800006D8800FB05801FFA80F80420F8F7F8F90E -:10D810004044208102210520F8F7E3F978430121F3 -:10D8200087B20520F8F7DDF900FB057087B2052007 -:10D83000F8F7E6F938440BE005200121F8F7D1F9B3 -:10D84000534B9D88684385B20520F8F7D9F92844E1 -:10D8500060813FE1544B00201D68F8F7D1F9DFF8F3 -:10D86000648195F90630B8F902203227534393FBBF -:10D87000F7F3184420800120F8F7C2F995F90E302B -:10D88000B8F90020534393FBF7F73844608021E157 -:10D89000464B1B7813F0040F454B02D11B689B8845 -:10D8A0000BE01968394A0B88B2F9062049889A4278 -:10D8B00003DB9142B4BF0B461346E381E289394B47 -:10D8C000394F1A803B4B1B681D7845B30220F8F78F -:10D8D00097F93A68B2F91030518A984203DB0BB2DB -:10D8E0009842B8BF0346344909684889C3EB000E23 -:10D8F000324B0FFA8EFE19880FFA81FCF44501DADB -:10D900000D4401E001DD4D1B1D8092F91620B3F995 -:10D9100000305343642293FBF2F31844A080284B59 -:10D920001B88DB050CD5194B1A88D7F80090E280CC -:10D9300022819A88184F62815B880325A38101E0C8 -:10D94000134BF1E709EBC50393F90630B7F90680ED -:10D95000284608FB03F8642398FBF3F8A7F8068031 -:10D96000F8F74EF901354044072DF88007F102071A -:10D97000E8D1AFE00D4B1B7813F0040F0C4B23D113 -:10D980001B689B882CE000BFE1270020620200207A -:10D99000BC120020940500201200002098050020F1 -:10D9A00004090020A8270020A81E0020D527002059 -:10D9B000B01E0020B41E0020B81E0020A41E0020AF -:10D9C00054020020A80300201968AD4A0B88B2F960 -:10D9D000062049889A4203DB9142B4BF0B461346A6 -:10D9E000E381E289A74BA84D1A80A84B03201B882E -:10D9F0000121DF0503D5F8F7F4F8A14F02E0F8F7AD -:10DA0000F0F8A34FB7F80280022100FB08F01FFADC -:10DA100080F90320F8F7E5F83F88012100FB079023 -:10DA2000E8800420F8F7DDF800FB08F002211FFA77 -:10DA300080F80420F8F7D5F800FB07802881032040 -:10DA4000F8F7DEF8E3881844E0800420F8F7D8F807 -:10DA50002389184420813DE001210420F8F7C1F812 -:10DA60008B4D6F88784387B204202781F8F7C8F878 -:10DA70003844208101210520F8F7B3F82D88684348 -:10DA800085B26581E0E6824B0325B3F804909846A1 -:10DA900028460221F8F7A5F800FB09F0012187B21A -:10DAA0002846F8F79EF8C5F106035B0838F81330EE -:10DAB00000FB037087B224F815702846F8F7A0F829 -:10DAC000384424F815000135072DE1D16C4BDA8874 -:10DAD0006C4B1A806F4DDFF8E491AB6813F0200FA8 -:10DAE00034D00020F8F78CF8208080460120F8F729 -:10DAF00087F8694B644F1B6860801A0626D5674B10 -:10DB00001B681B7813F0020F654B23D0D9F800C0B7 -:10DB1000B3F900109CF90E209CF906C0B3F902304D -:10DB20004A43CCF1000C03FB0CF3322192FBF1F2DF -:10DB30006FF0310C92B293FBFCFC9444E04493FBF5 -:10DB4000F1F1A7F800800A4410447880D9F8001059 -:10DB5000002319E0D9F80010B3F902C091F90620AA -:10DB6000B3F900300CFB02FC32229CFBF2FCE044D7 -:10DB7000A7F8008091F90E104B4393FBF2F2E3E714 -:10DB8000E2520233102B0CD0E05E31F9232001EB7E -:10DB9000830790427F88F3DB3AB28242A8BF0246F5 -:10DBA000EEE73E4B1B681B785B0704D4354934789D -:10DBB000088801231BE03B4B00241F780423043F0B -:10DBC000FFB25FFA87F84FFA88F2D4420BD4364A94 -:10DBD00003F10109381932F813105FFA89F9C0B25C -:10DBE000FBF78DFE4B460134042CECD1DEE7A3425B -:10DBF00008D231F9132000B28242A8BF104680B289 -:10DC00000133F4E7294B4FEA44081A68AB6803F480 -:10DC100080550395244D03F01009254BB5F9066096 -:10DC2000244D1B782F68244D03F00403DBB2D5F894 -:10DC300000C002930023434562D0B2F802A004B2B0 -:10DC4000544505DD0F4CC0EB0A0A1D5B55441D53BE -:10DC5000039D0C4C002D33D07D8931F903A0AE42D9 -:10DC6000CBBFBCF802509588B2F802B0BCF800B047 -:10DC7000AA4503DBDA45B4BF55465D46E55238E0B8 -:10DC800062020020A8270020120000205402002079 -:10DC9000BC1200203020002050020020BC1E0020BA -:10DCA000A80300208B07002096060020B01E00204D -:10DCB000D5270020B81E0020AC1E0020A81E002082 -:10DCC00031F903A01588B2F802B0AA4503DBDA45A2 -:10DCD000B4BF55465D46E55204EB030ABC89A64233 -:10DCE00007DAB9F1000F01D1148800E09488AAF88E -:10DCF0000040029C14B9044C1C5BCC5202339AE7DE -:10DD000005B0BDE8F08F00BFBC0F00202DE9F04149 -:10DD1000FDF7CBFD10B90A20F7F7CCFD824C4FF48C -:10DD2000EF622046814904F0D3F894F854374FF459 -:10DD3000E072022B84BF002384F8543794F85437E0 -:10DD40007B4E02FB034303F5057393F850203360C9 -:10DD5000022A84BF002283F8502093F85030754A7D -:10DD600013700A2202FB0343734A03F256731360D3 -:10DD7000A36842F201021A403AB944F208021A407A -:10DD80001AB9694A43F400539360A368D90703D5CD -:10DD90004FF40050FBF793FBA3685A0409D5082001 -:10DDA000FBF78DFB4FF40050FBF789FB0120FBF7DD -:10DDB00086FBA3681B0706D54FF40050FBF77FFBDB -:10DDC0000120FBF77CFBA3689F040ED54FF40040B5 -:10DDD000FBF775FB4FF40060FBF771FB4FF48030ED -:10DDE000FBF76DFB4020FBF76AFBA3685D0603D5DC -:10DDF0004FF48030FBF763FBA368980408D503F465 -:10DE00002063B3F5206F03D14FF40060FBF757FB9D -:10DE10004A4D4B4B2F461D60F8F7C8F9494B05F1A9 -:10DE20001C0201201A60FAF734FE01460120FAF7BD -:10DE3000FFFC002849D00220FAF72BFE0146022001 -:10DE4000FAF7F6FC002840D02020FAF722FE01461F -:10DE50002020FAF7EDFCA368190601D5002834D07C -:10DE60001020FAF716FE01461020FAF7E1FCA3682D -:10DE70001A0700D548B30420FAF70BFE0146042028 -:10DE8000FAF7D6FC30B90820FAF703FE014608205D -:10DE9000FAF7CEFCA3685B0503D400231A461946A3 -:10DEA00009E00028F9D110E079B90121C00708D4B0 -:10DEB0000C33302B0BD024481844007A8507F5D555 -:10DEC000F2E70132D2B2022AF2D9F8F799F9F7F75C -:10DED000D3FB1E4D1E4B32681D601E4B101D18607B -:10DEE00002F175010023A846CD5C55B901EB030E84 -:10DEF0009EF802C09EF803E0F44502D2164B1D7056 -:10DF000002E00433A02BEFD1144B15490B601549E7 -:10DF100050330B601178144B012903D0022929D00A -:10DF2000124928E0124926E03020002000F80108BC -:10DF3000E8030020140E00208C0500204021002062 -:10DF40003C010020B80F00206800002000210020C4 -:10DF50000C0E0020100E002048000020242100207C -:10DF600004040020A00500209C000020056E00088D -:10DF70005D6C000833491960334B02F5D9721A60A1 -:10DF8000FBF7D6FB3568314B05F5D3721A60304B81 -:10DF900000229A802F4B304A304E136005F5B37241 -:10DFA0003260A3F1220272602E332D4A05F5D7713B -:10DFB000F36005F5D87311607361C6F808803761A6 -:10DFC000B4F8F00000F020FFF061B4F8F20000F0C7 -:10DFD0001BFF95F858303062337695F87430183658 -:10DFE000737094F825312A1D33731E4BB5F8620106 -:10DFF0001E601D4B1A601D4B05F160021A601C4B20 -:10E0000005F164021A601B4B05F25D121A601A4B8F -:10E01000C3F8008000F0FCFE0146184801F000F84B -:10E02000174900F049FF174B17491860E86D00F0D9 -:10E0300043FF01464FF07C5000F0F2FF134B186095 -:10E04000BDE8F081AD700008200A002028200020E3 -:10E05000C80900202821002070040020A81E0020EC -:10E0600098050020A4040020D4030020F004002020 -:10E07000C80200207C0500208405002000006144C7 -:10E080004C3D0F4488050020DB0F4940EC04002084 -:10E0900001480249FBF7AEBB00080040481F0020C2 -:10E0A00001480249FBF7A6BB00040040201F0020E6 -:10E0B0004FF080400149FBF79DBB00BFF81E0020D8 -:10E0C00001480249FBF796BB002C0140D01E0020FE -:10E0D00001480249FBF78EBB002C0140D01E0020F6 -:10E0E00038B5204CD4F8F0301D88ADB2AA0618D54A -:10E0F000D4F8CC201AB1988880B2904711E09B8860 -:10E10000D4F8BC20D4F8B410DBB28B54D4F8BC20C3 -:10E11000D4F8AC300132B2FBF3F103FB1123C4F8A5 -:10E12000BC302B061DD5D4F8C820D4F8C4100D4B34 -:10E130008A4210D0D3F8B800D3F8F010805C0132D6 -:10E14000C0B28880D3F8B010B2FBF1F001FB10220E -:10E15000C3F8C82038BDD3F8F030DA6822F0800266 -:10E16000DA6038BDD01E00200F4BD3F8442111884F -:10E17000090618D5D3F81C11D3F8180181420ED026 -:10E18000D3F80C01405C0131C0B29080D3F8042177 -:10E19000B1FBF2F002FB1011C3F81C117047D368F9 -:10E1A00023F08003D3607047D01E00200C480D4B35 -:10E1B0004FF400525A60D0F828214FF6FE731168D0 -:10E1C0000B401360D0F81821D0F81C319A4202D0CD -:10E1D000F430FCF78DBC012380F83831704700BF64 -:10E1E000D01E002000000240FCF79BBCFCF799BC4D -:10E1F000084A13689B020BD5074B00211970074989 -:10E200004FF6FE73086803400B604FF40013536031 -:10E21000704700BF00000240CE2700206C00024083 -:10E22000F9F7E2BFF9F7E0BFF6F7E2BAF6F7E0BABE -:10E23000074B1A685969490408D5520406D54FF4AA -:10E2400080425A61034B012283F84821704700BF86 -:10E2500000040140D01E002010B51B4B1A78510756 -:10E2600031D51A4C22F004021A70A3685A050AD557 -:10E27000FEF74CF804200121FAF79BFC18B104F5D5 -:10E280009670FDF767FFA3681B031CD5104B1A7827 -:10E29000012A0ED90F4C0122206821791A70F7F754 -:10E2A0002BFB2068A168F7F731FB20688021FAF783 -:10E2B00001FB80200121FAF77CFC20B10648BDE873 -:10E2C0001040FDF747BF10BDD527002030200020AB -:10E2D000BA0D00201C2000205C21002070B5FAF748 -:10E2E000D9FC38B3144C237A0BB9A38070BD134DFD -:10E2F0002E78C6F38000FAF7DFFC90B1104B46F0A1 -:10E3000002061A680F4B51892E7019805189598065 -:10E3100052899A800C4AD2685288DA80E3880133A5 -:10E32000E380FAF7A3FC10B92B785B0702D4BDE8B1 -:10E33000704091E770BD00BFC8090020D5270020BC -:10E34000C4090020960600201C2000200F4B1A68EC -:10E3500042F001021A6059680D4A0A405A601A6870 -:10E3600022F0847222F480321A601A6822F4802229 -:10E370001A605A6822F4FE025A604FF41F029A6033 -:10E38000044B4FF000629A60704700BF00100240DB -:10E390000000FFF800ED00E0024B1A6801321A603D -:10E3A000704700BF2C20002008B5084BB3F8D800F8 -:10E3B000074B1A780023D9B2914204D2054921F8BB -:10E3C00013000133F7E7FFF72FF9FEE72C200020B9 -:10E3D000E1270020A827002081F0004102E000BFD3 -:10E3E00083F0004330B54FEA41044FEA430594EA15 -:10E3F000050F08BF90EA020F1FBF54EA000C55EA50 -:10E40000020C7FEA645C7FEA655C00F0E2804FEA20 -:10E410005454D4EB5555B8BF6D420CDD2C4480EA02 -:10E42000020281EA030382EA000083EA010180EA32 -:10E43000020281EA0303362D88BF30BD11F0004F80 -:10E440004FEA01314FF4801C4CEA113102D04042B6 -:10E4500061EB410113F0004F4FEA03334CEA1333F1 -:10E4600002D0524263EB430394EA050F00F0A78009 -:10E47000A4F10104D5F1200E0DDB02FA0EFC22FA04 -:10E4800005F2801841F1000103FA0EF2801843FAF8 -:10E4900005F359410EE0A5F120050EF1200E012AE9 -:10E4A00003FA0EFC28BF4CF0020C43FA05F3C01827 -:10E4B00051EBE37101F0004507D54FF0000EDCF1A0 -:10E4C000000C7EEB00006EEB0101B1F5801F1BD349 -:10E4D000B1F5001F0CD349085FEA30004FEA3C0C4D -:10E4E00004F101044FEA445212F5800F80F09A8043 -:10E4F000BCF1004F08BF5FEA500C50F1000041EB47 -:10E50000045141EA050130BD5FEA4C0C404141EB4A -:10E51000010111F4801FA4F10104E9D191F0000F71 -:10E5200004BF01460020B1FA81F308BF2033A3F1F4 -:10E530000B03B3F120020CDA0C3208DD02F1140CEB -:10E54000C2F10C0201FA0CF021FA02F10CE002F126 -:10E550001402D8BFC2F1200C01FA02F120FA0CFC1F -:10E56000DCBF41EA0C019040E41AA2BF01EB045168 -:10E57000294330BD6FEA04041F3C1CDA0C340EDC66 -:10E5800004F11404C4F1200220FA04F001FA02F3A9 -:10E5900040EA030021FA04F345EA030130BDC4F167 -:10E5A0000C04C4F1200220FA02F001FA04F340EA5C -:10E5B0000300294630BD21FA04F0294630BD94F00D -:10E5C000000F83F4801306BF81F480110134013DF4 -:10E5D0004EE77FEA645C18BF7FEA655C29D094EA65 -:10E5E000050F08BF90EA020F05D054EA000C04BFE3 -:10E5F0001946104630BD91EA030F1EBF00210020CE -:10E6000030BD5FEA545C05D14000494128BF41F06C -:10E61000004130BD14F580043CBF01F5801130BDD0 -:10E6200001F0004545F0FE4141F470014FF000005B -:10E6300030BD7FEA645C1ABF194610467FEA655C0C -:10E640001CBF0B46024650EA013406BF52EA0335AE -:10E6500091EA030F41F4002130BD00BF90F0000F9C -:10E6600004BF0021704730B54FF4806404F13204D8 -:10E670004FF000054FF0000150E700BF90F0000F91 -:10E6800004BF0021704730B54FF4806404F13204B8 -:10E6900010F0004548BF40424FF000013EE700BF88 -:10E6A00042004FEAE2014FEA31014FEA02701FBF18 -:10E6B00012F07F4393F07F4F81F06051704792F0EA -:10E6C000000F14BF93F07F4F704730B54FF4607464 -:10E6D00001F0004521F0004120E700BF50EA0102AF -:10E6E00008BF704730B54FF000050AE050EA01025C -:10E6F00008BF704730B511F0004502D5404261EBCC -:10E7000041014FF4806404F132045FEA915C3FF40C -:10E71000DCAE4FF003025FEADC0C18BF03325FEAA5 -:10E72000DC0C18BF033202EBDC02C2F1200300FA5A -:10E7300003FC20FA02F001FA03FE40EA0E0021FA7F -:10E7400002F11444C1E600BF70B54FF0FF0C4CF469 -:10E75000E06C1CEA11541DBF1CEA135594EA0C0F1F -:10E7600095EA0C0F00F0DEF82C4481EA030621EA5A -:10E770004C5123EA4C5350EA013518BF52EA033595 -:10E7800041F4801143F4801338D0A0FB02CE4FF047 -:10E790000005E1FB02E506F00042E0FB03E54FF077 -:10E7A0000006E1FB03569CF0000F18BF4EF0010E6F -:10E7B000A4F1FF04B6F5007F64F5407404D25FEA6B -:10E7C0004E0E6D4146EB060642EAC62141EA55511E -:10E7D0004FEAC52040EA5E504FEACE2EB4F1FD0C60 -:10E7E00088BFBCF5E06F1ED8BEF1004F08BF5FEADE -:10E7F000500E50F1000041EB045170BD06F0004690 -:10E8000046EA010140EA020081EA0301B4EB5C043C -:10E81000C2BFD4EB0C0541EA045170BD41F4801134 -:10E820004FF0000E013C00F3AB8014F1360FDEBF59 -:10E83000002001F0004170BDC4F10004203C35DA35 -:10E840000C341BDC04F11404C4F1200500FA05F3B8 -:10E8500020FA04F001FA05F240EA020001F0004259 -:10E8600021F0004110EBD37021FA04F642EB0601CF -:10E870005EEA430E08BF20EAD37070BDC4F10C04F9 -:10E88000C4F1200500FA04F320FA05F001FA04F2BD -:10E8900040EA020001F0004110EBD37041F10001A9 -:10E8A0005EEA430E08BF20EAD37070BDC4F12005B4 -:10E8B00000FA05F24EEA020E20FA04F301FA05F21C -:10E8C00043EA020321FA04F001F0004121FA04F2C4 -:10E8D00020EA020000EBD3705EEA430E08BF20EA94 -:10E8E000D37070BD94F0000F0FD101F000464000CE -:10E8F00041EB010111F4801F08BF013CF7D041EA50 -:10E90000060195F0000F18BF704703F00046520053 -:10E9100043EB030313F4801F08BF013DF7D043EA24 -:10E920000603704794EA0C0F0CEA135518BF95EADA -:10E930000C0F0CD050EA410618BF52EA4306D1D161 -:10E9400081EA030101F000414FF0000070BD50EA80 -:10E95000410606BF1046194652EA430619D094EA0A -:10E960000C0F02D150EA013613D195EA0C0F05D1F4 -:10E9700052EA03361CBF104619460AD181EA030148 -:10E9800001F0004141F0FE4141F470014FF0000000 -:10E9900070BD41F0FE4141F4780170BD70B54FF09B -:10E9A000FF0C4CF4E06C1CEA11541DBF1CEA13551B -:10E9B00094EA0C0F95EA0C0F00F0A7F8A4EB0504FD -:10E9C00081EA030E52EA03354FEA013100F08880F4 -:10E9D0004FEA03334FF0805545EA131343EA1263BD -:10E9E0004FEA022245EA111545EA10654FEA002672 -:10E9F0000EF000419D4208BF964244F1FD0404F52B -:10EA0000407402D25B084FEA3202B61A65EB030586 -:10EA10005B084FEA32024FF480104FF4002CB6EB43 -:10EA2000020E75EB030E22BFB61A754640EA0C00C3 -:10EA30005B084FEA3202B6EB020E75EB030E22BF03 -:10EA4000B61A754640EA5C005B084FEA3202B6EB44 -:10EA5000020E75EB030E22BFB61A754640EA9C0003 -:10EA60005B084FEA3202B6EB020E75EB030E22BFD3 -:10EA7000B61A754640EADC0055EA060E18D04FEA91 -:10EA8000051545EA16754FEA06164FEAC30343EA31 -:10EA900052734FEAC2025FEA1C1CC0D111F4801FFE -:10EAA0000BD141EA00014FF000004FF0004CB6E7F7 -:10EAB00011F4801F04BF01430020B4F1FD0C88BF96 -:10EAC000BCF5E06F3FF6AFAEB5EB030C04BFB6EBA1 -:10EAD000020C5FEA500C50F1000041EB045170BD94 -:10EAE0000EF0004E4EEA113114EB5C04C2BFD4EBC1 -:10EAF0000C0541EA045170BD41F480114FF0000E45 -:10EB0000013C90E645EA060E8DE60CEA135594EAC0 -:10EB10000C0F08BF95EA0C0F3FF43BAF94EA0C0FC3 -:10EB20000AD150EA01347FF434AF95EA0C0F7FF438 -:10EB300025AF104619462CE795EA0C0F06D152EA8C -:10EB400003353FF4FDAE1046194622E750EA410670 -:10EB500018BF52EA43067FF4C5AE50EA41047FF481 -:10EB60000DAF52EA43057FF4EBAE12E74FEA4102E4 -:10EB700012F5001215D211D56FF47873B3EB62520F -:10EB800012D94FEAC12343F0004343EA505311F036 -:10EB9000004F23FA02F018BF404270474FF00000C8 -:10EBA000704750EA013005D111F0004008BF6FF006 -:10EBB000004070474FF00000704700BF4A0011D27C -:10EBC00012F5001211D20DD56FF47873B3EB6252C7 -:10EBD0000ED44FEAC12343F0004343EA505323FAD3 -:10EBE00002F070474FF00000704750EA013002D148 -:10EBF0004FF0FF3070474FF0000070474FEA41027E -:10EC0000B2F1E04324BFB3F5001CDCF1FE5C0DD98A -:10EC100001F0004C4FEAC0024CEA5070B2F1004FD4 -:10EC200040EB830008BF20F00100704711F0804FD7 -:10EC300021D113F13872BCBF01F00040704741F49C -:10EC400080114FEA5252C2F11802C2F1200C10FAA0 -:10EC50000CF320FA02F018BF40F001004FEAC12384 -:10EC60004FEAD32303FA0CFC40EA0C0023FA02F328 -:10EC70004FEA4303CCE77FEA625307D150EA0133FE -:10EC80001EBF4FF0FE4040F44000704701F00040CE -:10EC900040F0FE4040F40000704700BF80F00040AC -:10ECA00002E000BF81F0004142001FBF5FEA410364 -:10ECB00092EA030F7FEA226C7FEA236C6AD04FEA64 -:10ECC0001262D2EB1363C1BFD218414048404140A9 -:10ECD000B8BF5B42192B88BF704710F0004F40F45B -:10ECE000000020F07F4018BF404211F0004F41F477 -:10ECF000000121F07F4118BF494292EA030F3FD043 -:10ED0000A2F1010241FA03FC10EB0C00C3F1200355 -:10ED100001FA03F100F0004302D5494260EB4000E4 -:10ED2000B0F5000F13D3B0F1807F06D340084FEA4F -:10ED3000310102F10102FE2A51D2B1F1004F40EB44 -:10ED4000C25008BF20F0010040EA030070474900AC -:10ED500040EB000010F4000FA2F10102EDD1B0FA77 -:10ED600080FCACF1080CB2EB0C0200FA0CF0AABF6C -:10ED700000EBC25052421843BCBFD040184370470A -:10ED800092F0000F81F4000106BF80F40000013210 -:10ED9000013BB5E74FEA41037FEA226C18BF7FEAE7 -:10EDA000236C21D092EA030F04D092F0000F08BF29 -:10EDB0000846704790EA010F1CBF0020704712F010 -:10EDC0007F4F04D1400028BF40F00040704712F14F -:10EDD00000723CBF00F50000704700F0004343F0B4 -:10EDE000FE4040F4000070477FEA226216BF0846EA -:10EDF0007FEA23630146420206BF5FEA412390EAAD -:10EE0000010F40F4800070474FF0000304E000BFA2 -:10EE100010F0004348BF40425FEA000C08BF704753 -:10EE200043F0964301464FF000001CE050EA010217 -:10EE300008BF70474FF000030AE000BF50EA01022C -:10EE400008BF704711F0004302D5404261EB410119 -:10EE50005FEA010C02BF84460146002043F0B6433E -:10EE600008BFA3F18053A3F50003BCFA8CF2083A63 -:10EE7000A3EBC25310DB01FA02FC634400FA02FC6C -:10EE8000C2F12002BCF1004F20FA02F243EB020073 -:10EE900008BF20F00100704702F1200201FA02FCD5 -:10EEA000C2F1200250EA4C0021FA02F243EB0200C8 -:10EEB00008BF20EADC7070474FF0FF0C1CEAD0520C -:10EEC0001EBF1CEAD15392EA0C0F93EA0C0F6FD0CD -:10EED0001A4480EA010C400218BF5FEA41211ED0AB -:10EEE0004FF0006343EA501043EA5111A0FB013197 -:10EEF0000CF00040B1F5000F3EBF490041EAD3716C -:10EF00005B0040EA010062F17F02FD2A1DD8B3F1E7 -:10EF1000004F40EBC25008BF20F00100704790F056 -:10EF2000000F0CF0004C08BF49024CEA502040EAA8 -:10EF300051207F3AC2BFD2F1FF0340EAC25070476E -:10EF400040F400004FF00003013A5DDC12F1190FAC -:10EF5000DCBF00F000407047C2F10002410021FA1E -:10EF600002F1C2F1200200FA02FC5FEA310040F136 -:10EF7000000053EA4C0308BF20EADC70704792F0AF -:10EF8000000F00F0004C02BF400010F4000F013AE7 -:10EF9000F9D040EA0C0093F0000F01F0004C02BFE2 -:10EFA000490011F4000F013BF9D041EA0C018FE751 -:10EFB0000CEAD15392EA0C0F18BF93EA0C0F0AD057 -:10EFC00030F0004C18BF31F0004CD8D180EA01007D -:10EFD00000F00040704790F0000F17BF90F0004F16 -:10EFE000084691F0000F91F0004F14D092EA0C0FF8 -:10EFF00001D142020FD193EA0C0F03D14B0218BF8B -:10F00000084608D180EA010000F0004040F0FE40D0 -:10F0100040F40000704740F0FE4040F4400070476C -:10F020004FF0FF0C1CEAD0521EBF1CEAD15392EAEB -:10F030000C0F93EA0C0F69D0A2EB030280EA010CDB -:10F0400049024FEA402037D04FF0805343EA111174 -:10F0500043EA10130CF000408B4238BF5B0042F1D2 -:10F060007D024FF4000C8B4224BF5B1A40EA0C0077 -:10F07000B3EB510F24BFA3EB510340EA5C00B3EBA9 -:10F08000910F24BFA3EB910340EA9C00B3EBD10F97 -:10F0900024BFA3EBD10340EADC001B0118BF5FEAE9 -:10F0A0001C1CE0D1FD2A3FF650AF8B4240EBC25012 -:10F0B00008BF20F0010070470CF0004C4CEA5020D3 -:10F0C0007F32C2BFD2F1FF0340EAC250704740F422 -:10F0D00000004FF00003013A37E792F0000F00F014 -:10F0E000004C02BF400010F4000F013AF9D040EA92 -:10F0F0000C0093F0000F01F0004C02BF490011F426 -:10F10000000F013BF9D041EA0C0195E70CEAD1531D -:10F1100092EA0C0F08D142027FF47DAF93EA0C0F04 -:10F120007FF470AF084676E793EA0C0F04D14B02E8 -:10F130003FF44CAF08466EE730F0004C18BF31F09A -:10F14000004CCAD130F000427FF45CAF31F0004394 -:10F150007FF43CAF5FE700BF4FF0FF3C06E000BF2D -:10F160004FF0010C02E000BF4FF0010C4DF804CD50 -:10F170004FEA40024FEA41037FEA226C18BF7FEA60 -:10F18000236C11D001B052EA530C18BF90EA010F62 -:10F1900058BFB2EB030088BFC81738BF6FEAE170F1 -:10F1A00018BF40F0010070477FEA226C02D15FEA8D -:10F1B000402C05D17FEA236CE4D15FEA412CE1D0F9 -:10F1C0005DF8040B704700BF844608466146FFE7C0 -:10F1D0000FB5FFF7C9FF002848BF10F1000F0FBDA2 -:10F1E0004DF808EDFFF7F4FF0CBF012000205DF89B -:10F1F00008FB00BF4DF808EDFFF7EAFF34BF012020 -:10F2000000205DF808FB00BF4DF808EDFFF7E0FFB8 -:10F2100094BF012000205DF808FB00BF4DF808ED09 -:10F22000FFF7D2FF94BF012000205DF808FB00BF6C -:10F230004DF808EDFFF7C8FF34BF012000205DF84E -:10F2400008FB00BF4FEA4002B2F1FE4F0FD34FF070 -:10F250009E03B3EB12620DD94FEA002343F0004343 -:10F2600010F0004F23FA02F018BF404270474FF0F1 -:10F270000000704712F1610F01D1420205D110F078 -:10F28000004008BF6FF0004070474FF0000070472B -:10F2900042000ED2B2F1FE4F0BD34FF09E03B3EB00 -:10F2A000126209D44FEA002343F0004323FA02F02C -:10F2B00070474FF00000704712F1610F01D1420218 -:10F2C00002D14FF0FF3070474FF00000704700BF91 -:10F2D00073B96AB9002908BF0028BCBF00204FF0ED -:10F2E0000041C4BF6FF000414FF0FF3000F03CB868 -:10F2F00082B0EC462DE9005000F006F8DDF804E09D -:10F3000002B00CBC704700BF2DE9704F089E144638 -:10F310001D468046894600F029F804FB01F3A4FB52 -:10F3200000AB00FB05329344B8EB0A0869EB0B090C -:10F33000C6E90089BDE8708F2DE9704F089E14461C -:10F340001D468046894600F061F900FB05F5A0FBEB -:10F3500004AB04FB0154A344B8EB0A0869EB0B09A6 -:10F36000C6E90089BDE8708F704700BF00292DE90C -:10F37000F00FC0F2A1800024002BC0F29880154647 -:10F3800006460F46002B3FD18A4258D9B2FA82F383 -:10F390004BB1C3F1200201FA03F720FA02F29D40BB -:10F3A00000FA03F61743290CB7FBF1F201FB1277C1 -:10F3B000A8B200FB02F34FEA164C4CEA0747BB42E7 -:10F3C00009D97F1902F1FF3C80F00581BB4240F270 -:10F3D0000281023A2F44FF1AB7FBF1F301FB1371CC -:10F3E00000FB03F0B6B246EA0141884208D9491948 -:10F3F00003F1FF3780F0F180884240F2EE80023B5B -:10F4000043EA0242002303E08B420AD900231A4652 -:10F410001046194614B1404261EB4101BDE8F00FBE -:10F420007047B3FA83F8B8F1000F40F088808B4240 -:10F4300002D3824200F2E28000230122E8E712B9FF -:10F440000123B3FBF2F5B5FA85F2002A3AD17F1B0E -:10F45000280C1FFA85FC0123B7FBF0F100FB1177A4 -:10F460000CFB01F24FEA164848EA0747BA4207D9AF -:10F470007F1901F1FF3802D2BA4200F2C48041463E -:10F48000BF1AB7FBF0F200FB12700CFB02FCB6B225 -:10F4900046EA0040844507D9401902F1FF3702D2FD -:10F4A000844500F2AE803A4642EA0142B0E7E443C6 -:10F4B000524263EB430362E7404261EB41014FF08C -:10F4C000FF3459E79540C2F1200927FA09F126FADD -:10F4D00009F99740280CB1FBF0F800FB18111FFA4E -:10F4E00085FC0CFB08F349EA07094FEA194747EA8C -:10F4F00001418B4206FA02F608D9491908F1FF3298 -:10F500007AD28B4278D9A8F102082944C91AB1FBF2 -:10F51000F0F300FB13170CFB03F21FFA89F949EA19 -:10F520000747BA4207D97F1903F1FF3160D2BA42C7 -:10F530005ED9023B2F44BF1A43EA08438CE7C8F167 -:10F54000200225FA02F103FA08FC27FA02F320FA56 -:10F5500002F207FA08F741EA0C0C4FEA1C49B3FB28 -:10F56000F9F109FB11331FFA8CFA0AFB01FB17436F -:10F570003A0C42EA03439B4505FA08F008D913EB1D -:10F580000C0301F1FF3235D29B4533D90239634474 -:10F59000CBEB0303B3FBF9F209FB12330AFB02FACC -:10F5A000BFB247EA0347BA4508D917EB0C0702F187 -:10F5B000FF331BD2BA4519D9023A674442EA0145E2 -:10F5C000A5FB0001CAEB07078F424FF000030AD3E7 -:10F5D00005D02A461CE76246FDE63B4610E706FAE0 -:10F5E00008F68642F5D26A1E002311E71A46E5E7BF -:10F5F0000B46A0E71146CBE7904687E743464246D5 -:10F6000006E7023A50E702392F4439E72DE9F00FB7 -:10F61000144605460E46002B43D18A4253D9B2FA0E -:10F6200082F757B1C7F1200620FA06F601FA07F370 -:10F6300002FA07F400FA07F51E43210CB6FBF1F2BB -:10F6400001FB1266A0B200FB02F32F0C47EA06464C -:10F65000B34209D9361902F1FF3780F0FD80B34279 -:10F6600040F2FA80023A2644F61AB6FBF1F301FBA7 -:10F67000136100FB03F0ADB245EA0141884208D9AD -:10F68000091903F1FF3680F0E980884240F2E680F4 -:10F69000023B43EA0242002310461946BDE8F00F40 -:10F6A00070478B424CD8B3FA83F6002E4FD18B4271 -:10F6B00002D3824200F2DD80BDE8F00F0023012278 -:10F6C00010461946704712B90124B4FBF2F4B4FA9B -:10F6D00084F2002A40F08280091B260CA7B2012385 -:10F6E000B1FBF6F006FB101107FB00F24FEA154CD8 -:10F6F0004CEA01418A4207D9091900F1FF3C02D2C4 -:10F700008A4200F2C8806046891AB1FBF6F206FB15 -:10F71000121107FB02F7ADB245EA0145AF4208D925 -:10F720002C1902F1FF3180F09B80A74240F29880B3 -:10F73000023A42EA004210461946BDE8F00F70470F -:10F7400000231A4610461946BDE8F00F7047C6F16F -:10F75000200522FA05F703FA06F421FA05F301FA67 -:10F7600006FB20FA05F53C434FEA1448B3FBF8FCCE -:10F7700008FB1C331FFA84F909FB0CFA45EA0B0B52 -:10F780004FEA1B4545EA03439A4502FA06F204D9BB -:10F790001B190CF1FF356FD3AC46CAEB0303B3FB67 -:10F7A000F8F508FB153309FB05F91FFA8BFB4BEA4B -:10F7B0000347B94504D93F1905F1FF3362D31D460C -:10F7C00045EA0C4CACFB0223C9EB07079F424FF004 -:10F7D00000054AD346D062462B465DE79440C2F10D -:10F7E000200921FA09FC914020FA09F9260CBCFBFA -:10F7F000F6F806FB18CCA7B207FB08F349EA0109A3 -:10F800004FEA194141EA0C4C634500FA02F509D967 -:10F810001CEB040C08F1FF323BD2634539D9A8F147 -:10F820000208A444C3EB0C0CBCFBF6F306FB13C1AB -:10F8300007FB03F21FFA89F949EA01418A4207D915 -:10F84000091903F1FF3022D28A4220D9023B214418 -:10F85000891A43EA084343E73A4605E7334618E77F -:10F860000A4666E7B0409042B5D20CF1FF32002361 -:10F8700012E7334632460FE79A458DD9ACF1020CB8 -:10F8800023448AE7B9459AD9023D274498E70346BD -:10F89000DEE79046C6E70238214435E74FF0FF3CEB -:10F8A00006E000BF4FF0010C02E000BF4FF0010C7A -:10F8B0004DF804CD4FEA410C7FEA6C5C4FEA430CF3 -:10F8C00018BF7FEA6C5C1BD001B050EA410C0CBF42 -:10F8D00052EA430C91EA030F02BF90EA020F0020A4 -:10F8E000704710F1000F91EA030F58BF994208BF0B -:10F8F00090422CBFD8176FEAE37040F001007047C8 -:10F900004FEA410C7FEA6C5C02D150EA013C07D11E -:10F910004FEA430C7FEA6C5CD6D152EA033CD3D069 -:10F920005DF8040B704700BF8446104662468C4663 -:10F930001946634600E000BF01B5FFF7B7FF002896 -:10F9400048BF10F1000F01BD4DF808EDFFF7F4FFBF -:10F950000CBF012000205DF808FB00BF4DF808ED4A -:10F96000FFF7EAFF34BF012000205DF808FB00BF6D -:10F970004DF808EDFFF7E0FF94BF012000205DF88F -:10F9800008FB00BF4DF808EDFFF7CEFF94BF012044 -:10F9900000205DF808FB00BF4DF808EDFFF7C4FF3D -:10F9A00034BF012000205DF808FB00BF1C481D4942 -:10F9B000026800608A4200F01D80002100F004B857 -:10F9C000194B5B58435004311848194B42189A425E -:10F9D000FFF4F6AF174A00F003B8002342F8043BE7 -:10F9E000154B9A42FFF4F9AFFEF7B0FC00F038F87F -:10F9F000FFF7FEBF114E124830601248016821F037 -:10FA000070610160410201600F4C182020600F49B5 -:10FA10000F4808600F48D0F800D040680047000049 -:10FA2000F04F0020EFBEADDEC07F010800000020D7 -:10FA30003801002038010020F4270020181002406F -:10FA40000900000004000140140C0140000C0140BA -:10FA50004434434400F0FF1FFFF7FEBF00000000E6 -:10FA60002DE9804893B0F0F753FBB14EB14CD6F876 -:10FA70000880002318F0080F2370374600F0E78055 -:10FA800063681B7A042B00F2E080DFE803F00303D5 -:10FA9000058AB100237AD9E0627AA64B002A00F0E9 -:10FAA000D48000225A7293F82020120700F1CD80F2 -:10FAB000D97A9A7A01F0070042EA00225A621A7B48 -:10FAC00002F03F00400140EAD1019962597B890070 -:10FAD00041EA92119A7B02F0010041EA8021D96249 -:10FAE000D97B01F00F00C00140EA52021A631A7C70 -:10FAF00002F07F00000140EA11115963597C49006E -:10FB000041EAD212997C01F0030042EA40229A6352 -:10FB1000DA7C02F01F00800140EA9101D963197D6F -:10FB2000C90041EA5212997D1A645A7D01F007001A -:10FB300042EA00225A64DA7D02F03F00400140EAC6 -:10FB4000D1019964197E890041EA92115A7E02F02E -:10FB5000010041EA8021D964997E01F00F00C001C3 -:10FB600040EA52021A65DA7E02F07F00000140EAA4 -:10FB700011115965197F490041EAD212597F01F0EC -:10FB8000030042EA40229A659A7F02F01F0080013A -:10FB900040EA9101D965D97FC90041EA52121A663B -:10FBA00051E094F86420634B002A4ED0002283F881 -:10FBB000642093F86620012A47D193F88A20102AFE -:10FBC00084BF102283F88A2094F88A105A4A0023AE -:10FBD000D8B2884202F1020235D212F8010C12F8B2 -:10FBE000025C40EA0525554840F823500133EFE711 -:10FBF00094F8CC204F4B42B3002283F8CC2093F8EA -:10FC0000CD20A82A21D193F8E050F5B9494901EB5C -:10FC1000450393F8D00093F8D13003EB0020FEF7B2 -:10FC20001DFD3FA3D3E90023FEF7B8FE3EA3D3E9B1 -:10FC30000023FEF7D5FBFEF7C1FF414B43F825003B -:10FC40000135082DE2D1012300E00023237018F4D0 -:10FC5000804F08D094F8043123B1364B002283F84A -:10FC6000042101232370237843B118F4807F05D049 -:10FC7000304BD3F808311B681B689847314B22780A -:10FC80001B6832B92B4AD2F80C219A1AD243D20FF0 -:10FC900000E0012292B3F2F727F994F81021254BE6 -:10FCA000002A00F0CC83D3F814114D0742F1D7801D -:10FCB000D3F81821100707D4B3F81C2122F008024A -:10FCC000A3F81C2102F0CBB8B3F81C0100F0080225 -:10FCD00092B2002A42F0C38040F00800A3F81C0151 -:10FCE000D3F82401C3F83421C3F82001B3F830015C -:10FCF000C3F83821A3F8280102F0B1B8D4F83C21A8 -:10FD0000511CC4F83C11052A00F29183DFE812F07F -:10FD10001C00AE006E031C0168038A03AFF3008071 -:10FD20009A999999999919400000000000707740BC -:10FD30003020002038010020A0010020C401002054 -:10FD40001C020020C0270020D4F81421784D12078F -:10FD500040F16D83D5F840219A1A002AC0F26783DA -:10FD600003F5C33805F5A27008F1A008C5F8408175 -:10FD7000F8F75CF86F4B05F5A27001461A78F5F7B5 -:10FD8000C5FA95F84A1105F5A27011F0040F17D0C5 -:10FD9000C5F84C810022BB180025A3F8FE50644B27 -:10FDA000855A03F5A87E22F80E5003F5AB7E22F8A3 -:10FDB0000E500232062AEED121F0040183F84A11D6 -:10FDC00094F85C315A4AA3B1B2F84411B6F8FE3047 -:10FDD000CB1AA2F84431B2F84611B6F80031CB1A6A -:10FDE000A2F84631B2F84811B6F80231CB1AA2F89F -:10FDF0004831D4F84C314E4A002B00F018834E495C -:10FE0000C3EB08038B4202F5A87502F5AB7119D854 -:10FE10004A4BDA6882F00802DA600023C25A35F9E8 -:10FE200003E017B2BE45C4BFDFF818E123F80E2087 -:10FE300031F903E0BE45BCBF414FDA530233062B14 -:10FE4000ECD1F4E20023C2F84C3135F903E0C85E8E -:10FE5000FA1870444FF0020E734490FBFEF0062B2C -:10FE6000A2F8FE00F1D1FBF7A5FCE0E2D4F81421E2 -:10FE70002F4D500740F1DB82D5F860219A1A002AF5 -:10FE8000C0F2D582C5F8603195F86431012B14D0E9 -:10FE900002D3022B29D0CAE2D5F870319847D5F8A1 -:10FEA00074319847012385F86431B5F86A21D5F893 -:10FEB00060311344C5F86031B9E2D5F8783198471C -:10FEC000D5F86C319847D5F86031B5F8682105F55B -:10FED000C0701344C5F8603105F5C271D5F87C31A6 -:10FEE0009847022385F86431A1E2D5F89001D5F84E -:10FEF0008C1100784B1C0027834285F86471D5F87B -:10FF000088E1D5F8802103D1012385F894313B465F -:10FF10000748C4F88C3100EB8101C1F8982100EB4F -:10FF20008301D1F898117244521AC4F888217EE2F4 -:10FF300038010020CF2700207FC3C901000C0140F9 -:10FF40008E02002088020020D4F81421510703D526 -:10FF5000B04991F8941111B9D70640F16882D4F8EC -:10FF60005822AC4DC2EB030B46F2A712934540F268 -:10FF70005E82A94FC5F85832B7F80080B8F1000F7B -:10FF80002FD0D5F89031D5F85C221878D5F8883183 -:10FF90000138B3FBF0F0082392FBF3F1521A10443E -:10FFA000C5F85C0290FBF3F0FEF732FF9B49FFF7C8 -:10FFB00037F89B4902F0C8FA01464FF07E50FEF731 -:10FFC00071FE9849FEF778FFFFF73CF908F1FF381A -:10FFD0000023C5F86002A7F80080C5F86432C5F8B0 -:10FFE0006832D4F89051D4F8883128780138B3FBBE -:10FFF000F0F0FEF709FF8949FFF712F8884902F08F +:1045300001F010FC11B0BDE8F08F00BFE00A0020D0 +:104540008450010830200020740600201E04002042 +:1045500008020020032810B50F4B0DD80F4A12682F +:1045600094888C4208D2D2888A4205D9012202FA64 +:1045700000F01A78104318701B780F2B0BD1064BE4 +:1045800000221A70064B998808B2142802DD1439EB +:10459000998010BD9A8010BD7C1200202C20002034 +:1045A000AC0A0020024B9A8801329A80704700BF03 +:1045B000AC0A0020074B1A68074B1178B3F90400C6 +:1045C00053780B4403EB83039842D4BF00200120AF +:1045D000704700BF2C200020AC0A0020064BB3F926 +:1045E0000400064B1B681B7803EB83039842D4BF7F +:1045F00000200120704700BFAC0A00202C200020C2 +:1046000010B50446FFF7EAFF002814BF204600203B +:1046100000F0010010BD024B01221A72704700BF6A +:10462000AC0A0020014B187A704700BFAC0A00208A +:10463000034BB3F90400D0F1010038BF00207047EC +:10464000AC0A0020014B00229A807047AC0A00207F +:1046500003685A1C026019707047016B0346C268F8 +:1046600010B5406941B1196C541A005D013918BF89 +:104670000A46C0B21A6410BD196A405C0131B1FB30 +:10468000F2F402FB1412C0B21A6210BD026B03698D +:104690001AB15168013B026C02E0C169026A013B38 +:1046A000881A1840C0B27047436B13B190F84400A9 +:1046B0007047826A436AD31A584258417047437917 +:1046C0009B070AD5436A8269D154426A0369013261 +:1046D000B2FBF3F103FB112343627047437913F0FC +:1046E000010307D0C368C169026A013B881A1840F8 +:1046F000C0B2704718467047437910B513F00103F4 +:1047000004460DD0FFF7EAFF58B1226A6369985C4E +:10471000E3680132B2FBF3F103FB1123236210BD06 +:10472000184610BD426A806A131A584258417047B1 +:104730004171704710F80A3C0133DBB20A2B00F8D4 +:104740000A3C0AD910F8123C23B910F8131C034A8A +:1047500022F81130002300F80A3C7047641300204F +:10476000334A10B5136C90681944081A40F68C232C +:1047700098429160D060516013463CD9127893F909 +:1047800045108A420BD1111F082908D893F846100A +:10479000182901D8013103E083F8442002E0002108 +:1047A00083F8461093F944108A421CD1204991F8AD +:1047B0004710C1B1002191421E4806DA03EB810483 +:1047C000246920F811400131F5E7511E00EB410149 +:1047D0001630814203D0002421F8024FF9E7164930 +:1047E00008780130087083F84520002201211A70F2 +:1047F00083F8471010BD92F84710B9B1A0F2EF242A +:1048000040F2DA518C4208D811780B2905D80B1DDB +:104810000131117042F8230010BD002283F84720B7 +:10482000991804320020302A0861F9D110BD00BF68 +:104830007008002064130020C41D0020024B1A6C75 +:10484000013211441964704770080020024B53F87C +:1048500020301B681980704798090020074BA1F58C +:104860007A7153F820304FF47A701A681B894B43E1 +:1048700093FBF0F39BB21380704700BF98090020B0 +:104880002DE9F04F504A514E17687389844630899C +:10489000A7EB032785B0039187FB0001B288CB11FA +:1048A0001404C209F08842EA416287FB000114EB5C +:1048B000020872884FF000054FEAC2344FEA102216 +:1048C000B08945EB030942EA01620B1287FB000144 +:1048D00014EB020A4FEAD05242EA41224FF000059F +:1048E00045EB030B12F5FA604FEAE15343F1000187 +:1048F000CDE90001B0F5FA6F71F1000147DAA2FBD2 +:10490000024502FB03F1052605EB4105A4FB060168 +:1049100006FB05114D104FEA3004B8EB040869EBB3 +:10492000050984082A4844EA81748D104FF0FF314C +:10493000BAEB040A6BEB050BDDE9004584428D41BF +:1049400025DA40F6AC5012184FF0000143EB01039A +:1049500002FB03F1A2FB02236FF0060003EB41030D +:10496000544200FB0344A2FB000118EB0008214461 +:104970004FF00B0449EB0109A2FB040104FB0311F6 +:1049800049104FEA3000BAEB000A6BEB010B114BF8 +:104990001A68A2FB0A0102FB0B11420D42EAC12276 +:1049A0004B15B2EB080263EB0903D00B40EA43401E +:1049B000BCF1000F01D0CCF80000039808B10099B9 +:1049C000016005B0BDE8F08F6814002024080020C5 +:1049D00024FAFFFF6C140020324B2DE9F0411C88B3 +:1049E000314B0A265A89B3F91250A41A1A89ED02DA +:1049F0005443B3F91420E413224495FBF2F2224409 +:104A0000DA615643A2F57A6202FB02F4B3F904803C +:104A1000B3F902C0B3F90E7002FB0CFC02FB08F202 +:104A2000B3F90C802413674304FB08F4241404EB4B +:104A300062320232DC88921002F50042B3F9205053 +:104A40006243B3F900304FEAEC2404EBE72404EBB3 +:104A50008304AC40154B02341B68D20BA3EBA404B7 +:104A60004CF250332B41634355BF5B00B3FBF2F371 +:104A7000B3FBF2F35B001A12524340F6DE3462439A +:104A80000B4C08365C43241404EB224202F6CF623E +:104A9000361103EB221300B1036001B10E60BDE8D3 +:104AA000F08100BF78140020380800207414002022 +:104AB00043E3FFFF2DE9F04F0C68836889B0D0F81D +:104AC00000A0D0F804800646204603938B460DF0E4 +:104AD000C3FC074620460DF033FDDBF80440814659 +:104AE00020460DF0B9FC054620460DF029FDDBF807 +:104AF00008200446104601920DF0AEFC019A834650 +:104B000010460DF01DFD3946029058460AF0C4FAD1 +:104B10003946049002980AF0BFFA59460590484673 +:104B20000AF0BAFA0299069048460AF0B5FA294600 +:104B3000079058460AF0B0FA014650460AF0ACFA1F +:104B40002146834606980AF0A7FA014605980AF01E +:104B50009BF9014640460AF09FFA014658460AF082 +:104B600093F92146834604980AF096FA014607987D +:104B70000AF088F9014603980AF08EFA0146584671 +:104B80000AF082F93060029905F100400AF084FAD7 +:104B9000014650460AF080FA2146834607980AF0FB +:104BA0007BFA014604980AF06DF9014640460AF086 +:104BB00073FA014658460AF067F92146834605987C +:104BC0000AF06AFA014606980AF05EF9014603986F +:104BD0000AF062FA014658460AF056F9214670601A +:104BE00050460AF059FA2946044609F100400AF0F5 +:104BF00053FA014640460AF04FFA014620460AF0B1 +:104C000043F93946044628460AF046FA0146039815 +:104C10000AF042FA014620460AF036F9B06009B0BF +:104C2000BDE8F08F2DE9F84F2E4E04463768384620 +:104C30000DF012FC054638460DF082FC7668804681 +:104C400030460DF009FC834630460DF079FCD4F86F +:104C500004900646294648460AF01EFAA76882468E +:104C6000414638460AF018FA014650460AF00AF959 +:104C70002168824658460AF00FFA414604464846E3 +:104C80000AF00AFA31460AF007FA014620460AF00D +:104C9000FBF83146044638460AF0FEF929460AF088 +:104CA000FBF9014620460AF0EFF8014650460DF0A8 +:104CB000D5FC0D490AF0F0F90C490AF0A1FA0C4BA9 +:104CC00019680AF0E1F80B490AF09AFA0DF0FAFBBC +:104CD00083B21A0444BF00F5B4739BB218B2BDE8A6 +:104CE000F88F00BF200400200000E144DB0F4940A2 +:104CF0005C08002000002041064B1B7803F00403F1 +:104D000003F0FF001BB1044B1888C0F3C01000F083 +:104D100001007047D5270020100200202DE9F04146 +:104D200002780346202A00F10100F9D0092AF7D0C1 +:104D30002D2A02D10346414D04E02B2A08BF034629 +:104D40004FF07E551E460024334616F8012BA2F183 +:104D50003007F9B209290DD8394920460AF09CF9E3 +:104D6000044638460AF044F9014620460AF08CF819 +:104D70000446E9E72E2A17D1314F334616F8010BC6 +:104D80003038C2B2092A0FD80AF032F939460AF08F +:104D900037FA014620460AF077F829490446384692 +:104DA0000AF07AF90746E8E71A7802F0DF02452AA6 +:104DB00038D15A782D2A02D10233012604E02B2A59 +:104DC00014BF013302330026013B002713F8012FE3 +:104DD000303AD1B2092903D80A2101FB0727F5E7A8 +:104DE000B7F59A7F28BF4FF49A77B8464FF07E51B7 +:104DF000B8F1070F07D9084612490AF04DF9A8F192 +:104E000008080146F4E707F0070737B108460C49E0 +:104E10000AF042F9013F0146F7E72EB120460AF0B9 +:104E2000EFF904E04FF07E5120460AF035F90146D3 +:104E300028460AF031F9BDE8F08100BF000080BFCC +:104E40000000204120BCBE4CF0B50124B0FBF4F5BD +:104E50008D4201D34C43F9E70026DCB1B0FBF4F5F9 +:104E600004FB1500B4FBF1F41EB9002D01DC002C8D +:104E7000F3D1092D03F101075FFA85FC04DD002A57 +:104E80000CBF5725372500E0302565441D700136DD +:104E90003B46E2E71C70F0BDF0B50124B0FBF4F531 +:104EA0008D4201D34C43F9E70026DCB1B0FBF4F5A9 +:104EB00004FB1500B4FBF1F41EB9002D01DC002C3D +:104EC000F3D1092D03F101075FFA85FC04DD002A07 +:104ED0000CBF5725372500E0302565441D7001368D +:104EE0003B46E2E71C70F0BD70B50646B6FBF2F437 +:104EF0000846154614B12046FFF7F6FF05FB14647B +:104F0000024B1B5D00F8013B70BD00BFB768010894 +:104F10002DE9F041069C002B06460F460CBF4FF0D2 +:104F200020084FF03008234613F8011B09B9154635 +:104F300003E0002AFBDD013AF6E7002D04DD3046F0 +:104F40004146B847013DF8E714F8011B11B130465E +:104F5000B847F9E7BDE8F08180EAE073A3EBE073BE +:104F60008B4206DB002801DD401A704702D008445E +:104F7000704700207047034B9A6822EA000098604F +:104F8000704700BF34200020214B224A1B68126862 +:104F900010B51A60204A116859605168926899608A +:104FA000DA601E4A116819615168926859619A6104 +:104FB0001B4A1168D9615168926819625A62194A8C +:104FC00011881985518859859188D2889985DA8503 +:104FD000154A118819865188598692889A86134AEB +:104FE0001188D9865188928819875A87104A117872 +:104FF00000228A4207DA0F4C03EB420034F81240D9 +:1050000001328487F5E70C4A5289A3F85E2010BD6F +:1050100020050020C4270020E4130020F013002006 +:10502000FC1300201E020020600400200804002061 +:10503000E7270020AC270020120000200E4B1B7831 +:10504000BBB10E4B1B681A78032A06D10C4B18789B +:1050500002288CBF0020012070475B7823B1094BE8 +:105060001868C0F3C0407047074B1878C0F3800041 +:1050700070470120704700BF360E002084060020D4 +:10508000C40600200C020020D5270020114A30B5AC +:105090000028B8BF4042104C90FBF2F304FB030021 +:1050A0003C2568430D4D90FBF2F22D682D7B25B910 +:1050B00003EB830303EB830301E0C3EB031302EB76 +:1050C000830304FB02020B804FF47A7392FBF3F22A +:1050D0004A8030BD80969800806967FFAC0600204A +:1050E000034B1B681878C31E58425841704700BFD5 +:1050F0008406002008B506480CF0C0FFC0B2142892 +:1051000005D8034A431C20211154D8B2F7E708BD43 +:10511000491E0020094A0A48002310B5116803708F +:105120001A46CC1864880CB9CC5C24B10433013223 +:10513000802BD2B2F5D1027010BD00BFEC0600206A +:105140007007002010B50B4B0B4819780B4B5A78A1 +:105150004B085C1E047001F0010109480B44037008 +:1051600008495308581E087002F00102064913440A +:105170000B7010BDA9070020A40700207C1200209E +:10518000A6070020A7070020A5070020F0B50F4ABA +:105190000F4816780F4A0023176843701A461946BD +:1051A0000546D0B2B0420CD217F8220001320409F1 +:1051B0009C4200F00F00A8BF631C8842A8BF411C9E +:1051C000EFE76B70044B1970F0BD00BF7007002053 +:1051D0007C120020EC060020A9070020F8B5101A68 +:1051E0000C461F4609F004FF0546381B09F000FF76 +:1051F000174B079E196809F04FFF294604462846B9 +:1052000009F04AFF21460746204609F045FF0146BE +:10521000384609F039FE0DF0ABFB0E4909F03CFFB2 +:105220000AF026F9069B2146186005F100400DF0B2 +:1052300015FA094909F030FF084909F025FE0AF07E +:10524000F1F80028BCBF00F50C40A0303060F8BD7C +:105250004C0000202C7D8E3FA00CB34500A00C46D6 +:1052600010B509F0C5FE002104460AF0D1F808B1D6 +:10527000204601E004F10040054909F0C1FF05495D +:1052800009F00AFF0DF0E8F8034B186010BD00BFED +:105290008096184B35FA8E3C4C00002070B50446C1 +:1052A000007909F0A1FE1E4909F0AAFF1D4D1E4E0E +:1052B0002860A07B09F098FE194909F0A1FFEE6073 +:1052C0006860607909F090FE184909F099FF184D5F +:1052D0002860E07B09F088FE114909F091FF6860C1 +:1052E000607E09F081FE134909F08AFFEE60A86034 +:1052F000A07909F079FE0D4909F082FF0E4D286072 +:10530000207C09F071FE064909F07AFF6860A07EF2 +:1053100009F06AFE074909F073FFEE60A86070BDEE +:105320000000C842381200200000FA44000020416A +:105330004812002000007A446C12002044F25063AE +:10534000984203DDA0F50C40A0387047034B98420B +:10535000BCBF00F50C40A030704700BFB0B9FFFFE4 +:105360002DE9F041038A87890446BFB20D461F40EC +:10537000002F36D0B7FA87F34FF00042DA40D2431D +:1053800091B21B3B21821740042BF1D8DFE803F0D8 +:10539000221F1C1903006B6A33B103F1FF3800238D +:1053A0001FFA88F86B6203E0B4F82C801FFA88F8C3 +:1053B0002E6A002EDCD03368304641469847766826 +:1053C000F7E72868A18E08E06868218F05E0A868E3 +:1053D000A18F02E0E868B4F84010036889B29847EA +:1053E000C6E7BDE8F0810C4B800A98420CD003D888 +:1053F000B0F5801F0ED00BE0084B984206D0493321 +:10540000984205D100207047022070470320704762 +:10541000FE207047012070470100100002001000BC +:1054200090F83B3210B57BB990F83A3290F83922B7 +:10543000934209D201219940B0F8404201332143FF +:10544000A0F84012DBB2F3E710BD8379012B03D142 +:10545000D1F1010138BF0021D0F834315A681B89DD +:1054600009B11361704753617047044B53F8203002 +:105470001BB107289CBF1B6819807047C809002012 +:105480002DE9F0410F88002347FA03F2D2072BD50C +:105490008A7803F0070512F0100F18BF91F803C0C7 +:1054A00002F00F0618BF46EA0C06AD004FF00F0CD5 +:1054B0000CFA05FC06FA05F5DC0850F82480282AC9 +:1054C00028EA0C0C45EA0C0540F8245005D10122CD +:1054D0009A40C46824EA020205E0482A04D1012265 +:1054E0009A40C4682243C2600133102BCCD1BDE87E +:1054F000F08100BF70B50E46202115460CF0B1FDBD +:105500000446B8B1441C20460CF00DFEB0F5617F96 +:1055100005DB40F634039842A8BF184601E04FF47B +:1055200061701923A0F5617090FBF3F030702B7857 +:1055300001332B70204620210CF093FD0446B8B1B6 +:10554000441C20460CF0EFFDB0F5617F05DB40F612 +:1055500034039842A8BF184601E04FF46170192344 +:10556000A0F5617090FBF3F070702B7801332B7015 +:10557000204670BD70B586B005460CF07FFDC0B208 +:1055800008BB044606236343444A03F58873126844 +:1055900019201344591D4D789A7A454305F56175D4 +:1055A0005B7900958D78684300F561700190C8784B +:1055B000029009793A4803912146013401F02EFC0A +:1055C0000C2CDFD168E028460CF0ADFD0B285FDC29 +:1055D00006267043314B00F588701E682021064472 +:1055E0000023681C8DF817300CF03BFD741D054638 +:1055F00058B1451C28460CF096FD032805D89DF8A7 +:105600001730607101338DF81730284620210CF0D7 +:1056100028FD054658B1451C28460CF084FD0D2890 +:1056200005D870719DF8173001338DF81730284672 +:10563000611C0DF11702FFF75DFF20210CF011FD39 +:10564000054658B1451C28460CF06DFD0C2805D8C0 +:105650009DF81730E07001338DF81730284620216F +:105660000CF0FFFC50B101300CF05DFD0D2805D8A9 +:105670009DF81730207101338DF817309DF81730E1 +:10568000062B09D02046002106220CF0B6FC03E0D0 +:1056900004480C2101F0C2FB06B070BD3C030020A1 +:1056A000DC6801080D710108F0B585B007460CF003 +:1056B000E5FCC0B2E0B90446324B04F11C021B68A1 +:1056C000192003EB8203591D8D785A79454305F55E +:1056D00061759B790095C978484300F56170019028 +:1056E00021462948013401F099FB282CE4D146E0F9 +:1056F00038460CF018FD27283DDC224B00F11C0633 +:105700001B68781C03EB8606202100238DF80F30E0 +:105710000CF0A7FC751D044658B1441C20460CF043 +:1057200002FD152805D870719DF80F3001338DF8F2 +:105730000F30204620210CF094FC044658B1441C44 +:1057400020460CF0F0FC0D2805D89DF80F3068704D +:1057500001338DF80F302046A91C0DF10F02FFF721 +:10576000C9FE9DF80F30042B09D0284600210422E1 +:105770000CF043FC03E00548282101F04FFB05B085 +:10578000F0BD00BF3C030020FC6801080D7101085A +:10579000F0B5884C884A23689D8AADB2E9B211F011 +:1057A000010F32D0198821F400610904090C198015 +:1057B000198889B241F480611980002111707F49F4 +:1057C00008787F49A8B1507818B97E480078FF283A +:1057D0000FD1012050707C480078022804D118882D +:1057E00080B240F400601880097841F0010119820C +:1057F00002E1097801F0FE011982724B1B78FF2B40 +:1058000000F0FA80FF231370F6E08F073CD5BFF35A +:105810005F8F6D490878C0B2012814D1674D2D788B +:105820008DB155787DB1198821F480610904090C86 +:105830001980BFF35F8F198B1988907089B241F47A +:10584000007119801BE0188BBFF35F8F0878022866 +:105850000BD15A48007840B1507830B1198821F402 +:1058600080610904090C1980C0E00978032906D178 +:105870005249097819B15178002940F0B7809988C8 +:1058800089B241F48061B6E04E075BD50121917089 +:105890004A49097800293AD05178002937D04A4935 +:1058A00010780978494D022919881ED921F48061A0 +:1058B0000904090C19801F8A2E68C1B2FFB240B2D8 +:1058C0003754188880B240F4007018808B1C137015 +:1058D000236828681D8A013149B2EDB24554998880 +:1058E00089B241F48061998027E089B241F4007166 +:1058F00019801E8A2D68C1B2F6B240B22E541B8A9E +:10590000481C40B2DBB203312B54117015E05178C2 +:1059100011B92F49097841B1198889B241F4007150 +:10592000198013780133137007E0198889B241F4A4 +:1059300080711980204B0121597021680B88D8058E +:10594000FCD459E001F0400101F0FF061E48F1B11E +:105950001E49B3F810C00F6811785FFA8CFCCDB205 +:105960006E1C49B2F6B207F801C01670077876B21D +:10597000F11C8F4205D1998821F480610904090C3A +:1059800099800378B34237D10235157034E0290687 +:1059900032D511784DB26F1C1ED00E4E01313668D3 +:1059A000C9B2755D1170EDB21D82007849B28842AE +:1059B00022D11BE050140020801200205814002037 +:1059C0005514002056140020641400206014002098 +:1059D000571400205C140020134916700978C9B2CE +:1059E00019821249097809B9017829B9998821F4ED +:1059F00080610904090C99800D4B92F90010187808 +:105A00000C4B421C91420DD100225A709B7833B14D +:105A10002268938823F440731B041B0C9380064B6D +:105A200000221A70F0BD00BF561400205814002048 +:105A30006414002080120020651400202DE9F04F2E +:105A4000624C63686249581C0A78894602F0FF0C70 +:105A50000AB10346F6E7277B667BA57B2169636075 +:105A6000E0461FFA88F213B21F2B00F393805949C6 +:105A700001EB8300C278807831F82310C0F1FF0079 +:105A800080B2002861D0C0F1FF0050433C23B1FB3D +:105A9000F3FA0012BAF1050F5AD8DFE80AF0030B47 +:105AA0001A283846161A4E43C5B2B6FBF3F62E44F2 +:105AB000F6B248E0B1FBF3F703FB1717BFB2C5B26C +:105AC000C7F13C07101A4743B7FBF3F72F441646BC +:105AD00029E0B1FBF3F503FB1515C7B2ADB2101AFF +:105AE0004543B5FBF3F53D44EDB2164630E0B1FB5E +:105AF000F3F603FB1616B6B2C7B2C6F13C06101A8F +:105B00004643B6FBF3F63E441546F6B220E0B1FB41 +:105B1000F3F703FB1717C6B2BFB2101A4743B7FB20 +:105B2000F3F737441546FFB212E0B1FBF3F503FB80 +:105B30001515ADB2C6B2C5F13C05101A4543B5FB0B +:105B4000F3F53544EDB2174602E015461646174602 +:105B50004FEA072A4AEA064A4AEA050A17230121B8 +:105B600099400CF1170211EA0A0FC3EB02021A491D +:105B70000CBF0920112092B213F1FF338854EED2EA +:105B80000CF1180C08F101081FFA8CFC1FFA88F8B8 +:105B9000124966E7012389F80030114B628140F217 +:105BA0002A3227736673A5732161A4F808C05A606E +:105BB0000C4A00219184118889B241F001011180C1 +:105BC0001A6842F001021A60BDE8F08F80120020CE +:105BD000CE270020F00600200C0B00208C120020A5 +:105BE0006C0002400004004038B5114B114D1A788A +:105BF000114C29688AB162690244914217D300208E +:105C0000187000F02AFE2B6863610C4B1A780AB1F9 +:105C1000013A1A700123237638BD6269C832914275 +:105C200005D30120187000F018FE2B68636138BDA1 +:105C3000F30F00203020002080120020EE0300200F +:105C400037B5214D8DF807306B7E8DF8062002AAFE +:105C50008DF804008DF805101A4412F8042C443A0B +:105C6000D2B20F2A29D81949022B31F8124003D891 +:105C700014B12046FFF7B8FF6B7E134A022B09D9F7 +:105C8000134B19685369091B8B4203D200235376C7 +:105C9000104A13702B7E012B00D09CB96B7E022B17 +:105CA00002D8094A013353760B4B0020287618702E +:105CB00003B0BDE8304000F0D0BD022B4FF0C80467 +:105CC000D7D9D9E703B030BD801200205651010862 +:105CD00030200020EE030020F30F002030B585B007 +:105CE00004AC002524F8025D0091ADF806002146C1 +:105CF000102000F021FF9DF80600214600F01CFF57 +:105D00009DF80700214600F017FF9DF8000021468E +:105D100000F012FF9DF80100214600F00DFF9DF8F4 +:105D20000200214600F008FF9DF80300214600F024 +:105D300003FF9DF80E002946C043C0B200F0FCFEF0 +:105D4000024B1A68024B1A6005B030BD30200020AB +:105D5000D80600200449054B0968002218701A6112 +:105D600059611A76704700BF30200020E00A0020F9 +:105D7000114B70B51B685E89104B186880F31000DA +:105D8000301A08F06BFD00220D4B08F0CDFD0446E3 +:105D900030460D4608F062FD02460B462046294675 +:105DA00008F0ECFE08F0D2FF6428A8BF642020EAC7 +:105DB000E070C0B270BD00BF98060020A4060020AD +:105DC00000005940104B043033F91030B3F5617FB7 +:105DD00005DB40F633029342A8BF134601E04FF4BF +:105DE000617308781922504300F28330984208DA30 +:105DF0004878504300F283309842B4BF002001201D +:105E000070470020704700BF720700204D4B2DE9FE +:105E1000F74FB3F9000009F0EBF84B4909F03CF9F2 +:105E200004460CF08DFB074620460CF015FB474B53 +:105E300006461B68DFF8208193F80390444DB9F1C2 +:105E4000000F4CD0DFF814A1B8F90200BAF8023004 +:105E5000C9F100041FFA83FB1BB2C01AFFF76EFAE8 +:105E6000A04203DB4845A8BF484600E02046BAF8F8 +:105E700000308344B8F900009AB21BB21FFA8BFBC2 +:105E8000C01A0192AAF802B0FFF758FAA042019A8C +:105E900003DB4845B4BF04464C461444A4B20FFA91 +:105EA0008BF0AAF8004009F0A3F8804620B209F070 +:105EB0009FF831460446404609F0EEF839468146DF +:105EC000204609F0E9F80146484608F0DBFF214981 +:105ED00009F096F909F0A6FA288040461DE0B8F9C5 +:105EE000020009F085F88146B8F9000009F080F851 +:105EF00031460446484609F0CFF8394680462046E8 +:105F000009F0CAF80146404608F0BCFF114909F003 +:105F100077F909F087FA28804846394609F0BCF835 +:105F200031460746204609F0B7F80146384608F0E2 +:105F3000ABFF084909F064F909F074FA688003B00E +:105F4000BDE8F08F3E04002035FA8E3C040B0020A3 +:105F5000E227002000002041140F0020100F002035 +:105F6000084BDA68D10709D4DA68520708D4DB682D +:105F700013F0100F0CBF042003207047012070475E +:105F800002207047002002401E4B2DE9F0431A7892 +:105F90001D460AB31C4B07781E781C4B93F800C0B3 +:105FA00002231B4A03F10108D45C344104F00F04BE +:105FB000BC420CD20B2C0AD812F8039012F80880BD +:105FC00002EB840209EA0C0408EB04241461023396 +:105FD000102BE6D100232B7003788B420FD90C4B8A +:105FE00093F8400060B10B4A890012780B4418699D +:105FF00002B1400800F5777080B2BDE8F083002060 +:10600000BDE8F08340010020C00A0020C10A002042 +:106010009C120020C20A002007299ABF024B33F8C5 +:1060200021000020704700BFD8010020034B03EB84 +:106030008101486CC0F3CF00704700BF9C12002064 +:1060400008B5074B53F8210008F0CEFF054909F0C9 +:1060500023F8054908F018FF09F00AFA80B208BDD4 +:106060005C0100200000203F00005C44014B33F83D +:106070001100704772070020014B33F81100704780 +:1060800064130020034B4FF4805208B11A6170472B +:106090005A61704700080140034B4FF4805208B129 +:1060A0005A6170471A6170470008014038B50C68A2 +:1060B000054620460BF0E2FF214602462868BDE86F +:1060C00038400BF0E3BFCB78F0B5DA0648BF8A78EA +:1060D000098803F00F0548BF154311F0FF0F1DD0CD +:1060E000046800220127974007EA0106BE4211D149 +:1060F00097004FF00F0C0CFA07FC05FA07F724EA9B +:106100000C04282B44EA070401D1466102E0482B25 +:1061100008BF06610132082AE4D10460FF291FD9B3 +:106120004468002202F108060127B74007EA010689 +:10613000BE4211D197004FF00F0C0CFA07FC05FA84 +:1061400007F724EA0C04282B44EA070401D146612E +:1061500002E0482B08BF06610132082AE2D1446000 +:10616000F0BD10B50446FFF7FBFE012806D11CB1B7 +:10617000FFF7F6FE013CF8E7052010BD002C08BF34 +:10618000052010BD8A6810B50C6A036814430A69BB +:1061900023F4FF4314434A6923F0700314438A69CC +:1061A0001443CA6914434A6A14438A6A2243134354 +:1061B0000360CB6843600B6883604B68C36010BDAD +:1061C00002684FF6FE7313400360002303604360D0 +:1061D0008360C3602A4B984222D02A4B984229D030 +:1061E000294B984230D0294B984237D0284B9842BF +:1061F0003ED0284B984206D153F8682C42F47002E6 +:1062000043F8682C7047244B984206D153F87C2CF5 +:1062100042F0706243F87C2C7047204B984206D1C4 +:1062200053F8042C42F00F0243F8042C70471C4B27 +:10623000984206D153F8182C42F0F00243F8182C7B +:106240007047184B984206D153F82C2C42F47062D8 +:1062500043F82C2C7047144B984206D153F8402C2D +:1062600042F4704243F8402C7047104B984205D1DD +:1062700053F8542C42F4702243F8542C704700BF5A +:10628000080002401C00024030000240440002406E +:10629000580002406C0002408000024008040240A6 +:1062A0001C040240300402404404024058040240EE +:1062B0002DE9F843574B0C460168013AC3F88410A6 +:1062C0008188A3F88810072A42D8DFE802F0040A80 +:1062D000101822292F35B3F884202280B3F88620A5 +:1062E00013E0B3F886202280B3F8842005E0B3F8E9 +:1062F000842052422280B3F88620524205E0B3F84F +:10630000862052422280B3F884206280B3F888301D +:106310001DE0B3F8842052422280B3F8862012E0B8 +:10632000B3F886202280B3F884200CE0B3F88420F0 +:106330002280B3F8862005E0B3F8862052422280FE +:10634000B3F8842052426280B3F888305B42A38065 +:10635000314B1B78002B5AD1B4F9000008F048FEED +:106360008046B4F9020008F043FE0746B4F9040081 +:1063700008F03EFE294D06462968404608F08CFE8E +:10638000E9688146384608F087FE0146484608F02D +:106390007BFDA9698146304608F07EFE01464846ED +:1063A00008F072FD0CF08EF869682080404608F015 +:1063B00073FE29698146384608F06EFE014648465C +:1063C00008F062FDE9698146304608F065FE014645 +:1063D000484608F059FD0CF075F8A9686080404601 +:1063E00008F05AFE69698046384608F055FE0146B5 +:1063F000404608F049FD296A0746304608F04CFE41 +:106400000146384608F040FD0CF05CF8A080BDE87D +:10641000F88300BF9C12002038000020E80700200D +:10642000074B084A1B7812889A4207D3064A12681B +:10643000907898428CBF0020012070470020704760 +:106440009C0600209C0E00209806002010B5194BD9 +:1064500093F88A20511C83F88A10174902F007022A +:106460004878164903EB420331F81010A3F88C105A +:1064700000231846124A9A5A02331044102B80B255 +:10648000F8D1C00808F0B4FD0E4908F005FE0E4929 +:1064900008F0B6FE0D4B04461B68187808F0A8FDFE +:1064A0000146204608F0F8FD08F0E2FF084B18709E +:1064B00010BD00BF9C120020D0070020E007002084 +:1064C000281300203333534000F07F459806002006 +:1064D0009C06002010B50F4B93F89C20102A84BF17 +:1064E000102283F89C200C4A93F89C100023D8B209 +:1064F000884202F102020AD212F8010C12F8024C90 +:1065000040EA0424054840F823400133EFE7012026 +:1065100010BD00BF9C120020A0010020E01200204E +:10652000034B1B68DA79511CD9711344187A7047F0 +:10653000B806002010B5FFF7F3FF0446FFF7F0FFA1 +:1065400004EB002080B210BD10B5FFF7F3FF044646 +:10655000FFF7F0FF04EB004010BD0B4AA2F130033F +:10656000197A81420BD00C339342F9D1074B197A37 +:10657000014004D10C339342F9D1084603E0184698 +:106580000BB15868704770479800002068000020E1 +:1065900000230549DAB2595C814203D001330C2B48 +:1065A000F7D11A4610467047116901082DE9F047E6 +:1065B0008278C6781E4BC2F1640802EB820C54420A +:1065C0005FFA88F84FEA4C0CC6F16409A4B203F1F3 +:1065D0001807A5B228B2002804DC002D14BF154608 +:1065E000012500E0454600FB00FA6D430AFB06FA70 +:1065F0009AFBF5F54D4468434FF00A0A90FBFAF018 +:10660000604480B258800D88B1F802A000B2C5EB9A +:106610000A0A00FB0AF04FF47A7A90FBFAF005447C +:1066200023F8025F0A34BB42A4B2D2D1BDE8F0879E +:10663000BE0F002010B544780078002303FB03F15F +:106640001939614301F6C4115943414340F6C4125C +:1066500091FBF2F1034A22F813100133072BEDD11D +:1066600010BD00BFA80F002010B5044C2068FFF734 +:10667000E1FF20680249BDE8104097E7FC040020D4 +:106680000421002010B5094A094913688C68126872 +:106690009342F8D1074A106811684FF47A72504358 +:1066A000001BB0FBF1F002FB030010BD3020002006 +:1066B00010E000E0B807002038B5124C0123054671 +:1066C00084F84030FFF7DEFFD4F8A03041F2883282 +:1066D000C31A9342C4F8A43084BF002384F8A830BE +:1066E00094F8A830EDB20F2BC4F8A000E55403D104 +:1066F000054B01221A7038BD024A013382F8A830D6 +:1067000038BD00BF9C1200204001002010B5044697 +:10671000FFF7B8FF0E4B41F28831D3F8AC20C3F835 +:10672000AC00821A8A42C3F8B02084BF002283F8EA +:10673000B42093F8B430074A142BD45403D1064B39 +:1067400001221A7010BD024A013382F8B43010BD24 +:106750009C120020C3010020C201002010B5044695 +:10676000FFF790FF174AD2F8B830C2F8B800C31A42 +:10677000B3F57A6F84BF002382F8BC3092F8BC3046 +:1067800023B9A82C1DD110490B7007E0022B03D1AF +:106790000C4981F89C4001E0242B01D80B49CC54D2 +:1067A0000133DBB282F8BC3092F89C2052000532F3 +:1067B000934206D1034B002283F8BC20024B0122F6 +:1067C0001A7010BD9C1200209C0100209D01002029 +:1067D00038B50446FFF756FF124B40F6C411D3F804 +:1067E000C020C3F8C000821A8A4284BF002283F806 +:1067F000C42093F8C4200AB90F2C11D10A480021F3 +:10680000017052B1094D182A154405F8014C04D104 +:10681000012283F8C410027038BD013283F8C4200D +:1068200038BD00BF9C120020410100204201002021 +:1068300038B50446FFF726FF0546FFF723FF401B48 +:10684000A042FAD338BD10B504462CB14FF47A708B +:10685000FFF7EEFF013CF8E710BD08B5014B1B68E0 +:10686000984708BDDC2700202DE9F04106460F4679 +:1068700090460025EBB2434518D20024E3B2B34260 +:106880000FD20B4B0120DA68013482F00802DA6083 +:10689000FFF7E3FF3846FFF7D6FF0020FFF7DDFFE5 +:1068A000ECE73C20FFF7CFFF0135E3E7BDE8F081DF +:1068B000000C014040F2DB14604308B50D4B102280 +:1068C0005A6108221A61841E0A4B2046DA6882F057 +:1068D0001002DA60DA6882F00802DA60FFF7B3FFCC +:1068E0000120FFF7BAFF1920FFF7ADFF0020FFF7E7 +:1068F000B4FFE9E7000C014008B503685B699847FD +:1069000008BD08B503681B69984708BD08B503684A +:10691000DB68984708BD08B503689B68984708BDC1 +:1069200008B503685B68984708BD10B5044C20683B +:10693000FFF7F6FF18B12068FFF7EDFFF6E710BD8F +:10694000841E002008B503681B68984708BD064BE5 +:1069500010B5044621461868FFF7F4FF034B1B6887 +:106960009A7954409C7110BDBC060020B8060020E6 +:1069700038B5044624200D46FFF7E9FF4D20FFF708 +:10698000E6FF002C084C0CBF3E202120FFF7DFFF64 +:106990002368002228469A71FFF7D9FF236893F8ED +:1069A0004900BDE83840D2E7B80600200146002083 +:1069B000DEE7F8B50E4E0F4C0F4DC1B207463068FA +:1069C00084F8C510FFF7BEFF2B6894F8C5109A79BC +:1069D00030684A409A71C7F3072184F8C510FFF761 +:1069E000B1FF2B6894F8C5109A794A409A71F8BDA6 +:1069F000BC0600209C120020B8060020F8B51B4DF4 +:106A00001B4C1C4F0646C1B2286884F8C610FFF71D +:106A100099FF3B6894F8C6109A7928684A409A71A1 +:106A2000C6F3072184F8C610FFF78CFF3B6894F883 +:106A3000C6109A7928684A409A71C6F3074184F8CB +:106A4000C610FFF77FFF3B6894F8C6109A79286854 +:106A50004A409A71310E84F8C610FFF773FF3B6805 +:106A600094F8C6109A794A409A71F8BDBC06002085 +:106A70009C120020B806002010B5441E14F8011F17 +:106A800021B1034B1868FFF75DFFF7E710BD00BFAA +:106A9000781E0020014B186854E700BF4C140020FA +:106AA000014B014618684DE72020002010B5044630 +:106AB0007F2C06D964F07F00C0B2FFF7F1FFE40934 +:106AC000F6E7E0B2BDE81040EAE7430083EAE07091 +:106AD000ECE770B5104E114C114D4720FFF7E0FF69 +:106AE0003078FFF7E3FF23682868C01AFFF7EDFF4F +:106AF00063686868C01AFFF7E8FF0A4B1888FFF759 +:106B0000D5FF094B1888FFF7D1FF337823742B6822 +:106B1000A3606B68E36070BD74060020600600200F +:106B200078060020AA060020A8060020014B18685D +:106B300008E700BF20200020A0F17D03012B70B5E5 +:106B400004460D460A4E05D830687D21FFF7FAFE4F +:106B500084F0200430682146FFF7F4FE35B12B881D +:106B60001C4404EB142404F0FF042C8070BD00BF0F +:106B7000C806002038B5054C05465E212068FFF7A1 +:106B8000E1FE20682946BDE83840DBE688060020A3 +:106B9000014B5E211868D5E68806002010B50A4C26 +:106BA0005E280146206805D15D21FFF7CBFE2068F5 +:106BB0003E2105E05D2903D1FFF7C4FE20683D2199 +:106BC000BDE81040BEE600BF8806002010B50446B0 +:106BD000C0B2FFF7E3FFC4F30720BDE81040FFF7A2 +:106BE000DDBF38B50D4D1020FFF7C4FF28686424C1 +:106BF00090FBF4F000B2FFF7E9FF2120FFF7BAFFA6 +:106C00002B6893FBF4F004FB103484EAE470A0EBEF +:106C1000E47000B2BDE83840D8E700BF201A002079 +:106C2000054B1B6803EBC00090F9063019420CBFFE +:106C300001204FF0FF307047A81E00200A4B1A6851 +:106C400002EBC002D379FF2B07D00849097899429B +:106C500003D9074A32F8130004E00728D4BF90880C +:106C600040F2DC5000B27047A81E0020C30A00208A +:106C70007207002010B5054C00202188FEF7F5FBB7 +:106C800061880120BDE81040FEF7EFBB1200002034 +:106C90002DE9F04F064689B00F4615469B462978E8 +:106CA000002900F0B880252902D001353046B0E037 +:106CB0006C78302C03D002354FF0000903E0AC783B +:106CC0004FF001090335A4F13003092B4FF0000800 +:106CD0001AD8A4F13003DAB2092A07D80A2B13DC38 +:106CE0000A2202FB083815F8014BF2E7A4F1610310 +:106CF000052B02D8A4F15703F0E7A4F14103052BBB +:106D000002D8A4F13703E9E76C2C03BF2C780122E9 +:106D100001350022632C66D006D8252C77D0582C5C +:106D20003FD0002C77D0BAE7732C63D002D8642C04 +:106D300011D0B4E7752C02D0782C32D0AFE70BF12C +:106D4000040A05ACDBF800000A2112B10022234638 +:106D500013E0234620E00BF1040A05ACDBF8000049 +:106D600072B1002806DA2D238DF8143040420DF15F +:106D7000150300E023460A210022FEF78DF80DE0FE +:106D8000002806DA2D238DF8143040420DF115034A +:106D900000E023460A210022FEF756F8D34600946D +:106DA0001AE00BF1040303930DF1140ADBF8000061 +:106DB000102132B1583C624262415346FEF76CF8F2 +:106DC00006E0B4F158035A425A415346FEF73CF8E4 +:106DD000DDF80CB0CDF800A03046394642464B46AF +:106DE000FEF796F85BE730469BF800100BF10404C1 +:106DF000B8470AE0DBF80030304600933946424697 +:106E000000230BF10404FEF783F8A34647E730465E +:106E10002146B84743E709B0BDE8F08F0FB407B586 +:106E20000A4904AB08680A4953F8042B096801931E +:106E3000FFF72EFF074B1868FFF763FD0028F9D016 +:106E400003B05DF804EB04B0704700BFB407002046 +:106E5000B00700204C140020F8B507460BF00EF9DF +:106E6000044638B9194B1A485A791A4B013A53F863 +:106E7000221028E03846184922460BF007F960B97D +:106E80001648FFF7F9FD164C54F8041F19B11548C0 +:106E9000FFF7C4FFF8E7144805E000250D4B53F851 +:106EA000256026B91148BDE8F840FFF7E5BD384632 +:106EB000314622460BF0EAF801350028EED1034BAB +:106EC0000B485D713146BDE8F840A7E7342000204B +:106ED0001D69010804530108C473010831690108E0 +:106EE00000530108446901087C70010848690108E1 +:106EF0005D69010870B504460BF0C0F808B91E487A +:106F00002EE020461D490BF033F900242646254685 +:106F100078B12CB1012C06D10BF005F9064602E040 +:106F20000BF001F905461549002001340BF020F95A +:106F3000EEE70B2D04D9BDE8704011480C216DE738 +:106F4000012C07DC0F4B294633F915200E48BDE80C +:106F5000704063E7A6F57A73B3F57A7F03D90B48DF +:106F6000BDE870405AE70A4829463246FFF756FF07 +:106F7000044B23F8156070BD6F690108AD6B010803 +:106F8000A969010894100020CF690108E769010888 +:106F9000096A01082DE9F74304460BF06FF8C0B207 +:106FA00090B9304C054694F8D711B4F8D42194F830 +:106FB000D6312D48009129460135FFF72FFF102DBE +:106FC00004F10404EFD14AE020460BF0ACF80F289E +:106FD000054636DC204620210BF043F8234FEDB266 +:106FE000D7F80090441CAD00002620460BF09BF81B +:106FF0005FFA86F8B8F1010F83B208D0B8F1020F3A +:107000000BD0B3F5B47F1ED23A6853530AE0FF2B7E +:1070100019D83B682B44987004E0FF2B13D83B68C9 +:107020002B44D87020462C210BF01BF8044608B1E5 +:10703000441C02E0B8F1020F05D10136032ED4D171 +:107040000DE00B4806E009EB0500002104220AF0E0 +:10705000D4FF0848102103B0BDE8F043DEE603B0DA +:10706000BDE8F08334200020226A0108080B0020CC +:10707000366A01085A6A0108F0B500231946CEB2F3 +:1070800000220C2505FB02F70D48D4B23F5CB74245 +:1070900003D00132042AF4D10BE0FF2C09D0094AB5 +:1070A00005FB04001A4492F82C21074C0133A25C22 +:1070B00002720131052901D0032BE0D9F0BD00BFD8 +:1070C00068000020342000201169010810B54F200D +:1070D000FFF75EFA0C4C84F82C010020FFF758FAF9 +:1070E0004FF4E133C4F83031C4F83431C4F83831E6 +:1070F000C4F83C31522384F82D0184F82E0184F821 +:107100002F0184F8403110BD3420002070B50546B1 +:10711000441E14F8011F61B1064E30460AF0A1FF6B +:107120000028F6D0861B0448631B304480F81031D9 +:10713000EFE770BDFC6F01083420002030B587B048 +:1071400005460C4603A800210C220AF056FF2846EB +:10715000002108F05DF920B128462A4907F094FE85 +:1071600003E02846274907F08DFE274907F094FFE2 +:1071700008F058F9054685EAE570A0EBE570694628 +:107180000A22FDF7B1FE00239D420370ACBF20230D +:107190002D2368468DF80C300AF070FF012807D1C6 +:1071A00030238DF80D308DF80E308DF80F300CE057 +:1071B000022805D130238DF80D308DF80E3004E013 +:1071C000032804BF30238DF80D30694603A80AF068 +:1071D0003BFF03A80AF052FF0338C5B22A4603A9B1 +:1071E00020460AF075FF00236355204607490AF040 +:1071F0002BFF03A9204629440AF026FF204607B0AA +:1072000030BD00BF6F12033A00007A44686A01087B +:107210002DE9F04389B004460AF030FFC6B2002ED3 +:107220006CD18B48FFF728FC8A4C2069002108F0BC +:10723000C7F840BB013688483146FFF7EFFD2069AB +:1072400004A9FFF77BFF01468448FFF7E7FD60696B +:1072500004A9FFF773FF01468048FFF7DFFDA0692F +:1072600004A9FFF76BFF01467C48FFF7D7FDE069F3 +:1072700004A9FFF763FF01467948FFF7CFFD0C2E05 +:1072800004F11004D1D10025764C2F462B464FF047 +:107290000008B04504F1100415DA184654F8101C23 +:1072A00007F0F2FD54F80C1C8146284607F0ECFD6F +:1072B00054F8081C0546384607F0E6FD08F10108B9 +:1072C0004B460746E5E76848019302950397FFF7A9 +:1072D000D3FB002401ABE058644920F0004008F0E3 +:1072E00097F8634B634A0434002814BF10461846CD +:1072F000FFF7C2FB0C2CEDD15F4891E020465F49BF +:1073000005220AF0C3FE38B9524B00220344103064 +:10731000C0281A61F8D197E02046594904220AF0A2 +:10732000B5FE06462046002E40D120210AF099FEE7 +:10733000002800F08980451C28460AF09FFE34464C +:107340008046504B53F824600EB94F4868E02846F9 +:1073500031465FFA88F20AF099FE671C20BB3D4B6C +:107360000021C2181030C02811619C46F7D1474B4C +:10737000002403EBC702D2F804E09846BEF1000FE8 +:1073800004D143483146FFF749FD55E018F837303E +:107390009C42F6DA23010CEB0305103573440FCB46 +:1073A000013485E80F00F1E73C46CAE70AF0BBFE6E +:1073B000461E0B2E074643DC204620210AF051FED4 +:1073C000054640B1451C2846FDF7A8FC214B3F016E +:1073D000D851012400E00446284620210AF041FE4D +:1073E000054640B1451C2846FDF798FC194B013471 +:1073F00003EB06135861284620210AF032FE0546A9 +:1074000040B1451C2846FDF789FC124B013403EBC3 +:1074100006139861284620210AF023FE18B91D485A +:10742000FFF72AFB10E00130FDF778FC094B032C35 +:1074300003EB0616F061F2D11748FFF7E9FE03E00F +:1074400016480C21FFF7EAFC09B0BDE8F08300BF45 +:10745000726A0108342000209D6A0108A36A0108AD +:107460004670010848200020A76A01080AD7233C7B +:107470006E6A01086A6A01087C700108B66A010830 +:10748000BC6A01080453010848690108044901085D +:10749000C16A0108D16A0108DE6B01080B6B0108A3 +:1074A0000A88F0B54B888F880E89CD88002A3AD19A +:1074B000048C834A24F001042404240C0484018BEA +:1074C000048C89B221F0F30141EA0616B6B290426B +:1074D000A4B246EA070743F0010315D002F50062A3 +:1074E000904211D0B0F1804F0ED0A2F59832904268 +:1074F0000AD002F58062904206D002F58062904286 +:1075000018BF24F00A0401D124F0020423430783A6 +:107510000384038B23F00C031B041B0C0383038BDA +:107520009BB21D4344E0042A44D1048C644A24F0F5 +:1075300010042404240C0484018B048C21F4407175 +:107540000905090D41EA063189B241EA072790424F +:10755000A4B2BFB212D002F5006290420ED0B0F1D8 +:10756000804F0BD0A2F59832904207D002F580628E +:10757000904203D002F58062904207D124F02004AB +:1075800044EA03139BB243F0100304E024F0A00488 +:1075900043F01003234307830384038B23F44063E6 +:1075A0001B041B0C0383038B9BB243EA0525ADB27E +:1075B0000583F0BD082A018C3ED121F480710904B5 +:1075C000090C0184818B3E4A89B221F0F301048CBD +:1075D00041EA0616B6B29042A4B246EA070712D0B4 +:1075E00002F5006290420ED0B0F1804F0BD0A2F5B0 +:1075F0009832904207D002F58062904203D002F5A3 +:107600008062904207D124F4007444EA03239BB2C1 +:1076100043F4807304E024F4206443F48073234330 +:1076200087830384838B23F00C031B041B0C83834D +:10763000838B9BB21D4341E021F480510904090C66 +:107640000184828B048C22F440721205120D42EAEE +:10765000072242EA06361A4AA4B29042B6B212D0C3 +:1076600002F5006290420ED0B0F1804F0BD0A2F52F +:107670009832904207D002F58062904203D002F522 +:107680008062904207D124F4005242EA033292B25F +:1076900042F4805205E047F6FF52224043F4805303 +:1076A0001A4386830284838B23F440631B041B0CE0 +:1076B0008383838B9BB243EA0525ADB28583F0BDFE +:1076C000002C01401FB50123ADF808300023ADF8B0 +:1076D0000C30ADF80A30094BADF804101B7801A945 +:1076E000012B08BF0323ADF8062008BFADF80C300E +:1076F000FFF7D6FE05B05DF804FB00BF6908002067 +:1077000038B510F80E2C044650F8043C52B901224A +:1077100000F80E2C20F80C1C197B18680222BDE81A +:107720003840CFE730F80C2C20F80A1C891A89B2AF +:1077300020F8081C074A10F80F0C002522F810103A +:1077400004F80E5C1868197B2A46FFF7BBFF04F8A3 +:10775000065C38BD641300201F4B10B55A6802F058 +:107760000C02042A03D0082A04D01C4A14E01C4A44 +:10777000126811E05A685968C2F38342C90302F1E2 +:10778000020201D4174906E0596811F4003F144978 +:10779000096818BF49084A4302605968124AC1F390 +:1077A0000311545C0168E14041605C68C4F3022449 +:1077B000145D21FA04F484605C68C4F3C224145D8F +:1077C000E140C1605B68C3F381331A44137CB1FBB1 +:1077D000F3F1016110BD00BF0010024000127A00F9 +:1077E0002400002000093D0050000020024B1A69CF +:1077F00022EA00001861704700100240954B2DE905 +:10780000F74F1B78013B012B00F22081924B1E7831 +:10781000864240F01B81914B1B78022B00F01681B1 +:107820008F4B904D13F806808F4B83F800808F4B61 +:107830001A7801921AB18E4B33F9160007E08C4A80 +:107840002B6832F9160003F100432B60404207F029 +:10785000CFFB884907F0D4FCDFF838A20446DAF8F9 +:1078600000B00021584607F0ABFD0027DFF82C924E +:10787000002859D0D9F800B02046594607F0C8FD75 +:1078800068B17D4B2A687B491A60C9F800402046E0 +:1078900007F002FC07F0C6FD784BD880BDE05846E3 +:1078A000394607F0B5FD002800F0B780744B1A7810 +:1078B000002A31D12046296807F0E4FA4FF07E51C2 +:1078C00007F088FD6F4C28B160686F4907F0E4FB52 +:1078D00060600FE06D49606807F0DEFBDFF8CCA167 +:1078E0008346514607F076FD10B9C4F804B001E0B4 +:1078F000C4F804A0624A01231370654B00221B6880 +:10790000C9F8007043449A72019A82F00103574A01 +:107910001370604B1F6080E05F4BCAF800401A682C +:10792000554BFA325A6078E02046594607F052FD2E +:1079300048B1584A4F491460204607F0ADFB07F0A4 +:1079400071FD4E4BD880534BD9F80090D3F800A06E +:107950004846514607F096FA4F4B83461968464B06 +:107960005A688A1A002A0BDA4FF07E5107F050FD50 +:10797000002852D02046514607F04AFD00284CD03E +:107980003D4A4846116807F043FD3E4C38B1206837 +:107990003E4907F081FB3C492060A06807E058465B +:1079A0004FF0804107F034FD28B1A068374907F057 +:1079B00073FBA06004E02068334907F06DFB206092 +:1079C000334B2C492068D3F8009007F065FB07F093 +:1079D0004FFD09F80800A06807F04AFD019AC84465 +:1079E00082F00103214A88F814001370294B1F60AC +:1079F0002A4B1F60224B1A780132D2B2032A01D0DF +:107A00001A700AE000221A701E4B2549586807F0C8 +:107A100043FB07F02DFD88F80A001EB9174B1A88A2 +:107A200064321A80114A13780BB11E4B00E01E4BD2 +:107A30002B600F4B33F9160007F0DAFA0D4907F007 +:107A4000DFFB0146286807F01DFA00E0084603B096 +:107A5000BDE8F08F70040020C4040020D40400208E +:107A60007846010874040020D5040020C5040020D5 +:107A700028040020000020417C130020921A0020DE +:107A8000C6040020D80400200AD7833FEC51783F79 +:107A9000D0040020C804002030200020CC040020A6 +:107AA00000007A440000A0410000A0C16F12833A98 +:107AB00010B50848FEF7E0FF074B1C682046FEF7AC +:107AC00020FF18B90A20FEF7BEFEF7E7034A044B71 +:107AD000DA6010BD336B0108781E00200400FA053F +:107AE00000ED00E008B50748FEF7C6FF064A002390 +:107AF00013729363054A137004F024FEBDE8084036 +:107B0000FFF7D6BF3F6B01087C130020D42700206D +:107B100008B50448FEF7B0FF05F0A0FABDE808403C +:107B2000FFF7C6BF6B6B01082DE9F04F002487B04B +:107B3000074604919246059380462546022DDFF8BC +:107B400088914FEA450607D104984379B9F90400B2 +:107B50001B3343435B1148E0524B39F9151033F99D +:107B6000153003EB4101CAF10003994203DB514593 +:107B7000B4BF0B4653464C49059A31F906B0915FA4 +:107B8000CBEB030303EB010BFDF7B6F898B1474BC2 +:107B900058465B5D039307F02BFA454907F030FB2D +:107BA000039B01461846FFF729FE414907F074FA86 +:107BB00007F038FC83463F4B1988C80711D4049856 +:107BC0008A07037939F9060003F11B0300FB03F36D +:107BD0004FEA231309D57A7C02FB0BFB03EB2B2323 +:107BE00003E0FB7903FB0BF31B11334A98F80AB04F +:107BF000905F042290FBF2F0181A7B5D2F4A4343FA +:107C0000DB1101932E4B01351988A35801FB00FCB1 +:107C10004FEAEC2C0BFB0C33DFF8B0C0B3F5001FC0 +:107C2000A8BF4FF400136345B8BF6346A3504FEAA3 +:107C3000633C244B0909E258E050821A4FF6FF706A +:107C4000B0FBF1F14A4303F10C0003F1180B21588A +:107C500054F80B90921189442250CDF80890914429 +:107C600098F8142044F80B1002FB09F1019809124E +:107C7000084403F1240260449053019803F12C025C +:107C8000A050032D03F1380203F1440344F802C06D +:107C9000E15008F1010804F104047FF44FAF07B08C +:107CA000BDE8F08FE227002028040020765101086B +:107CB000000020411002002060040020900F0020EE +:107CC00068040020B81300201E0200200000E0FF1E +:107CD0002DE9F04F89B00793994B0692B3F9022032 +:107CE000B3F90030002AB8BF5242002BB8BF5B4244 +:107CF00000249A42B8BF1A46039005922646A04631 +:107D000027460494A3462546DFF86092B9F8003070 +:107D100099075AD0022D58D0894BDDF818C0F25E71 +:107D2000884BF35E03EB4202CCF100039A4203DB83 +:107D300063469A42B8BF1346834ADDF81CC036F941 +:107D400002A03CF90620CAEB030303EB020AFCF78E +:107D5000D3FF90B17D4B504615F803B007F048F9BA +:107D60007B4907F04DFA01465846FFF747FD784931 +:107D700007F092F907F056FB824603986423C27914 +:107D80006FF0040102FB0AF292FBF3F2C37E01FBE7 +:107D900003FB5A4505DB03EB83039A42B4BF9346CA +:107DA0009B466C4A42F21071A35853448B42A8BFC1 +:107DB0000B4669498B42B8BF0B460399A35091F813 +:107DC00011A00AFB03F31B130493B9F8003003F06E +:107DD0000302012A01D1022D3DD1594A5F49B75E04 +:107DE000895F039A81EAE170A0EBE17012F805C0A7 +:107DF0005B4AB0F5206F54F802801DDC022D15D0CF +:107E00005020784390FBFCFC042091FBF0F1C1EB87 +:107E10000C0CE0445348B8F57A5FA8BF4FF47A5889 +:107E20008045ACBF42F80480105107E087EAE77054 +:107E3000A0EBE7706428E3DD00211151484AA15806 +:107E40007D2291FBF2F8039A2A44927A02FB08F809 +:107E5000402298FBF2F89A0716D5022D14D0059B04 +:107E6000DDF814C0C3F5FA720CFB08F07B43DDF8B3 +:107E700010C002FB0B3302FB0C024FF4FA7193FBB0 +:107E8000F1F392FBF1F208E0DB0701D5022D02D1FC +:107E900042463B4601E0049A5B463049DFF8D0A0F9 +:107EA000715A4FF0040C0FFA81F915F80AA099FBEA +:107EB000FCF00AFB00F06FF04F0A90FBFAF0184458 +:107EC000294B019036F903A0F152CAEB090999FB3D +:107ED000FCF903F1140A03F1080C54F80C0054F8EF +:107EE0000A1044F80C90DFF88CC0014415F80CC05F +:107EF000494402910CFB01F14FF0200C91FBFCF185 +:107F000044F80A000198C1EB0209A3F12C0C81444A +:107F100026F80C900135A3F1240C44F80C004942DA +:107F2000A3F11800032DA3F10C032250E15006F138 +:107F3000020604F104047FF4E7AE09B0BDE8F08F57 +:107F40001E020020E22700202804002076510108AC +:107F500000002041FC0E0020F0D8FFFF600400204C +:107F6000900F002080C1FFFF0814002010020020A5 +:107F7000B60F0020BC0F00202DE9F04F89B0079309 +:107F80007A4B814618880491059207F02DF87849BC +:107F900007F082F8002403904F4625462646022E1D +:107FA000DFF80CA20BD10499BAF904004B790A331B +:107FB000584307F01DF86F4907F022F944E06E4B73 +:107FC0003AF90520EB5E05991A444B429A4203DBCD +:107FD0000B469A42B8BF1346684AAA5E9B1A079A94 +:107FE000505F184407F004F8654907F009F9804626 +:107FF000FCF782FE28B1634B4146985DFFF7FEFB1C +:108000008046614B1A88D10705D54046D9F84410FF +:1080100007F042F818E004993AF905000B7901924B +:108020001433584306F0E4FF524907F0E9F8019A87 +:108030008346930709D5D9F84810404607F02CF835 +:108040000146584606F020FF8346504A505F06F02E +:10805000CFFF4F4AD16807F01FF882465146584675 +:1080600006F010FF396A804607F016F8DFF844B1D1 +:1080700006900399404607F00FF8F96A07F00CF8EC +:1080800054F80B1006F000FF4249804607F0A2F9B1 +:1080900038B94046404907F0BBF920B1DFF8F88015 +:1080A00001E0DFF8F0804BF80480DFF80CB15046B7 +:1080B00054F80B1006F0E6FE44F80BA003460399B3 +:1080C0004FF07E50029307F09BF8029B0146184642 +:1080D00006F0E2FF0BF10C03E2580BF1180B54F819 +:1080E0000B10824610460192029306F0CDFE5146D7 +:1080F00006F0CAFE019A029B44F80B2044F803A044 +:10810000264907F07DF8B96B06F0C6FF2449824680 +:1081100007F060F938B95046224907F079F920B1E3 +:10812000DFF880A001E0DFF878A00698414606F06D +:10813000ABFE514606F0A6FE0AF0C4F91A4BB0F5A4 +:108140007A7FA8BF4FF47A709842B8BF18460136BC +:10815000164B032EE85204F1040405F1020507F161 +:1081600004077FF41CAF09B0BDE8F08F680400205D +:10817000BD37863500004842E22700202804002051 +:108180000000204176510108100200206004002008 +:108190004003002000007AC300007A430000404002 +:1081A000000096C30000964318FCFFFFDC1300207C +:1081B0001E0200209C0F0020281400202DE9F0470B +:1081C000734A86B013789146DFF8D881C3B901228B +:1081D000D8F8001089F800206E4A1A445068884286 +:1081E00003D00C33302BF7D10022022353726A4B99 +:1081F0006A48C3F8D010FEF73FFC6948FEF73CFC24 +:10820000D8F80000FEF78CFB002800F0BE80654B1C +:10821000614C1868FEF77FFB0928014601D03F2812 +:108220004FD14FF0000AA56B5F4F56462DB15F4806 +:1082300039682A4609F02AFF10B9BA4606B93E46FF +:108240005B4B0C379F42F1D3CEB13768DAF800E0D0 +:108250002B46F85C1EF80310814201D0A3630EE0A8 +:108260005A1C41B92D2B06D8A26323442020224456 +:108270001872117203E04D4958541346E9E7A36B95 +:108280000BB1564512D04B48FEF7F6FB564509D8C0 +:1082900056F80C0BFEF7F0FBD8F800000921FEF7AA +:1082A00051FBF3E73E48FEF7E7FB0025A36B9D4239 +:1082B000A6D23E4BD8F80000595DFEF743FB0135CE +:1082C000F4E7A36B33B904283BD104F10800FFF7AE +:1082D00009FC5AE00C2801D137488CE70A2901D063 +:1082E0000D2949D13548FEF7C7FBA36BE2180023DF +:1082F0001372227A232A17D00493314B2B4E00930A +:1083000003A8294915220C23039609F010FF0546FE +:1083100038B1006809F0B2FE0130AB6830449847CC +:1083200002E02848FEF7A8FB20480021302209F08F +:1083300064FE0023A36399F80030002B7FF45DAF47 +:1083400023E00C28C8D07F2903D159E72F2B3FF613 +:1083500057AFA1F12002D2B25E2A3FF651AF13B956 +:1083600020293FF44DAF5A1CA263D8F800001C44EA +:108370002172FEF7E7FA43E77F29E7D1013BA363C8 +:10838000002223441A72104838E706B0BDE8F0878F +:10839000D4270020680000207C130020726B0108A5 +:1083A000AA6B0108781E002098560108841300204B +:1083B00094570108AF6B0108B46B01087C70010889 +:1083C000AD600008BF6B0108DB6B01082DE9F04FC1 +:1083D000D84AD94C85B01068516802AB03C3DFF8A6 +:1083E000988300214FF4EF62204609F006FE04F561 +:1083F0000573C8F80030D14B0025DFF880A31D704D +:1084000004F25673CAF80030032363710223A36099 +:1084100040F24C404FF41673A4F8F030A4F81C015D +:10842000FA2340F26C70A4F8F230A4F81E012A235B +:108430001920A4F8EE3084F825014FF4FA7340F2C5 +:108440007E40A4F8F630A4F8D000202340F23A7021 +:1084500084F8F430A4F8D2006E234FF47A7084F8D4 +:108460000431A4F8D4002B2340F27E5084F8053167 +:10847000A4F8D600212340F2EA500126552240F20A +:10848000DC514FF01E0B4FF0320984F80631A4F88E +:10849000D8004FF4C87340F2B4502270A4F80831E9 +:1084A000A4F81A11A4F8DA00A4F8DE3084F8EC601D +:1084B00084F821B184F8246184F82761A4F8DC9061 +:1084C000A4F8E0908DE80600FEF700FE40F6AC53FD +:1084D000A381D8F8003028271720A57318761F71BC +:1084E00083F80EB05F7183F80FB058761D700B20C3 +:1084F000019A1872142058721875502098776420C9 +:10850000D8774FF0080E782083F813E05873DFF81F +:1085100070C28B484FF00E0E9A7183F80AE02D223C +:108520004FF05A0E4FF00A0B1A745A7783F80BE08B +:108530001F73DA7583F821609D7683F807905D7468 +:10854000DD769D741D7783F815B0C3F824C0D86319 +:1085500018644FF08240D8624FF07C50986379489D +:10856000C3F828C05864784A7848DFF818C20099E0 +:108570001A635A639864C3F84CC084F856E74FF006 +:10858000410EA4F85E1784F857E784F85A5784F828 +:108590005B5784F8589784F8595784F85C579A6663 +:1085A0006B4A0421DA666B4A83F858101521D865A6 +:1085B00083F8607083F861701A6783F87460A3F8B9 +:1085C0005450A3F85650A3F8525083F864106248F0 +:1085D000FEF79CFDD8F800304FF44872A3F86221F2 +:1085E000C82283F8A7214FF49662A3F8A82140F28D +:1085F000D932A3F8AA2140F6430283F85F7183F8C9 +:108600006061A3F8AC2183F85D5183F85E5183F873 +:10861000645183F8A6B11A46474656464FF47F7117 +:10862000A2F866114FF4FA61A2F8681102A840F2AC +:10863000DC51A2F86A11415D013582F86C11082DF8 +:108640004FF0FF0182F86D1102F10802E6D101221C +:1086500083F8AE2183F8AF2183F8B021C82183F8D5 +:10866000B6216422A3F8B211A3F8B82114214FF463 +:10867000967283F8B411A3F8BA211E21282283F838 +:10868000B511A3F8BC210023E21810330021C02B40 +:108690001161F9D131480021402209F0AEFC0023DC +:1086A0002F49E218595804330868382BC2F8D4010E +:1086B000F6D12C480021802209F09FFC2A4B294D3D +:1086C00003F1300E186859682A4603C2083373450F +:1086D0001546F7D1FCF71EFDFCF758FDFCF732FDFF +:1086E0003F68012539464FF4E072204884F87457FA +:1086F00084F8755709F078FC39464FF4E0721C484D +:1087000009F072FC33681B4A5968186803C219895A +:1087100022F8021B1968C4F86A17596851601B894E +:1087200084F824541381022384F8E43505B0BDE8AD +:10873000F08F00BF7851010834200020F80E00208F +:108740008FC2753DCDCC4C3D9A99193F0000A04099 +:10875000F6287C3F3D0A773FDF6B010808220020A6 +:108760009048010888210020805101080824002039 +:10877000C8250020942700203C030020FC04002092 +:10878000000020400000404008B50548FEF774F99D +:10879000FFF71CFE04F062FCBDE80840FFF788B953 +:1087A000E86B010810B50A4C23681BB101F004FA0C +:1087B00000232360074B1B7813B1012B03D010BD9E +:1087C0004FF4006201E04FF48052034B1A8010BD59 +:1087D0001C08002021080020000000202DE9F04F97 +:1087E000012828BF0120142101FB00F389B0DFF824 +:1087F000BCB101900BEB03025BF803706548019B71 +:10880000654E0760F469037110691589B2F80A9022 +:108810002043546849EA0508F0610222C4F8108038 +:1088200020468DF80E1003A9ADF80C808DF80F20AE +:10883000FCF726FE4FF0080AA268154203D10A2071 +:10884000FDF7F6FFF8E70A206561FDF7F1FF256106 +:108850000A20FDF7EDFFBAF1010AEDD10A20C4F8B4 +:108860001490FDF7E5FF0A206561FDF7E1FF0A209E +:108870002561FDF7DDFF0222C4F8109020468DF837 +:108880000F2003A91C228DF80E20ADF80C80FCF7F8 +:10889000F7FD424A9742326905D142F40012326133 +:1088A0004FF4001004E042F4800232614FF4800083 +:1088B000FEF79CFFBA8803A822F440721204120C3F +:1088C000BA803A88012592B242F001023A80BC880F +:1088D000FEF742FF24F03F04059831492404B0FB21 +:1088E000F1F1240C0C43A4B2BC803A88142322F08A +:1088F00001021204120C3A802A4A0024B0FBF2F260 +:108900004FF49670414392B24FF47A70002A91FB73 +:10891000F0F108BF0122013142F4004289B23984EA +:10892000BA833A8803A892B242F001023A803A88A8 +:1089300022F4816222F002021204120C3A804FF4F7 +:1089400080423A81019A8DF80D4003FB02B77B7B90 +:108950008DF80E408DF80C308DF80F5003F0AAFB07 +:108960003B7B9DF80F208DF80C308DF80D408DF875 +:108970000E401AB103A803F09DFB07E0590903F06C +:108980001F039D40084A203142F8215009B0BDE83C +:10899000F08F00BF5014002000100240005400402F +:1089A00040420F00804F120000E100E0B05101088A +:1089B00008B5054B1A88013292B21A80034B187918 +:1089C000FFF70CFF002008BD481A002050140020BB +:1089D00013B51E4B4000C0B2587102AC18689971B3 +:1089E00004F8012D00210122DA71DC6019721C618A +:1089F0001A755A75997538B38288920515D402880C +:108A0000D4050DD447F230520188890502D5013AC8 +:108A1000FAD112E08AB1028892B242F480720280E6 +:108A2000828892B242F44072828047F23052597D7D +:108A300011B1013AFBD100E012B9FFF7B9FF03E031 +:108A4000024B987D80F0010002B010BD5014002050 +:108A5000024640213C20BBE7024680213C20B7E78C +:108A600008B55038C0B2FFF7F7FF0020FFF7F4FF5A +:108A7000BDE808401020EFE7772048210122A7E752 +:108A8000772058210122A3E7064B002193F82020EC +:108A9000054B9201343219707720F42102F0FC0268 +:108AA00096E700BF380800201C200020034B00225E +:108AB0001A707720F4212E228AE700BF1C200020A4 +:108AC00010B5174C23681BB101F076F80023236022 +:108AD0006B2180226820FFF77BFF6420FDF7B3FE47 +:108AE000192100226820FFF773FF6B210322682001 +:108AF000FFF76EFF372102226820FFF769FF094B5D +:108B00001A211A786820FFF763FF1B2118226820BA +:108B1000FFF75EFFBDE8104068201C21102257E7D8 +:108B20001C0800203900002008B51920FDF78BFE35 +:108B3000682015210022FFF74BFF10B90320FDF735 +:108B4000B9FE0C4B16211A78682042F01802FFF784 +:108B50003FFF172100226820FFF73AFF3D21012245 +:108B60006820FFF735FFBDE8084068203E2101225C +:108B70002EE700BF3A00002013B500222A211C2056 +:108B8000FFF726FF0E2102221C20FFF721FF0F21F5 +:108B900003221C20FFF71CFF2B2112221C20FFF7B1 +:108BA00017FF164B02249A69154842F004029A6195 +:108BB0002023ADF8043004230DEB03018DF80630BB +:108BC0008DF80740FCF75CFC22462C211C20FFF7A7 +:108BD000FFFE2D2101221C20FFF7FAFE2E2100228C +:108BE0001C20FFF7F5FE2A2105221C20FFF7F0FECE +:108BF000044B4FF480721A8002B010BD0010024086 +:108C0000000801400000002008B50F2108221820AC +:108C1000FFF7DEFE0E2218201021FFF7D9FE024BCF +:108C20004FF480521A8008BD0000002008B5134B95 +:108C300053201B782D2108227BB1FFF7C9FE31217B +:108C40000A225320FFF7C4FE2C210C225320FFF7E9 +:108C5000BFFE53203821902209E0FFF7B9FE3121F1 +:108C60000A225320FFF7B4FE53202C210A22FFF7DB +:108C7000AFFE034B40F209121A8008BD2008002005 +:108C80000000002010B540001C4CC0B26071A17102 +:108C900001200021E1712072227560752068236136 +:108CA000E360A17540B383889B0515D40388D9057B +:108CB0000DD447F230530288920502D5013BFAD118 +:108CC00012E08BB103889BB243F4807303808388E6 +:108CD0009BB243F44073838047F23053627D12B1FC +:108CE000013BFBD100E01BB9BDE81040FFF760BEBF +:108CF000024B987D80F0010010BD00BF5014002091 +:108D000037B50622044603216B461E20FFF7BAFF43 +:108D10009DF801309DF80000154D43EA002000B297 +:108D200006F066F9296806F0B7F906F07BFB9DF8B6 +:108D3000033020809DF8020043EA002000B206F0D4 +:108D400057F9A96806F0A8F906F06CFB9DF8053004 +:108D5000A0809DF8040043EA002000B206F048F924 +:108D6000696806F099F906F05DFB608003B030BDDC +:108D70003C00002007B5002101AB03227720FFF75C +:108D800081FF9DF805009DF80430000240EA034091 +:108D90009DF80630184303B05DF804FB08B5FFF7F3 +:108DA000E9FF014B986108BD5014002008B5FFF79A +:108DB000E1FF014BD86108BD50140020104B13B5E2 +:108DC0001B78104C13B9238C0133238401ABF6219B +:108DD00003227720FFF756FF9DF805309DF8042009 +:108DE0001B0243EA02439DF806201343064AB2F9E8 +:108DF0002020C2F10802D340636202B010BD00BF60 +:108E00001C20002050140020380800200B4B13B504 +:108E10001B780B4C13B9238C0133238401ABF6214F +:108E200002227720FFF72EFF9DF804209DF80530E1 +:108E300043EA0223238502B010BD00BF1C2000209E +:108E40005014002013B5062204466B463B216820CF +:108E5000FFF718FF9DF800209DF8013043EA022338 +:108E600023809DF802209DF8033043EA02236380AB +:108E70009DF804209DF8053043EA0223A38002B048 +:108E800010BD13B5062204466B4643216820FFF748 +:108E9000F9FE9DF800209DF8013043EA022323806B +:108EA0009DF802209DF8033043EA022363809DF879 +:108EB00004209DF8053043EA0223A38002B010BDD0 +:108EC00007B52320FDF7BFFC6820752101220DF1B5 +:108ED0000703FFF7D7FE28B19DF80700B0F168033C +:108EE0005842584103B05DF804FB13B50222044612 +:108EF00001AB1B216820FFF7C5FE9DF804209DF8FB +:108F0000053043EA022303F54E534FF48C721033BD +:108F100093FBF2F32333238002B010BD13B5062276 +:108F200004466B461D216820FFF7ACFE9DF800202B +:108F30009DF8013043EA022323809DF802209DF82A +:108F4000033043EA022363809DF804209DF8053036 +:108F500043EA0223A38002B010BD13B506220446E3 +:108F60006B4601211C20FFF78DFE9DF801309DF816 +:108F700000209DF8021043EA022242F38D020423EE +:108F800092FBF3F222809DF8032042EA012242F391 +:108F90008D0292FBF3F262809DF804109DF805208B +:108FA00042EA012242F38D0292FBF3F3A38002B066 +:108FB00010BD13B5062204466B4602211820FFF7A8 +:108FC00061FE9DF800309DF801209B0803EB022311 +:108FD00023809DF802309DF803209B0803EB0223B9 +:108FE00063809DF804309DF805209B0803EB022365 +:108FF000A38002B010BD2F4B2DE9F3411B7805462D +:10900000002B39D0002426462746A04608226B466E +:1090100053203221FFF736FE9DF801209DF80030E5 +:10902000013403EB02231BB29DF8032098449DF802 +:109030000230E4B203EB02231BB21F449DF805206B +:109040009DF80430202C03EB02231BB21E449DF834 +:10905000073003F07F0301D0002BD7D1164B98FBCC +:10906000F4F897FBF4F796FBF4F6A5F800806F8010 +:10907000AE8083F82A401AE006226B465320322144 +:10908000FFF700FE9DF801209DF8003003EB02235E +:109090002B809DF803209DF8023003EB02236B80A8 +:1090A0009DF805209DF8043003EB0223AB8002B04D +:1090B000BDE8F081200800205014002013B5224C98 +:1090C00023689A8A92B20192019A12F4706F1CBFBF +:1090D0000122A275019A12F4E06F29D01A8B9A88A6 +:1090E00022F480621204120C9A80019A91051FD416 +:1090F0001A8892051CD41A88D0050ED51A88D10575 +:10910000FCD41A8892B242F400721A801A8892052E +:10911000FCD42079FFF762FB0AE01A8892B242F48D +:1091200000721A809A8822F440721204120C9A80FB +:109130002268938A23F470631B041B0C9382002320 +:10914000637502B010BD00BF501400200B4B07B573 +:109150009A690B4842F010029A614FF40053ADF83F +:10916000043002238DF8073001A910238DF8063052 +:10917000FCF786F903B05DF804FB00BF0010024065 +:109180000010014010B50446204608F077FF10F0AB +:10919000FF0F06D10C4B0D481978BDE81040FDF7C4 +:1091A0003DBE204608F0BFFF02280CD8064B0A221D +:1091B0001870074B074C02FB0030074B0630186055 +:1091C000FDF752FAE0E710BDF80E0020FE6B010833 +:1091D00084270020DE6B0108FC0400201FB501235A +:1091E000ADF80830ADF80410002301A9ADF80A303D +:1091F000ADF80C30ADF80620FEF752F905B05DF879 +:1092000004FB10B5A0F5127494F83C22C2B9A36A0D +:10921000616A994229D0591CA069A162C05C236986 +:10922000C0B299424FEA400343F40073A4F83E32BF +:109230004FF00A0384F83D3228BFA262012312E0F6 +:1092400094F93D327BB1B4F83E1220464B08A4F8A5 +:109250003E3201F00101FCF7F8F894F83D32013B91 +:1092600084F83D3201E084F83C3294F83832002B27 +:109270004FD194F839320133DBB2092B84F83932FB +:1092800004D12046BDE81040FCF7CAB80A2B40D1F3 +:1092900094F83B322BB9B4F8403243F00103A4F800 +:1092A00040326379D9071CD5B4F84002820501D455 +:1092B000C30705D4B4F844320133A4F8443210E0B3 +:1092C000E36AC0F347000BB198470AE0E3696269BB +:1092D000D054E269E3680132B2FBF3F103FB1123DE +:1092E000E361012284F8382294F83B220023012A0A +:1092F00084F839320DD1A27984F83B32236B012AEC +:109300001868197B14BF02220022BDE81040FFF745 +:1093100065BF10BD10B5A0F513746379DB074CD59C +:1093200094F8383213B3236B1868828DC2F34E025F +:10933000828494F83C2222B1B4F842220132A4F88B +:109340004222A279197B012A0CBF02220022FFF7D8 +:1093500045FF012384F83B32002384F8393284F836 +:109360003A3284F83832A4F8403210BD94F83B32D7 +:109370002046012B04BF94F8393284F83A32FCF7C6 +:109380004FF894F83B12236BA27949B9012184F874 +:109390003B128A421868197B0CBF0222002208E0A7 +:1093A000002184F83B12012A1868197B14BF02229D +:1093B0000022BDE81040FFF711BF10BD426A10B592 +:1093C0008469A154416A02690131B1FBF2F402FBE4 +:1093D00014124262426B32B11368DB0708D4BDE855 +:1093E000104002F0FFBD036DDA6842F08002DA60DF +:1093F00010BD2DE9F84FFDF745F98B4E8B4A3368C8 +:109400000546C31A934240F29580894B8949002250 +:1094100009789A701A71DA775A75874A99771975A7 +:1094200011680A2291FBF2F11977091259778349E1 +:10943000096891FBF2F283F82020121283F82120B0 +:109440007F4B804A1978804B91761B7813F0020F7E +:10945000134602D12D23D3766BE004298CBF33222F +:109460003222DA76794A7A4C1768DFF8089297FB4D +:10947000F4FC09FB0C7A4FF0060808FB0AFA506866 +:10948000744A0CEB8C0C9AFBF2FB02FB1BAA0CEB54 +:109490008C0C4FFA8BFB0BEB8C0C1FFA8CFC90FBAB +:1094A000F4F483F80AC04FEA1C2C83F80BC009FBC4 +:1094B000040C08FB0CFCFF0F5F729CFBF2F702FB35 +:1094C00017C2642192FBF1F25A7412129A74624A22 +:1094D000C00F12889873242042439AFBF1FA92FB42 +:1094E000F1F15E4AD9711288C1F30721DA74120AC8 +:1094F0001A755B4A197211880A22B1FBF2F202F561 +:10950000FA7292B204EB84045A75120A7FB204EB29 +:1095100084049A75534A07EB8404A4B2128883F832 +:109520000CA0DC734FEA2A2A240A83F80DA01C74CD +:109530001A7735603379DFF8F0804BB94A4C2068F0 +:10954000FDF7EEF9494B1B78002B44D1012848D890 +:10955000F068354C002865D027793FB1236940F683 +:10956000B732EB1A93420AD8BDE8F88F0123237172 +:109570003D4B02211868FDF7BFF9277528E0637D90 +:10958000394A43B910680121E3602371FDF7B4F94A +:10959000FDF7CBF91CE0013BDBB26375217D94F84C +:1095A00016E03BB94B1C0EF1010E237584F816E052 +:1095B00010680BE0034613F8017B0EF1010E3944ED +:1095C00010682175E36084F816E03946FDF7BAF9B2 +:1095D0003561BDE8F88F0028BAD02068FDF79BF907 +:1095E0001DE00228224F03D0FDF79FF9012303E07D +:1095F0003A781AB1C8F808503B70A9E7D8F8083093 +:10960000EB1AB3F57A6FA3D3012320683B70FDF703 +:1096100082F907462068FDF77EF9802F98D103F084 +:10962000BDFD95E7BDE8F88F7C1400203F0D0300D9 +:109630003C0E00209C060020A0060020A40600206E +:1096400074060020680E00201E040020780600200A +:109650008096980040420F00A80600204C1A002077 +:10966000AA0600204E1A0020841E0020901E002012 +:1096700064000020806967FFF7B50368174C184D38 +:1096800023600B68174E63600068FBF7E9FD95E8FF +:109690000300154B0196009394E80C00FBF79EFD28 +:1096A0003668124B60681E606B68114FC01A05F077 +:1096B0009FFC104B196805F0EFFC05F0B3FE226823 +:1096C0002B687860D31A3B600B4B1E600B4B1B68FA +:1096D000DA880B4B1A8003B0F0BD00BF20120020C7 +:1096E000780600202C12002028120020681200208A +:1096F000301200204C00002060120020040B0020DB +:109700005C1200202DE9F043142285B08146884682 +:109710001B48002108F071FC03261A4B0027B742B2 +:1097200024DA13F8042C0021C8B2013112B1501E02 +:109730000240F9E71C7AD1B2013214B1611E0C402B +:10974000F9E7421A002A0EDD01ACA3F10C0595E8F9 +:10975000070084E8070093E8070085E8070094E81D +:10976000070083E8070001370C33D8E7013ED4D166 +:10977000034A4846414605B0BDE8F04302F084BFC5 +:1097800094140020740000200022064B13445968F2 +:10979000814203D00C32302AF7D1002300225A72C2 +:1097A0005A6070476800002038B50E4D04462B689B +:1097B000834207D10121FFF7E7FF284600214C2211 +:1097C00008F01BFCEB6CA3420AD120460121FFF7F5 +:1097D000DBFFBDE83840044800214C2208F00DBCF6 +:1097E00038BD00BFF80F00204410002010B5002342 +:1097F000054A1A445468844203D00C33302BF7D105 +:109800000022517210BD00BF680000202DE9F3470F +:1098100006461F464FF41473734347489246C418D4 +:1098200080460EB9454A02E0012E04D1444A226323 +:109830001032C4F83421434A0025C2500323637117 +:109840004FF480734FF00109E3602361D4F83431A1 +:1098500084F83C5284F8389284F8395284F846628D +:10986000586804F134029B68626104F59C72A2613D +:10987000E1622562E561A5626562A4F84252A4F83E +:109880004452ADF804300225102301A9C4F808A001 +:10989000A7718DF806308DF80750FBF7F1FD236BAB +:1098A00001A958689B688DF80750ADF8043048232B +:1098B0008DF80630FBF7E4FD49462046FBF7C5FD71 +:1098C0003220FCF7C0FF204BD4F834911B681D46B2 +:1098D000B5FBFAF1B1F5803F03D3012DF8D96D083E +:1098E000F6E71A4A4846B3FBF2F289B2D2B203F065 +:1098F000DFFC4FF414735E43154B06F5127608EB4C +:10990000060548F8063048462946002202F09EFA2D +:10991000266B012F14BF022200223068317BFFF733 +:109920005DFC0C4B30466B60291D002202F08EFA64 +:10993000204602B0BDE8F087A81400208466010824 +:10994000A4660108D8510108A800002040420F0079 +:10995000039200081593000803460A4690F8460251 +:10996000D96A9B7952E7F8B50022074637491301B7 +:1099700001F11800185CB84204D00132082AF5D170 +:109980000020F8BD324E0B44183306F2CC45082FA8 +:109990000FCB344685E80F001BD009D8022F0ED01C +:1099A000042F16D0012F4FD12A4B1B685B6847E06C +:1099B000202F42D0402F06D0102F45D122E0254B3A +:1099C0001B689B6802E0234B1B681B69C6F8D034F8 +:1099D00036E0214B1B681B7853B1013B012B0AD9A0 +:1099E000FBF77EFB002814BF4FF46143002304E023 +:1099F0004FF4165301E04FF49643C4F8D034C4F842 +:109A0000D43421E0154B1B681B7A042B1CD8DFE8EB +:109A100003F00A0A030A0A00114BC6F8D034C6F84C +:109A2000D434032306E04FF4E133C6F8D034C6F84B +:109A3000D434012384F8D93406E0064B1B68DB6874 +:109A4000C6F8D4342846F8BD0648F8BDD8510108F8 +:109A50007C14002090100020840600203C0100208F +:109A6000A08601004819002010B50446FFF77BFFCF +:109A700001462046FFF746FE4368187A10F00100C1 +:109A800018BF586810BD38B505460C46FFF76BFF88 +:109A900001462846FFF736FE28B143681B7A1C4270 +:109AA0000CBF0020012038BD38B50B4B05469B6824 +:109AB0005A050ED5FBF714FB044650B10820E9B255 +:109AC000FFF7E1FF30B1054B1C78231F5C425C417E +:109AD00000E00124204638BD34200020C4060020C8 +:109AE000234B70B519684FF47A73B1FBF3F1214B36 +:109AF00021481A78214B224D1B78FDF78FF9214B15 +:109B000021481968214B2E68B1FBF3F1FDF786F966 +:109B100000241F4BE2B253F8221049B1012303FA8B +:109B200002F2324202D01B48FDF778F90134F0E727 +:109B30002A6892070DD5184A1848127803EB820359 +:109B4000196AFDF76BF9164B197A11B11548FDF733 +:109B500065F91548FCF790FFBDE87040134B1448B9 +:109B60001A88144B92B219884FF4EF63FDF756B977 +:109B7000302000209C060020306C01089800002056 +:109B800008020020A80000206E6C010840420F006F +:109B90007052010844690108DA2700208C6C010822 +:109BA000AC030020966C01087C700108481A002064 +:109BB0009A6C0108680400200C4B07B51B681968F3 +:109BC00019B10B4A9069014391619A889868ADF880 +:109BD000042002228DF8072004220DEB02018DF8EB +:109BE0000620FBF74DFC03B05DF804FB1C080020C9 +:109BF000001002402DE9F74FA24E0C46377805467B +:109C00001146006891469B4622467B1C06F8043BA1 +:109C100002F09AFAAB686868ADF8043018238DF842 +:109C2000063001A902238DF80730FBF729FC2B7BB6 +:109C30003F0106EB070A2C680C2B00F2F280DFE8EC +:109C400013F00D00F000F000F0004D00F000F00007 +:109C5000F0008200F000F000F000B600238C8A488B +:109C600023F001031B041B0C2384218CA288238B6B +:109C7000844223F073034FEA03434FEA134389B24C +:109C800092B243F0700314D000F50060844210D00B +:109C900000F5406084420CD000F58060844208D01A +:109CA00000F58060844204D021F0020141F00301FC +:109CB00007E021F00E0122F4407241F0030142F46A +:109CC0008072A2802383A4F834B02184238B23F0F4 +:109CD00008031B041B0C43F0080332E0238C6A4882 +:109CE00023F010031B041B0C2384218CA288238BDC +:109CF000844223F4E6434FEA03434FEA134389B215 +:109D000092B243F4E04308D000F50060844204D0EE +:109D100021F0200141F0300107E021F0E00122F4C0 +:109D2000406241F0300142F48062A2802383A4F8B3 +:109D300038B02184238B23F400631B041B0C43F4F1 +:109D4000006323836DE0238C4F4823F480731B044E +:109D50001B0C2384218CA288A38B844223F07303E1 +:109D60004FEA03434FEA134389B292B243F07003C0 +:109D700008D000F50060844204D021F4007141F461 +:109D8000407107E021F4606122F4405241F44071D7 +:109D900042F48052A280A383A4F83CB02184A38B18 +:109DA00023F008031B041B0C43F0080338E0B4F84D +:109DB00020C0354A2CF4805C4FEA0C4C4FEA1C4C16 +:109DC000A4F820C0B4F820C0A388B4F81C802CF4F8 +:109DD000005C28F4E6484FEA08484FEA0C4C4FEA8A +:109DE00018484FEA1C4C94429BB248F4E0484CF4AB +:109DF000405C03D002F50062944203D123F4804317 +:109E000043F48043A380A4F81C80A4F840B0A4F8D5 +:109E100020C0A38B23F400631B041B0C43F40063DA +:109E2000A383AB7B43B1B4F844306FEA43436FEA9A +:109E300053439BB2A4F8443023889BB243F0010300 +:109E400023802B7B0C2B14D8DFE803F007131313AC +:109E50000A1313130D131313100004F1340307E056 +:109E600004F1380304E004F13C0301E004F1400391 +:109E7000F3515046AAF80890CAF8044003B0BDE870 +:109E8000F08F00BF58190020002C014040F2E93348 +:109E90000E4A1189890709D5908140F2E9330B4AAE +:109EA0001189C9070DD59089C0B27047013B9BB29B +:109EB000002BEDD1064BFF201A88013292B21A8096 +:109EC0007047013B9BB2002BE9D1F3E7003800401B +:109ED000CE07002038B5874A874B92F8C41033F874 +:109EE000110018B982F8C4004FF4036092F8C4104E +:109EF000B0F5C06F01F10101C9B27E4B82F8C41008 +:109F00004DD019D8B0F5007F44D006D8B0F5807F89 +:109F100042D0B0F5887F64D038BDB0F5806F73D083 +:109F2000B0F5826F00F0B080B0F5047F40F0E080C3 +:109F3000724B53211B78D5E0B0F5006F31D00DD8AE +:109F4000B0F5E26F55D0B0F5E46F56D0B0F5E06FE4 +:109F500040F0CE806A4BB3F9001051E0B0F5036FCA +:109F600007D0B0F5046F3FD0B0F5026F40F0C0806D +:109F7000ACE0644B1B689A0640F1BA80624B1B78D8 +:109F80009B0740F1B580614B24211B885943642312 +:109F9000123136E05E4B25E0D3F8C810A3E05D4BEC +:109FA00020E0584B1B689D0640F1A280564B1B7861 +:109FB0009C0740F19D8011F0010F574B08D0596864 +:109FC0000029BCBF494241F0804141F0004105E019 +:109FD00019680029BCBF494241F080414FF400603C +:109FE00081E04E4B19687EE04D4B6421B3F900309F +:109FF00078E0434BB3F9021002E0414BB3F904108F +:10A000002C2391FBF3F16EE093F8CC100131C9B22F +:10A01000032988BF012183F8CC1092F8CC3042F29A +:10A02000107159433F4B1B78D80748BF01319A073D +:10A0300048BF02315D073C4B48BF04311B88DC0739 +:10A0400048BF0A31980748BF14311A0648BF283163 +:10A05000DD0548BF28315C0748BF6431180748BF99 +:10A06000C8319A0548BF01F5C8719D0648BF01F582 +:10A070007A71DC0648BF01F5FA61580648BF01F560 +:10A080007A614FF480602EE01E4B284C1D6815F05D +:10A09000200516D01C4B1B7813F0020F0CBF0021BB +:10A0A0004FF47A7113F0010F0CBF00234FF4FA63E1 +:10A0B00019441F4B1B781944FBF710FE0023237033 +:10A0C00038BD2946FBF70AFE257038BD0D4B1B68CD +:10A0D0009A060DD50C4B1B789B0709D5154B4FF4F1 +:10A0E0007A711B885943FBF7F9FD104B00221A7057 +:10A0F00038BD00BF58190020106C01089C060020D4 +:10A1000008040020080200201E040020A8060020E9 +:10A11000A0060020A4060020780600209406002057 +:10A120003E040020D527002010020020D406002085 +:10A1300074060020AA0600202DE9F04FAA4C87B033 +:10A14000D4F8D030C3EB000946F2A713994540F28A +:10A150003782A64EC4F8D0003388A54FA54D63B30F +:10A160002B68D4F8D42018783B680138B3FBF0F0A2 +:10A17000082392FBF3F1521A1044C4F8D40090FB68 +:10A18000F3F004F035FF9C4905F03AF89B4908F0DC +:10A1900067FA01464FF07E5004F074FE984904F0CF +:10A1A0007BFF05F03FF93388C4F8D800013B3380CA +:10A1B0000023C4F8DC30C4F8E0302B6838681B7822 +:10A1C000013BB0FBF3F004F00FFF8B4905F018F8EA +:10A1D0008A4908F045FA01464FF07E5004F052FEDD +:10A1E000874904F059FF08F06DF92B6807465D6850 +:10A1F000D4F8C80004F0FCFE294604F04DFF0646E2 +:10A20000D4F8D800381A04F0F3FE294607464FF078 +:10A210007E5004F037FE0146384604F03DFF01460B +:10A22000304604F031FE08F04DF9764B0746B3F99D +:10A230000050B3F90230002DB8BF6D42002BB8BFFB +:10A240005B429D42B8BF1D462DB26F4BFA2D186878 +:10A250001E4614DC04F0CCFE8046284604F0C8FEFE +:10A2600001466A4804F00EFE0146404604F014FF21 +:10A27000664904F0C5FF05F0D5F8054601E04FF04A +:10A28000FF356B1EC62B356005D87F1BC4F8E47004 +:10A29000C4F8C8502DE0D4F8E430002D524EC3EB82 +:10A2A000070702DCC6F8C87023E0C5F5967004F015 +:10A2B0009FFE574904F0A4FF0446284604F098FE88 +:10A2C000214604F0E9FE0546384604F091FE214699 +:10A2D00007464FF07E5004F0D5FD0146384604F0A5 +:10A2E000DBFE0146284604F0CFFD05F09BF8C6F8DA +:10A2F000C800484B484E1868019304F075FE474962 +:10A30000044604F0C9FE8346B06804F071FE444A76 +:10A3100005461068029204F06BFE0146284604F0E0 +:10A320006FFF40490490096804F0B6FE214604F02E +:10A33000B3FE30490590D1F800804FF07C5104F015 +:10A34000ABFE594604F0A8FE274C8446D4F8DC70D6 +:10A3500059463846D8F80CA0D4F8C850CDF80CC0EF +:10A3600004F09AFEDDF80CC00146604604F08CFD56 +:10A37000D4F8E01004F088FD514604F08DFE8346C9 +:10A38000284604F035FE514684464FF07E50CDF805 +:10A390000CC004F077FDDDF80CC00146604604F007 +:10A3A0007BFE0146584604F06FFD0599C4F8E000B5 +:10A3B0008246384604F068FD0021C4F8DC003160B4 +:10A3C0007160B160019B029A1960084B07461B88B7 +:10A3D0001160002B40F0F4800B4B134E1B68013BC7 +:10A3E000C62B23D8356025E058190020D827002037 +:10A3F0005C0200206402002080E6C547B1DC423EDA +:10A40000D048874A28040020A400002000006144AE +:10A410000000C842C82700204C040020BD37863504 +:10A420005C0400206008002018020020504604F060 +:10A43000F9FF3060D4F8E800281A04F0D9FD624929 +:10A4400004F02AFE8246484604F0CEFD01465046FE +:10A4500004F0D6FE04F0E6FF40F2DC535B4A98427B +:10A46000A8BF18469042B8BF10460A21C4F8E85069 +:10A47000FAF772FDD8F8085081462946384604F0AC +:10A480000BFE0746484604F0B3FD294680464FF0D0 +:10A490007E5004F0F7FC0146404604F0FDFD014605 +:10A4A000384604F0F1FCC4F8DC0008F00BF8052194 +:10A4B0008046FAF751FD464A464B1188186001F272 +:10A4C0001F3189B240F23E639942D4F8EC7008D84B +:10A4D000508800F21F3080B298428CBF00200120CB +:10A4E00000E00020002866D03B4B3C4D1B7803BBAE +:10A4F0003B4B3C481A6833680A21D21AB2F5FA7FFE +:10A50000A8BF4FF4FA728242A8BF1046FAF724FDA2 +:10A510002B688022DB78584390FBF2F3B3F5967FEB +:10A52000A8BF4FF49673A2F5D6729342B8BF1346F4 +:10A5300001E02D4B1B682A68C8EB0303557A2021E4 +:10A540005D4395FBF1F52949D67C0868B5F5967F02 +:10A55000A8BF4FF4967503FB0600254BB0F5C81F46 +:10A56000A8BF4FF4C8109842B8BF18464FF4005324 +:10A57000086090FBF3F01F4B9D42ACBF4519C51816 +:10A58000507F04F035FD39460646049804F07CFC03 +:10A590000146304604F080FD4FF06C5104F07CFD24 +:10A5A00004F040FF6FF095039628A8BF96209842CC +:10A5B000B8BF1846281A104B1860049BC4F8EC303A +:10A5C00007B0BDE8F08F00BF0024744924FAFFFFF4 +:10A5D0002804002094060020F4040020D01E00204F +:10A5E000140200200CFEFFFFD027002028020020CC +:10A5F0000000E7FFD4FEFFFF2C0200202DE9F0470A +:10A60000054607F03BFD2E4B0446D3F808809A46DA +:10A6100090B92C48FCF730FA2B4B53F8241049B171 +:10A620000123A34013EA080F02D02848FCF7F6FBE9 +:10A630000134F1E7264821E028462649224607F062 +:10A6400025FD58B92448FCF717FA244C54F8041F88 +:10A650000029EFD01D48FCF7E1FBF7E72B78002637 +:10A660002D2B03BF013504F1FF344FF001094FF0EA +:10A670000009154B53F8267027B91948BDE8F04773 +:10A68000FCF7FAB928463946224607F0FFFCA8B97C +:10A690000120B040B9F1000F03D0FAF76CFC11486B +:10A6A00004E040EA0800CAF808000F48FCF7E4F9A3 +:10A6B00039460E48BDE8F047FCF7B0BB0136D8E795 +:10A6C00034200020306D01086053010844690108FE +:10A6D0007C700108C4730108436D01085C530108D4 +:10A6E000586D01086F6D0108796D01084670010809 +:10A6F0002DE9F04F692887B0044600F0A78200F2E8 +:10A7000096802E2800F0398562D8242800F009852B +:10A710002BD8202800F08282222800F0BE83012856 +:10A7200040F05C852C20FCF741F90020FCF70FF984 +:10A730002046FCF70CF90020FCF709F94320FCF750 +:10A7400006F94C20FCF703F94620FCF700F94C20F1 +:10A75000FCF7FDF82046FCF7FAF80020FCF7F7F8C4 +:10A760000020FCF7F4F80024F0E0282800F0E18451 +:10A7700012D8262840F03285924C0320FCF716F9B7 +:10A78000B4F9E600FCF715F9B4F9E800FCF711F9A3 +:10A79000B4F9EA0000F034BC2A2800F0D5842C2853 +:10A7A00040F01C85874C0720FCF700F994F818014D +:10A7B000FCF7CDF8B4F91E01FCF7FBF8B4F91A0167 +:10A7C000FCF7F7F8B4F91C01FCF7F3F800F0C2BC91 +:10A7D000642800F0E3801AD8322800F0BB840AD83D +:10A7E000302840F0FB84774C8020FCF7DFF804F140 +:10A7F000800500F0D8BC342800F06F83402840F07A +:10A80000ED840820FCF7D2F8002400F0ACBC6628E8 +:10A8100000F09C81C0F0F080672800F0D0816828AB +:10A8200040F0DC841020FCF7C1F8002406E2732815 +:10A8300000F0BA8355D86D2800F01B8212D86B281F +:10A8400000F0008440F2BB835F4C0620FCF7AEF8BA +:10A85000B4F90000FCF7ADF8B4F90200FCF7A9F870 +:10A860005A4B0EE26F2800F06782C0F00D8270280C +:10A8700000F08182722840F0B184524C1620FCF71F +:10A8800095F80020FCF795F8B4F9D000FCF791F8A2 +:10A890004F4DB4F9D200FCF78CF8B4F9D400FCF7B2 +:10A8A00088F82B68B3F9A801FCF783F80020FCF7BF +:10A8B00080F80020FCF7A2F82B68B3F952000A23B5 +:10A8C00090FBF3F0FCF775F894F80401FCF73FF8FF +:10A8D00094F80601FCF73BF894F80501FCF737F80B +:10A8E000E5E3782800F0778110D8752800F0C98258 +:10A8F000C0F01483762800F0B683772840F06E8489 +:10A90000344D00242878FCF751F842E3A42800F0E5 +:10A91000D08310D8A02840F061840C20FCF746F8C2 +:10A920002D4B1868FCF76AF82C4B1868FCF766F892 +:10A930002B4B1868FAE3F02800F0E683FE2840F07D +:10A940004D840820FCF732F80024D5E3254B1B6822 +:10A95000185D0134FBF7FBFF042CF7D1224B0024D8 +:10A960001878FCF726F8214B185D0134FBF7EFFF50 +:10A970000B2CF8D100241E4B185D0134FBF7E7FFC8 +:10A98000082CF8D10720FBF7E2FF0024194B185DD3 +:10A990000134FBF7DCFF072CF8D188E30720094CD2 +:10A9A000FCF704F8E620FBF7D2FF6079FBF7CFFF56 +:10A9B0000020FBF7CCFF94F82631002B0CBF0420BD +:10A9C0000C20B3E334200020280400203E040020A3 +:10A9D0003C030020761E0020E8F7FF1FECF7FF1F66 +:10A9E000F0F7FF1FAC000020D627002018630108F5 +:10A9F00024630108F96201080B20FBF7D7FFB64B6F +:10AA0000B3F90000FBF7D5FFB44B188800B2FBF791 +:10AA1000D0FFB34B1B68C3F3C000C3F380028000B8 +:10AA200040EA4200C3F340021043C3F3401240EA3D +:10AA3000C20003F010031843FBF7BBFFA94B1A88B1 +:10AA400012F0010F0CBF0020022012F0020F0CBF09 +:10AA50000021042112F0040F0CBF0023102312F078 +:10AA6000400F0CBF00242024019312F0100F9E4BC6 +:10AA700002940CBF00244FF4007412F0200F1B68E6 +:10AA800003940CBF00244FF4806412F4807F04947C +:10AA90000CBF00244FF4006402F0080B03F4807A2A +:10AAA000059403F4805903F4005803F4004C03F4B4 +:10AAB000803E03F4003703F4802603F4002503F4FA +:10AAC000801403F0C00343EA0B0343EA0A0343EA9A +:10AAD000090343EA080343EA0C0343EA0E0E834BDF +:10AAE0004EEA07073E431B7835432C43C3F38003EC +:10AAF000234303430B430199029C0B4303992343D4 +:10AB0000049C0B430599234312F4007F43EA01039D +:10AB10000CBF00224FF400121A43754B00201C7822 +:10AB20000346A3420CD273495D5C012101FA05F58D +:10AB3000154218BF994003F1010318BF0843F0E71D +:10AB4000FBF75CFF6C4B93F8540709E31220FBF70B +:10AB50002DFF6A4B6A4C1B88B3F5806F22D9002504 +:10AB6000605F082390FBF3F00235FBF722FF062D10 +:10AB7000F6D1644CB4F90000FBF71BFFB4F90200F6 +:10AB8000FBF717FFB4F904005F4CFBF712FFB4F9B1 +:10AB90000000FBF70EFFB4F90200FBF70AFFB4F95F +:10ABA00004002DE2B4F90000FBF703FFB4F9020042 +:10ABB000FBF7FFFEB4F90400FBF7FBFED9E710201A +:10ABC000FBF7F4FE0024514B185D0134FBF7BFFE88 +:10ABD000102CF8D116E23820FBF7E8FE00254C4E89 +:10ABE00005F12C043368E4002344B3F90600FBF7B5 +:10ABF000E0FE336801352344B3F90800FBF7D9FEC2 +:10AC000033682344B3F90A00FBF7D3FE33681C44CE +:10AC1000207BFBF79CFE082DE1D1F3E10820FBF738 +:10AC2000C5FE00243A4B1B6803EBC40393F86D0187 +:10AC30000134FBF78CFE082CF4D1E3E1354B185DB1 +:10AC40000134FBF784FE102CF8D1DBE1324D0024F7 +:10AC50002878400000F0FE00FBF7A8FE2B789C420D +:10AC600080F0D0812D4B33F91400FBF7A2FE0134A4 +:10AC7000F4E70620FBF79AFE294B1868FBF7BEFEA7 +:10AC8000284BB3F90000BBE10720FBF78FFE264BF2 +:10AC90004FF6FF741878FBF75AFE244B1868A04251 +:10ACA000A8BF204620EAE07000B2FBF782FE204BEE +:10ACB000B3F90000FBF77DFE0F4B93F80C211D4B01 +:10ACC00018680028B8BF40420AB10A235843A0427E +:10ACD000A8BF204600B293E168040020481A002073 +:10ACE00008020020100200200C020020D5270020BE +:10ACF000761E0020601E002034200020000000206E +:10AD00000804002060040020380400201200002005 +:10AD10003C030020AC270020C30A0020720700205B +:10AD200018020020940600209C060020A4060020A3 +:10AD3000A20E0020A0060020B34C0720FBF736FE31 +:10AD400023681878FBF703FE23685878FBF7FFFDAC +:10AD500023681879FBF7FBFD23685879FBF7F7FDAB +:10AD600023689879FBF7F3FD23689878FBF7EFFDEC +:10AD70002368D878F4E1A54D1E20FBF717FE2B6859 +:10AD800000241B78022B69D12B68A14903EB8403B3 +:10AD9000586A04F081F907F095FBFA28A8BFFA2059 +:10ADA00020EAE070C0B2FBF7D2FD2B68994903EBB3 +:10ADB0008403186B04F070F907F084FBFA28A8BF2D +:10ADC000FA2020EAE070C0B2FBF7C1FD2B6892497F +:10ADD00003EB8403D86B04F05FF907F073FB64287E +:10ADE000A8BF642020EAE070C0B20134FBF7AFFDD9 +:10ADF000032CC9D1072C2B681ED1986C844904F010 +:10AE00004BF907F05FFBFA28A8BFFA2020EAE070B0 +:10AE1000C0B2FBF79CFD2B687D49D86C04F03CF96F +:10AE200007F050FBFA28A8BFFA2020EAE070C0B271 +:10AE3000FBF78DFD00200BE023441879FBF787FD1D +:10AE40002B682344987BFBF782FD2B682344187EF4 +:10AE50000134FBF77CFD0A2CCCD1D3E02B682344D2 +:10AE60001879FBF774FD2B682344987BFBF76FFD83 +:10AE70002B682344187E0134FBF769FD0A2CEDD1C1 +:10AE8000C0E02F20FBF792FD644C14F8010F00285E +:10AE900000F0B880FBF75BFDF7E7A020FBF786FD2D +:10AEA00000245A4B04F11C021B680C2103EB8203A3 +:10AEB0005D1D5B4A5B79013401FB0323187AFBF7C4 +:10AEC00046FD6878FBF743FDA878FBF740FDE8787E +:10AED000FBF73DFD282CE4D194E04820FBF766FD0C +:10AEE000002506266E43494B06F588761B6801351A +:10AEF0001E44B07AFBF72BFD7079FBF728FDB07983 +:10AF0000FBF725FDF079FBF722FD307AFBF71FFDFB +:10AF1000707AFBF71CFD0C2DE3D173E000270124B0 +:10AF20000025404B1B789D4222DA3F4BE95C002311 +:10AF30003B4A03EB02089A5C8A4204D00C33B3F517 +:10AF40008A7FF5D112E0D8F8040007F097F881461F +:10AF50000CB9264601E0074408E04E4506DAD8F869 +:10AF60000430985DFBF7F3FC0136F6E70135D8E7CE +:10AF7000002C47D0F8B2FBF719FD0024D0E7284A8F +:10AF800099189A5C82420BD00C33B3F58A7FF6D1C4 +:10AF900001342B789C4235D2234BE05C0023EEE752 +:10AFA000087AFBF7D4FCF3E70820FBF7FFFC012449 +:10AFB000E0B20134FBF7CBFC092CF9D122E01020E0 +:10AFC000FBF7F4FC194B1A4C187800F00200FBF761 +:10AFD000BEFC184B1878FBF7BAFC2068FBF70EFD97 +:10AFE0006068FBF70BFD144BB3F90000FBF7E1FCC5 +:10AFF000124BB3F90000FBF7DCFC114BB3F9020074 +:10B00000FBF7D7FC0120EAE0FC0400203C03002011 +:10B01000000020410000C84200007A44BB520108F1 +:10B02000704F0108761E0020601E00201E040020C4 +:10B030007806002074060020AA060020A80600203A +:10B04000481A0020674C0520FBF7B0FCB4F9040057 +:10B05000FBF7AFFCB4F90600FBF7ABFC624B1878CA +:10B0600000F001007CE0FBF75BFA06461220FBF7DC +:10B070009DFC0EB95D4B02E0102E03D15C4B1D68A8 +:10B080005C6801E0002425463046FBF760FC28465A +:10B09000FBF7B4FC2046FBF7B1FC564B1868FBF7F6 +:10B0A000ADFC0020FBF785FC0020FBF782FC0020B4 +:10B0B00056E04C4D0024287A2E4680000130C0B264 +:10B0C000FBF774FC287AFBF742FC337A9C4299D256 +:10B0D000494D285DFBF73BFC05F11003185DFBF7BC +:10B0E00036FC05F12003185D3035FBF730FC285D98 +:10B0F000FBF72DFC0134E8E7404B185F0234FBF707 +:10B1000058FC082CF8D17DE73D4C0420FBF74EFCA1 +:10B110002368B3F95600FBF74CFC2368B3F95400DD +:10B120006EE70420FBF742FC364B9868FBF766FCA1 +:10B1300068E7344C0420FBF739FCB4F90801FBF74D +:10B1400038FCB4F90A015BE70120FBF72FFC2D4B1B +:10B15000587905E00120FBF729FC2A4B93F82001E0 +:10B16000FBF7F5FB4EE7274B234493F8100101341E +:10B17000FBF7EDFB082CF6D144E74020FBF716FC6B +:10B18000204C04F14005B4F9D401FBF712FC94F80B +:10B19000D601FBF7DCFB043494F8D301FBF7D7FBB3 +:10B1A000AC42F0D12EE7B4F85601043400F03F0071 +:10B1B000FBF7FFFBB4F85201C0F38410FBF7F9FB77 +:10B1C00094F850010009FBF7C2FB94F8500100F01D +:10B1D0000F00FBF7BCFBAC42E5D113E7002007B042 +:10B1E000BDE8F08F481A0020AC100020580600205F +:10B1F000080F002014020020511A0020921A00208B +:10B200003C030020342000202DE9F0418CB01D4685 +:10B210009DF848308846012B174608D1A84B984224 +:10B2200040F04681042203F548431A6165E0A54BCE +:10B2300098425ED1A448A54B87600360A44BA90740 +:10B24000436103F1C00383614FF0C003C360036136 +:10B250009C4B036503F104038364C36403F5484313 +:10B2600003F154030363A3F11403D3F8D42F43630E +:10B2700042F48042C3F8D42FD3F8D02F42F0010219 +:10B28000C3F8D02F4FF002038DF803304FF4007352 +:10B29000ADF800304FF018038DF8023003D58D481B +:10B2A0006946FAF7EDF81C232A078DF8023003D51A +:10B2B00088486946FAF7E4F84FF48063ADF8003047 +:10B2C00048238DF80230EB0703D582486946FAF728 +:10B2D000D7F80E238DF804300022012301A88DF841 +:10B2E00005308DF806208DF80730774C00F0E2FE2F +:10B2F00055E0734B984240F0DF80774B734A9F6074 +:10B300001A60C022DA601A61744AAE075A6102F10B +:10B31000C0029A616A4A1A6502F104029A64DA6408 +:10B320006F4BDA6942F40032DA615A6942F0010285 +:10B330005A614FF002038DF803304FF00403ADF86B +:10B3400000304FF018038DF8023003D5614869468C +:10B35000FAF796F81C232C078DF8023003D55D48C8 +:10B360006946FAF78DF80823ADF80030E8074FF08A +:10B3700048038DF8023003D556486946FAF780F83D +:10B3800026238DF804300022012301A88DF8053012 +:10B390008DF806208DF8073000F08CFE4E4C00260C +:10B3A000012384F844302662E661A6626662C4F82E +:10B3B0002C806571A760A671204600F09BFD15F0FA +:10B3C000090F31D0206B002826D0E36C039601933F +:10B3D0004FF480530A9380230693E3680596049301 +:10B3E0002023099363690796029308960B96FAF750 +:10B3F000E7FE01A9206BFAF7C5FE236B1A6842F03D +:10B4000001021A60226D918A89B241F04001918255 +:10B410005B689BB2236407E0236D4FF6DF721A80EE +:10B42000DA6842F02002DA6015F00A0F2CD0606B67 +:10B4300028B3A36C002601934FF480530A93802312 +:10B4400006932369029604931023039305960796A7 +:10B45000089609960B96FAF7B3FE606B01A9FAF706 +:10B4600091FE636B1A6842F002021A605E605E60D1 +:10B47000236D9A8A92B242F080029A8204E0236D90 +:10B48000DA6842F08002DA60236D29079A8992B265 +:10B4900042F400529A819A8A03D592B242F008028D +:10B4A00003E022F008021204120C9A82204604E003 +:10B4B000044B98423FF4BEAE00200CB0BDE8F081D2 +:10B4C0000044004000380140C81F0020EC52010831 +:10B4D0009C1A002000080140741F00201C1C002042 +:10B4E0000010024010B50446204606F0C7FD10F0DB +:10B4F000FF0F07D10B4B0C4893F85417BDE81040D1 +:10B50000FBF78CBC204606F00EFE022808D8054B3F +:10B51000064C83F8540701F0A1FD02F0E7FCE3E7D5 +:10B5200010BD00BF34200020026C0108DE6B010852 +:10B530002DE9F04F844985B0054606F067FD834943 +:10B54000002828460CBF0124072406F05FFD80492F +:10B550000028284608BF022406F058FD002808BF2E +:10B560000424E10740F1BE807A48FBF757FC002035 +:10B5700000F08AFA784F7948FBF750FC7848FBF7DF +:10B580004DFC7A79774B784803EB82035969FBF7D6 +:10B5900045FC3869002103F013FF00285CD13D46CB +:10B5A0000646D5F810800021404603F009FF002828 +:10B5B0004ED101366D483146D5F814B0D5F818A0F3 +:10B5C000D5F81C90FBF72AFC4046002103F002FF4F +:10B5D00010B16748FBF722FC69464046FBF7AEFD19 +:10B5E00001466448FBF71AFC5846002103F0F2FEBE +:10B5F00010B15F48FBF712FC69465846FBF79EFD09 +:10B6000001465C48FBF70AFC5046002103F0E2FECD +:10B6100010B15748FBF702FC69465046FBF78EFD18 +:10B6200001465448FBF7FAFB4846002103F0D2FEDE +:10B6300010B14F48FBF7F2FB69464846FBF77EFD29 +:10B6400001464D48FBF7EAFB0C2E05F11005A8D189 +:10B650004A48711CFBF7E2FB4948FBF7DFFB494D09 +:10B66000D7F8088055F8041F19B14748FBF7D6FBF7 +:10B67000F8E70D46454B53F8256056B10123AB4022 +:10B6800013EA080F03D042483146FBF7C7FB0135E8 +:10B69000F0E74048FBF7C2FB31467B1893F81031C6 +:10B6A00004AA13443C4A8A5C0131082903F8102C8F +:10B6B000F3D10023694639488DF80830FBF7AEFB1B +:10B6C0003748FBF7ABFB374800F034FE3648FBF752 +:10B6D000A5FB3448FBF75EFC3448FBF79FFB40209A +:10B6E00000F0C8FCA2071AD53148FBF797FB314898 +:10B6F000FBF794FB2B48FFF7F5FE2F48FBF78EFB7B +:10B700002848F9F7D1FF2D48FBF788FB2548F9F7C2 +:10B7100031FF2648FBF782FB802000F0ABFC63077B +:10B720000FD52748FBF77AFB2648FBF777FB1D4828 +:10B73000FDF728FD1D48FBF771FB4FF4807000F00A +:10B7400099FC05B0BDE8F08F876D01087F7901088D +:10B750008E6D0108946D010834200020A26D01084F +:10B76000B46D0108EC520108C06D0108CB6D0108F1 +:10B77000AD6B0108936C010846700108D36D010898 +:10B78000E56D01085C530108F56D0108605301087F +:10B79000036E0108106E0108FC6F01081C6E0108A1 +:10B7A000256E0108DE6B0108316E01087C7001080E +:10B7B0003F6E0108526E0108606E01086A6E010852 +:10B7C000796E01088A6E01082DE9F04F87B098461E +:10B7D00082460F4616469DF84040FEF7C4F80DF12C +:10B7E000080E0546034600F1100C186859687246A9 +:10B7F00003C2083363459646F7D12B7B0BB90396FA +:10B800000496504602A9FDF77DFF054640B1436806 +:10B81000586830B1504602A92A4600F035FFF4E7D7 +:10B8200033E0AB6895F800B093F80090B9F1040FDD +:10B830002BD8DFE809F003062A0F11000094144802 +:10B8400001E014480094394632464346FFF7DCFCD9 +:10B8500004460BE0002000E0012039462346324632 +:10B86000FDF7D4FF41460446FBF746F864B10A4BA6 +:10B8700084F8049003EB8B03C3F800436B68204605 +:10B880005C605146FDF7B2FF204607B0BDE8F08F7F +:10B8900000380140004400409C1A0020F7B5274CB6 +:10B8A000274DE369284643F48043E361236901A9F6 +:10B8B00043F48043236118238DF806304FF420436E +:10B8C000ADF8043003238DF80730F9F7D9FD0423D0 +:10B8D0004FF480460DEB030128468DF806304FF4F7 +:10B8E0008057ADF80460F9F7CBFD1023284601A975 +:10B8F0008DF80630ADF80470F9F7C2FD2F612369A9 +:10B90000304633432361FBF771FF0E4B1A8802F474 +:10B91000415242F4457242F003021A809A8B22F49B +:10B9200000621204120C9A8307221A821A8892B2B9 +:10B9300042F040021A8003B0F0BD00BF0010024088 +:10B94000000C01400038004008B501F087FB02F010 +:10B95000CDFABDE808400F2014210122FAF784BF78 +:10B9600070B53E4B3E4D1C68D5F81033E31A002BE2 +:10B9700072DB04F5C3343B48A034C5F81043FDF72F +:10B98000BFF9394B37481A780146FAF791FC374B23 +:10B990001A781E4612F0040F13D0C5F81443002382 +:10B9A000334900201944A1F8FE002E493148595A64 +:10B9B0001952063019520233062BF1D122F004023B +:10B9C00032702D4B1B7883B1264B294A1888B2F868 +:10B9D000FE10411A19805888B2F80011B2F80221FD +:10B9E000411A598099888A1A9A80D5F814331C4ACA +:10B9F000002B31D02149E41A8C4202F5467002F244 +:10BA00001E3116D81E4BDA6882F00802DA60002375 +:10BA1000144AC55E9A5A14B2A542C4BF154D5A5372 +:10BA2000CD5EA542BCBF174C1A530233062BEFD193 +:10BA300070BD0023C2F81433C55ECC5E0C4A2C44A2 +:10BA400002251A442B4494FBF5F4062BA2F8FE4081 +:10BA5000F2D1BDE8704077E770BD00BFC427002079 +:10BA60009C1A002038040020E02700201E0400203B +:10BA700034200020B41D0020680800207FC3C901C5 +:10BA8000000C0140BA1D002007B5064B0648009384 +:10BA9000064B074A1968074BFBF7C0F903B05DF87E +:10BAA00004FB00BFF962010811700108C800002002 +:10BAB000186301082463010810B50748FAF7DCFF92 +:10BAC0000024064B0648E218E15852680C34FBF794 +:10BAD000A5F9FC2CF5D110BD2D7001089856010870 +:10BAE0004370010837B582880446836810060D4606 +:10BAF00006D529494FF4E07091F8541700FB013343 +:10BB0000D10504D525490A20097800FB013302F04C +:10BB10003F02042A12D006D8012A0DD0022A2FD1C2 +:10BB200093F900102DE0102A0AD0202A0AD0082A02 +:10BB300026D1B3F9001024E0197822E0198820E01A +:10BB400019681EE069461868FBF7F8FA01461448C0 +:10BB5000FBF764F9F5B1E06803F04AFA6946FBF7D0 +:10BB6000EDFA01460F48FBF759F9206903F040FA56 +:10BB70006946FBF7E3FA01460A48FBF74FF909E08B +:10BB800000210948FBF74AF925B10848E168226914 +:10BB9000FBF744F903B030BD34200020F80E00203C +:10BBA000936C0108926C0108B27101084B70010896 +:10BBB0002DE9F041002407462546114B3946E65849 +:10BBC00004EB0308304606F095FA58B10D483146AB +:10BBD000FBF724F940460021FFF784FF0A48FBF7F2 +:10BBE0001DF90135143440F62C339C42E5D125B9BA +:10BBF0000648BDE8F041FAF73FBFBDE8F08100BF5D +:10BC000094570108E37001087C7001085270010824 +:10BC10002DE9F74F044606F031FA054620B1012818 +:10BC200019D123782A2B16D15648FAF725FF00247C +:10BC3000554B5648E618E158FBF7F0F830462946D0 +:10BC4000FFF750FF5248FAF717FF143440F62C3331 +:10BC50009C42EDD192E020463D2106F002FA0028F8 +:10BC600000F08780034613F8012C202A01D1013B04 +:10BC7000F9E7451C2846C4EB030A06F054FA83464C +:10BC80002846F9F74BF80026054614237343DFF8DE +:10BC9000F89053F8097003EB0908384606F0EEF9FE +:10BCA00003461A4620463946019306F0EFF9019BF8 +:10BCB000002855D15FFA8AF29A4251D1D8F80C0087 +:10BCC00003F096F90146284603F098FB002845D07A +:10BCD000D8F8100003F08CF90146284603F084FBE5 +:10BCE00000283BD0B8F804309B064FF0140303FB48 +:10BCF0000696B28858BF5D4614062946B36806D535 +:10BD000024484FF4E07490F8540704FB0033D00546 +:10BD100004D521480A24007804FB003302F03F02D6 +:10BD2000042A0BD004D8013A012A0CD819700AE071 +:10BD3000102A05D0202A05D0082A04D1198002E053 +:10BD4000196000E01D6039461448FBF767F830467B +:10BD5000002103B0BDE8F04FFFF7C4BE104803E078 +:10BD600001368F2E91D10F4803B0BDE8F04FFAF79E +:10BD700083BE204603B0BDE8F04F19E703B0BDE82D +:10BD8000F08F00BF6A70010894570108E370010842 +:10BD90007C70010834200020F80E00207F7001081C +:10BDA0008A700108527001087FB5044606F066F9F2 +:10BDB000082824D100231F49E25C0968114449780E +:10BDC00001F00301022908BF203AE2540133082B95 +:10BDD000F1D10025665D1848314606F042F928B1D8 +:10BDE00001356019314606F03CF918B11348FAF7ED +:10BDF00043FE1CE0082DEDD12046FBF787F91048E3 +:10BE0000FAF73AFE00230F4A04A91A4492F81021C7 +:10BE10000A440949595C0133082B02F80C1CF2D181 +:10BE20000023094801A98DF80C30FAF7F7FF04B098 +:10BE300070BD00BFCC000020FC6F0108AA70010893 +:10BE4000CA7001083420002046700108F8B5046863 +:10BE5000054620460E461746F9F7C5FA032845D889 +:10BE60002B7B9B089AB246B94FF0020C0CFA03F3F5 +:10BE7000A18989B221EA0303A3810A2101FB0021E0 +:10BE80001B4B43F82160043143F8217046B12A7BF3 +:10BE90000225920805FA02F2A1890A4392B2A28110 +:10BEA000282202FB003000F12002EFF3128650231B +:10BEB00083F312880023C1180D6915B115600A6952 +:10BEC00004320433102BF6D100231360F3B283F352 +:10BED0001188036A23B1A3899BB243F0010304E0F4 +:10BEE000A38923F001031B041B0CA381F8BD00BF31 +:10BEF000D41E002070B5046D4279A38902F00401BC +:10BF000023F400531B041B0C0546866886B0A381EE +:10BF100001F0FF0021B14FF480604FF4005100E0C8 +:10BF2000014612F0010F14BF0423002312F0020F88 +:10BF30001CBF43F008039BB212F0080F228A18BFFF +:10BF40000C2392B222F4405211432182A28992B270 +:10BF500022F4B05222F00C02104303439BB2A3819F +:10BF6000A38A01A823F440731B041B0CA382FBF7D4 +:10BF7000F3FB1949049A039B8C4208BF1346A2891C +:10BF80001921594312B2002AB4BF7600B600B1FBA2 +:10BF9000F6F16423B1FBF3F21201100903FB101157 +:10BFA000A08900B2002806DAC9003231B1FBF3F3F0 +:10BFB00003F0070305E009013231B1FBF3F303F0AD +:10BFC0000F031A4392B22B6D22819A8992B242F4E6 +:10BFD00000529A8106B070BD00380140417189E776 +:10BFE000816087E7826A8169436B1144D960416A45 +:10BFF000914203D98A1A5A60816204E001698A1A5F +:10C000005A6000228262002280F844201A6842F0BE +:10C0100001021A60704738B5114B124C9968124BE7 +:10C020001A681D465288114203D0FAF72BFB206094 +:10C0300011E0FAF727FB236898420CD9C01A0B4B82 +:10C040003B22B0FBF2F01B68B0F5967FC8BF4FF003 +:10C05000FF3003B118602B685A68054B5A6138BD30 +:10C06000000C0140C01D00203403002030030020DC +:10C070000004014070B5064600240B4BE518AA8861 +:10C0800016420AD0E1580948FAF7C8FE28460021AE +:10C09000FFF728FD0648FAF7EFFC143440F62C337E +:10C0A0009C42EAD170BD00BF94570108DF700108BF +:10C0B0007C7001080D4B0278D9684378C943C1F3FD +:10C0C0000221C1F1040103FA01F1094B0901C9B2CE +:10C0D0001A4482F8001302780120510902F01F026D +:10C0E00000FA02F243F82120704700BF00ED00E0A3 +:10C0F00000E100E0134B026810B51C68D1430C400E +:10C100001C605C682140596019680A431A60026823 +:10C110009C68D1430C409C60DC682140D960417927 +:10C12000102906D1996811439960D9680A43DA60E9 +:10C1300010BD01F1804303F5823319680A431A6088 +:10C1400010BD00BF00040140254B10B55343254AE4 +:10C15000254C12680139B2FBF3F20388013AA04280 +:10C1600089B292B29BB212D004F50064A0420ED004 +:10C17000B0F1804F0BD0A4F59834A04207D004F55D +:10C180008064A04203D004F58064A04202D123F071 +:10C1900070039BB2154CA04206D004F58064A04207 +:10C1A0001CBF23F440739BB203800F4B81859842E0 +:10C1B00002850FD003F5006398420BD003F540636E +:10C1C000984207D003F58063984203D003F580635B +:10C1D000984201D1002303860123838210BD00BF52 +:10C1E00040420F00A8000020002C01400010004039 +:10C1F000284BF0B51D6800222748165C1418AB19AF +:10C20000597801F0040101F0FF0371B10132102AE5 +:10C21000F2D10020F0BD1BB103EB83035B00DBB266 +:10C2200010F8012B303A1344DBB2221A022AF2DC56 +:10C23000002184420AD919B101EB81014900C9B238 +:10C2400010F8012B303A1144C9B2F2E72E2E14D166 +:10C25000601C00220424067802EB8202AF197F786A +:10C2600052007F0792B203D5303A3244013092B285 +:10C27000013C14F0FF04EED100E000220748062440 +:10C280004143642000FB02120548B2FBF4F200FBBC +:10C290000320F0BDCC000020BB10002040420F0066 +:10C2A0008096980030B5002213460D495C5C9CB125 +:10C2B0002E2C04D1013378B11C1800250D550A2409 +:10C2C0006243C95CA1F13004092C9CBF303A52187A +:10C2D0000E2B03D80133E8E7104630BD002030BDF7 +:10C2E000BB1000200FB407B504AB53F8042B00209B +:10C2F00004490193FAF7CCFC03B05DF804EB04B0F9 +:10C30000704700BF2D6B00080EB40FB505AB53F896 +:10C31000042B0190064901A80393FAF7B9FC019B8D +:10C3200000221A7004B05DF804EB03B0704700BF40 +:10C33000514600082DE9F0438DB0054605F09EFEFC +:10C34000C0B2002858D104467F4B00211E68142239 +:10C3500007A805F052FEA500002303A905A8039332 +:10C36000059377190B7183801A46DFF8F0E1B7F86F +:10C3700002C03EF8138018EA0C0F0CD00EF10A0E22 +:10C380000DF1300813F80EE002F1010C424402F8FE +:10C3900024EC5FFA8CF20133052BE6D100231A4618 +:10C3A000DFF8C0E1B7F802C013F80E8018EA0C0FEE +:10C3B0000CD00EF1060E0DF1300813F80EE002F16C +:10C3C000010C424402F81CEC5FFA8CF20133062B9C +:10C3D000E6D1735D8DE803001A0907A85B4903F0F5 +:10C3E0000F03FFF791FF2146594807AA0134FAF7D6 +:10C3F00015FD202CA8D1A3E0284605F094FE1F28A7 +:10C40000044600F3918028462021E4B205F029FE7D +:10C410001F2C01D94F4888E04B4B471C1B6800215B +:10C4200003EB84042046042205F0E7FD00254A4B77 +:10C4300007AE304600210A2215F803905FFA85F80E +:10C4400005F0DBFD0023FA5CF91832B10A2B04D0A9 +:10C450004A4502D0F2540133F5E74A4501F101079C +:10C4600067D1B8F1020F0DD0B8F1030F0CD0B8F1BD +:10C47000010F0BD0304605F056FE2378C0B243EAD8 +:10C4800000100AE0002219E0002226E0304605F004 +:10C490004AFE237800F00F001843207038E0013383 +:10C4A000062B0AD02D4800F115069E5D8E42F6D16E +:10C4B0000344D97B63880B43638001320CA9D3B258 +:10C4C0000B4413F8141C19B30023EBE7412B1DD0C8 +:10C4D000542B08BF04230ED00132D3B20DF1300823 +:10C4E000434413F8143C9BB1492B01D1002302E0D3 +:10C4F000572B07D10123194931F8131063880B43D7 +:10C500006380E9E7462BE1D10223F4E70323F2E756 +:10C510000135042D8BD10124F8F7FCFDF8F736FE28 +:10C52000F8F710FE64B975E70D482021FAF776FC9C +:10C5300006E020460021042205F05FFD0024EBE721 +:10C540000DB0BDE8F08300BFEC060020E9700108E3 +:10C55000F57001085A6A0108CF530108B453010865 +:10C5600001710108C35301083F4A2DE9F84F916852 +:10C5700040F201130B4040F201118B4293460AD165 +:10C580003A4B1A7893F801905A70B9EB020918BF28 +:10C590004FF0010901E04FF001094FF00008344B62 +:10C5A0005FFA88F41B78A3425CD9324B324E1B6889 +:10C5B000324F23B93B685B8926F814304FE03A6864 +:10C5C000072C94BF12F804A0A24629485146984768 +:10C5D000DBF808300546DB0509D5B9F1000F06D0B8 +:10C5E000274B50461B6829461B68DB699847A5F214 +:10C5F000EE2240F2DC5392B29A4288BF3B68DBF8ED +:10C60000082088BF5D8942F2010313402BB31D4B04 +:10C610001978164B01F0030202EB840293F86200D2 +:10C6200003EB420255801A4620B9032915D901218E +:10C6300083F8621002EBC40399885D8802EB440220 +:10C640000D44D9881B890D441D44ADB2A2F8645035 +:10C6500004232DB295FBF3F5ADB226F8145008F182 +:10C6600001089CE7BDE8F88F34200020C41D00209D +:10C67000C30A0020CC0A0020720700203C010020E1 +:10C68000FC010020A00E00202DE9F74F2A4B157C5D +:10C690009B68019003F0400903F4007C03F4005808 +:10C6A000032D45D80C246C43244B0198E618377AA7 +:10C6B000013538423AD0E35C4BB1012B07D0032B54 +:10C6C00004D0042B14BF0423032300E00223DFF86B +:10C6D00070A01F010AEB0704B9F1000F06D11AF888 +:10C6E00007B0ABF1030BBBF1010F1FD9BCF1000F79 +:10C6F00006D0B8F1000F03D11AF80770042F15D037 +:10C700004F7B94F80CA007EA0A0ABA450ED14F688D +:10C71000606887420AD38F68A068874206D8137082 +:10C7200094605660D1601574104602E0EDB2B7E730 +:10C73000002003B0BDE8F08F342000206800002006 +:10C74000D4530108094B30B59D68094B05F4805559 +:10C750001868084B1C6800230DB1828800E0A2888D +:10C7600005495A520233182BF6D130BD342000202F +:10C77000AC1E0020B01E002094100020F8B500244C +:10C78000204BE0B21F78B8420CD21F4B33F8101088 +:10C790001E4B53F820301BB10B2801D8DB6898479B +:10C7A0000134EDE71A4B9B685B032AD50025194E2F +:10C7B0002B46EAB2BA4224D2726854689C4218D01E +:10C7C0002046F8F710FEEFF31283502282F312880E +:10C7D00011494FF0280CA28C0CFB001092B20132D0 +:10C7E0004262A28ADBB292B242F00102A28283F3D9 +:10C7F000118856F8043F00221B6801351A80234631 +:10C80000D7E7F8BDE7270020AC27002098090020D3 +:10C810003420002094090020D41E00202DE9F04F80 +:10C82000AF4E85B03778032F14D9AE4BAE48B3F96D +:10C830000410B0F904200029B8BF49426FF0630327 +:10C840005B1A9A4204DB01F164039342A8BF1346CA +:10C8500083801FE0012F1DD8A44BA54C1B78013B02 +:10C86000142B00F2E381DFE813F09100E101E10114 +:10C8700068009F00E101E1013101E101E101E10115 +:10C88000E101E101BD00E101E101E101E101E101BD +:10C89000A301BA01934B9749B3F806A0924B0968DC +:10C8A000B3F80280B3F80090B3F904B0924C02914F +:10C8B0000025BD4204F11004CED20FFA8AF002F036 +:10C8C00097FB54F8101C02F0E7FB03460FFA88F0C0 +:10C8D000019302F08DFB54F8081C02F0DDFB019B74 +:10C8E0000146184602F0D0FA03460FFA89F0019388 +:10C8F00002F07EFB54F80C1C02F0CEFB019B0146BB +:10C90000184602F0C1FA029A034692F90000019318 +:10C9100040420BFB00F002F06BFB54F8041C02F0E9 +:10C92000BBFB019B0146184602F0AEFA02F07AFD0D +:10C93000724B23F815000135BBE702210420FAF7FA +:10C940006FF9694D0121AF8878431FFA80F8042000 +:10C95000FAF766F96D8800FB05801FFA80F804205D +:10C96000FAF76CF94044208102210520FAF758F9C2 +:10C970007843012187B20520FAF752F900FB0570D0 +:10C9800087B20520FAF75AF938440BE00520012157 +:10C99000FAF746F9544B9D88684385B20520FAF7AB +:10C9A0004DF92844608141E1554B00201D68FAF79C +:10C9B00045F9DFF8688195F90630B8F90220322789 +:10C9C000534393FBF7F3184420800120FAF736F91C +:10C9D00095F90E30B8F90020534393FBF7F738442C +:10C9E000608023E1474B1B7813F0040F464B02D1C4 +:10C9F0001B689B880BE019683A4A0B88B2F906203D +:10CA000049889A4203DB9142B4BF0B461346E38147 +:10CA1000E2893A4B3A4F1A803C4B1B681D7855B35C +:10CA20000220FAF70BF93A68B2F91030518A9842AD +:10CA300003DB0BB29842B8BF034635490968488901 +:10CA4000C3EB000E334B0FFA8EFEB3F87C100FFAD7 +:10CA500081FCF44501DA0D4401E002DD4D1BA3F831 +:10CA60007C5092F91620B3F97C305343642293FB37 +:10CA7000F2F31844A080284B1B88DB050CD5194B1A +:10CA80001A88D7F80090E28022819A88184F628134 +:10CA90005B880325A38101E0134BF1E709EBC50394 +:10CAA00093F90630B7F90680284608FB03F864239B +:10CAB00098FBF3F8A7F80680FAF7C0F80135404470 +:10CAC000072DF88007F10207E8D1AFE00D4B1B7886 +:10CAD00013F0040F0C4B23D11B689B882CE000BF84 +:10CAE000E72700201E020020DC13002004050020A0 +:10CAF0001200002008050020E8090020AC270020D3 +:10CB0000A81E0020D5270020B01E0020B41E002043 +:10CB1000B81E0020C41D00201002002028040020A0 +:10CB20001968AD4A0B88B2F9062049889A4203DB9E +:10CB30009142B4BF0B461346E381E289A74BA84D4F +:10CB40001A80A84B03201B880121DF0503D5FAF7C3 +:10CB500067F8A14F02E0FAF763F8A34FB7F8028035 +:10CB6000022100FB08F01FFA80F90320FAF758F8B9 +:10CB70003F88012100FB0790E8800420FAF750F875 +:10CB800000FB08F002211FFA80F80420FAF748F8A9 +:10CB900000FB078028810320FAF750F8E388184447 +:10CBA000E0800420FAF74AF82389184420813DE008 +:10CBB00001210420FAF734F88B4D6F88784387B24F +:10CBC00004202781FAF73AF8384420810121052012 +:10CBD000FAF726F82D88684385B26581DEE6824B38 +:10CBE0000325B3F80490984628460221FAF718F86E +:10CBF00000FB09F0012187B22846FAF711F8C5F1C8 +:10CC000006035B0838F8133000FB037087B224F882 +:10CC100015702846FAF712F8384424F81500013543 +:10CC2000072DE1D16C4BDA886C4B1A806F4DDFF821 +:10CC3000E491AB6813F0200F34D00020F9F7FEFF29 +:10CC4000208080460120F9F7F9FF694B644F1B688B +:10CC500060801A0626D5674B1B681B7813F0020FFD +:10CC6000654B23D0D9F800C0B3F900109CF90E2011 +:10CC70009CF906C0B3F902304A43CCF1000C03FB27 +:10CC80000CF3322192FBF1F26FF0310C92B293FB74 +:10CC9000FCFC9444E04493FBF1F1A7F800800A44C3 +:10CCA00010447880D9F80010002319E0D9F800105A +:10CCB000B3F902C091F90620B3F900300CFB02FC75 +:10CCC00032229CFBF2FCE044A7F8008091F90E10A0 +:10CCD0004B4393FBF2F2E3E7E2520233102B0CD00A +:10CCE000E05E31F9232001EB830790427F88F3DB7C +:10CCF0003AB28242A8BF0246EEE73E4B1B681B7861 +:10CD00005B0704D435493478088801231BE03B4B8A +:10CD100000241F780423043FFFB25FFA87F84FFA1C +:10CD200088F2D4420BD4364A03F10109381932F89B +:10CD300013105FFA89F9C0B2F8F797FB4B4601343C +:10CD4000042CECD1DEE7A34208D231F9132000B263 +:10CD50008242A8BF104680B20133F4E7294B4FEA64 +:10CD600044081A68AB6803F480550395244D03F01A +:10CD70001009254BB5F90660244D1B782F68244D0A +:10CD800003F00403DBB2D5F800C00293002343454F +:10CD900062D0B2F802A004B2544505DD0F4CC0EBDE +:10CDA0000A0A1D5B55441D53039D0C4C002D33D0C6 +:10CDB0007D8931F903A0AE42CBBFBCF80250958803 +:10CDC000B2F802B0BCF800B0AA4503DBDA45B4BF44 +:10CDD00055465D46E55238E01E020020AC27002093 +:10CDE0001200002010020020DC130020342000205C +:10CDF0000C020020BC1E0020280400206C0800202B +:10CE000072070020B01E0020D5270020B81E002089 +:10CE1000AC1E0020A81E002031F903A01588B2F82E +:10CE200002B0AA4503DBDA45B4BF55465D46E5527C +:10CE300004EB030ABC89A64207DAB9F1000F01D15D +:10CE4000148800E09488AAF80040029C14B9044CAD +:10CE50001C5BCC5202339AE705B0BDE8F08F00BFEF +:10CE6000941000204B8810B5DC0607D52C4B1479A4 +:10CE70001B6853F824402B4B43F820404B889B06FB +:10CE800007D5274B54791B6853F82440254B43F8AA +:10CE900020404B881C070DD5234B0C781B78B3EB37 +:10CEA000141F07DB1E4BD4781B6853F824401D4B1E +:10CEB00043F820404B889B070DD51C4B0C781B7802 +:10CEC000B3EB141F07DC164B54781B6853F824404F +:10CED000144B43F820404B88DC070ED5144B0C78DC +:10CEE0001B7804F00F049C4207DC0D4B14781B6880 +:10CEF00053F824400B4B43F820404B885B070ED57A +:10CF00000C4B09781B7801F00F01994207DB044BA9 +:10CF100092781B6853F82220024B43F8202010BD62 +:10CF2000080B0020F0060020A7070020A50700201E +:10CF3000A4070020A607002070B50A4E00EB800071 +:10CF400006440024331913F8A00C074B01341D7854 +:10CF50006840FBF77DFD052CF4D12846BDE8704004 +:10CF6000FBF776BD14540108E6270020642928BF8A +:10CF70006421F8B501FB00F7642497FBF4F405463F +:10CF8000E4B20026F3B2A34204D29F20FFF7D4FFFD +:10CF90000136F7E7AC420BD2142097FBF0F0C4EB5C +:10CFA00084136638C4EB83031844C0B2FFF7C4FF90 +:10CFB0000134E4B2AC4238BF9A20F7D3F8BD0F4B2E +:10CFC00010B50446185CFFF7B7FF0D4B33F914306A +:10CFD000B3F57A7F05DBB3F5FA6FA8BF4FF4FA63B8 +:10CFE00001E04FF47A73A3F57A730A2293FBF2F10E +:10CFF0000920C9B2BDE81040FFF7B8BFFC6F0108B7 +:10D000007207002010B5441E14F8010F10B1FFF78D +:10D0100093FFF9E710BD0F4B1A78552A16D15A889D +:10D02000B2F5EF6F12D11A79BE2A0FD193F8762795 +:10D030000020EF2A0CD113F8012B5040064A9342EE +:10D04000F9D1D0F1010038BF0020704700207047AF +:10D05000704700BF00F8010878FF01084A4B5522CD +:10D060002DE9F3411A704FF4EF625A80BE221A7113 +:10D07000EF2283F87627002283F8772711461E4691 +:10D08000B35C0132B2F5EF6F81EA0301F8D13E4B98 +:10D090003E4A83F877173E4B04275A6002F18832E4 +:10D0A0005A600020013F17F0FF075DD0384B342253 +:10D0B000384CDA60C4F309037BB1331903F17843C8 +:10D0C000A3F5FC33D3F800804FF400500023019304 +:10D0D000F9F747F80428E5D11BE04FF43020F9F7C1 +:10D0E00040F80428DED12A4D4FF430202B6943F05C +:10D0F00002032B616C612B6943F040032B61F9F74C +:10D1000030F82A6941F6FD73134004282B61D4D00E +:10D11000C8E71F4D4FF400502B6943F001032B610A +:10D120001FFA88F32380F9F71CF8042812D1A31CF6 +:10D130000193019B4FEA1848A3F800804FF4005078 +:10D14000F9F70FF82B6941F6FE721A4004282A619C +:10D1500006D0A7E72B6941F6FE721A402A61A1E7C3 +:10D160000D4B04349C42A5D1094B04281A6942F0A6 +:10D1700080021A6102D1FFF74EFF10B90A20F9F7B9 +:10D1800099FB02B0BDE8F0813420002023016745FF +:10D190000020024000F8010878FF01088A2802D028 +:10D1A0008E2809D07047094B1B689B060DD5084B8C +:10D1B0001B7853B9074A03E0054B1B782BB9064A85 +:10D1C000064B1A60064B2D221A7070470802002089 +:10D1D00080140020680E00203C0E002088140020DF +:10D1E000911400207FB52B4B2B4C9A69206042F0A4 +:10D1F00001029A61294D03881026ADF804302846B3 +:10D20000022301A98DF807308DF80660F8F738F988 +:10D21000236828465B88ADF8043004230DEB030136 +:10D220008DF80630F8F72CF922680F20137A03F0F6 +:10D2300003018900884003F0FC0303F1804303F5F8 +:10D2400080339D6825EA0000012505FA01F1986008 +:10D250009868014399605368114A02A85361029388 +:10D2600000238DF80C308DF80E508DF80D60FEF710 +:10D2700041FF23680B4A5B7A59B203F01F039D40BC +:10D280004909094B42F821501A68084B3C3A1A6088 +:10D2900004B070BD0010024034030020000C0140B7 +:10D2A0000004014000E100E0302000202C030020B9 +:10D2B00013B504460068FEF747FF236801A81A88E3 +:10D2C00092B242F001021A80637B00228DF8043092 +:10D2D00001238DF805308DF806208DF80730FEF714 +:10D2E000E9FE02B010BD10B5AE20FBF7B5FBD420AF +:10D2F000FBF7B2FB8020FBF7AFFBA820FBF7ACFBF2 +:10D300003F20FBF7A9FBD320FBF7A6FB0020FBF790 +:10D31000A3FB4020FBF7A0FB8D20FBF79DFB142017 +:10D32000FBF79AFBA120FBF797FBC820FBF794FBC8 +:10D33000DA20FBF791FB1220FBF78EFB8120FBF735 +:10D340008BFBCF20FBF788FBD920FBF785FBF12077 +:10D35000FBF782FBDB20FBF77FFB4020FBF77CFB2E +:10D36000A420FBF779FBA620FBF776FBAF20FBF7A9 +:10D3700073FBA620FBF770FBAE20FBF76DFB2020B4 +:10D38000FBF76AFB0020FBF767FBB020FBF764FBB1 +:10D390004020FBF761FB0020FBF75EFB1020FBF752 +:10D3A0005BFB4FF48064013C0020A4B2FBF750FB10 +:10D3B000002CF8D18120FBF74FFBC820FBF74CFB7A +:10D3C000BDE81040AF20FBF747BB2DE9F341F9F76B +:10D3D00059F9AB4D07462B68C31A002BC0F2F081F8 +:10D3E00000F5C333A0332B60A64B2A791E78C6F311 +:10D3F0008006B21A18BF01222E714EB1002A00F029 +:10D40000DF81A14B5A789A7001225A701A7020E07D +:10D410009D4B2AB1DA7842F00202DA709A785A709B +:10D42000D9788A0705D4984A9068381AC043C00F43 +:10D4300000E00120944A187058B1CC0709D513793F +:10D440009249013303F0030313710B4493F88032C4 +:10D4500053708D4C23784BB3FFF745FFB020FBF79B +:10D46000FBFA4020FBF7F8FA0020FBF7F5FA102052 +:10D47000FBF7F2FA4FF4806808F1FF3800201FFA3A +:10D4800088F8FBF7E5FAB8F1000FF5D14046FBF755 +:10D49000E7FA7F4B627853F82200FFF7B3FDE37899 +:10D4A00023F00203E3707B4B3B44A3606378052BBE +:10D4B00000F27381DFE813F0080071011B007700B0 +:10D4C00006001C010024D5E07349744A7448FEF735 +:10D4D0001BFF0120FBF7C4FA7148FFF793FD714B66 +:10D4E0006F4871491A68FEF70FFF022050E16F4B39 +:10D4F0009A68984612F0020F2ED06D4C0A232178BC +:10D500006C4FB1FBF3F203FB12133978DBB26448C2 +:10D5100000916949FEF7F8FEF7F7ECFD0120FBF7F3 +:10D520009FFA5F48FFF76EFD644B3A7818682478DD +:10D530008378642102FB13444C4341780220CB1AC8 +:10D540005A43B4FBF2F4E4B2FBF78AFA2146152001 +:10D55000FFF70CFD032400E00124D8F8083018057B +:10D5600040F11B81564B57491F680968642397FB9C +:10D57000F3F203FB1273009149485349FEF7C4FECE +:10D58000F7F7B8FD2046FBF76BFA4548FFF73AFD81 +:10D59000F8F7EEFB0746601CFBF762FA15203946E8 +:10D5A000FFF7E4FCF9E00120484FFBF759FA48483F +:10D5B000FFF728FD3B68990715D546493848B1F96A +:10D5C0000020B1F90230B1F904100324009142495E +:10D5D000FEF79AFEF7F78EFD0220FBF741FA30487E +:10D5E000FFF710FD00E002243B68DA0718D53B493D +:10D5F0002B48B1F90020B1F90230B1F9041004F15F +:10D60000010800913649FEF77FFEF7F773FD2046CB +:10D61000FBF726FA2248FFF7F5FC5FFA88F8444644 +:10D620003B681B0740F1B9802E491D48B1F9002025 +:10D63000B1F90230B1F9041000912B49FEF764FEF4 +:10D64000F7F758FD2046A3E00E2C00F0A6806008F6 +:10D650000130FBF705FA2046FFF7B1FC3B78A34207 +:10D6600006D92020FFF768FC601CC0B2FFF7A7FCBA +:10D670000234E4B21D4F3B78A342E5D88DE000BFF1 +:10D68000441E0020D5270020100800201454010853 +:10D69000B0000020404B4C0023710108F9620108E2 +:10D6A000491E0020C80000202B71010834200020F2 +:10D6B0009C06002098000020367101089806002082 +:10D6C000A0060020A40600204E71010808020020D8 +:10D6D00063710108080400207971010850030020DB +:10D6E000897101083804002099710108C30A0020DB +:10D6F000354C364994F854273548FEF705FE01208D +:10D70000FBF7AEF93248FFF77DFC324B32491F7808 +:10D710002F483A46FEF7F8FD0220FBF7A1F92C4806 +:10D72000FFF770FC0A2303FB07472C4997F857279C +:10D730002748FEF7E9FDF7F7DDFC0320FBF790F93A +:10D740002348FFF75FFC264997F856272048FEF745 +:10D75000DBFDF7F7CFFC0420FBF782F91C48FFF74D +:10D7600051FC204997F85A271948FEF7CDFDF7F7E5 +:10D77000C1FC0520FBF774F91548FFF743FC14487A +:10D78000194997F85B27FEF7BFFDF7F7B3FC0620B2 +:10D79000FBF766F90E48FFF735FC8EB9B020FBF7B2 +:10D7A0005BF90820FBF758F91720FBF755F9EC7ED9 +:10D7B0000E4B185D013404F00304FFF7BDFBEC765B +:10D7C00002B0BDE8F08100BF34200020A97101083B +:10D7D000491E0020F80E0020B5710108C67101082D +:10D7E000D2710108DE710108EB710108F8710108BE +:10D7F0002DE9F3412D4B1B78042B50D14020F8F735 +:10D80000ACFE044670B12046F9F77BF818B90A203F +:10D81000F9F719F8F7E7264B20461B681969F9F75D +:10D8200075F80BE0224B21461B6800901A694020D6 +:10D830000323FDF7C9FF0446002830D01D4D28689A +:10D8400041798B0703D441F00201F9F755F81A4BDF +:10D8500008221A6110221A612868F9F761F858B194 +:10D86000144B154E082718687761F9F754F80146EC +:10D870002046F9F767F837612046F9F751F8002894 +:10D88000EAD00D4E102777612046D5F80080F9F7D1 +:10D8900042F801464046F9F755F83761DCE707489A +:10D8A00002B0BDE8F041F9F7E7B800BFE00A002098 +:10D8B000DC0A0020000B0020000C01402F72010840 +:10D8C0002DE9F743124C814604F1980894F84A6018 +:10D8D000C6B9D9F804200025009501202946032364 +:10D8E000FDF772FF074620B97EB94FF49642012634 +:10D8F000F1E7204629464C2204F07FFB01232760F4 +:10D9000084F84A304C344445E0D103B0BDE8F0839C +:10D91000F80F0020F7B5524B524C2360F9F7ACFBDF +:10D920000120FCF7C1F8002800F084804E4BFF2155 +:10D9300018461622256804F060FB002202704B4A4C +:10D940000121126803469707817504D541700321B0 +:10D95000817502218170560704D5997D481C987500 +:10D960000320585412F00A0F0CD09A7D04219954C8 +:10D97000511CC9B205205854D11C02329975D2B23B +:10D98000062199543A4FBA68900604D5997D481CEF +:10D99000987507205854110608D5997D09205854C8 +:10D9A000881C01319875C9B20A2058547979082920 +:10D9B00001D00E2904D1997D481C98750B2058542C +:10D9C000997D4FF00C0E481CC0B212F0040F264E89 +:10D9D000987503F801E003D00231B175102131547C +:10D9E000997D97F84571481CC0B24FF0120E002F78 +:10D9F0000CBF002702F001071B4E987503F801E0E9 +:10DA00001FB10231B17513213154997D1427481C7F +:10DA1000C0B298755F549305134E03D50231152398 +:10DA2000B175335413480021982204F0E6FA2846D1 +:10DA3000FFF746FF0220FCF737F870B10220F8F735 +:10DA40008CFD2568084C0146A06130B90090AA6899 +:10DA500002200323FDF7B8FEA06103B0F0BD00BFB4 +:10DA60006021002090100020601E0020080200208D +:10DA700034200020F80F0020A44B2DE9F3411B783F +:10DA8000002B00F07381F7F7D9FAA14F06463B78D7 +:10DA9000834200F06B819F4D2B681B78002800F0BB +:10DAA000E88063BB0420F8F758FD9B4C01462060DA +:10DAB000DFF86C8290B143794FF4165188F81C302E +:10DAC0008368C8F82030F8F721FF20680221F8F7B2 +:10DAD00013FF20680421FBF789FE10E08F4B042020 +:10DAE0001B684FF416529B7800930223FDF76CFEDF +:10DAF0004379206088F81C308368C8F820302B6890 +:10DB000093F80080B8F1010F2BD10420F8F725FD20 +:10DB1000834C0146606288B143794FF4964184F8A2 +:10DB200028308368E362F8F7F1FE606A4146F8F74F +:10DB3000E3FE606A0421FBF759FE12E000904346C1 +:10DB400004204FF49642FDF73FFE4379606284F86B +:10DB500028308368E3620379033B012B98BF84F884 +:10DB600030802B681D78022D41D10420F8F7F5FC98 +:10DB70006B4C0146606388B143794FF4964184F859 +:10DB800038308368E363F8F7C1FE606B2946F8F725 +:10DB9000B3FE606B0421FBF729FE0CE000902B46DE +:10DBA00004204FF49642FDF70FFE4379606384F83A +:10DBB00038308368E363656B5A4C94F84A30022B23 +:10DBC00009D094F89620022A00F0CE801BB14C3484 +:10DBD000002A18BF0024544B1C6044B12046002189 +:10DBE0004C2204F00AFA0223256084F84A30F7F741 +:10DBF00077FA002800F0B6804C4D2B78002B40F0CF +:10DC0000B1800820F8F7A9FC494C0146206090B18A +:10DC1000434B42794FF4614183F8402082685A6453 +:10DC2000F8F774FE20680821F8F766FE20680821DE +:10DC3000FBF7DCFD96E03F4B08201B684FF4614288 +:10DC40009B7800930346FDF7BFFD206040B10123A0 +:10DC500042792B70324B83F8402082685A6481E00D +:10DC6000354B1B78002B7DD004232B70FFF752FE21 +:10DC700078E083B9284CDFF8A880206898F81C1059 +:10DC8000F8F73AFE2068D8F82010F8F73FFE206831 +:10DC90000421FBF779FD2B681B78012B0DD1204C5B +:10DCA000606A94F82810F8F727FE606AE16AF8F7CE +:10DCB0002DFE606A0421FBF767FD2B681B78022BA1 +:10DCC0000DD1174C606B94F83810F8F715FE606BA7 +:10DCD000E16BF8F71BFE606B0421FBF755FDF7F7CE +:10DCE000FFF900283ED0114D2B7813F0FB0F39D0EF +:10DCF000114B0F4C1B780BB320680821FBF744FD38 +:10DD000004232B70FFF706FE2AE000BF80060020E8 +:10DD1000810600208406002088060020AC06002032 +:10DD2000601E0020F80F0020B4060020C40600206A +:10DD3000C8060020980E0020360E0020DFF8348040 +:10DD4000206898F84010F8F7D7FD2068D8F84410FC +:10DD5000F8F7DCFD20680821FBF716FD04232B7083 +:10DD6000002323603E7001E04C3434E702B0BDE88C +:10DD7000F08100BF601E002073B54D490B7813F091 +:10DD8000010F03F0040200F08780002A40F08D802C +:10DD9000980700F1818043F004030B70454B464C1B +:10DDA0001A88464B1A80A3685A0505D50420FBF74C +:10DDB0005BFE08B1FBF7F8FCA3681B0375D5802058 +:10DDC000FBF752FE08B1FBF7EFFC3D4D2A78012A24 +:10DDD0006BD194F8740794F87517374B884204D3C5 +:10DDE00083F8742783F8752711E00A46034632B199 +:10DDF00093FBF2F602FB163613463246F7E790FB2A +:10DE0000F3F091FBF3F384F8740784F875378020FE +:10DE1000F8F7A3FB2B4C0146206090B142792A4BC6 +:10DE20004FF4E1311A708268284B1A60F8F76EFDE2 +:10DE300020680221F8F760FD20688021FBF7D6FCFE +:10DE40000EE000904FF4E13280200223FDF7BCFC8D +:10DE5000206028B142791C4B1A7082681B4B1A60F3 +:10DE600023680BB92B7020E0194B00211A68194B5D +:10DE700019481A60194B14221960194B19600223B2 +:10DE80002B7004F0BAF8174B174A02F164011A60BC +:10DE9000C83259609A6008E03AB90220FF21012295 +:10DEA00002B0BDE87040F8F7DFBC02B070BD00BF43 +:10DEB000D52700203E04002034200020040F00203D +:10DEC0000C050020202000202420002028200020F5 +:10DED00030200020100500206006002014050020DE +:10DEE0001C050020200500202C0500202DE9F04114 +:10DEF000FFF791F810B90A20F8F7DCFC824C4FF4D8 +:10DF0000EF622046814904F06FF894F854374FF4DB +:10DF1000E072022B84BF002384F8543794F85437FE +:10DF20007B4E02FB034303F5057393F850203360E7 +:10DF3000022A84BF002283F8502093F85030754A9B +:10DF400013700A2202FB0343734A03F256731360F1 +:10DF5000A36842F201021A403AB944F208021A4098 +:10DF60001AB9694A43F400539360A368D90703D5EB +:10DF70004FF40050F6F7FFFFA3685A0409D50820B4 +:10DF8000F6F7F9FF4FF40050F6F7F5FF0120F6F72A +:10DF9000F2FFA3681B0706D54FF40050F6F7EBFF1E +:10DFA0000120F6F7E8FFA3689F040ED54FF4004068 +:10DFB000F6F7E1FF4FF40060F6F7DDFF4FF4803035 +:10DFC000F6F7D9FF4020F6F7D6FFA3685D0603D524 +:10DFD0004FF48030F6F7CFFFA368980408D503F418 +:10DFE0002063B3F5206F03D14FF40060F6F7C3FF51 +:10DFF0004A4D4B4B2F461D60F9F73EF8494B05F152 +:10E000001C0201201A60FBF7AEFC01460120FBF761 +:10E0100079FB002849D00220FBF7A5FC014602202D +:10E02000FBF770FB002840D02020FBF79CFC01464A +:10E030002020FBF767FBA368190601D5002834D020 +:10E040001020FBF790FC01461020FBF75BFBA36858 +:10E050001A0700D548B30420FBF785FC01460420CD +:10E06000FBF750FB30B90820FBF77DFC0146082088 +:10E07000FBF748FBA3685B0503D400231A46194647 +:10E0800009E00028F9D110E079B90121C00708D4CE +:10E090000C33302B0BD024481844007A8507F5D573 +:10E0A000F2E70132D2B2022AF2D9F9F70FF8F8F703 +:10E0B000DBFA1E4D1E4B32681D601E4B101D186092 +:10E0C00002F175010023A846CD5C55B901EB030EA2 +:10E0D0009EF802C09EF803E0F44502D2164B1D7074 +:10E0E00002E00433A02BEFD1144B15490B60154906 +:10E0F00050330B601178144B012903D0022929D029 +:10E10000124928E0124926E03420002000F80108D6 +:10E110003C030020F80E0020FC04002044210020D5 +:10E120003C01002090100020680000200421002005 +:10E13000F00E0020F40E00204800002028210020CE +:10E1400058030020840600209C000020D17C000899 +:10E15000297B000834491960344B02F5D9721A60E2 +:10E16000F7F79CF83668324B06F5D3721A60314BDC +:10E1700000229A80304B314A314D136006F5B3725C +:10E180002A60A3F122026A602E332E4A06F5D77167 +:10E19000EB6006F5D87311606B61C5F808802F61DC +:10E1A000B4F8F00000F020FFE861B4F8F20000F0ED +:10E1B0001BFF96F8583005F118022B7696F874304C +:10E1C00028626B7694F82531B6F8620185F8243020 +:10E1D0001D4B1A60331DAB621C4B06F160021A60C6 +:10E1E0001B4B06F164021A601A4B06F25D121A60AC +:10E1F000194BC3F8008000F0FBFE0146174800F001 +:10E20000FFFF174900F048FF164B17491860F06DE3 +:10E2100000F042FF01464FF07C5000F0F1FF134B3D +:10E220001860BDE8F08100BF797F0008040B002072 +:10E230002C200020AC0A00202C210020C403002048 +:10E24000A81E002008050020F80300205804002024 +:10E2500064020020E8040020F00400200000614473 +:10E260004C3D0F44F8040020DB0F494048040020D7 +:10E2700001480249F7F774B8000800404C1F00201D +:10E2800001480249F7F76CB800040040241F002041 +:10E290004FF080400149F7F763B800BFFC1E002033 +:10E2A00001480249F7F75CB8002C0140D41E002059 +:10E2B00001480249F7F754B8002C0140D41E002051 +:10E2C00038B5204CD4F8F0301D88ADB2AA0618D568 +:10E2D000D4F8CC201AB1988880B2904711E09B887E +:10E2E000D4F8BC20D4F8B410DBB28B54D4F8BC20E2 +:10E2F000D4F8AC300132B2FBF3F103FB1123C4F8C4 +:10E30000BC302B061DD5D4F8C820D4F8C4100D4B52 +:10E310008A4210D0D3F8B800D3F8F010805C0132F4 +:10E32000C0B28880D3F8B010B2FBF1F001FB10222C +:10E33000C3F8C82038BDD3F8F030DA6822F0800284 +:10E34000DA6038BDD41E00200F4BD3F84421118869 +:10E35000090618D5D3F81C11D3F8180181420ED044 +:10E36000D3F80C01405C0131C0B29080D3F8042195 +:10E37000B1FBF2F002FB1011C3F81C117047D36817 +:10E3800023F08003D3607047D41E00200C480D4B4F +:10E390004FF400525A60D0F828214FF6FE731168EE +:10E3A0000B401360D0F81821D0F81C319A4202D0EB +:10E3B000F430FDF717BE012380F83831704700BFF5 +:10E3C000D41E002000000240FDF725BEFDF723BE4D +:10E3D000084A13689B020BD5074B002119700749A7 +:10E3E0004FF6FE73086803400B604FF40013536050 +:10E3F000704700BF00000240CE2700206C000240A2 +:10E40000FAF75CBEFAF75ABEF7F7C2B9F7F7C0B928 +:10E41000074B1A685969490408D5520406D54FF4C8 +:10E4200080425A61034B012283F84821704700BFA4 +:10E4300000040140D41E002010B51B4B1A78510770 +:10E4400031D51A4C22F004021A70A3685A050AD575 +:10E45000FFF712FB04200121FBF715FB18B104F5AF +:10E460009670FFF72DFAA3681B031CD5104B1A7882 +:10E47000012A0ED90F4C0122206821791A70F8F771 +:10E480003BFA2068A168F8F741FA20688021FBF781 +:10E490007BF980200121FBF7F6FA20B10648BDE8A0 +:10E4A0001040FFF70DBA10BDD52700203420002002 +:10E4B0000C050020202000206021002070B5F6F718 +:10E4C0008DF838B3144C237A0BB9A38070BD134D6B +:10E4D0002E78C6F38000F6F793F890B1104B46F013 +:10E4E00002061A680F4B51892E7019805189598084 +:10E4F00052899A800C4AD2685288DA80E3880133C4 +:10E50000E380F6F757F810B92B785B0702D4BDE823 +:10E51000704091E770BD00BFAC0A0020D5270020F5 +:10E52000A80A002072070020202000200F4B1A6844 +:10E5300042F001021A6059680D4A0A405A601A688E +:10E5400022F0847222F480321A601A6822F4802247 +:10E550001A605A6822F4FE025A604FF41F029A6051 +:10E56000044B4FF000629A60704700BF00100240F9 +:10E570000000FFF800ED00E0024B1A6801321A605B +:10E58000704700BF3020002008B5084BB3F8D80012 +:10E59000074B1A780023D9B2914204D2054921F8D9 +:10E5A00013000133F7E7FEF7E9F8FEE7302000201B +:10E5B000E7270020AC27002081F0004102E000BFE7 +:10E5C00083F0004330B54FEA41044FEA430594EA33 +:10E5D000050F08BF90EA020F1FBF54EA000C55EA6E +:10E5E000020C7FEA645C7FEA655C00F0E2804FEA3F +:10E5F0005454D4EB5555B8BF6D420CDD2C4480EA21 +:10E60000020281EA030382EA000083EA010180EA50 +:10E61000020281EA0303362D88BF30BD11F0004F9E +:10E620004FEA01314FF4801C4CEA113102D04042D4 +:10E6300061EB410113F0004F4FEA03334CEA13330F +:10E6400002D0524263EB430394EA050F00F0A78027 +:10E65000A4F10104D5F1200E0DDB02FA0EFC22FA22 +:10E6600005F2801841F1000103FA0EF2801843FA16 +:10E6700005F359410EE0A5F120050EF1200E012A07 +:10E6800003FA0EFC28BF4CF0020C43FA05F3C01845 +:10E6900051EBE37101F0004507D54FF0000EDCF1BE +:10E6A000000C7EEB00006EEB0101B1F5801F1BD367 +:10E6B000B1F5001F0CD349085FEA30004FEA3C0C6B +:10E6C00004F101044FEA445212F5800F80F09A8061 +:10E6D000BCF1004F08BF5FEA500C50F1000041EB65 +:10E6E000045141EA050130BD5FEA4C0C404141EB69 +:10E6F000010111F4801FA4F10104E9D191F0000F90 +:10E7000004BF01460020B1FA81F308BF2033A3F112 +:10E710000B03B3F120020CDA0C3208DD02F1140C09 +:10E72000C2F10C0201FA0CF021FA02F10CE002F144 +:10E730001402D8BFC2F1200C01FA02F120FA0CFC3D +:10E74000DCBF41EA0C019040E41AA2BF01EB045186 +:10E75000294330BD6FEA04041F3C1CDA0C340EDC84 +:10E7600004F11404C4F1200220FA04F001FA02F3C7 +:10E7700040EA030021FA04F345EA030130BDC4F185 +:10E780000C04C4F1200220FA02F001FA04F340EA7A +:10E790000300294630BD21FA04F0294630BD94F02B +:10E7A000000F83F4801306BF81F480110134013D12 +:10E7B0004EE77FEA645C18BF7FEA655C29D094EA83 +:10E7C000050F08BF90EA020F05D054EA000C04BF01 +:10E7D0001946104630BD91EA030F1EBF00210020EC +:10E7E00030BD5FEA545C05D14000494128BF41F08B +:10E7F000004130BD14F580043CBF01F5801130BDEF +:10E8000001F0004545F0FE4141F470014FF0000079 +:10E8100030BD7FEA645C1ABF194610467FEA655C2A +:10E820001CBF0B46024650EA013406BF52EA0335CC +:10E8300091EA030F41F4002130BD00BF90F0000FBA +:10E8400004BF0021704730B54FF4806404F13204F6 +:10E850004FF000054FF0000150E700BF90F0000FAF +:10E8600004BF0021704730B54FF4806404F13204D6 +:10E8700010F0004548BF40424FF000013EE700BFA6 +:10E8800042004FEAE2014FEA31014FEA02701FBF36 +:10E8900012F07F4393F07F4F81F06051704792F008 +:10E8A000000F14BF93F07F4F704730B54FF4607482 +:10E8B00001F0004521F0004120E700BF50EA0102CD +:10E8C00008BF704730B54FF000050AE050EA01027A +:10E8D00008BF704730B511F0004502D5404261EBEA +:10E8E00041014FF4806404F132045FEA915C3FF42B +:10E8F000DCAE4FF003025FEADC0C18BF03325FEAC4 +:10E90000DC0C18BF033202EBDC02C2F1200300FA78 +:10E9100003FC20FA02F001FA03FE40EA0E0021FA9D +:10E9200002F11444C1E600BF70B54FF0FF0C4CF487 +:10E93000E06C1CEA11541DBF1CEA135594EA0C0F3D +:10E9400095EA0C0F00F0DEF82C4481EA030621EA78 +:10E950004C5123EA4C5350EA013518BF52EA0335B3 +:10E9600041F4801143F4801338D0A0FB02CE4FF065 +:10E970000005E1FB02E506F00042E0FB03E54FF095 +:10E980000006E1FB03569CF0000F18BF4EF0010E8D +:10E99000A4F1FF04B6F5007F64F5407404D25FEA89 +:10E9A0004E0E6D4146EB060642EAC62141EA55513C +:10E9B0004FEAC52040EA5E504FEACE2EB4F1FD0C7E +:10E9C00088BFBCF5E06F1ED8BEF1004F08BF5FEAFC +:10E9D000500E50F1000041EB045170BD06F00046AE +:10E9E00046EA010140EA020081EA0301B4EB5C045B +:10E9F000C2BFD4EB0C0541EA045170BD41F4801153 +:10EA00004FF0000E013C00F3AB8014F1360FDEBF77 +:10EA1000002001F0004170BDC4F10004203C35DA53 +:10EA20000C341BDC04F11404C4F1200500FA05F3D6 +:10EA300020FA04F001FA05F240EA020001F0004277 +:10EA400021F0004110EBD37021FA04F642EB0601ED +:10EA50005EEA430E08BF20EAD37070BDC4F10C0417 +:10EA6000C4F1200500FA04F320FA05F001FA04F2DB +:10EA700040EA020001F0004110EBD37041F10001C7 +:10EA80005EEA430E08BF20EAD37070BDC4F12005D2 +:10EA900000FA05F24EEA020E20FA04F301FA05F23A +:10EAA00043EA020321FA04F001F0004121FA04F2E2 +:10EAB00020EA020000EBD3705EEA430E08BF20EAB2 +:10EAC000D37070BD94F0000F0FD101F000464000EC +:10EAD00041EB010111F4801F08BF013CF7D041EA6E +:10EAE000060195F0000F18BF704703F00046520072 +:10EAF00043EB030313F4801F08BF013DF7D043EA43 +:10EB00000603704794EA0C0F0CEA135518BF95EAF8 +:10EB10000C0F0CD050EA410618BF52EA4306D1D17F +:10EB200081EA030101F000414FF0000070BD50EA9E +:10EB3000410606BF1046194652EA430619D094EA28 +:10EB40000C0F02D150EA013613D195EA0C0F05D112 +:10EB500052EA03361CBF104619460AD181EA030166 +:10EB600001F0004141F0FE4141F470014FF000001E +:10EB700070BD41F0FE4141F4780170BD70B54FF0B9 +:10EB8000FF0C4CF4E06C1CEA11541DBF1CEA135539 +:10EB900094EA0C0F95EA0C0F00F0A7F8A4EB05041B +:10EBA00081EA030E52EA03354FEA013100F0888012 +:10EBB0004FEA03334FF0805545EA131343EA1263DB +:10EBC0004FEA022245EA111545EA10654FEA002690 +:10EBD0000EF000419D4208BF964244F1FD0404F549 +:10EBE000407402D25B084FEA3202B61A65EB0305A5 +:10EBF0005B084FEA32024FF480104FF4002CB6EB62 +:10EC0000020E75EB030E22BFB61A754640EA0C00E1 +:10EC10005B084FEA3202B6EB020E75EB030E22BF21 +:10EC2000B61A754640EA5C005B084FEA3202B6EB62 +:10EC3000020E75EB030E22BFB61A754640EA9C0021 +:10EC40005B084FEA3202B6EB020E75EB030E22BFF1 +:10EC5000B61A754640EADC0055EA060E18D04FEAAF +:10EC6000051545EA16754FEA06164FEAC30343EA4F +:10EC700052734FEAC2025FEA1C1CC0D111F4801F1C +:10EC80000BD141EA00014FF000004FF0004CB6E715 +:10EC900011F4801F04BF01430020B4F1FD0C88BFB4 +:10ECA000BCF5E06F3FF6AFAEB5EB030C04BFB6EBBF +:10ECB000020C5FEA500C50F1000041EB045170BDB2 +:10ECC0000EF0004E4EEA113114EB5C04C2BFD4EBDF +:10ECD0000C0541EA045170BD41F480114FF0000E63 +:10ECE000013C90E645EA060E8DE60CEA135594EADF +:10ECF0000C0F08BF95EA0C0F3FF43BAF94EA0C0FE2 +:10ED00000AD150EA01347FF434AF95EA0C0F7FF456 +:10ED100025AF104619462CE795EA0C0F06D152EAAA +:10ED200003353FF4FDAE1046194622E750EA41068E +:10ED300018BF52EA43067FF4C5AE50EA41047FF49F +:10ED40000DAF52EA43057FF4EBAE12E74FEA410202 +:10ED500012F5001215D211D56FF47873B3EB62522D +:10ED600012D94FEAC12343F0004343EA505311F054 +:10ED7000004F23FA02F018BF404270474FF00000E6 +:10ED8000704750EA013005D111F0004008BF6FF024 +:10ED9000004070474FF00000704700BF4A0011D29A +:10EDA00012F5001211D20DD56FF47873B3EB6252E5 +:10EDB0000ED44FEAC12343F0004343EA505323FAF1 +:10EDC00002F070474FF00000704750EA013002D166 +:10EDD0004FF0FF3070474FF0000070474FEA41029C +:10EDE000B2F1E04324BFB3F5001CDCF1FE5C0DD9A9 +:10EDF00001F0004C4FEAC0024CEA5070B2F1004FF3 +:10EE000040EB830008BF20F00100704711F0804FF5 +:10EE100021D113F13872BCBF01F00040704741F4BA +:10EE200080114FEA5252C2F11802C2F1200C10FABE +:10EE30000CF320FA02F018BF40F001004FEAC123A2 +:10EE40004FEAD32303FA0CFC40EA0C0023FA02F346 +:10EE50004FEA4303CCE77FEA625307D150EA01331C +:10EE60001EBF4FF0FE4040F44000704701F00040EC +:10EE700040F0FE4040F40000704700BF80F00040CA +:10EE800002E000BF81F0004142001FBF5FEA410382 +:10EE900092EA030F7FEA226C7FEA236C6AD04FEA82 +:10EEA0001262D2EB1363C1BFD218414048404140C7 +:10EEB000B8BF5B42192B88BF704710F0004F40F479 +:10EEC000000020F07F4018BF404211F0004F41F495 +:10EED000000121F07F4118BF494292EA030F3FD061 +:10EEE000A2F1010241FA03FC10EB0C00C3F1200374 +:10EEF00001FA03F100F0004302D5494260EB400003 +:10EF0000B0F5000F13D3B0F1807F06D340084FEA6D +:10EF1000310102F10102FE2A51D2B1F1004F40EB62 +:10EF2000C25008BF20F0010040EA030070474900CA +:10EF300040EB000010F4000FA2F10102EDD1B0FA95 +:10EF400080FCACF1080CB2EB0C0200FA0CF0AABF8A +:10EF500000EBC25052421843BCBFD0401843704728 +:10EF600092F0000F81F4000106BF80F4000001322E +:10EF7000013BB5E74FEA41037FEA226C18BF7FEA05 +:10EF8000236C21D092EA030F04D092F0000F08BF47 +:10EF90000846704790EA010F1CBF0020704712F02E +:10EFA0007F4F04D1400028BF40F00040704712F16D +:10EFB00000723CBF00F50000704700F0004343F0D2 +:10EFC000FE4040F4000070477FEA226216BF084608 +:10EFD0007FEA23630146420206BF5FEA412390EACB +:10EFE000010F40F4800070474FF0000304E000BFC1 +:10EFF00010F0004348BF40425FEA000C08BF704772 +:10F0000043F0964301464FF000001CE050EA010235 +:10F0100008BF70474FF000030AE000BF50EA01024A +:10F0200008BF704711F0004302D5404261EB410137 +:10F030005FEA010C02BF84460146002043F0B6435C +:10F0400008BFA3F18053A3F50003BCFA8CF2083A81 +:10F05000A3EBC25310DB01FA02FC634400FA02FC8A +:10F06000C2F12002BCF1004F20FA02F243EB020091 +:10F0700008BF20F00100704702F1200201FA02FCF3 +:10F08000C2F1200250EA4C0021FA02F243EB0200E6 +:10F0900008BF20EADC7070474FF0FF0C1CEAD0522A +:10F0A0001EBF1CEAD15392EA0C0F93EA0C0F6FD0EB +:10F0B0001A4480EA010C400218BF5FEA41211ED0C9 +:10F0C0004FF0006343EA501043EA5111A0FB0131B5 +:10F0D0000CF00040B1F5000F3EBF490041EAD3718A +:10F0E0005B0040EA010062F17F02FD2A1DD8B3F106 +:10F0F000004F40EBC25008BF20F00100704790F075 +:10F10000000F0CF0004C08BF49024CEA502040EAC6 +:10F1100051207F3AC2BFD2F1FF0340EAC25070478C +:10F1200040F400004FF00003013A5DDC12F1190FCA +:10F13000DCBF00F000407047C2F10002410021FA3C +:10F1400002F1C2F1200200FA02FC5FEA310040F154 +:10F15000000053EA4C0308BF20EADC70704792F0CD +:10F16000000F00F0004C02BF400010F4000F013A05 +:10F17000F9D040EA0C0093F0000F01F0004C02BF00 +:10F18000490011F4000F013BF9D041EA0C018FE76F +:10F190000CEAD15392EA0C0F18BF93EA0C0F0AD075 +:10F1A00030F0004C18BF31F0004CD8D180EA01009B +:10F1B00000F00040704790F0000F17BF90F0004F34 +:10F1C000084691F0000F91F0004F14D092EA0C0F16 +:10F1D00001D142020FD193EA0C0F03D14B0218BFA9 +:10F1E000084608D180EA010000F0004040F0FE40EF +:10F1F00040F40000704740F0FE4040F4400070478B +:10F200004FF0FF0C1CEAD0521EBF1CEAD15392EA09 +:10F210000C0F93EA0C0F69D0A2EB030280EA010CF9 +:10F2200049024FEA402037D04FF0805343EA111192 +:10F2300043EA10130CF000408B4238BF5B0042F1F0 +:10F240007D024FF4000C8B4224BF5B1A40EA0C0095 +:10F25000B3EB510F24BFA3EB510340EA5C00B3EBC7 +:10F26000910F24BFA3EB910340EA9C00B3EBD10FB5 +:10F2700024BFA3EBD10340EADC001B0118BF5FEA07 +:10F280001C1CE0D1FD2A3FF650AF8B4240EBC25030 +:10F2900008BF20F0010070470CF0004C4CEA5020F1 +:10F2A0007F32C2BFD2F1FF0340EAC250704740F440 +:10F2B00000004FF00003013A37E792F0000F00F032 +:10F2C000004C02BF400010F4000F013AF9D040EAB0 +:10F2D0000C0093F0000F01F0004C02BF490011F444 +:10F2E000000F013BF9D041EA0C0195E70CEAD1533C +:10F2F00092EA0C0F08D142027FF47DAF93EA0C0F23 +:10F300007FF470AF084676E793EA0C0F04D14B0206 +:10F310003FF44CAF08466EE730F0004C18BF31F0B8 +:10F32000004CCAD130F000427FF45CAF31F00043B2 +:10F330007FF43CAF5FE700BF4FF0FF3C06E000BF4B +:10F340004FF0010C02E000BF4FF0010C4DF804CD6E +:10F350004FEA40024FEA41037FEA226C18BF7FEA7E +:10F36000236C11D001B052EA530C18BF90EA010F80 +:10F3700058BFB2EB030088BFC81738BF6FEAE1700F +:10F3800018BF40F0010070477FEA226C02D15FEAAB +:10F39000402C05D17FEA236CE4D15FEA412CE1D017 +:10F3A0005DF8040B704700BF844608466146FFE7DE +:10F3B0000FB5FFF7C9FF002848BF10F1000F0FBDC0 +:10F3C0004DF808EDFFF7F4FF0CBF012000205DF8B9 +:10F3D00008FB00BF4DF808EDFFF7EAFF34BF01203E +:10F3E00000205DF808FB00BF4DF808EDFFF7E0FFD7 +:10F3F00094BF012000205DF808FB00BF4DF808ED28 +:10F40000FFF7D2FF94BF012000205DF808FB00BF8A +:10F410004DF808EDFFF7C8FF34BF012000205DF86C +:10F4200008FB00BF4FEA4002B2F1FE4F0FD34FF08E +:10F430009E03B3EB12620DD94FEA002343F0004361 +:10F4400010F0004F23FA02F018BF404270474FF00F +:10F450000000704712F1610F01D1420205D110F096 +:10F46000004008BF6FF0004070474FF00000704749 +:10F4700042000ED2B2F1FE4F0BD34FF09E03B3EB1E +:10F48000126209D44FEA002343F0004323FA02F04A +:10F4900070474FF00000704712F1610F01D1420236 +:10F4A00002D14FF0FF3070474FF00000704700BFAF +:10F4B00073B96AB9002908BF0028BCBF00204FF00B +:10F4C0000041C4BF6FF000414FF0FF3000F03CB886 +:10F4D00082B0EC462DE9005000F006F8DDF804E0BB +:10F4E00002B00CBC704700BF2DE9704F089E144657 +:10F4F0001D468046894600F029F804FB01F3A4FB71 +:10F5000000AB00FB05329344B8EB0A0869EB0B092A +:10F51000C6E90089BDE8708F2DE9704F089E14463A +:10F520001D468046894600F061F900FB05F5A0FB09 +:10F5300004AB04FB0154A344B8EB0A0869EB0B09C4 +:10F54000C6E90089BDE8708F704700BF00292DE92A +:10F55000F00FC0F2A1800024002BC0F29880154665 +:10F5600006460F46002B3FD18A4258D9B2FA82F3A1 +:10F570004BB1C3F1200201FA03F720FA02F29D40D9 +:10F5800000FA03F61743290CB7FBF1F201FB1277DF +:10F59000A8B200FB02F34FEA164C4CEA0747BB4205 +:10F5A00009D97F1902F1FF3C80F00581BB4240F28E +:10F5B0000281023A2F44FF1AB7FBF1F301FB1371EA +:10F5C00000FB03F0B6B246EA0141884208D9491966 +:10F5D00003F1FF3780F0F180884240F2EE80023B79 +:10F5E00043EA0242002303E08B420AD900231A4671 +:10F5F0001046194614B1404261EB4101BDE8F00FDD +:10F600007047B3FA83F8B8F1000F40F088808B425E +:10F6100002D3824200F2E28000230122E8E712B91D +:10F620000123B3FBF2F5B5FA85F2002A3AD17F1B2C +:10F63000280C1FFA85FC0123B7FBF0F100FB1177C2 +:10F640000CFB01F24FEA164848EA0747BA4207D9CD +:10F650007F1901F1FF3802D2BA4200F2C48041465C +:10F66000BF1AB7FBF0F200FB12700CFB02FCB6B243 +:10F6700046EA0040844507D9401902F1FF3702D21B +:10F68000844500F2AE803A4642EA0142B0E7E443E4 +:10F69000524263EB430362E7404261EB41014FF0AA +:10F6A000FF3459E79540C2F1200927FA09F126FAFB +:10F6B00009F99740280CB1FBF0F800FB18111FFA6C +:10F6C00085FC0CFB08F349EA07094FEA194747EAAA +:10F6D00001418B4206FA02F608D9491908F1FF32B6 +:10F6E0007AD28B4278D9A8F102082944C91AB1FB11 +:10F6F000F0F300FB13170CFB03F21FFA89F949EA38 +:10F700000747BA4207D97F1903F1FF3160D2BA42E5 +:10F710005ED9023B2F44BF1A43EA08438CE7C8F185 +:10F72000200225FA02F103FA08FC27FA02F320FA74 +:10F7300002F207FA08F741EA0C0C4FEA1C49B3FB46 +:10F74000F9F109FB11331FFA8CFA0AFB01FB17438D +:10F750003A0C42EA03439B4505FA08F008D913EB3B +:10F760000C0301F1FF3235D29B4533D90239634492 +:10F77000CBEB0303B3FBF9F209FB12330AFB02FAEA +:10F78000BFB247EA0347BA4508D917EB0C0702F1A5 +:10F79000FF331BD2BA4519D9023A674442EA014500 +:10F7A000A5FB0001CAEB07078F424FF000030AD305 +:10F7B00005D02A461CE76246FDE63B4610E706FAFE +:10F7C00008F68642F5D26A1E002311E71A46E5E7DD +:10F7D0000B46A0E71146CBE7904687E743464246F3 +:10F7E00006E7023A50E702392F4439E72DE9F00FD6 +:10F7F000144605460E46002B43D18A4253D9B2FA2D +:10F8000082F757B1C7F1200620FA06F601FA07F38E +:10F8100002FA07F400FA07F51E43210CB6FBF1F2D9 +:10F8200001FB1266A0B200FB02F32F0C47EA06466A +:10F83000B34209D9361902F1FF3780F0FD80B34297 +:10F8400040F2FA80023A2644F61AB6FBF1F301FBC5 +:10F85000136100FB03F0ADB245EA0141884208D9CB +:10F86000091903F1FF3680F0E980884240F2E68012 +:10F87000023B43EA0242002310461946BDE8F00F5E +:10F8800070478B424CD8B3FA83F6002E4FD18B428F +:10F8900002D3824200F2DD80BDE8F00F0023012296 +:10F8A00010461946704712B90124B4FBF2F4B4FAB9 +:10F8B00084F2002A40F08280091B260CA7B20123A3 +:10F8C000B1FBF6F006FB101107FB00F24FEA154CF6 +:10F8D0004CEA01418A4207D9091900F1FF3C02D2E2 +:10F8E0008A4200F2C8806046891AB1FBF6F206FB34 +:10F8F000121107FB02F7ADB245EA0145AF4208D944 +:10F900002C1902F1FF3180F09B80A74240F29880D1 +:10F91000023A42EA004210461946BDE8F00F70472D +:10F9200000231A4610461946BDE8F00F7047C6F18D +:10F93000200522FA05F703FA06F421FA05F301FA85 +:10F9400006FB20FA05F53C434FEA1448B3FBF8FCEC +:10F9500008FB1C331FFA84F909FB0CFA45EA0B0B70 +:10F960004FEA1B4545EA03439A4502FA06F204D9D9 +:10F970001B190CF1FF356FD3AC46CAEB0303B3FB85 +:10F98000F8F508FB153309FB05F91FFA8BFB4BEA69 +:10F990000347B94504D93F1905F1FF3362D31D462A +:10F9A00045EA0C4CACFB0223C9EB07079F424FF022 +:10F9B00000054AD346D062462B465DE79440C2F12B +:10F9C000200921FA09FC914020FA09F9260CBCFB18 +:10F9D000F6F806FB18CCA7B207FB08F349EA0109C1 +:10F9E0004FEA194141EA0C4C634500FA02F509D986 +:10F9F0001CEB040C08F1FF323BD2634539D9A8F166 +:10FA00000208A444C3EB0C0CBCFBF6F306FB13C1C9 +:10FA100007FB03F21FFA89F949EA01418A4207D933 +:10FA2000091903F1FF3022D28A4220D9023B214436 +:10FA3000891A43EA084343E73A4605E7334618E79D +:10FA40000A4666E7B0409042B5D20CF1FF3200237F +:10FA500012E7334632460FE79A458DD9ACF1020CD6 +:10FA600023448AE7B9459AD9023D274498E70346DB +:10FA7000DEE79046C6E70238214435E74FF0FF3C09 +:10FA800006E000BF4FF0010C02E000BF4FF0010C98 +:10FA90004DF804CD4FEA410C7FEA6C5C4FEA430C11 +:10FAA00018BF7FEA6C5C1BD001B050EA410C0CBF60 +:10FAB00052EA430C91EA030F02BF90EA020F0020C2 +:10FAC000704710F1000F91EA030F58BF994208BF29 +:10FAD00090422CBFD8176FEAE37040F001007047E6 +:10FAE0004FEA410C7FEA6C5C02D150EA013C07D13D +:10FAF0004FEA430C7FEA6C5CD6D152EA033CD3D088 +:10FB00005DF8040B704700BF8446104662468C4681 +:10FB10001946634600E000BF01B5FFF7B7FF0028B4 +:10FB200048BF10F1000F01BD4DF808EDFFF7F4FFDD +:10FB30000CBF012000205DF808FB00BF4DF808ED68 +:10FB4000FFF7EAFF34BF012000205DF808FB00BF8B +:10FB50004DF808EDFFF7E0FF94BF012000205DF8AD +:10FB600008FB00BF4DF808EDFFF7CEFF94BF012062 +:10FB700000205DF808FB00BF4DF808EDFFF7C4FF5B +:10FB800034BF012000205DF808FB00BF1C481D4960 +:10FB9000026800608A4200F01D80002100F004B875 +:10FBA000194B5B58435004311848194B42189A427C +:10FBB000FFF4F6AF174A00F003B8002342F8043B05 +:10FBC000154B9A42FFF4F9AFFEF7B0FC00F038F89D +:10FBD000FFF7FEBF114E124830601248016821F055 +:10FBE00070610160410201600F4C182020600F49D4 +:10FBF0000F4808600F48D0F800D040680047000068 +:10FC0000F04F0020EFBEADDE38810108000000207B +:10FC10003801002038010020F82700201810024089 +:10FC20000900000004000140140C0140000C0140D8 +:10FC30004434434400F0FF1FFFF7FEBF0000000004 +:10FC40002DE9804895B0F0F763FADFF8D8B2B449EF +:10FC500000238BF800308B68D84613F0080F00F0B3 +:10FC6000D180DBF804301B7A042B00F2C880DFE877 +:10FC700003F00303068C9A009BF80800C0E09BF891 +:10FC80000920A84B002A00F0BA8000225A7293F88B +:10FC90002020170700F1B380D97A9A7A01F0070083 +:10FCA00042EA00225A621A7B02F03F00400140EA19 +:10FCB000D1019962597B890041EA92119A7B02F045 +:10FCC000010041EA8021D962D97B01F00F00C00117 +:10FCD00040EA52021A631A7C02F07F00000140EAF7 +:10FCE00011115963597C490041EAD212997C01F003 +:10FCF000030042EA40229A63DA7C02F01F0080018E +:10FD000040EA9101D963197DC90041EA5212997DF7 +:10FD10001A645A7D01F0070042EA00225A64DA7D33 +:10FD200002F03F00400140EAD1019964197E890048 +:10FD300041EA92115A7E02F0010041EA8021D96421 +:10FD4000997E01F00F00C00140EA52021A65DA7E86 +:10FD500002F07F00000140EA11115965197F490046 +:10FD600041EAD212597F01F0030042EA40229A652B +:10FD70009A7F02F01F00800140EA9101D965D97F86 +:10FD8000C90041EA52121A6637E09BF86420654BBD +:10FD9000AAB3002283F8642093F86630012B2ED199 +:10FDA000F6F798FB2CE09BF88A205E4B3AB30022D2 +:10FDB00083F88A2093F88B20A82A20D193F89E40BC +:10FDC000ECB908EB440393F88E0093F88F3003EB03 +:10FDD0000020FEF733FD4EA3D3E90023FEF7CEFE4D +:10FDE0004DA3D3E90023FEF7EBFBFEF7D7FF4E4B05 +:10FDF00043F824000134082CE3D1012000E0002066 +:10FE00008BF8000046498B685E0409D59BF8C0203A +:10FE100022B1444A002182F8C01001228BF8002050 +:10FE20009BF800203AB1DD0505D53E4BD3F8C43030 +:10FE30001B681B6898473D4D9BF80030286833B914 +:10FE4000384BD3F8C830C31ADB43DB0F00E0012383 +:10FE500093B3F2F749F89BF8CC20324B002A00F01C +:10FE6000F080D3F8D0104C0742F19080D3F8D42022 +:10FE7000100707D4B3F8D82022F00802A3F8D8203E +:10FE800002F084B8B3F8D80000F0080292B2002A59 +:10FE900042F07C8040F00800A3F8D800D3F8E000DE +:10FEA000C3F8F020C3F8DC00B3F8EC00C3F8F4208A +:10FEB000A3F8E40002F06AB8DBF8F8305A1CCBF87B +:10FEC000F820052B00F2B580DFE803F0030B917DED +:10FED0008AADDBF8D0301B0740F1AB80FBF740FD6B +:10FEE000A7E0DBF8D0300F4C5F0740F1A280D4F8D8 +:10FEF000FC30C31A002BC0F29C8094F80031C4F887 +:10FF0000FC00012B25D013D3022B3AD091E000BF87 +:10FF10009A999999999919400000000000707740CA +:10FF20003420002038010020D8010020C427002000 +:10FF3000D4F80C319847D4F810319847012384F84D +:10FF40000031B4F80621D4F8FC301344C4F8FC3076 +:10FF50006FE0D4F814319847D4F808319847D4F8B2 +:10FF6000FC30B4F8042104F58E701344C4F8FC305E +:10FF700004F59071D4F818319847022384F80031C1 +:10FF800057E0D4F82C11D4F828010978431C002636 +:10FF90008B4284F80061D4F82471D4F81C2103D179 +:10FFA000012384F83031334608EB8000C0F8342157 +:10FFB00008EB8301D1F834113A44521ACBF82831B6 +:10FFC000CBF8242135E0DBF8D0305E0703D56B4A4F +:10FFD00092F830210AB9DC062BD5FAF7ADF828E003 +:10FFE00067498B68190624D5F3F7A8FB21E0DBF8F5 +:10FFF000D020624BD2061CD5624AD3F8F4111268A5 :020000040801F1 -:10000000A3FA01464FF07E50FEF74CFE8549FEF7FD -:1000100053FF02F0CBF96F688146D4F86C02FEF70B -:10002000F7FE3946FEF748FF8046D4F86002C0EB81 -:100030000900FEF7EDFE394681464FF07E50FEF78F -:1000400031FE01464846FEF737FF01464046FEF7BF -:100050002BFE02F0ABF9B4F97072B4F97232002FD2 -:10006000B8BF7F42002BB8BF5B429F42B8BF1F465C -:10007000DFF8C4813FB2FA2F8246D8F8000014DCC2 -:10008000FEF7C6FE81463846FEF7C2FE01466648C8 -:10009000FEF708FE01464846FEF70EFF6249FEF7EE -:1000A000BFFFFFF7CFF8074601E04FF0FF377B1E99 -:1000B000C62BC8F8007006D8C7EB0A03C4F8743220 -:1000C000C4F86C722EE0D4F87432002FDFF844913B -:1000D000C3EB0A0A02DCC9F86CA223E0C7F59670EC -:1000E000FEF796FE5149FEF79BFF80463846FEF725 -:1000F0008FFE4146FEF7E0FE07465046FEF788FEBB -:10010000414682464FF07E50FEF7CCFD01465046F8 -:10011000FEF7D2FE01463846FEF7C6FDFFF792F81D -:10012000C9F86C02424B18680193FEF76DFE414915 -:100130000746FEF7C1FE8246D4F88002FEF768FE4D -:100140008046D4F88402FEF763FE01464046FEF77F -:1001500067FFD4F888120490FEF7AEFE3946FEF72A -:10016000ABFE4FF07C51D4F86482D5F80C90D4F8F3 -:100170006C720290FEF7A0FE5146FEF79DFE5146BE -:10018000024640460392FEF797FE039A0146104648 -:10019000FEF78AFDD4F86812FEF786FD4946FEF7A1 -:1001A0008BFE82463846FEF733FE494602464FF044 -:1001B0007E500392FEF776FD039A01461046FEF745 -:1001C0007BFE01465046FEF76FFDDDF808C0C4F81F -:1001D0006802814661464046FEF766FD0022C4F88B -:1001E0006402C4F87822C4F87C22C4F88022C4F8DF -:1001F0008422019B80461A60074B1B88002B40F02D -:1002000016810D4B1B68013BC62B17D80149C1F85D -:10021000247119E038010020C427002080E6C5477A -:10022000B1DC423ED048874A000061440000C84229 -:10023000C8270020BD378635A40000204846FFF7B8 -:1002400001F8A54AC2F82401D4F88C02381AFEF746 -:10025000DFFDA249FEF730FE81465846FEF7D4FD89 -:1002600001464846FEF7DCFEFEF7ECFF40F2DC53A9 -:100270009B4A9842A8BF18469042B8BF10460A2130 -:10028000C4F88C72F9F70CF9AD68814629464046EE -:10029000FEF712FE07464846FEF7BAFD294680469D -:1002A0004FF07E50FEF7FEFC01464046FEF704FE8E -:1002B00001463846FEF7F8FCC4F8640202F076F80E -:1002C00005218046F9F7ECF8B4F8702240F23E635D -:1002D00002F21F3292B29A42C4F89002D4F8947299 -:1002E0000AD87D4AB2F8720200F21F3080B29842FA -:1002F0008CBF0020012000E0002000286AD094F884 -:100300009832754D13BBD5F82021D5F824317548A6 -:10031000D31AB3F5FA7FA8BF4FF4FA738342A8BF8C -:1003200018460A21F9F7BCF8D5F89C328022DB7810 -:10033000584390FBF2F3B3F5967FA8BF4FF4967342 -:10034000A2F5D6729342B8BF134601E0664B1B6814 -:10035000D4F89C22C8EB0303517A20205943D57C62 -:1003600091FBF0F1D4F83401B1F5967FA8BF4FF4BA -:10037000967103FB05005D4BB0F5C81FA8BF4FF495 -:10038000C8109842B8BF18464FF40055C4F834015D -:1003900090FBF5F0564DA942ACBF45184519507F6A -:1003A000FEF736FD394680460498FEF77DFC01468F -:1003B0004046FEF781FD4FF06C51FEF77DFDFEF7E4 -:1003C00041FF6FF095039628A8BF96209842B8BFCA -:1003D0001846281A049BC4F83801C4F8943226E061 -:1003E000B3681D0623D5F3F7A9F920E0D4F814214A -:1003F000394BD0061BD53F4AD3F8A01212683C31C6 -:100400008A4214D3C3F8A022D3F8A8723A4A3B4DCB -:10041000C3F8A4223B880B202B61F5F709FA3B882F -:100420006B6104E0B368990301D5FBF718FCD4F8BD -:100430003C31052B03DD284B0022C3F83C21F5F7A6 -:1004400029F92F4B1860B3892BB1D4F8AC22821A4A -:10045000002AC0F2D68618441F4D7379C4F8AC0246 -:10046000059305F53170D4F8B832D4F8B0729847D6 -:1004700005F53170014694F8CA22F4F747FF214B85 -:100480001B88002B00F0B880D5F8CC324FF0000963 -:100490001B7805F534750493C8461A4BB3F800A0D1 -:1004A000194BBAF57A7F03D1002243F809202A615B -:1004B000164A32F9080053F80920024443F809208B -:1004C000FEF7A6FC2A690132012A2A6120D1002305 -:1004D00068602860AB6046E0380100200024744961 -:1004E00024FAFFFF0CFEFFFFD02700200000E7FFEB -:1004F000D4FEFFFF2C200020A4000020000C0140AF -:10050000C0270020CC27002044040020FC0300204A -:10051000D5F800C003926146CDF808C00190FEF7FF -:10052000C1FB039A83461046FEF772FC014658460B -:10053000FEF776FDDDF808C001466046FEF7B4FB25 -:10054000019B02461146686018460392FEF7AAFB1B -:1005500001465846FEF7B0FCA968FEF7A5FB039AD2 -:10056000E8602A60A860684A002302F1540BBAF1DF -:10057000010F28F8023028F80B30DFF89CA12CD1AD -:100580002869012807DD0138FEF742FC0146E868CA -:10059000FEF746FD00E0002002F05EF903460498F5 -:1005A00058B10193FEF734FC019B01461846FEF753 -:1005B0003FFE10B14FF47A731CE0544B4FF47A7243 -:1005C00059F803300A2003F5FA7393FBF2F32BF882 -:1005D00008300F210122F5F747F908F10208B8F1B8 -:1005E000060F09F1040905F114057FF456AFBAF8B6 -:1005F0000030013BAAF800300023454D05F531726B -:1006000005F54671985A595A411A99520233062BE8 -:10061000F3D1D5F8143113F0020300F00583D5F8B7 -:10062000243305F54B70984705F54B70014695F856 -:100630003223F4F76BFEB5F8343305F54B78002B15 -:1006400045D00022D5F838031346314D38F902C0A1 -:10065000B5F8341305F54F7EB1F5C87F04BF00210E -:100660004EF803105EF80310294D61444EF8031054 -:10067000043300210C2B28F80210815202F10202EF -:10068000E3D1B5F83433012B1CD1D5F83C334FF40A -:10069000C872C83393FBF2F30380D5F84033C833F4 -:1006A00093FBF2F34380D5F84433C83393FBF2F263 -:1006B000184B1B88D21A8280A7F85410A7F856103E -:1006C000FBF778F8B4F83433013BA4F83433B3685B -:1006D0005A0740F18480B4F848230D4B322A1DD1CB -:1006E000D3F838231188A3F84A1351889288A3F8C5 -:1006F0004C13A3F84E23B7F85420A3F85023B7F8AF -:100700005620A3F852230BE0FC03002044040020F1 -:100710003801002000000020CC270020002A3CD017 -:100720000021D4F838530A46914838F901E0B0F86E -:10073000483300F55576322B04BF0023B350B05830 -:100740008B4B7044B050043200200C2A28F8010072 -:10075000685201F10201E7D1B3F84823012A17D109 -:1007600083F86123052283F86223B3F84A2383F8D0 -:1007700060032A80B3F84C236A80B3F84E23AA8022 -:10078000B3F85023B3F85233A7F85420A7F85630E3 -:10079000B4F84833013BA4F8483394F86323744B0E -:1007A000EAB1D3F85453D3F838133220002295FB22 -:1007B000F0F583F863230D80D3F8585395FBF0F5DB -:1007C0004D80D3F85C3393FBF0F06A4B1B88C01A62 -:1007D0008880A7F85420A7F85620FAF7EBFFD4F842 -:1007E0003833B4F82C131A8800268A1AA4F82C235C -:1007F000B4F82E135A88B1468A1AA4F82E239B887F -:10080000B4F83023D31AA4F83033F4F743FFD4F804 -:1008100064330546C31A18460493FEF7F5FAD4F874 -:1008200068130690FEF748FBD4F86C83C4F8645351 -:1008300098F800A0079035464F4F785FFEF7E8FA2A -:100840000799FEF739FB09A98851BAF1000F2DD09D -:100850005046FEF7DDFA01464FF07E50FEF7E0FB12 -:100860000246114607F1AC0B4FF07E500392FEF7A3 -:1008700019FA56F80B10FEF71FFB07F168018446C2 -:10088000485FCDF808C0FEF7C3FA039AB83711469F -:10089000FEF712FBDDF808C001466046FEF704FAD9 -:1008A0004BF80600FEF7CEFC785304E007F1B802DF -:1008B0006837E95BA952314F0436EA5F0235062DED -:1008C00002FB0299B8D12B4D4FF0640A2A880AFB2B -:1008D00009F3524393FBF2FAAAF1490A07F108001F -:1008E00009A91FFA8AFAF5F7B5F9BAF13B0FD8F85A -:1008F000046011D9B4F99003FEF78AFAD4F88C6336 -:1009000001463046FEF794FC194F94F84A3100280E -:1009100038D043F0080337E04FF07E513046FEF701 -:10092000C3F901464FF07E50FEF77AFB4FF0000B03 -:100930008246134B304653F81B100193FEF7BCFA66 -:10094000024637F90B000392FEF762FA039A01465A -:100950001046FEF7A9F95146FEF7AEFA019B43F89F -:100960001B000BF1020BBBF1060FE2D1C2E700BF87 -:100970003801002000000020FC030020B404002007 -:10098000BC04002023F008033146D4F8880387F81C -:100990004A3101F0D7FD0746C4F89403D4F8840324 -:1009A000D4F88CB300F10046D4F888030146FEF772 -:1009B00083FA594682465846FEF77EFA014650466B -:1009C000FEF772F901F048FF0146304601F0BAFD2A -:1009D000A6490646C4F898033846FEF76DFA01F0BA -:1009E000E5FCA249A4F870023046FEF765FA01F072 -:1009F000DDFCD4F81431A4F872021B0739D59C48E9 -:100A000009A9F5F727F9D8F808904FF07E51484624 -:100A1000FEF74AF901464FF07E50FEF701FB4FF01A -:100A2000000B8246934D484605F5677353F81B103B -:100A30000193FEF741FA05F5A271024631F90B0068 -:100A40000392FEF7E5F9039A01461046FEF72CF9EA -:100A50005146FEF731FA019B43F81B000BF1020BE4 -:100A6000BBF1060FDED11846F8F780FBA5F8A80306 -:100A700041E0DFF814A209A90AF10400F5F7EAF849 -:100A80006868D5F808B00146FEF716FAD5F80C905C -:100A9000594605465846FEF70FFA01462846FEF726 -:100AA00003F9494605464846FEF706FA0146284638 -:100AB000FEF7FAF801F0D0FE00210546FEF790FBA4 -:100AC000A0B9DAF804002946FEF7AAFA2946CAF8BE -:100AD0000400DAF80800FEF7A3FA2946CAF808006D -:100AE000DAF80C00FEF79CFACAF80C006248F8F736 -:100AF0003DFBA4F8A80361490698FEF7DDF907F16C -:100B00000047814606F10046B4F9A8030C970D96FC -:100B1000FEF77EF95A4900F10040FEF7CDF90E903C -:100B2000B4F97C03FEF774F90F90B4F97E03FEF775 -:100B30006FF91090B4F98003FEF76AF90CA91190CF -:100B40000FA8F5F787F898F801304A4D012B19D115 -:100B50004C4B1B785E070ED4D5F8AC33402093FB8A -:100B6000F0F0181AFEF754F91199FEF79DF8FEF708 -:100B700069FBC5F8AC033F4BD3F8AC03402390FBB3 -:100B8000F3F001E0404B1888FEF742F90146119856 -:100B9000FEF788F8D4F8B41311904846FEF784F8AD -:100BA00001464846FEF73CFAD4F8B05306462946BB -:100BB0001198FEF777F801463046FEF77DF90146B9 -:100BC0002846FEF771F80646C4F8B0030F98D4F82B -:100BD000787201F0EBFBD4F8B8532978F8F760FC91 -:100BE0003844C4F878021098D4F87C7201F0DEFB27 -:100BF0002978F8F755FC3844C4F87C023046D4F81C -:100C0000807201F0D3FB6978F8F74AFC1F4B049D12 -:100C10001A6838442A441A60D4F88432C4F880022E -:100C20000133C4F8843205E0A5F82C33A5F82E333F -:100C3000A5F830330F4DB5F8C432A5F8BC33B5F87C -:100C4000C632A5F8BE33059B012B21D1B5F9C223CD -:100C5000B5F9C83203EB4203032293FBF2F39BB2D4 -:100C6000A5F8C033A5F8C23316E000BF4C3D0F44D1 -:100C7000D40400203801002004000020BD37863550 -:100C800035FA8E3CD527002000000020C827002020 -:100C9000B5F8C832A5F8C033F4F7FCFCC14B012706 -:100CA0001860D5F8C833C5F8C803C31AA5F8C4330B -:100CB000F1F73EFED5F81831BB4E13F4801385F8DA -:100CC000107100F08D80B6F81C31180600F1D48048 -:100CD000B64B1B78590770D596F8CC23B44B12B19C -:100CE00096F8CD233AB10022C5F8D02301221A7418 -:100CF000002285F8CD231B7CD5F8B062032B96F833 -:100D00000090A94F06F1040885F8CC3306D140467F -:100D100007F575714C2201F0DBF844E0012B07D197 -:100D200007F5757041464C2201F0D2F8002302E02D -:100D3000022B02D1012387F82034012384F82134C7 -:100D400084F822340023C4F82434C4F82834994A9F -:100D500094F82034C4F82C8413441B7C964A1E4417 -:100D600084F83134C4F8D023307984F83094FEF715 -:100D70004FF89249FEF754F9C4F83404B07BFEF7FB -:100D800047F88F49FEF74CF9C4F83804307EFEF777 -:100D90003FF88C49FEF790F8C4F83C04FEF778FA67 -:100DA00000233076B373B5F81C3143F08003A5F807 -:100DB0001C31012385F840345EE04FF00008D6F87E -:100DC000D0034146FEF70CFA8146002854D1FAF7C9 -:100DD000F1FC774BC6F8D08386F8CC931F744BE0B8 -:100DE000B6F81CA11AF0800F3BD096F8CC23DFF8A0 -:100DF000C081511E012924D87149D6F83804FEF764 -:100E00005BF8FEF745FAD6F82C7496F831946E49E3 -:100E1000B94489F80A00D6F83C04FEF74DF8FEF70D -:100E200037FA89F814003878FDF7F2FF0146FDF72C -:100E30003BFFFEF72DFABB7AB8703B733B7DBB7569 -:100E400006E0032A04D186F8CC3388F8107004E059 -:100E500098F81030013388F810302AF0800AA5F88D -:100E60001CA1524B1B785A0706D495F840341BB18D -:100E70004D4B012283F8CD23D5F814914A4A19F03D -:100E8000080F524F38D0B2F82E1101F145039BB232 -:100E90008A2B2DD8B2F81C315B0729D5B2F8A803EC -:100EA000B2F8423495F84A61C21A92B293B218B2BB -:100EB000B330BCBF02F5B4739BB21AB2B32AC4BF3D -:100EC000A3F5B4739BB2360797F8EC00364A13D5F6 -:100ED00040B240424343D2F8B0021BB2007B4343CE -:100EE0006FF01D0093FBF0F31944A2F82E1103E0FC -:100EF000B5F8A833A5F8423419F0140F00F0988023 -:100F0000B5F81C21284B02F40272002A00F09080F0 -:100F100093F84A2102F0100202F0FF0052B1B3F838 -:100F20002C1197F92701D3F8382100FB0212A3F8FE -:100F30002C217DE0D3F84424D1789278002947D041 -:100F4000B3F830E1B3F928110FFA8EF6C1EB060CB5 -:100F5000BCF1000FB8BFCCF1000C94450FDD8E4200 -:100F6000C8BF52421FFA8EFEC8BF92B2C3F8340106 -:100F70007244012083F84804A5F8302158E093F822 -:100F800048242AB1D3F8242183F84804C3F8202147 -:100F9000D5F83831D5F84C24194413885288994231 -:100FA0003FE000BFC027002038010020D5270020E7 -:100FB00000000020504501080000A0410000204131 -:100FC00000007A445555553F9A99993F30200020AA -:100FD000B3F92801B3F93061361A86EAE67EAEEB42 -:100FE000E67E96450ADD022296FBF2F6764A166008 -:100FF000012283F8982283F848240AE093F84824D1 -:101000003AB1D3F8242183F89812C3F8202183F849 -:101010004814D5F84C14D5F838210B880244498877 -:101020009A4203DB8A42B4BF13460B46A5F830311F -:10103000D5F8B082654E98F864A1BAF1000F5BD084 -:10104000B6F81C31980757D0D6F88403B6F830218B -:10105000D6F888C30146D6F88CB30492CDF808C000 -:10106000FDF72AFFDDF808C002466146604603929C -:10107000FDF722FF039A01461046FDF715FE59467B -:10108000024658460392FDF717FF039A01461046A1 -:10109000FDF70AFE01F0E0FB01465846FDF7C0FFF0 -:1010A0004B490190FEF7B0F8019BF8B9184601F0E2 -:1010B000F9F9D6F85014FDF7FFFE01F077F9B0F515 -:1010C000617FA8BF4FF46170FDF7A2FE4149FDF7B3 -:1010D000A7FF01F0A9F906465046FDF799FE3146F3 -:1010E000FDF7EAFE01F062F980B200E00020DDF8D1 -:1010F00010B08344A5F830B119F0200F0BD0B5F82B -:101100001C3103F0300333B1304B93F84A31D90727 -:1011100001D5F3F7ABFE304B08F104001E68D5F89B -:10112000541408F15403B7F8F620B047FCF7CCFA92 -:10113000D5F85834002B5AD0244B93F85C34013B3B -:10114000142B4FD8DFE803F00B4E4E27514E4E1FA5 -:101150004E4E4E4E4E2F4E4E4E4E4E272F00D5F831 -:1011600060345B782BB11D4B0020998BF8F7C7FBDF -:101170003DE01B4B1B7803F0040303F0FF00002B42 -:10118000F1D10146F2E7154D0020298BF8F7B7FBA6 -:101190000120698BEAE7114D0020698BF8F7AFFB5E -:1011A0000120A98BE2E70D4D0020298BF8F7A7FB62 -:1011B0000120698BF8F7A3FB0220A98BF8F79FFBAE -:1011C0000320E98BD2E700BFD027002038010020A0 -:1011D0008FC2753CEFB6B0449C0000200000002098 -:1011E000D5270020BB689A0601D5F4F725FDFCF74A -:1011F0001BFAC94B1B7823B9BB681B0301D5FBF74E -:1012000095FAC54BC54D1B78C54E002B40F0D883D1 -:10121000B3685F0540F1D48395F86434002B00F087 -:10122000CF83F8F755F9002800F0CA8395F86534A4 -:10123000002B00F0C583D5F868341B78002B40F0F4 -:101240002E82D5F86C04F4F76BFB002840F027825F -:10125000DFF8E892D5F87024D9F800309A1A7C2A81 -:1012600040F21D82C5F8703495F87434804601331D -:1012700085F8743408F12400A84FC0B2F4F77AFC62 -:1012800007F55F7333F91800FDF7C2FDA54B8246E1 -:101290001888FDF7BDFD01465046FDF7C1FEA24985 -:1012A000FDF70AFEFDF7CEFF08F1010800B2F4F7E2 -:1012B0008DFCB8F1030FDDD13020F4F75BFCB7F9FA -:1012C0009002F4F783FCF4F763FC97F87434980702 -:1012D00030D1D7F8703441F2883293421BD91020B4 -:1012E000F4F748FCD7F86C024FF0640890FBF8F074 -:1012F00000B2F4F76BFC2120F4F73CFCD7F86C3219 -:1013000093FBF8F008FB103888EAE870A0EBE8706F -:1013100000B2F4F75BFC1420F4F72CFCB5F9A80339 -:10132000F4F754FC1C20F4F725FC0020F4F74EFCE5 -:10133000F4F72EFC95F87434784F590740F0898102 -:101340000220F4F717FCD7F884316422323393FB80 -:10135000F2F000B2F4F73AFC0320F4F70BFC734B05 -:101360001B7813F0040F4FF0050304D0B7F93001D8 -:1013700090FBF3F005E0D7F878245289B2FBF3F044 -:1013800000B2F4F723FCB3689A076AD5684F94F863 -:101390007C243B7840F63401B2FBF3F24A432A2125 -:1013A000B2FBF1F2B4F87E14062091FBF3F803FBD4 -:1013B00018184FEA08181FFA88F848EA02281FFA96 -:1013C00088F8C2F3032248EA0208F4F7D3FB0FFAC5 -:1013D00088F0F4F7FBFBB4F87E243B78013292B23C -:1013E00092FBF3F103FB1123A4F87E3494F87C34D0 -:1013F0006E275F43152397FBF3F73A204FF0640AFB -:10140000F4F7B8FBB7FBFAF84046F4F7DFFB3B20F4 -:10141000F4F7B0FB0AFB187080B24FF00A080530F1 -:1014200090FBF8F000B2F4F7D1FB2820F4F7A2FB10 -:10143000D4F8800490FBF8F000B2F4F7C7FB042066 -:10144000F4F798FBD4F878345B8913B1F3F7C0FC58 -:1014500004E0324BD3F8840480F3100000B2F4F7B8 -:10146000B5FBD5F814312D4C9B0640F1868094F8DD -:101470004A319F071AD51120F4F77CFBB4F8880491 -:10148000FDF7FCF822A3D3E90023FDF75DF9002264 -:10149000284BFCF7A7FFFDF769FB00B2F4F796FBBA -:1014A0001920F4F767FB0020F4F790FB95F84A3118 -:1014B000B5F88A4413F0020F08BF00240120F4F7A6 -:1014C00059FB20B2F4F782FB0920F4F753FB00200C -:1014D000F4F77CFB184B95F88C441B88B3F5967F8A -:1014E0000BD90E4A92F8742402F00F02072A04D88E -:1014F00042F20F74A342B8BF1C460520F4F73AFB32 -:10150000D5F890345B7BDBB920B234E0AFF30080D8 -:101510007B14AE47E17A843FD427002038010020B5 -:10152000302000200000002000007A44D527002051 -:10153000980000200000E03FA00000202C200020A8 -:10154000A4F12000FDF79AF8C1A3D3E90023FDF729 -:1015500025FAFDF753FB00210446FDF74BFE10B1C1 -:101560004FF03F4101E04FF07C512046FDF79CFBDE -:10157000FDF768FE00B2F4F729FBD5F814319806A0 -:101580000ED4B54B0021D3F890446068FDF728FED7 -:1015900000285CD1A0680021FDF722FE002856D16A -:1015A00095F84A21AC4B910703D493F89424012A6F -:1015B00007D10123D5F89874D5F89C4485F8943464 -:1015C0000FE0D3F89044A5496068FDF775FCFDF77E -:1015D00039FEA2490746A068FDF76EFCFDF732FE12 -:1015E00004460FA93846F7F79BFF1320F4F7C2FA19 -:1015F000BDF93C00F4F7EAFA1B20F4F7BBFABDF999 -:101600003E00F4F7E3FA2320F4F7B4FA002FACBF5E -:101610004E205320F4F7DAFA0FA92046F7F780FF9F -:101620001220F4F7A7FABDF93C00F4F7CFFA1A201C -:10163000F4F7A0FABDF93E00F4F7C8FA2220F4F757 -:1016400099FA002CACBF45205720F4F7BFFAF4F705 -:101650009FFA95F87434282B21D17F4B0022D9F8BA -:10166000004083F874244FF47A73B4FBF3F8172026 -:101670003C24F4F77FFAB8FBF4F7B7FBF4F004FB73 -:101680001070000200B2F4F7A1FA1820F4F772FA11 -:1016900004FB178000B2F4F799FAF4F779FAD5F859 -:1016A00068341B78012B01D1F6F739FFD5F868347F -:1016B000694C1B78022B1BD1D4F8A034C3B1C4F8F9 -:1016C000A4341B68664AC4F8A834D4F8AC34134474 -:1016D000987CF8F7D3F9D4F8A4349879F4F737F96B -:1016E000D4F8AC340133092B88BF0023C4F8AC34E0 -:1016F000F7F740FF002800F0638195F8B034013B14 -:10170000012B00F25D81D5F8B404F4F709F9524CCD -:10171000544FD8B1D4F8B404F4F7FDF894F8B824D1 -:101720003B687E2A0FD102221B2884F8B024C4F81B -:10173000BC3405D00D2803D0342801D0672802D14D -:10174000012385F8C03485F8B804DCE73B68D4F899 -:10175000BC2441F658319A1A8A4203D9032384F8EB -:10176000B0342DE1D4F8C4249B1A042B40F2288114 -:1017700094F8C034002B00F0238194F8C8243A4B2D -:1017800033F8120018B984F8C8044FF4036095F8D0 -:10179000C834B0F5C06F03F10103DBB22E4C85F8FD -:1017A000C83450D01CD8B0F5007F46D009D8B0F569 -:1017B000807F45D0B0F5887F40F00281D4F8901248 -:1017C000F9E0B0F5806F7ED0B0F5826F00F0C38095 -:1017D000B0F5047F40F0F48094F87C345321E9E0C4 -:1017E000B0F5006F42D00CD8B0F5E26F62D0B0F522 -:1017F000E46F65D0B0F5E06F40F0E280B4F97C139F -:101800005AE0B0F5036F07D0B0F5046F4ED0B0F5D5 -:10181000026F40F0D580C1E0D4F814319A0640F14F -:10182000CF8094F84A319B0740F1CA80B4F88834DD -:1018300024215943642312313FE0D4F88014BAE0E4 -:10184000D4F86C12B7E0D4F88414B4E0AFF300809D -:10185000CDCCCCCCCCCCFC3F380100208096184BB2 -:10186000504501082C20002074610108D4F814218F -:10187000970640F1A58094F84A21900740F1A08096 -:10188000D90709D5D4F89C140029BCBF494241F0BE -:10189000804141F0004106E0D4F898140029BCBF13 -:1018A000494241F080414FF400606BE0B4F9A83345 -:1018B00064217FE0B4F97E132C2391FBF3F17AE0ED -:1018C000B4F98013F8E794F8C93442F21071013387 -:1018D000DBB2032B84F8C93484BF012384F8C934F4 -:1018E00095F8C9345943AE4B1B78DA0748BF01312C -:1018F0009F0748BF02315C07B5F81C3148BF04316F -:10190000D80748BF0A319A0748BF14311F0648BF9D -:101910002831DC0548BF2831580748BF64311A0711 -:1019200048BFC8319F0548BF01F5C8719C0648BF34 -:1019300001F57A71D80648BF01F5FA615A0648BF29 -:1019400001F57A614FF48060F3F7F8F9954B0022C6 -:1019500083F8C02434E0D4F8141111F0200717D014 -:1019600094F84A3113F0020F0CBF00214FF47A7142 -:1019700013F0010F0CBF00234FF4FA63194495F8DC -:101980008C341944F3F7DAF9002385F8C03417E0F2 -:101990003946F3F7D3F984F8C07411E0D4F8143160 -:1019A0009B060DD594F84A319F0709D5B4F88A34BF -:1019B0004FF47A715943F3F7C1F9002384F8C03426 -:1019C000B368DC037EF551A895F8CA34754C002B3A -:1019D0003EF44BA8744B1B78002B7EF446A8F3F71B -:1019E00059FED4F8CC340746C31A6FEA0308D4F87A -:1019F000D0344FEAD878C31A6FEA030AD4F8D43443 -:101A00004FEADA7AC3EB00096FEA09094FEAD9799C -:101A1000B9F1000F06D1BAF1000F03D1B8F1000FF0 -:101A20003EF423A84FF0000B95F85C355FFA8BF479 -:101A30009C42DFF870C147D25C49DCF8D834A20080 -:101A4000096813446244C2F8DC145988C8050BD4F1 -:101A50008B0536D5524B1B785C0754BF544B554B06 -:101A60001B68C2F8DC342CE01946534A2046019327 -:101A7000CDF808C0FBF762FADDF808C0019BBCF89E -:101A80001C2112F0400F03D0204619464B4A16E0A5 -:101A9000500703D520461946494A10E0110703D5DF -:101AA00020461946474A0AE0900703D520461946C2 -:101AB000454A04E0D10704D5444A20461946FBF7BD -:101AC0003DFA0BF1010BAFE79C000023A3421FD0AE -:101AD000D5F8D82433491A445288520516D501F254 -:101AE000DC42D0580890B1F964057821A0F57A70ED -:101AF00048434FF47A7190FBF1F000F22B1040F262 -:101B0000671190FBF1FE01FB1E0199520433DDE7E2 -:101B1000B9F1000F2BD007F5C333A033C5F8D43487 -:101B200095F882351F4C13BB84F88335B3689E0744 -:101B300005D5F3F7A3FC10B1012384F88335D5F85C -:101B40008435184C1B689B68984728B194F88335F6 -:101B500043F0020384F88335114B1B7813F0050F13 -:101B600005D195F8833543F0040385F8833595F85E -:101B7000832522B90B4B93F88235002B66D095F85C -:101B8000821511F0010FA1F10C0033D103291FD8E8 -:101B9000064B074C12F0040F18BF234619E000BF94 -:101BA000D527002038010020CE27002070610108D1 -:101BB000504501085C4501086C4501087245010863 -:101BC000784501087E450108844501088A450108D9 -:101BD000B84B0439072904D8B74912F0010F18BFD0 -:101BE0000B46C0B2032810D8B44912F0020F18BF38 -:101BF0000B460AE0C0B2032806D8AE4BB04912F03B -:101C0000020F18BF0B4600E0AA4B002195F85C05B7 -:101C1000CCB2A042AB4E0CD9D6F8D804A4002044D4 -:101C20004088000603D518683444C4F8DC04013148 -:101C3000ECE7B9F1000F13D05AB195F88225A14B0A -:101C40000132D2B2142A09D1002207E0B9F1000F03 -:101C500006D095F88235002BEFD101E083F882257C -:101C6000BAF1000F23D0B5F92C31B5F92A21322170 -:101C7000002AB8BF5242002BB8BF5B4293FBF1F37E -:101C800092FBF1F1DBB2C9B28B4238BF0B468E4AF0 -:101C90000BB192FBF3F23A44C5F8D02495F88825AD -:101CA000884B0AB9012200E0002283F8882595F8C4 -:101CB0008825844B22B9854AC3F88C25002009E089 -:101CC0007C4AF9E7D3F8D81494000E197688760682 -:101CD00007D4013095F85C15C2B29142794BF1D826 -:101CE00099E0B3F92A61192E21DD11F822E093F869 -:101CF00090C50EF00F09E145D3F88C6508DC93F828 -:101D000091C5BCEB1E1F03DC23443468C3F8DC44DC -:101D100011F8224095F892E504F00F0CF445694B58 -:101D20002DDB93F891E5BEEB141F28DC22E0193679 -:101D300025DA11F822E093F890C50EF00F09E1457D -:101D4000D3F88C6508DC93F893C5BCEB1E1F03DB4E -:101D500023443468C3F8DC4411F8224095F892E536 -:101D600004F00F0CF445574B09DB93F893E5BEEBF9 -:101D7000141F04DB346803EB8203C3F8DC44B5F9B9 -:101D80002C41504B192C1BDD11F822E093F8906583 -:101D90000EF00F0CB445D3F88C450ADC93F891C5CE -:101DA000BCEB1E1F05DCD4F800E003EB8203C3F894 -:101DB000DCE411F8223003F00F01B1421EDD88E7A8 -:101DC000193486DA11F822E093F892650EF00F0CC0 -:101DD000B445D3F88C450ADB93F891C5BCEB1E1FC4 -:101DE00005DCD4F800E003EB8203C3F8DCE411F86F -:101DF000223003F00F01B142FFF66BAF95F8931557 -:101E0000B1EB131FFFF665AF2E4B03EB8202236885 -:101E1000C2F8DC345DE7B8F1000F1CD093F89525CB -:101E200093F8941507F543478818013890FBF2F4AE -:101E300002FB140083F89715013183F8960591FB96 -:101E4000F2F002FB10125037D2B2C3F8CC7483F810 -:101E5000982583F89425F2F721FEFDF706BECB0600 -:101E60007EF5EDAAD4F81821164B910207D4B3F8E9 -:101E70001C2122F40072A3F81C21FEF7E0BAB3F88B -:101E80001C1101F4007292B2002A7EF4D8AA41F427 -:101E90000071A3F81C11D3F82411C3F83421C3F83E -:101EA0002011B3F83011C3F83821A3F82811FEF738 -:101EB000C6BA00BF706101085445010858450108C1 -:101EC0005C45010838010020400D030090450108E1 -:101ED00010B50023934203D0CC5CC4540133F9E71E -:101EE00010BD02440346934202D003F8011BFAE7F7 -:101EF000704700000D4B70B51D680022845C2B19E3 -:101F00005B7803F00303012B8B5C08BF2034EE18D1 -:101F1000767806F00306012E08BF2033E41A02D1BA -:101F20000132002BEAD1204670BD00BFCC0000205A -:101F300010B50446224613780134002BFAD1CC5C4C -:101F4000D4540133002CFAD110BDC9B2024610F8A6 -:101F5000013B1BB18B42F9D1104670470029FBD0E1 -:101F600018467047034613F8012B002AFBD1181AB4 -:101F7000013870470F4BF0B51E680023934215D00F -:101F8000C55C7419647804F00304012CCC5C08BFB0 -:101F9000203537197F7807F00307012F08BF203459 -:101FA0002D1B04D10133002CE8D100E00025284688 -:101FB000F0BD00BFCC00002010B5034632B111F8CF -:101FC000014B013A03F8014B002CF7D11A4493421C -:101FD00003D0002103F8011BF9E710BD30B50378E9 -:101FE0000BB1044604E00B78002B18BF002030BD75 -:101FF00022461078013438B10023C85C28B1D55C82 -:102000008542F5D10133F8E730BD104630BD0021DF -:102010000A2200F001B92DE9F04E82468B461F4698 -:10202000144612B90020BDE8F08E002BFAD000262D -:10203000A642F7D2A5196D0807FB05B950464946D7 -:10204000089B9847002802DB03D06E1C25462C46CF -:10205000EEE74846BDE8F08E174B2DE9F0411D68CC -:102060000646AC6D0F46FCB9502000F0E3F8A865B9 -:102070008460AB6D046044601C61DC60AB6D9C618E -:102080005C61AB6DDC629C62AB6D5C631C63AB6DD1 -:10209000DC639C63AB6D5C641C64AB6DDC649C6452 -:1020A000AB6D1C77AB6D5C6230463946AA6D01237F -:1020B000BDE8F04100F002B830010020F0B508B9E9 -:1020C000106828B3044614F8015B0F4617F8016B3B -:1020D0003EB1B542FAD10BB12046F3E7146003706C -:1020E000F0BD4DB915602846F0BD17F8016BAE4242 -:1020F00007D0002EF9D11C46234613F8015B0F468A -:10210000F3E715B10021217000E02B461360F0BD0C -:10211000F0BD000084463F482DE9F04FD0F8008024 -:102120000E46344614F8015B08EB0500407800F0D9 -:10213000080000F0FF0708B12646F2E72D2D03D175 -:10214000B41C7578012703E02B2D04BF7578B41CEF -:1021500033F010000DD1302D08D1207800F0DF00D1 -:10216000582851D165781023023402E0002B08BFB3 -:102170000A23002F0CBF6FF0004A4FF0004ABAFB51 -:10218000F3F903FB19AA0026304608EB050B9BF870 -:1021900001B01BF0040F01D0303D0BE01BF0030B2E -:1021A0001BD0BBF1010F14BF4FF0570B4FF0370B93 -:1021B000CBEB05059D4210DAB6F1FF3F0AD048454A -:1021C00006D801D1554503DC03FB0050012601E090 -:1021D0004FF0FF3614F8015BD7E7731C0CD1002FCA -:1021E0004FF022030CBF6FF000404FF00040CCF8DE -:1021F00000302AB9BDE8F08F07B1404242B106B1C4 -:10220000611E1160BDE8F08F002B08BF0823B0E706 -:10221000BDE8F08FCC00002030B51346044A0546D7 -:102220000C46106829462246BDE83040FFF772BFD1 -:1022300030010020024B0146186800F003B800BFCF -:102240003001002070B5CD1C25F0030508350C2D9C -:1022500038BF0C25002D06463FDB8D423DD3214B78 -:102260001C6818462146A1B10B685B1B0ED40B2BD2 -:1022700003D90B60CC18CD501FE08C4202D16268AC -:1022800002601AE04B6863600C4616E00C46496831 -:10229000E9E7154C23681BB9304600F027F82060A9 -:1022A0002946304600F022F8431C014615D0C41CD4 -:1022B00024F0030484420AD1256004F10B00231D9D -:1022C00020F00700C31A0BD05A42E25070BD3046CE -:1022D000611A00F00BF80130EED10C2333600020BE -:1022E00070BD00BFE8270020E427002038B5064C69 -:1022F000002305460846236000F008F8431C02D17D -:10230000236803B12B6038BDF0270020094A136809 -:1023100063B118446946884202D810601846704775 -:10232000054B0C221A604FF0FF307047034B1360CF -:10233000EFE700BFEC270020F0270020F427002063 -:1023400000B5194A20F00043934283B0014617DDDF -:10235000B3F1FF4F04DBFCF7A5FC03B05DF804FB11 -:10236000694601F03BF800F00302012A0098019948 -:1023700011D0022A0AD09AB1012201F0F3FDECE754 -:10238000002101F0F3F903B05DF804FB01F0EEF970 -:1023900000F10040E1E701F0E5FD00F10040DCE77D -:1023A00001F0E4F9D9E700BFD80F493F30B5C0F3D9 -:1023B000C754A4F17F031E2B83B0014620DC581CB8 -:1023C0001BDB162B4FEAD17509DDC1F3160040F473 -:1023D0000000963CA04005B1404203B030BD114B17 -:1023E00053F825402046FCF75FFC019001982146F8 -:1023F000FCF758FC20F0004333B9002003B030BD97 -:10240000FCF720FF03B030BDC0F31604C0F3C75083 -:1024100044F40004C0F1960024FA00F0002DDCD052 -:10242000DAE700BF807B010800B51D4A20F00043B9 -:10243000934283B0014618DDB3F1FF4F04DBFCF794 -:1024400031FC03B05DF804FB694600F0C7FF00F003 -:102450000300012818D002280ED0D0B100980199AD -:1024600001F084F900F10040EBE70021002201F0C7 -:1024700079FD03B05DF804FB00980199012201F099 -:1024800071FD00F10040DCE70098019901F06EF960 -:10249000D7E700980199012201F064FDD1E700BF60 -:1024A000D80F493F70B58AB0054600F023FA224C98 -:1024B000064694F90030013303D0284601F0C4FFEA -:1024C00010B930460AB070BD284601F06BFF4FF0DE -:1024D0007E51FCF7ADFE0028F3D0184901220023FD -:1024E0002846009208930191FCF7DAF802460B4661 -:1024F0001348CDE90423CDE9022301F0ABFD94F9A3 -:102500000030CDE90601022B0BD0684601F0A0FD9A -:1025100038B1089B53B9DDE90601FCF76FFB0AB03F -:1025200070BD02F00FF821230360F2E702F00AF811 -:10253000089B0360EFE700BF34010020887B01089F -:10254000947B010800F03EBB2DE9F0418AB00746BC -:102550000C4600F0C7FB9B4E054696F90030013350 -:1025600003D0204601F070FF18B928460AB0BDE834 -:10257000F081384601F068FF8046002832D12046BD -:102580000021FCF72DFE0028EFD08F4A01233846AA -:1025900001920093CDF82080FCF782F8CDE902018A -:1025A0002046FCF77DF8894B96F900400022CDE9E2 -:1025B0000623631CCDE904010DD0022C0BD0684624 -:1025C00001F046FD002800F09A80089B1BB101F045 -:1025D000B9FF089B0360DDE90601FCF70FFB0AB0B9 -:1025E000BDE8F08138460021FCF7FAFD18B320461B -:1025F0000021FCF7F5FD8046002855D072490122E4 -:1026000000233846009208930191FCF749F8CDE980 -:1026100002012046FCF744F896F90040002200230E -:10262000CDE90401CDE90623002CC8D0674B002278 -:10263000CDE90623CFE7284601F0B8FE8046002802 -:1026400062D028460021FCF7CBFD00288DD038460B -:1026500001F0ACFE002888D0204601F0A7FE00283B -:1026600083D05949042200233846009208930191EF -:10267000FCF716F8CDE902012046FCF711F896F9AF -:10268000004000220023022CCDE90401CDE90623FD -:1026900000F08880684601F0DBFC002800F08280B2 -:1026A000089B002B97D092E7204601F07FFE002880 -:1026B0003FF45BAF20460021FCF79CFD00283FF46F -:1026C00054AF414A0123384601920093CDF820804F -:1026D000FBF7E6FFCDE902012046FBF7E1FF347886 -:1026E000CDE904010022002C30D0394B022CCDE979 -:1026F00006232ED101F026FF21230360D0E701F04D -:1027000021FF2123036060E7384601F04FFE0028D7 -:1027100097D0204601F04AFE002892D0284601F0CA -:1027200093FE0346D8B928490122384608930092FF -:102730000191FBF7B5FFCDE902012046FBF7B0FFA1 -:102740003478CDE90401002C31D100220023CDE9F9 -:102750000623684601F07CFC0028A1D1CAE71A4A8A -:102760000323384600930192CDF82080FBF798FFB1 -:10277000CDE902012046FBF793FF96F90030CDE941 -:102780000401384643BB134B4FF060420021CDE9B2 -:102790000623FCF72FFD00283FD196F90030022BCD -:1027A0007FF478AF01F0CEFE2223036078E70020AB -:1027B000002102460B46FCF7F1F8022CCDE9060198 -:1027C00098D0C6E734010020907B01080000F03F5C -:1027D0000000F0FFFFFFEF471C4B00220021CDE976 -:1027E0000623FCF707FD0028D7D020464FF07C5188 -:1027F000FCF762FBFBF754FF04460D4601F030FC8A -:1028000002460B4620462946FDF79EF80028C4D113 -:102810000F4B0022CDE90623BFE720464FF07C5145 -:10282000FCF74AFBFBF73CFF04460D4601F018FCA1 -:1028300002460B4620462946FDF786F80028ACD113 -:10284000044B4FF06042CDE90623A6E70000F07F7D -:102850000000F0FFFFFFEFC770B58AB0054600F03B -:1028600031FF224C064694F90030013308D0284647 -:1028700001F0EAFD20B128460021FCF7BBFC10B9AD -:1028800030460AB070BD1A49012200232846019142 -:1028900000920893FBF704FF2478CDE90401CDE909 -:1028A00002017CB900220023CDE90623684601F02D -:1028B000CFFB88B1089BA3B9DDE90601FCF79EF9BF -:1028C0000AB070BD0020002102460B46FCF766F8F6 -:1028D000022CCDE90601E9D101F034FE2123036089 -:1028E000E8E701F02FFE089B0360E5E734010020D4 -:1028F000987B0108F8B520F00043B3F17E5F0446F1 -:1029000010D008DCB3F17C5F11DAB3F10C5F00F397 -:1029100084809D48F8BD0146FCF7C4F90146FCF7E8 -:102920007FFBF8BD002840F3CD800020F8BD0028D3 -:10293000C0F2CA8001464FF07E50FCF7B3F94FF069 -:102940007C51FCF7B9FA044600F0BCFE8F490646FC -:102950002046FCF7B1FA8E49FCF7A6F92146FCF7B0 -:10296000ABFA8C49FCF79EF92146FCF7A5FA8A4997 -:10297000FCF79AF92146FCF79FFA8849FCF792F98F -:102980002146FCF799FA8649FCF78EF92146FCF7B7 -:1029900093FA844905462046FCF78EFA8249FCF7F3 -:1029A00081F92146FCF788FA8049FCF77DF9214638 -:1029B000FCF782FA7E49FCF775F92146FCF77CFAB0 -:1029C0004FF07E51FCF770F901462846FCF728FBD2 -:1029D0003146FCF771FA26F47F6525F00F050746AE -:1029E00029462846FCF768FA01462046FCF75AF9C2 -:1029F000294604463046FCF757F901462046FCF7C5 -:102A00000FFB01463846FCF74FF901462846FCF714 -:102A10004BF90146FCF748F9F8BD0146FCF74CFAC2 -:102A20005A490546FCF748FA5949FCF73DF9294649 -:102A3000FCF742FA5749FCF735F92946FCF73CFA0E -:102A40005549FCF731F92946FCF736FA5349FCF7AA -:102A500029F92946FCF730FA5149FCF725F92946AE -:102A6000FCF72AFA4F4906462846FCF725FA4E4954 -:102A7000FCF718F92946FCF71FFA4C49FCF714F942 -:102A80002946FCF719FA4A49FCF70CF92946FCF7E4 -:102A900013FA4FF07E51FCF707F901463046FCF778 -:102AA000BFFA01462046FCF707FA01464148FCF709 -:102AB000F9F801462046FCF7F5F801463E48FCF7D8 -:102AC000F1F8F8BD3D48F8BD4FF07E51FCF7ECF849 -:102AD0004FF07C51FCF7F0F92C490446FCF7ECF977 -:102AE0002B49FCF7E1F82146FCF7E6F92949FCF708 -:102AF000D9F82146FCF7E0F92749FCF7D5F821463B -:102B0000FCF7DAF92549FCF7CDF82146FCF7D4F9B2 -:102B10002349FCF7C9F82146FCF7CEF906462046C2 -:102B200000F0D0FD1F4905462046FCF7C5F91E49B7 -:102B3000FCF7B8F82146FCF7BFF91C49FCF7B4F8DC -:102B40002146FCF7B9F91A49FCF7ACF82146FCF725 -:102B5000B3F94FF07E51FCF7A7F801463046FCF779 -:102B60005FFA2946FCF7A8F91249FCF79BF80146E1 -:102B70002846FCF799F80146FCF796F801461048FC -:102B8000FCF790F8F8BD00BFDB0FC93F08EF113824 -:102B9000047F4F3A4611243DA80A4E3E90B0A63E0F -:102BA000ABAA2A3E2EC69D3D6133303F2D570140D2 -:102BB00039D119406821A233DA0FC93FDB0F4940F0 -:102BC000DA0F494021F00042B2F1FF4FF8B5044658 -:102BD00014DC20F00045B5F1FF4F06460EDCB1F1E4 -:102BE0007E5F3AD08F1707F0020747EAD07755B9D2 -:102BF000022F2FD0032F2FD13148F8BD0846214690 -:102C0000FCF752F8F8BDFAB1B2F1FF4F29D0B5F197 -:102C1000FF4F19D0AA1AD2153C2A19DC002938DB3B -:102C20002046FCF7FDF901F0BDFB01F0A5FA012FEC -:102C30002CD0022F22D0002F2FD02249FCF734F8BD -:102C40002149FCF72FF8F8BD002E15DB1F48F8BD11 -:102C50001E48ECE71C48F8BDF8BDBDE8F84001F09F -:102C60008BBAB5F1FF4F19D0022FF3D0032FC3D089 -:102C7000012F1BD00020F8BD1548F8BD1149FCF705 -:102C800013F801461048FCF70DF8F8BD00F10040BC -:102C9000F8BD3C32C4DA0020C9E7F8BD022F0CD0E1 -:102CA000032F08D0012F04D00A48F8BD4FF0004090 -:102CB000F8BD0948F8BD0948F8BD0948F8BD00BF8E -:102CC000DB0F49C02EBDBB33DB0F4940DB0FC93FD3 -:102CD000DB0FC9BFDB0F493FDB0F49BFE4CB16C099 -:102CE000E4CB16402DE9F04F31F0004987B00D4696 -:102CF0000C46074611D020F0004ABAF1FF4F80463B -:102D000005DD514807B0BDE8F04F01F0B7BBB9F1A0 -:102D1000FF4F07DDBAF17E5FF3D14FF07E5007B071 -:102D2000BDE8F08F002840DB0026B9F1FF4F34D01A -:102D3000B9F17E5F4CD0B4F1804F384655D0B4F134 -:102D40007C5F1BD001F02EFB0146BAF1000F1DD0B5 -:102D500028F04043B3F17E5F18D04FEAD87808F1ED -:102D6000FF3856EA080166D0B9F19A4F74DD374B47 -:102D70009A4533DC002C37DB0020D0E7B8F1000F98 -:102D8000E0DB07B0BDE8F04F00F09CBC002C41DB5D -:102D9000B8F1000F32DB0846C1E7BAF17E5FBCD064 -:102DA00027DD002CE8DB2846B9E7B9F1974F13DAA5 -:102DB000B9F17E5F0ADB4FEAE953C3F1960349FAA2 -:102DC00003F202FA03F34B4500F044820026AFE71A -:102DD000002C25DB3846A2E70226A6E71C4B9A45C5 -:102DE00040F39D82002CC7DD1A480146FCF764F8C9 -:102DF00095E7002CC0DA05F1004090E7AAF17E5A71 -:102E000056EA0A0A12D10846FBF74CFF0146FCF7C6 -:102E100007F984E74FF07E50FCF702F90146B7E767 -:102E200039464FF07E50FCF7FBF878E7012EB2D11F -:102E300001F1004073E739463846FBF733FF01469E -:102E4000FCF7EEF86BE700BF947B0108F7FF7F3FCC -:102E50000700803FCAF24971BAF5000F80F2028282 -:102E60004FF09741FCF728F86FF017028246B34BFA -:102E70004FEAEA51CAF3160A7F399A4501EB020C70 -:102E80004AF07E5740F3EB81AD4B9A4540F34282C6 -:102E900000220CF1010CA7F5000705920599A94B3A -:102EA000384653F82130CDF804C0194603920493F4 -:102EB000FBF7F8FE049981463846FBF7F5FE01461C -:102EC0004FF07E50FCF7ACF8034619464846029393 -:102ED000FBF7F2FF7910039A41F00051BB4601F570 -:102EE000802120F47F6727F00F070A4482461146AD -:102EF00038460392FBF7E0FF01464846FBF7D2FE57 -:102F0000039A814604991046FBF7CCFE01465846C9 -:102F1000FBF7C8FE01463846FBF7CEFF01464846A0 -:102F2000FBF7C0FE029B1946FBF7C6FF51468346DE -:102F30005046FBF7C1FF01468146FBF7BDFF8249C2 -:102F4000034648460293FBF7B7FF8049FBF7ACFE08 -:102F50004946FBF7B1FF7E49FBF7A6FE4946FBF762 -:102F6000ABFF7C49FBF7A0FE4946FBF7A5FF7A497A -:102F7000FBF79AFE4946FBF79FFF7849FBF794FE63 -:102F8000029B01461846FBF797FF3946814650469B -:102F9000FBF78AFE5946FBF78FFF4946FBF784FE95 -:102FA000394604903846FBF787FF6D490390FBF7DD -:102FB0007BFE0499FBF778FE20F47F6929F00F0966 -:102FC00049463846FBF778FF494607465846FBF71F -:102FD00073FF634983464846FBF764FE039A114634 -:102FE000FBF760FE01460498FBF75CFE5146FBF7D9 -:102FF00063FF01465846FBF757FE8346594638465D -:10300000FBF752FE20F47F6A2AF00F0A504655491A -:10301000FBF752FF544981465046FBF74DFF3946B6 -:10302000034650460293FBF73DFE01465846FBF728 -:1030300039FE4E49FBF740FF029B01461846FBF75D -:1030400033FE4B4B059A53F82210FBF72DFEDDF8AB -:1030500004C007466046FBF7DBFE464B059A04902A -:1030600053F822B039464846FBF71EFE5946FBF797 -:103070001BFE0499FBF718FE20F47F6A2AF00F0A62 -:1030800004995046FBF70EFE5946FBF70BFE4946E6 -:10309000FBF708FE01463846FBF704FE24F47F6484 -:1030A00024F00F04013E56EA0806814621462846D0 -:1030B0000CBF314F4FF07E57FBF7F4FD5146FBF745 -:1030C000FBFE494606462846FBF7F6FE014630461B -:1030D000FBF7EAFD214606465046FBF7EDFE0546A6 -:1030E00001463046FBF7E0FD00288146044620F00B -:1030F0000048AA4640F3F880B8F1864F00F3C2803A -:1031000000F0B280B8F17C5F00F3C4804FF000099A -:10311000C84624F47F6424F00F0420461749FBF7C7 -:10312000CBFE514605462046FBF7BCFD0146304626 -:10313000FBF7B8FD1249FBF7BFFE23E071C41C008A -:10314000D6B35D00B07B010842F1533E55326C3E70 -:1031500005A38B3EABAAAA3EB76DDB3E9A99193FF9 -:10316000000040400038763FA0C39D364F38763F80 -:10317000A87B0108A07B0108000080BF0072313FDE -:103180001872313F864906462046FBF795FE0146F8 -:103190003046FBF789FD064631462846FBF784FD9D -:1031A00029460446FBF77EFD01463046FBF77AFDD3 -:1031B000214606462046FBF77FFE7A490546FBF787 -:1031C0007BFE7949FBF76EFD2946FBF775FE7749D3 -:1031D000FBF76AFD2946FBF76FFE7549FBF762FDB9 -:1031E0002946FBF769FE7349FBF75EFD2946FBF7AD -:1031F00063FE01462046FBF755FD0546294620465D -:10320000FBF75AFE4FF0804182462846FBF74AFD05 -:1032100001465046FBF704FF314605462046FBF7C2 -:103220004BFE3146FBF740FD01462846FBF73AFDD1 -:103230002146FBF737FD01464FF07E50FBF732FD8C -:103240008144B9F5000FC0F2A58049463846FBF726 -:1032500033FE64E502F00102C2F1020668E50022D5 -:1032600005921BE6002202E653493046FBF71CFD9F -:10327000294682464846FBF715FD01465046FBF7B6 -:10328000D7FF38B138464D49FBF716FE4B49FBF7DF -:1032900013FE44E54FEAE858A8F17E084FF4000316 -:1032A00043FA08F32344C3F3C7524548C3F316084F -:1032B000A2F17F0140FA01F1C2F1960248F4000840 -:1032C00048FA02F8002C23EA01012846B8BFC8F1E9 -:1032D0000008FBF7E7FC824651463046FBF7E4FC6A -:1032E0004FEAC859044614E7364B98450ADC7FF488 -:1032F00009AF2946FBF7D6FC01463046FBF784FFB1 -:103300000028C7D038463049FBF7D6FD2E49FBF7D9 -:10331000D3FD04E501234FF400120593BEE54FF001 -:103320007E51FBF7BFFC29490746FBF7C5FD28493D -:1033300081463846FBF7C0FD394682463846FBF7E2 -:10334000BBFD4FF07A5183463846FBF7B5FD014689 -:103350002048FBF7A7FC3946FBF7AEFD01464FF0CE -:103360007C50FBF79FFC01465846FBF7A5FD1A4928 -:10337000FBF7A2FD01465046FBF794FC0746394691 -:103380004846FBF791FC20F47F6A2AF00F0A494671 -:1033900050467DE6414601F075F8014656E700BF0C -:1033A0008CBEBF354CBB31330EEADD3555B38A38A0 -:1033B000610B363BABAA2A3E3CAA3833CAF24971AC -:1033C000FFFF7F00000016436042A20D00AAB83F35 -:1033D00070A5EC36ABAAAA3E3BAAB83F2DE9F04F48 -:1033E000AB4A20F00044944289B006460D4664DDA5 -:1033F000A84A94421CDC0028A74940F3EC80FBF764 -:1034000051FCA64B24F00F049C42064664D0A4490C -:10341000FBF748FC014628603046FBF743FCA04917 -:10342000FBF740FC01236860184609B0BDE8F08F47 -:103430009C4A944262DDB4F1FF4F46DAE715863FBD -:10344000A4EBC7542046FBF7FDFEFBF7E1FC034667 -:10345000014620460593FBF725FC4FF08741FBF71B -:103460002BFD8046FBF7EEFEFBF7D2FC014604463F -:1034700040460694FBF716FC4FF08741FBF71CFD16 -:1034800000210790FBF7ACFE002800F0C580204625 -:103490000021FBF7A5FE002814BF01230223824868 -:1034A0000221019000913A4605A8294600F022FA2F -:1034B000002EC0F2A780034603E00022286000230C -:1034C0004A60184609B0BDE8F08F0146FBF7EAFBF9 -:1034D000002368602860F4E77449FBF7E3FB744954 -:1034E0000446FBF7DFFB014628602046FBF7DAFBCA -:1034F0006F49FBF7D7FB01236860E2E700F052FF5A -:103500006C490746FBF7D8FC4FF07C51FBF7CCFB2E -:10351000FBF798FE8246FBF77BFC5F498346FBF78F -:10352000CBFC01463846FBF7BDFB5D49804658465B -:10353000FBF7C2FCBAF11F0F81464946404618DC32 -:103540005D4B0AF1FF3253F8223024F0FF029A4219 -:103550000FD0FBF7A7FB07462F6039464046FBF725 -:10356000A1FB4946FBF79EFB002E686056DB5346E5 -:10357000A7E7FBF797FBE315C0F3C7529A1A082A8F -:103580000746E9DD494958460393FBF795FC074692 -:1035900039464046FBF786FB044621464046FBF78A -:1035A00081FB3946FBF77EFB414907465846FBF74E -:1035B00083FC3946FBF776FB814649462046FBF7FC -:1035C00071FB039BC0F3C7529B1A192B074641DCC2 -:1035D0002860A046C1E7FBF767FB304B24F00F04DF -:1035E0009C42064623D02E49FBF75EFB014628602D -:1035F0003046FBF757FB2A49FBF756FB4FF0FF33EA -:1036000068605EE795E80C0003F1004102F10042BA -:1036100043422A60696054E7032340E707F100470B -:1036200000F100402F606860CAF1000349E71F49BC -:10363000FBF73AFB1E490446FBF736FB01462860C0 -:103640002046FBF72FFB1A49FBF72EFB4FF0FF3309 -:10365000686036E719495846FBF72EFC074639469D -:103660002046FBF71FFB804641462046FBF71AFB2E -:103670003946FBF717FB124904465846FBF71CFC7A -:103680002146FBF70FFB81464946404661E700BFF4 -:10369000D80F493FE3CB1640800FC93FD00FC93F39 -:1036A00043443537800F4943387C0108004435379F -:1036B00008A3852E84F9223FB87B010800A3852E3C -:1036C00032318D2420F00042B2F1FF4FF8B50446AC -:1036D00003462DD25AB300283DDBB2F5000F4FEA66 -:1036E000E0502CD37F38C3F31603C20743F4000322 -:1036F00048BF5B00002740105B003E4619244FF096 -:103700008072B5189D4202DC5B1BAE181744013C69 -:103710004FEA43034FEA5202F3D113B107F001031A -:103720001F447F1007F17C5707EBC050F8BDF8BD70 -:103730000146FBF7C1FB2146FBF7B6FAF8BD14F4CE -:1037400000020FD15B00190202F10102FAD5C2F1A9 -:1037500001021044C6E70146FBF7A4FA0146FBF755 -:103760005FFCF8BD01221044BCE700BF2DE9F8431F -:1037700020F00046B6F1485F05460F4649DAFBF7F0 -:1037800061FD002800F09D8029462846FBF794FB48 -:103790004E490446FBF790FB4D49FBF785FA21465D -:1037A000FBF78AFB4B49FBF77DFA2146FBF784FBCD -:1037B0004949FBF779FA2146FBF77EFB4749FBF7BE -:1037C00071FA2146FBF778FB4549FBF76DFA214674 -:1037D000FBF772FB804620464FF07C51FBF76CFBF9 -:1037E000414606462046FBF767FB39460446284615 -:1037F000FBF762FB01462046FBF754FA01463046D0 -:10380000FBF750FA01464FF07E50FBF74BFABDE84C -:10381000F8830146FBF750FB2C490446FBF74CFBB1 -:103820002B49FBF741FA2146FBF746FB2949FBF7F9 -:1038300039FA2146FBF740FB2749FBF735FA2146C9 -:10384000FBF73AFB2549FBF72DFA2146FBF734FB42 -:103850002349FBF729FA2146FBF72EFB214B804633 -:103860009E42B8DD204B9E4227DC06F17F46314662 -:103870004FF07E50FBF716FA814620464FF07C5100 -:10388000FBF71AFB3146FBF70DFA41460646204688 -:10389000FBF712FB394604462846FBF70DFB0146B1 -:1038A0002046FBF7FFF901463046FBF7FBF90146DE -:1038B0004846FBF7F7F9BDE8F883DFF834900B4E84 -:1038C000DBE74FF07E50BDE8F88300BF4ED747AD31 -:1038D000F6740F317CF29334010DD037610BB63A98 -:1038E000ABAA2A3D9999993E0000483F0000903EBE -:1038F0000000383F2DE9F04FDFB00B93013B0293FE -:10390000D31E48BF131DB84C06466898DB1054F808 -:10391000204023EAE3730C93DB4302EBC3030894D8 -:103920000693089C029B0C9A1D190991C3EB020790 -:103930001DD4699C3D4404EB870901354FF0000814 -:1039400022AC0AE059F80800FBF762FA0137AF42EF -:1039500044F8080008F1040809D0002FF2DA013712 -:103960000020AF4244F8080008F10408F5D1089A95 -:10397000002AC0F2DF82089A0B9B02F101089C002A -:1039800022AF4FEA880827440025029A002AC0F295 -:10399000F28105EB070B4FF000094FF0000A56F8D3 -:1039A00009005BF8041DFBF787FA01465046FBF758 -:1039B0007BF909F10409A1458246F0D14AA840F8F3 -:1039C00005A004354545E0D1089A0EAB03EB820310 -:1039D0000D9391464FEA89030793079A5EAB134410 -:1039E000B9F1000F53F850AC23DD0DF134084AAFA4 -:1039F000174490440DAD4FF06E515046FBF75CFA02 -:103A0000FBF720FCFBF704FA4FF087418346FBF7F6 -:103A100053FA01465046FBF745F9FBF713FC5946AC -:103A200045F8040F57F8040DFBF73EF9454582466B -:103A3000E1D15046069900F025FD4FF0785105463A -:103A4000FBF73AFA00F0BAFC4FF08241FBF734FA88 -:103A500001462846FBF726F90546FBF7F3FB8246AD -:103A6000FBF7D6F901462846FBF71CF9069A804673 -:103A7000002A40F3678109F1FF310EA850F8213088 -:103A8000C2F1080043FA00F202FA00F01B1A06988D -:103A90009244C0F1070743FA07F70EA840F8213017 -:103AA000002F32DDB9F1000F0AF1010A40F37581F0 -:103AB0000EAB079A19461144002507E0C2F5807045 -:103AC00012B143F8040C01258B420BD053F8042BA0 -:103AD000002DF3D0C2F1FF028B4243F8042C4FF0CB -:103AE0000105F3D1069B002B0DDD012B00F0328187 -:103AF000022B08D109F1FF330EA951F8232002F05F -:103B00003F0241F82320022F70D040460021FBF7EE -:103B100067FB002800F08380089A09F1FF35AA426C -:103B20000DDC079A0EAB0D981344002253F8041DC8 -:103B3000834242EA0102F9D1002A40F0E481089B65 -:103B40000EA85A1E50F82230002B40F0F18100EBF5 -:103B50008202012352F8041D01330029FAD04B449C -:103B600099450A933DDADDF82CA022AACA44DDF873 -:103B7000308002EB8A02C844C9EB0309131D03928B -:103B80000593699A079B4FEA89094AAF02EB8808B7 -:103B9000CDF810901F44002558F8040FFBF738F9B2 -:103BA000029B039A002B50514FF0000B13DBDDF802 -:103BB00014A04FF00009AA4456F809005AF8041D51 -:103BC000FBF77AF901465846FBF76EF809F104094C -:103BD000A1458346F0D1049A0435954247F804BFC5 -:103BE000DAD1DDF82890F5E6507F010841464FF024 -:103BF0007E50FBF757F88046002D86D006994FF08F -:103C00007E5000F03FFC01464046FBF74BF88046F3 -:103C100040460021FBF7E4FA00287FF47DAF069BC5 -:103C200040465942CDF808A000F02CFC4FF08741E7 -:103C30000446FBF7F3FA002800F07F814FF06E5145 -:103C40002046FBF739F9FBF7FDFAFBF7E1F84FF0F7 -:103C500087410546FBF730F901462046FBF722F87D -:103C6000FBF7F0FA0EAB43F829002846FBF7EAFA17 -:103C7000069C09F1010508340EA9069441F82500B7 -:103C800006994FF07E5000F0FDFB002D04464FDBFF -:103C90006E1C4FEA8508C6EB867A0DF138094AABEF -:103CA000C1444FEA8A0A98444FF0000B59F80B00C0 -:103CB000FBF7AEF82146FBF7FFF84FF06E5148F8DE -:103CC0000B002046FBF7F8F8ABF1040BD345044694 -:103CD000ECD1DFF88C92DDF820A00024B3460395E8 -:103CE0000497BAF1000FB8BF002515DB0026374650 -:103CF000002501E0A7420FDC58F8061059F806002D -:103D0000FBF7DAF801462846FAF7CEFF0137BA4545 -:103D1000054606F10406EDDA5EA800EB84030134E3 -:103D2000A345A8F1040843F8A05CDAD1039D049FE1 -:103D3000689C032C00F29880DFE814F0CB009C0014 -:103D40009C00310010D109F1FF330EA951F8237006 -:103D50003F12A5E609F1FF330EA850F8232002F028 -:103D60007F0240F82320CEE64FF07C51FBF756FA55 -:103D700058B90746C9E64FF0000A4AA840F805A01E -:103D8000043545457FF401AE1EE6B9F1000F4FF052 -:103D900002070AF1010A3FF78BAE0025A2E6002DCB -:103DA00040F3DC804FEA850B5EAB36AE05F1FF3A9F -:103DB0005B4406EB8A0A53F8A08C54465B4635AA4E -:103DC000BB462F4600E0C84654F8045941462846F1 -:103DD00001920093FAF768FF814649462846FAF7B0 -:103DE00061FF4146FAF760FF019AC4F804909442DB -:103DF000A060009BE7D13D46012D5F469B4640F306 -:103E0000AD805EAB9B445BF8A04C00E044465AF8A2 -:103E1000049921464846FAF747FF804641464846FE -:103E2000FAF740FF2146FAF73FFF5645CAF80480EB -:103E3000CAF80800EAD16C1C06EB8404002008369E -:103E400054F8041DFAF730FFB442F9D1002F7ED0A8 -:103E5000369A379B099C00F1004002F1004203F1C1 -:103E60000043A06022606360029A02F007005FB026 -:103E7000BDE8F08F002DB8BF00200ADB36AE6C1C09 -:103E8000002006EB840454F8041DFAF70DFFB44239 -:103E9000F9D1002F35D000F10043099C0146236081 -:103EA0003698FAF7FFFE002D08DD36AC04EB8505E9 -:103EB00054F8041FFAF7F8FEAC42F9D10FB100F143 -:103EC0000040099A5060029A02F007005FB0BDE816 -:103ED000F08F002D39DB6C1C36AE002006EB84041D -:103EE00054F8041DFAF7E0FEB442F9D10FB100F125 -:103EF0000040099A1060029A02F007005FB0BDE826 -:103F0000F08F0346C9E7069A0EAC54F82530083AFC -:103F1000CDF808A00692002B7FF4B2AE04EB850327 -:103F200053F8041D013D083A0029F9D00692A7E68E -:103F3000012314E60B9B9C0046E52046FBF782F923 -:103F40000EAA4D4642F829009AE60020CEE7099CC9 -:103F5000369A379BA0602260636085E7002075E792 -:103F60005C7F01082DE9F84320F00043B3F1485F7E -:103F700004460F46904603DAFBF764F9002857D051 -:103F800021462046FAF798FF21460546FAF794FFA6 -:103F9000294906462846FAF78FFF2849FAF782FE94 -:103FA0002946FAF789FF2649FAF77EFE2946FAF7ED -:103FB00083FF2449FAF776FE2946FAF77DFF224966 -:103FC000FAF772FE8146B8F1000F22D038464FF062 -:103FD0007C51FAF771FF494680463046FAF76CFF8C -:103FE00001464046FAF75EFE2946FAF765FF394674 -:103FF000FAF758FE154905463046FAF75DFF0146C7 -:104000002846FAF751FE01462046FAF74BFEBDE876 -:10401000F88349462846FAF74FFF0C49FAF742FE63 -:104020003146FAF749FF2146FAF73EFEBDE8F8832C -:104030002046BDE8F88300BFD3C92E2F342FD732D6 -:104040001BEF3836010D50398988083CABAA2A3E4F -:104050000020704700200149704700BF0000F87F32 -:104060002DE9F043C1F30A5CACF2FF37132F83B0A4 -:1040700002460B460D46894680464FEAD17630DC33 -:10408000002F4CDB3A49394101EA030010432DD09F -:10409000490801EA030858EA02080CD04FF48023CB -:1040A0003B41132F25EA010141EA030914BF4FF0F8 -:1040B00000084FF000482F494B4601EBC606D6E9F1 -:1040C0000045424620462946FAF78CF9CDE9000121 -:1040D000DDE9000122462B46FAF782F903B0BDE87C -:1040E000F083332F07DDB7F5806F3ED010461946B9 -:1040F00003B0BDE8F083ACF2134C4FF0FF3121FA6E -:104100000CF10142F2D049080142D4D04FF080486E -:1041100048FA0CFC20EA010141EA0C08CBE721F047 -:1041200000410143E2D0C3F3130101434C420C436D -:104130001048590C240B490404F4002444EA0103F8 -:1041400000EBC601D1E9004520462946FAF74AF9B5 -:10415000CDE90001DDE900012B462246FAF740F9DE -:1041600021F0004343EAC671C2E7FAF73BF9BFE723 -:10417000FFFF0F00887F01082DE9F04120F0004586 -:10418000B5F1A14F0446064608DBB5F1FF4F6FDCE1 -:10419000002840F3A0806F48BDE8F0816E4B9D423F -:1041A00077DCB5F1445F68DB4FF0FF3721462046EE -:1041B000FAF782FE01468046FAF77EFE6749054619 -:1041C000FAF77AFE6649FAF76FFD2946FAF774FEA8 -:1041D0006449FAF769FD2946FAF76EFE6249FAF773 -:1041E00063FD2946FAF768FE6049FAF75DFD294646 -:1041F000FAF762FE5E49FAF757FD4146FAF75CFEB0 -:104200005C4980462846FAF757FE5B49FAF74AFDB3 -:104210002946FAF751FE5949FAF744FD2946FAF7BB -:104220004BFE5749FAF73EFD2946FAF745FE554938 -:10423000FAF738FD2946FAF73FFE7B1C0146404657 -:104240004CD0FAF731FD2146FAF736FE4E4B4F4D72 -:1042500053F82710FAF726FD2146FAF723FD014609 -:1042600055F82700FAF71EFD002E30DBBDE8F0817F -:104270000146FAF719FDBDE8F0814549FAF714FD4A -:104280004FF07E51FAF7D4FF00288DD02046BDE8CC -:10429000F08100F087F83F4B04469D4229DCA3F5EE -:1042A000D0039D4244DC0146FAF7FEFC4FF07E51FC -:1042B000FAF7F8FC4FF0804105462046FAF7F4FC87 -:1042C00001462846FAF7ACFE002704466EE700F1E7 -:1042D0000040BDE8F0813048BDE8F081FAF7E4FC29 -:1042E0002146FAF7E9FD01462046FAF7DBFCBDE876 -:1042F000F0812A4B9D4214DC4FF07F51FAF7D2FC3B -:104300004FF07F5105462046FAF7D6FD4FF07E511B -:10431000FAF7CAFC01462846FAF782FE022704464D -:1043200044E701461E48FAF77BFE032704463DE7B3 -:104330004FF07E51FAF7B6FC4FF07E51054620460D -:10434000FAF7B2FC01462846FAF76AFE012704464E -:104350002CE700BFDB0FC93FFFFFDF3ED769853C7D -:1043600059DA4B3D356B883D6E2EBA3D2549123EDC -:10437000ABAAAA3E21A215BD6BF16E3D95879D3D6E -:10438000388EE33DCDCC4C3E987F0108A87F0108D4 -:10439000CAF24971FFFF973FDB0FC9BFFFFF1B4008 -:1043A000000080BF20F00040704700BF20F00040B8 -:1043B000B0F1FF4FACBF0020012070472DE9F04164 -:1043C00020F00047FD0D7F3D162D064613DC002D25 -:1043D00080461BDB194F2F41074214D01849FAF7CA -:1043E00063FC0021FAF724FF68B1002E1BDB28EAEA -:1043F0000700BDE8F081B7F1FF4F04D30146FAF79B -:1044000053FCBDE8F0813046BDE8F0810C49FAF775 -:104410004BFC0021FAF70CFF0028F4D0002E08DB3B -:104420000020BDE8F0814FF4000343FA05F5A844ED -:10443000DDE7002FE7D00348BDE8F081FFFF7F00F4 -:10444000CAF24971000080BF30F0004001D1022063 -:104450007047A0F50003B3F1FE4F01D2042070476E -:10446000054B421E9A4201D803207047B0F1FF432A -:1044700058425841704700BFFEFF7F000048704718 -:104480000000C07F38B530F00044024603460D46B8 -:1044900014D0B4F1FF4F0DD2B4F5000F0FD3E40DDB -:1044A0002C44FE2C2EDC002C1DDD23F0FF4343EAC0 -:1044B000C45038BD0146FAF7F7FB38BD38BD4FF0A0 -:1044C0009841FAF7F9FC194B02469D4207DBC0F30D -:1044D000C7540346193CE3E7154800F02DF814498A -:1044E000FAF7EAFC38BD14F1160F13DA4CF2503328 -:1044F0009D421146F0DD0F4800F01EF80D49FAF715 -:10450000DBFC38BD11460B4800F016F80949FAF7F4 -:10451000D3FC38BD04F1190023F0FF4343EAC05037 -:104520004FF04C51FAF7C8FC38BD00BFB03CFFFF5C -:104530006042A20DCAF2497101F0004120F0004032 -:1045400008437047014B1868704700BF30010020D6 -:10455000780000FF000000FF3C0000FFF00000FFBB -:104560000001746564666D6A69736C67010B020D06 -:104570000A03050B030D0A03070B030D0A03090BBE -:10458000020D0A030A0B040D0A03080B040D0A03AB -:104590001E0000FF4A0100FF2C0100FF0E0100FF7A -:1045A000D20000FFB40000FF960000FF5A0000FF99 -:1045B0000000FFFF70610108B04501085445010883 -:1045C0009045010858450108AC45010850450108CF -:1045D000A8450108A4450108A04501085C4501085B -:1045E0009C45010898450108944501080800000011 -:1045F00000200000000C014010000000002000001E -:1046000000100140000C014008001002000C0140A5 -:1046100010001002000C0140040014020000000011 -:104620000000000003010000204C0108040000000D -:10463000E04B010804000000A04B0108020100004B -:10464000804B01080001000000000000060000008F -:10465000204B010806000000C04A010801010000CB -:104660000000000004000000804A0108060000006D -:10467000204A010808000000A049010808000000C5 -:104680002049010808000000A048010801010000BD -:104690000000000000010000000000000001000018 -:1046A000000000000400000060480108060000004F -:1046B00000480108000100000000000002010000A5 -:1046C000E0470108010100000000000000000000B8 -:1046D00000000000C2470108AA4701088C470108F2 -:1046E00074470108FD8C0008B98C0008958C0008FF -:1046F0006D8C00085D8C0008DDE20008E98C000884 -:104700000D8C0008DD8C0008CF8C00080000000034 -:1047100000C20100746201089762010801000000F4 -:1047200000E10000AC620108CE6201080200000056 -:1047300000960000E2620108046301080300000023 -:10474000004B0000186301083A63010804000000F0 -:1047500080250000096701080967010800010002BF -:104760000002000009170000010002000200000022 -:10477000010700000001080309030A040B040C04EC -:104780000D040404050406040704FFFF00020102EF -:1047900002020302040205020602070208030903DB -:1047A0000A040B040C040D04FFFF000108030903B5 -:1047B0000A030B030C030D0304030503060307039D -:1047C000FFFF0002010202020302040205020602C8 -:1047D0000702080309030A030B030C030D03FFFF81 -:1047E0000000803F0000000000000000000080BFCB -:1047F0000000803F00000000000000000000803F3B -:104800000000803F000080BF0000803F000080BFAC -:104810000000803F000080BF000080BF0000803F9C -:104820000000803F0000803F0000803F0000803F8C -:104830000000803F0000803F000080BF000080BF7C -:104840000000803F000000000000000000000000A9 -:104850000000803F00000000000000000000000099 -:104860000000803F000000000000803F0000803F0B -:104870000000803F000080BF000080BF00000000FB -:104880000000803F000000000000803F000080BF6B -:104890000000803F0000803F000080BF00000080DB -:1048A0000000803F0000803F000000BF0000803F0C -:1048B0000000803F000000BF000080BF0000803F7C -:1048C0000000803F000080BF0000003F0000803FEC -:1048D0000000803F0000003F0000803F0000803F5C -:1048E0000000803F0000003F000080BF000080BF4C -:1048F0000000803F000080BF000000BF000080BFBC -:104900000000803F000000BF0000803F000080BF2B -:104910000000803F0000803F0000003F000080BF9B -:104920000000803FF704353FF70435BF0000803FAB -:104930000000803FF70435BFF70435BF0000803F1B -:104940000000803FF70435BFF704353F0000803F8B -:104950000000803FF704353FF704353F0000803FFB -:104960000000803F00000000000080BF000080BF0A -:104970000000803F000080BF00000000000080BFFA -:104980000000803F000000000000803F000080BF6A -:104990000000803F0000803F00000000000080BF5A -:1049A0000000803F000080BF0000803F000080BF0B -:1049B0000000803F000080BF000080BF0000803FFB -:1049C0000000803F0000803F0000803F0000803FEB -:1049D0000000803F0000803F000080BF000080BFDB -:1049E0000000803F000080BF0000803F0000803F4B -:1049F0000000803F000080BF000080BF000080BF3B -:104A00000000803F0000803F0000803F000080BF2A -:104A10000000803F0000803F000080BF0000803F1A -:104A20000000803F000000BFD0B35D3F0000803F2A -:104A30000000803F000000BFD0B35DBF0000803F9A -:104A40000000803F0000003FD0B35D3F000080BF0A -:104A50000000803F0000003FD0B35DBF000080BF7A -:104A60000000803F000080BF00000000000080BF09 -:104A70000000803F0000803F000000000000803FF9 -:104A80000000803F000000000000803F000080BF69 -:104A90000000803F000080BF000080BF00000000D9 -:104AA0000000803F000000000000803F0000803FC9 -:104AB0000000803F0000803F000080BF0000000039 -:104AC0000000803FD0B35DBF0000003F0000803F8A -:104AD0000000803FD0B35DBF000000BF000080BF7A -:104AE0000000803FD0B35D3F0000003F0000803FEA -:104AF0000000803FD0B35D3F000000BF000080BFDA -:104B00000000803F00000000000080BF0000803FE8 -:104B10000000803F000000000000803F000080BFD8 -:104B20000000803F00000000A8AAAA3F0000803FCC -:104B30000000803F000080BFB0AA2ABF000080BFF5 -:104B40000000803F0000803FB0AA2ABF000080BF65 -:104B50000000803F00000000A8AAAA3F000080BF1C -:104B60000000803F000080BFB0AA2ABF0000803F45 -:104B70000000803F0000803FB0AA2ABF0000803FB5 -:104B80000000803F0000803F0000000000000000A7 -:104B90000000803F000080BF000000000000000017 -:104BA0000000803F000080BF0000803F000080BF09 -:104BB0000000803F000080BF000080BF0000803FF9 -:104BC0000000803F0000803F0000803F0000803FE9 -:104BD0000000803F0000803F000080BF000080BFD9 -:104BE0000000803F000000000000803F000080BF08 -:104BF0000000803F000080BF000000000000803FF8 -:104C00000000803F0000803F000000000000803F67 -:104C10000000803F00000000000080BF000080BF57 -:104C20000000803F00000000A8AAAA3F000000008A -:104C30000000803F000080BFB0AA2ABF0000000033 -:104C40000000803F0000803FB0AA2ABF00000000A3 -:104C50001000000000200000001001400040000093 -:104C600000100140010001020001030001040001E5 -:104C70000500010600010700010800010900010A02 -:104C800000010B00010C0103000000004E6301084D -:104C90000000000001000000536301080100000053 -:104CA000020000005A630108020000000300000037 -:104CB0006363010803000000040000006963010849 -:104CC00005000000050000006E63010806000000FA -:104CD00006000000786301080700000007000000DC -:104CE0008163010808000000080000008A630108D1 -:104CF0000900000009000000936301080A00000099 -:104D00000A0000009D6301080B0000000B0000007A -:104D1000A76301080C0000000C000000B16301084B -:104D20000D0000000D000000B96301080E00000036 -:104D30000E000000C16301080F0000000F0000001A -:104D4000C96301081000000010000000D2630108D0 -:104D50001100000011000000D963010812000000DA -:104D600012000000E36301081300000013000000BC -:104D7000EB6301081400000014000000F663010852 -:104D80001500000015000000006401081600000076 -:104D90001600000000000000FF000000B5620601E0 -:104DA0000300F00500FF19B56206010300F00300DF -:104DB000FD15B56206010300F00100FB11B56206A6 -:104DC000010300F00000FA0FB56206010300F002D3 -:104DD00000FC13B56206010300F00400FE17B56283 -:104DE000060103000102010E47B56206010300013E -:104DF00003010F49B56206010300010601124FB518 -:104E000062060103000112011E67B5620608060072 -:104E1000C80001000100DE6A00B562061608000342 -:104E20000703000000000031E501B5620616080026 -:104E300003070300510800008A4102B56206160804 -:104E4000000307030004E00400199D03B562061681 -:104E50000800030703000002020035EF04B56206F4 -:104E60001608000307030080010000B2E80090016B -:104E7000C800C800C800C800C800C800C800C800F2 -:104E800064000000C800C800C800C800320000016B -:104E90001E1E646464646464220046022100820170 -:104EA00020004302100001010000490201008801B6 -:104EB00002004C02120084011100900111009001C7 -:104EC0001100A0011100A00100540040000C01409D -:104ED000400080001F20000000002000005800401B -:104EE000000C0140000400082122000000004000E6 -:104EF000778D0008958D0008B18D0008858A00081F -:104F0000DD8D0008E98D000802000000802500000A -:104F100000C2010000000000200000008025000009 -:104F200000C20100010000004000000080250000D8 -:104F300000C2010000000000010000008025000008 -:104F400000C20100000000001000000080250000E9 -:104F500000C20100000300000400000080250000E2 -:104F6000004B0000000000000800000000E100000D -:104F700000E10000000400008000000000C2010009 -:104F800000C2010000000000524F4C4C3B504954FD -:104F900043483B5941573B414C543B506F733B5046 -:104FA0006F73523B4E6176523B4C4556454C3B4DE0 -:104FB00041473B56454C3B00C6670108BD670108A9 -:104FC000B167010840008000000100020004495759 -:104FD0004641540102040810204E45535755442CB5 -:104FE0003A3A0000E9840008458D0008138D000856 -:104FF000EDAA0008618D0008E9AA0008B66A010858 -:10500000BA6A0108C06A0108C66A0108C96A0108CB -:10501000D06A0108D36A0108D86A0108E46A010865 -:10502000E76A0108ED6A0108F46A0108FE6A0108EE -:10503000086B0108116B01081F6B01082B6B01083D -:10504000326B0108386B0108456B0108506B010891 -:105050005D6B010800000000FA690108016A01089F -:10506000066A0108176A0108216A01082C6A01080A -:10507000376A0108426A0108466A01084F6A010856 -:10508000556A01085F6A01086D6A0108706A0108C3 -:10509000806A0108876A0108906A01089A6A010813 -:1050A000A26A0108AD6A01080000000000000000CB -:1050B0000000004F00000007000700147F147F1459 -:1050C000242A7F2A1223130864623649552250008D -:1050D00005030000001C2241000041221C001408AE -:1050E0003E081408083E0808005030000008080870 -:1050F0000808006060000020100804023E51494585 -:105100003E00427F400042615149462141454B31BA -:105110001814127F1027454545393C4A494930014A -:10512000710905033649494936064949291E0036A1 -:1051300036000000563600000814224100141414F2 -:105140001414004122140802015109063249794120 -:105150003E7E1111117E7F494949363E414141222F -:105160007F4141221C7F494949417F090909013E8C -:105170004149497A7F0808087F00417F410020406B -:10518000413F017F081422417F404040407F020C94 -:10519000027F7F0408107F3E4141413E7F0909099B -:1051A000063E4151215E7F09192946464949493148 -:1051B00001017F01013F4040403F1F2040201F3F31 -:1051C0004038403F631408146307087008076151B2 -:1051D000494543007F41410002040810200041413D -:1051E0007F000402010204404040404001020400EC -:1051F0000020545454787F48444438384444442070 -:10520000384444487F3854545418087E0901020633 -:105210004949493F7F0804047800447D400020400C -:10522000443D007F1028440000417F40007C04186A -:10523000047C7C0804047838444444387C141414F6 -:1052400008081414187C7C0804040848545454209A -:10525000043F4440203C4040207C1C2040201C3C1B -:105260004030403C44281028440C5050503C44648A -:10527000544C44000836410000007F0000004136D5 -:10528000080002010204023E5555412200000000C0 -:105290000000007900001824742E24487E49424002 -:1052A0005D2222225D15167C161500007700000A8B -:1052B000555555280001000100000A0D0A04081484 -:1052C0002A1422040404041C000808080001010137 -:1052D0000101000205020044445F4444000004024E -:1052E000017E2020103E060F7F007F00181800006E -:1052F0000040502000000A0D0A0022142A1408174A -:1053000008342A7D1708046A593048454020420075 -:105310004200427E420042007E7E0042007E7E7E4F -:1053200042007E7E7E7E007E7E7E7E7E05040203BF -:10533000AB6C0108B46C0108D5450008D86C0108B5 -:10534000DC6C010809470008F26C0108F76C0108E1 -:10535000456300080B6D0108116D0108C960000864 -:1053600020670108226D0108B57800083F6D01082B -:10537000446D01089DB30008736D010809670108B9 -:10538000196C0008786D0108806D01088999000882 -:10539000946D0108986D0108BDA60008AB6D010869 -:1053A000BA6D010885C00008D46D010809670108BD -:1053B000C5A50008D96D0108DD6D010841AE0008E2 -:1053C000EC6D0108F06D0108B5A80008056D010835 -:1053D0000C6E01088D5F00081F6E0108256E010824 -:1053E000296000082E780108406E010851B30008BA -:1053F0004F6E0108406E0108B18200085B6E010823 -:10540000606E0108456C0008E3650108706E0108D4 -:105410001DA700089E6E0108926E010811D00008B9 -:10542000F47501080967010895A500084820507225 -:105430006F647563743A426C61636B626F78206667 -:105440006C696768742064617461207265636F724F -:10545000646572206279204E6963686F6C617320A5 -:10546000536865726C6F636B0A4820426C61636BB2 -:10547000626F782076657273696F6E3A310A4820E0 -:10548000446174612076657273696F6E3A310A0007 -:105490004D6F010887700108D27001082071010862 -:1054A0006D710108BB710108426F010806720108A5 -:1054B000F26A0108067201084B6F010806720108C2 -:1054C00048204669656C642047206E616D653A47E7 -:1054D00050535F6E756D5361742C4750535F636F0B -:1054E0006F72645B305D2C4750535F636F6F726403 -:1054F0005B315D2C4750535F616C746974756465F2 -:105500002C4750535F73706565640A48204669658F -:105510006C642047207369676E65643A302C312CC7 -:10552000312C302C300A48204669656C64204720B5 -:10553000707265646963746F723A302C372C372C43 -:10554000302C300A48204669656C64204720656E1F -:10555000636F64696E673A312C302C302C312C31FA -:105560000A48204669656C642048206E616D653A82 -:105570004750535F686F6D655B305D2C4750535FDC -:10558000686F6D655B315D0A48204669656C642013 -:1055900048207369676E65643A312C310A482046A9 -:1055A00069656C64204820707265646963746F7209 -:1055B0003A302C300A48204669656C6420482065E2 -:1055C0006E636F64696E673A302C300A0000020225 -:1055D0000308050A0B080A0A0B0C0E0E0F00000048 -:1055E000E8720108ED720108F1720108FA7201080F -:1055F0004F6A0108426A0108F672010800000000C3 -:1056000009670108A4720108AC720108B4720108AC -:10561000BC720108C3720108CE720108D67201087B -:10562000DE720108E37201080000000000000000C3 -:105630008025000000C201000600000001000000FB -:105640008025000000C201000700000003000000E8 -:1056500080250000004B000009000000040000004D -:1056600080250000004B000009000000FE720108C8 -:10567000440000003C20002000000000282300001F -:1056800007730108410000003E20002000000000D8 -:105690000100000015730108440000004A210020A9 -:1056A000B0040000A40600001C73010844000000C0 -:1056B0004C21002000000000D007000026730108E4 -:1056C000440000004E21002000000000D007000030 -:1056D000307301084200000050210020000000004B -:1056E000120000003D73010842000000512100201B -:1056F00001000000FF0000004873010842000000A4 -:105700005221002000000000010000005D7301082C -:10571000440000000021002000000000D00700002D -:105720006A7301084400000002210020000000000C -:10573000D007000077730108440000000421002016 -:1057400000000000D007000083730108440000003F -:105750000621002000000000D0070000937301081C -:10576000440000000821002000000000D0070000D5 -:10577000A4730108440000000A210020000000007A -:10578000D0070000AF730108440000000C21002086 -:1057900000000000D0070000C473010844000000AE -:1057A0000E21002032000000007D0000D3730108AC -:1057B000440000001021002032000000F20100002F -:1057C000E2730108410000005321002000000000A6 -:1057D00001000000EF730108410000005421002087 -:1057E00000000000010000000274010841000000F8 -:1057F0005521002000000000B40000000E740108D4 -:10580000410000005621002000000000640000005C -:105810001A7401084200000057210020FFFFFFFF1B -:105820000100000030740108410000005C210020EC -:10583000000000000B000000477401084100000058 -:105840005D210020000000000B0000005E740108D4 -:10585000410000005E210020000000000B0000005D -:1058600075740108410000005F2100200000000065 -:105870000B0000008C740108410000007021002022 -:10588000300000007E0000009D7401085000000000 -:1058900060210020B004000000C20100AA740108C9 -:1058A0005000000064210020B004000000C201008C -:1058B000B7740108500000006821002000000000BB -:1058C00000C20100C4740108500000006C210020D7 -:1058D000B004000000C20100DD74010841000000B6 -:1058E000582100200000000001000000EA740108B7 -:1058F00041000000592100200000000004000000C9 -:10590000F8740108410000005A2100200000000046 -:105910000100000008750108810000004C220020F1 -:1059200000000000C800000012750108810000009E -:105930005622002000000000C80000001C7501086D -:10594000810000006022002000000000C80000006C -:1059500026750108810000004D2200200000000093 -:10596000C8000000317501088100000057220020A6 -:1059700000000000C80000003C7501088100000024 -:105980006122002000000000C800000047750108E7 -:10599000810000004E22002000000000C80000002E -:1059A000517501088100000058220020000000000D -:1059B000C80000005B750108810000006222002021 -:1059C00000000000C80000006575010884000000A8 -:1059D000F623002000000000D007000073750108C6 -:1059E00081000000FA2300200000000001000000F8 -:1059F0008875010884000000FC2300200A000000D4 -:105A0000D00700009675010884000000FE230020E6 -:105A10000A000000D0070000A47501088100000002 -:105A2000F92300200000000064000000B2750108A6 -:105A30004100000048210020000000000300000099 -:105A4000C47501084100000074210020000000001E -:105A500003000000D77501084100000075210020F7 -:105A60000000000001000000E8750108410000008E -:105A7000762100200000000001000000FC750108F4 -:105A80006000000078210020A6FFFFFF5A00000000 -:105A900014760108600000007C2100204CFFFFFF0D -:105AA000B40000002C760108410000008021002095 -:105AB00000000000010000004576010841000000E0 -:105AC0008121002000000000010000005076010844 -:105AD000440000003E21002000000000204E000095 -:105AE0006176010841000000342100200000000020 -:105AF000FF0000006C760108410000003521002005 -:105B00000A00000032000000827601084100000017 -:105B1000362100200A0000003200000098760108BB -:105B20004400000038210020010000001027000080 -:105B3000AC760108440000003A210020000000007B -:105B400072060000C1760108410000003C210020DF -:105B50000000000001000000DF76010841000000A5 -:105B6000122100200000000008000000EA76010871 -:105B70004100000013210020000000000800000088 -:105B8000F47601084100000014210020000000000C -:105B900008000000FE7601084800000016210020E1 -:105BA0004CFFFFFF680100000F770108480000006C -:105BB000182100204CFFFFFF680100002177010839 -:105BC000480000001A2100204CFFFFFF6801000080 -:105BD0003177010844000000262100206400000005 -:105BE0008403000047770108440000001E210020C4 -:105BF0000000000000010000507701084100000093 -:105C000024210020000000008000000060770108CF -:105C1000440000002021002064000000E803000090 -:105C20007177010844000000222100206400000078 -:105C3000E80300008377010881000000A32300200F -:105C400001000000FA0000009577010881000000C3 -:105C5000A423002000000000010000008C77010850 -:105C600081000000A12300200000000020000000AF -:105C7000AA77010881000000A22300200000000094 -:105C800064000000B777010881000000A82300200D -:105C90000000000096000000D17701088400000099 -:105CA000A62300200100000084030000EB77010818 -:105CB000420000001C210020FFFFFFFF0100000048 -:105CC0000178010882000000F2230020FFFFFFFF9F -:105CD000010000000F78010882000000F32300207B -:105CE0000000000001000000217801088100000090 -:105CF0009422002000000000020000003678010815 -:105D0000010100008627002000000000FA000000CA -:105D10003E780108010100008727002000000000F4 -:105D20006400000046780108010100008827002077 -:105D300000000000640000004E780108010100002E -:105D40008927002000000000640000005778010847 -:105D5000010100008A27002000000000640000000C -:105D600067780108010100008B2700200000000077 -:105D70006400000070780108010100008C270020F9 -:105D800000000000640000007978010804010000B0 -:105D90008E270020E8030000D00700008878010863 -:105DA00081000000EA23002000000000C80000007D -:105DB0009778010881000000EB230020000000001C -:105DC000C8000000AA78010884000000EC2300202D -:105DD000E8030000D0070000BC7801088400000040 -:105DE000EE23002064000000D0070000CE780108F8 -:105DF00084000000F023002064000000B80B0000C5 -:105E0000E078010881000000F42300200000000079 -:105E1000FF000000ED780108410000001D21002076 -:105E20000000000009000000FA780108810000006D -:105E30009C22002000000000FA00000009790108FF -:105E400081000000A4220020000000006400000087 -:105E50001879010881000000A52200200000000040 -:105E60006400000026790108A0000000A0220020A4 -:105E700001000000140000003679010881000000D4 -:105E8000B822002000000000010000004579010850 -:105E9000880000009A220020D4FEFFFF2C010000A1 -:105EA000547901088800000098220020D4FEFFFFEA -:105EB0002C0100006279010881000000A822002066 -:105EC000000000003000000070790108A000000010 -:105ED000AC22002000000000010000007F790108D2 -:105EE000A0000000B022002000000000010000001F -:105EF0008B790108A0000000B422002000000000FF -:105F00000100000097790108880000009622002017 -:105F1000B0B9FFFF50460000A779010881000000DA -:105F2000442200200000000002000000B6790108B1 -:105F3000810000004922002000000000C80000008D -:105F4000BE790108810000005322002000000000FB -:105F5000C800000019770108810000005D220020C0 -:105F600000000000C8000000C679010881000000A0 -:105F70004822002000000000C8000000CD79010880 -:105F8000810000005222002000000000C800000034 -:105F900008770108810000005C220020000000005A -:105FA000C8000000D4790108810000004A220020C6 -:105FB00000000000C8000000DA790108810000003C -:105FC0005422002000000000C80000002B770108C8 -:105FD000810000005E22002000000000C8000000D8 -:105FE000E0790108A00000006C2200200000000001 -:105FF00064000000E9790108A00000007822002078 -:106000000000000064000000F2790108A000000018 -:10601000842200200000000064000000FB790108D9 -:10602000A0000000682200200000000064000000C2 -:10603000037A0108A0000000742200200000000084 -:10604000640000000B7A0108A000000080220020FC -:106050000000000064000000137A0108A0000000A6 -:106060007022002000000000640000001A7A01087D -:10607000A00000007C22002000000000640000005E -:10608000217A0108A0000000882200200000000002 -:1060900064000000287A0108A0000000902200207F -:1060A000000000000A000000367A0108A00000008D -:1060B0008C220020000000000A000000427A010843 -:1060C000810000004B22002000000000C8000000FA -:1060D000487A0108810000005522002000000000DD -:1060E000C80000004E7A0108810000005F220020F5 -:1060F00000000000C8000000547A01088100000080 -:106100004F22002000000000C80000005C7A010857 -:10611000810000005922002000000000C80000009B -:10612000647A010881000000632200200000000062 -:10613000C80000006C7A0108810000005122002094 -:1061400000000000C8000000727A01088100000011 -:106150005B22002000000000C8000000787A0108DF -:10616000810000006522002000000000C80000003F -:1061700000000000300810020002000100060008C4 -:106180000008100140080007100720070004100451 -:10619000200800000000004000080140010000004D -:1061A000001C002800000040000801400200000020 -:1061B000041C00280000004000080140040000000A -:1061C000081C0028000000400008014008000000F2 -:1061D0000C1C0028000400400008014040000000A2 -:1061E000001D00280004004000080140800000005D -:1061F000041D002800040040000C014001000000C4 -:10620000081D002800040040000C014002000000AE -:106210000C1D0028002C0140000801400001000076 -:10622000001B0128002C014000080140000800006C -:106230000C1B012800080040000C01404000000039 -:10624000001E002800080040000C014080000000F3 -:10625000041E002800080040000C0140000100005E -:10626000081E002800080040000C01400002000049 -:106270000C1E002824505542582C34312C312C301F -:106280003030332C303030312C3131353230302C0D -:10629000302A31450D0A0024504D544B3235312CF3 -:1062A0003131353230302A31460D0A002450554202 -:1062B000582C34312C312C303030332C30303031BC -:1062C0002C35373630302C302A32440D0A00245019 -:1062D0004D544B3235312C35373630302A32430D60 -:1062E0000A0024505542582C34312C312C30303097 -:1062F000332C303030312C33383430302C302A329B -:10630000360D0A0024504D544B3235312C3338347D -:1063100030302A32370D0A0024505542582C34317F -:106320002C312C303030332C303030312C3139326C -:1063300030302C302A32330D0A0024504D544B3269 -:1063400035312C31393230302A32320D0A00415287 -:106350004D3B00414E474C453B00484F52495A4F38 -:106360004E3B004241524F3B004D41473B004845A8 -:106370004144465245453B004845414441444A3B1F -:106380000043414D535441423B0043414D54524917 -:10639000473B0047505320484F4D453B0047505323 -:1063A00020484F4C443B0050415353544852553BB6 -:1063B000004245455045523B004C45444D41583BF9 -:1063C000004C45444C4F573B004C4C4947485453B4 -:1063D0003B0043414C49423B00474F5645524E4FCC -:1063E000523B004F53442053573B0054454C454DBE -:1063F000455452593B004155544F54554E453B006E -:10640000534F4E41523B0061646A72616E67652072 -:1064100025752025752025752025752025752025B5 -:10642000752025750D0A0061757820257520257564 -:106430002025752025752025750D0A00004F201098 -:1064400004430240010880C343757272656E742074 -:106450006D697865723A2025730D0A00417661698D -:106460006C61626C65206D69786572733A200025F5 -:10647000732000496E76616C6964206D697865727D -:1064800020747970650D0A004D6978657220736516 -:106490007420746F2025730D0A0055736167653A87 -:1064A0000D0A6D6F746F7220696E646578205B767B -:1064B000616C75655D202D2073686F77205B6F724E -:1064C000207365745D206D6F746F722076616C75DA -:1064D000650D0A004E6F2073756368206D6F746FD1 -:1064E000722C207573652061206E756D6265722057 -:1064F0005B302C2025645D0D0A004D6F746F722097 -:106500002564206973207365742061742025640DEF -:106510000A00496E76616C6964206D6F746F722039 -:1065200076616C75652C20313030302E2E32303053 -:10653000300D0A0053657474696E67206D6F746F57 -:106540007220256420746F2025640D0A00636F6C2F -:106550006F722025752025642C25752C25750D0A54 -:1065600000496E76616C696420636F6C6F7220699C -:106570006E6465783A206D757374206265203C20E6 -:1065800025750D0A005061727365206572726F7215 -:106590000D0A002E004E4709004F4B09004375734A -:1065A000746F6D206D697865723A200D0A4D6F74B5 -:1065B0006F720954687209526F6C6C095069746388 -:1065C00068095961770D0A002325643A090025738B -:1065D000090053616E69747920636865636B3A09D9 -:1065E000007265736574006C6F6164004C6F616468 -:1065F0006564202573206D69780D0A0057726F6EEF -:1066000067206E756D626572206F662061726775B6 -:106610006D656E74732C206E656564732069647893 -:106620002074687220726F6C6C20706974636820CB -:106630007961770D0A004D6F746F72206E756D620F -:106640006572206D7573742062652062657477656C -:10665000656E203120616E642025640D0A000D0AEC -:106660005265626F6F74696E67000D0A4C656176E2 -:10667000696E6720434C49206D6F64652C20756EF0 -:106680007361766564206368616E676573206C6F03 -:1066900073742E0D0A00536176696E67000D0A450A -:1066A0006E746572696E6720434C49204D6F646556 -:1066B0002C20747970652027657869742720746FA1 -:1066C0002072657475726E2C206F72202768656C5D -:1066D00070270D0A000D0A2320000D1B5B4B001BC9 -:1066E0005B324A1B5B313B314800556E6B6E6F77F6 -:1066F0006E20636F6D6D616E642C2074727920273B -:1067000068656C70270008200800414554523132FA -:10671000333400526573657474696E6720746F203A -:1067200064656661756C7473007261746570726F14 -:1067300066696C652025640D0A00303132333435CA -:10674000363738394142434445464748494A4B4C1D -:106750004D4E4F505152535455565758595A004563 -:106760006E61626C65642066656174757265733A0A -:106770002000417661696C61626C652066656174B8 -:10678000757265733A2000496E76616C69642066A3 -:10679000656174757265206E616D650D0A004469EE -:1067A0007361626C65642000456E61626C65642093 -:1067B0000044656320313020323031340031353AC5 -:1067C00033303A3430006534393261613600414645 -:1067D0004E4100436C65616E666C696768742F2575 -:1067E00073202573202F202573202825732900412D -:1067F0007661696C61626C6520636F6D6D616E645A -:10680000733A0D0A0025730925730D0A00202564CB -:1068100020256400556E6B6E6F776E20766172690D -:1068200061626C65206E616D650D0A004375727260 -:10683000656E742073657474696E67733A200D0A0F -:106840000025732073657420746F200056616C7589 -:10685000652061737369676E6D656E74206F757402 -:10686000206F662072616E67650D0A004D75737446 -:1068700020626520616E79206F72646572206F6698 -:106880002041455452313233340D0A00437572723F -:10689000656E742061737369676E6D656E743A20FE -:1068A00000736574202573203D200025752C257507 -:1068B0003A25733A2573006C65642025752025738D -:1068C0000D0A00496E76616C6964206C656420690C -:1068D0006E6465783A206D757374206265203C2083 -:1068E00025750D0A006D61737465720072617465BF -:1068F00073000D0A232076657273696F6E0D0A00AE -:106900000D0A232064756D70206D61737465720DBE -:106910000A000D0A23206D697865720D0A006D6901 -:106920007865722025730D0A00636D6978202564EF -:1069300000636D69782025642030203020302030BD -:106940000D0A000D0A0D0A232066656174757265D3 -:106950000D0A0066656174757265202D25730D0A38 -:1069600000666561747572652025730D0A000D0A55 -:106970000D0A23206D61700D0A006D617020257372 -:106980000D0A000D0A0D0A23206C65640D0A000D26 -:106990000A0D0A2320636F6C6F720D0A000D0A2323 -:1069A0002064756D702070726F66696C650D0A00E9 -:1069B0000D0A232070726F66696C650D0A000D0A5E -:1069C00023206175780D0A000D0A232061646A7224 -:1069D000616E67650D0A000D0A232064756D7020D5 -:1069E00072617465730D0A000D0A2320726174656B -:1069F00070726F66696C650D0A0052585F50504D99 -:106A0000005642415400494E464C494748545F4164 -:106A100043435F43414C0052585F53455249414CF8 -:106A2000004D4F544F525F53544F500053455256F0 -:106A30004F5F54494C5400534F46545345524941BB -:106A40004C00475053004641494C53414645005382 -:106A50004F4E41520054454C454D45545259004308 -:106A6000555252454E545F4D4554455200334400F3 -:106A700052585F504152414C4C454C5F50574D006D -:106A800052585F4D535000525353495F41444300A5 -:106A90004C45445F535452495000444953504C4173 -:106AA00059004F4E4553484F5431323500424C4106 -:106AB000434B424F580054524900515541445000F5 -:106AC00051554144580042490047494D42414C000C -:106AD0005936004845583600464C59494E475F578D -:106AE000494E47005934004845583658004F4354E2 -:106AF0004F5838004F43544F464C415450004F4379 -:106B0000544F464C41545800414952504C414E4517 -:106B10000048454C495F3132305F4343504D004897 -:106B2000454C495F39305F44454700565441494C14 -:106B3000340048455836480050504D5F544F5F531D -:106B40004552564F004455414C434F505445520016 -:106B500053494E474C45434F5054455200435553BB -:106B6000544F4D0041455254313233343536373865 -:106B70006162636465666768005265763A202573D2 -:106B8000005461726765743A20257300566F6C7407 -:106B9000733A2025642E2531642043656C6C733A6A -:106BA00020256400416D70733A2025642E253264DF -:106BB000206D41683A2025640020202020202020DC -:106BC000205820202020205920202020205A004119 -:106BD000203D202535642025356420253564004777 -:106BE000203D202535642025356420253564004D61 -:106BF000203D20253564202535642025356400504E -:106C0000726F66696C653A20256400526174652074 -:106C100070726F66696C653A2025640052432045A6 -:106C200078706F3A20256400524320526174653AAF -:106C30002025640052265020526174653A20256454 -:106C40000059617720526174653A202564007C2FD9 -:106C50002D5C00434C45414E464C49474854004149 -:106C6000524D454400424154544552590053454EFB -:106C7000534F52530052580050524F46494C450012 -:106C80004E415A45004572726F723A20456E6162FC -:106C90006C6520616E6420706C756720696E20479A -:106CA00050532066697273740D0A0061646A7261E0 -:106CB0006E67650073686F772F7365742061646A0F -:106CC0007573746D656E742072616E676573207381 -:106CD000657474696E6773006175780073686F77A7 -:106CE0002F736574206175782073657474696E679D -:106CF0007300636D69780064657369676E206375FE -:106D000073746F6D206D6978657200636F6C6F725C -:106D100000636F6E66696775726520636F6C6F7272 -:106D20007300726573657420746F206465666175A5 -:106D30006C747320616E64207265626F6F7400649E -:106D4000756D70007072696E7420636F6E6669672E -:106D5000757261626C652073657474696E67732007 -:106D6000696E2061207061737461626C6520666F6A -:106D7000726D00657869740066656174757265008E -:106D80006C697374206F72202D76616C206F722095 -:106D900076616C006765740067657420766172695E -:106DA00061626C652076616C7565006770737061F7 -:106DB00073737468726F7567680070617373746859 -:106DC000726F7567682067707320746F20736572C7 -:106DD00069616C0068656C70006C656400636F6E5F -:106DE000666967757265206C656473006D6170001B -:106DF0006D617070696E67206F66207263206368D2 -:106E0000616E6E656C206F72646572006D69786585 -:106E100072206E616D65206F72206C697374006DF5 -:106E20006F746F72006765742F736574206D6F7473 -:106E30006F72206F75747075742076616C75650063 -:106E4000696E64657820283020746F2032290072C2 -:106E500061746570726F66696C6500736176650058 -:106E60007361766520616E64207265626F6F740075 -:106E70006E616D653D76616C7565206F7220626C28 -:106E8000616E6B206F72202A20666F72206C6973AE -:106E9000740073686F772073797374656D207374F1 -:106EA000617475730048204669726D776172652060 -:106EB000747970653A436C65616E666C6967687475 -:106EC0000A0048204669726D7761726520726576A6 -:106ED0006973696F6E3A25730A0048204669726DBE -:106EE0007761726520646174653A25732025730AA1 -:106EF0000048207263526174653A25640A00482094 -:106F00006D696E7468726F74746C653A25640A00FA -:106F100048206D61787468726F74746C653A25648A -:106F20000A0048206779726F2E7363616C653A308E -:106F30007825780A0048206163635F31473A2575F8 -:106F40000A00736572766F5B355D0031004820463C -:106F500069656C642049206E616D653A6C6F6F7075 -:106F6000497465726174696F6E2C74696D652C610A -:106F7000786973505B305D2C61786973505B315D6B -:106F80002C61786973505B325D2C61786973495B61 -:106F9000305D2C61786973495B315D2C6178697370 -:106FA000495B325D2C61786973445B305D2C61789C -:106FB0006973445B315D2C61786973445B325D2C8D -:106FC0007263436F6D6D616E645B305D2C72634301 -:106FD0006F6D6D616E645B315D2C7263436F6D6DBF -:106FE000616E645B325D2C7263436F6D6D616E64C4 -:106FF0005B335D2C6779726F446174615B305D2C2B -:107000006779726F446174615B315D2C6779726F6F -:10701000446174615B325D2C616363536D6F6F74A7 -:10702000685B305D2C616363536D6F6F74685B31B7 -:107030005D2C616363536D6F6F74685B325D2C6DA3 -:107040006F746F725B305D2C6D6F746F725B315D4E -:107050002C6D6F746F725B325D2C6D6F746F725B31 -:10706000335D2C6D6F746F725B345D2C6D6F746F5C -:10707000725B355D2C6D6F746F725B365D2C6D6F5E -:10708000746F725B375D0048204669656C64204907 -:10709000207369676E65643A302C302C312C312CAA -:1070A000312C312C312C312C312C312C312C312CF8 -:1070B000312C312C302C312C312C312C312C312CE9 -:1070C000312C302C302C302C302C302C302C302CDF -:1070D000300048204669656C642049207072656400 -:1070E0006963746F723A302C302C302C302C302C79 -:1070F000302C302C302C302C302C302C302C302CB0 -:10710000302C342C302C302C302C302C302C302C9B -:10711000342C352C352C352C352C352C352C350094 -:1071200048204669656C64204920656E636F646918 -:107130006E673A312C312C302C302C302C302C30E6 -:107140002C302C302C302C302C302C302C302C315E -:107150002C302C302C302C302C302C302C312C304E -:107160002C302C302C302C302C302C300048204649 -:1071700069656C64205020707265646963746F7215 -:107180003A362C322C312C312C312C312C312C3103 -:107190002C312C312C312C312C312C312C312C3305 -:1071A0002C332C332C332C332C332C332C332C33E7 -:1071B0002C332C332C332C332C3300482046696578 -:1071C0006C64205020656E636F64696E673A302C82 -:1071D000302C302C302C302C372C372C372C302CBA -:1071E000302C302C382C382C382C382C302C302C9F -:1071F000302C302C302C302C302C302C302C302CAF -:10720000302C302C302C300053797374656D205540 -:107210007074696D653A202564207365636F6E64D0 -:10722000732C20566F6C746167653A202564202AA0 -:1072300020302E31562028256453206261747465F5 -:107240007279290D0A004350552025644D487A2C47 -:107250002064657465637465642073656E736F7212 -:10726000733A200041434348573A202573002E25A6 -:1072700063004379636C652054696D653A20256429 -:107280002C20493243204572726F72733A20256474 -:107290002C20636F6E6669672073697A653A2025D2 -:1072A000640D0A004144584C333435004D50553676 -:1072B000303530004D4D413834357800424D413243 -:1072C0003830004C534D333033444C4843004D501C -:1072D0005536303030004D5055363530300046414F -:1072E0004B45004E6F6E65004759524F0041434376 -:1072F000004241524F004750532B4D4147006C6FA5 -:107300006F7074696D6500656D665F61766F696445 -:10731000616E6365006D69645F7263006D696E5FC5 -:10732000636865636B006D61785F636865636B00BC -:10733000727373695F6368616E6E656C00727373FC -:10734000695F7363616C6500696E7075745F66690F -:107350006C746572696E675F6D6F6465006D696EF0 -:107360005F7468726F74746C65006D61785F7468C7 -:10737000726F74746C65006D696E5F636F6D6D61C3 -:107380006E640033645F6465616462616E645F6C47 -:107390006F770033645F6465616462616E645F6827 -:1073A0006967680033645F6E65757472616C003381 -:1073B000645F6465616462616E645F7468726F7457 -:1073C000746C65006D6F746F725F70776D5F726162 -:1073D000746500736572766F5F70776D5F7261744C -:1073E000650072657461726465645F61726D0064EA -:1073F000697361726D5F6B696C6C5F7377697463DD -:107400006800736D616C6C5F616E676C6500666CC3 -:107410006170735F73706565640066697865647731 -:10742000696E675F616C74686F6C645F6469720039 -:1074300073657269616C5F706F72745F315F7363E3 -:10744000656E6172696F0073657269616C5F706F00 -:1074500072745F325F7363656E6172696F0073652A -:107460007269616C5F706F72745F335F7363656EB6 -:107470006172696F0073657269616C5F706F7274BD -:107480005F345F7363656E6172696F007265626F0E -:107490006F745F636861726163746572006D7370AD -:1074A0005F626175647261746500636C695F6261DB -:1074B000756472617465006770735F626175647290 -:1074C000617465006770735F706173737468726F65 -:1074D0007567685F62617564726174650067707377 -:1074E0005F70726F7669646572006770735F736254 -:1074F00061735F6D6F6465006770735F6175746F52 -:107500005F636F6E666967006770735F706F735F4C -:1075100070006770735F706F735F69006770735F8F -:10752000706F735F64006770735F706F73725F700A -:10753000006770735F706F73725F69006770735F6D -:10754000706F73725F64006770735F6E61765F70F7 -:10755000006770735F6E61765F69006770735F6E5E -:1075600061765F64006770735F77705F72616469F2 -:107570007573006E61765F636F6E74726F6C735FAC -:1075800068656164696E67006E61765F73706565DA -:10759000645F6D696E006E61765F73706565645FD0 -:1075A0006D6178006E61765F736C65775F72617490 -:1075B000650073657269616C72785F70726F76696D -:1075C0006465720074656C656D657472795F707264 -:1075D0006F76696465720074656C656D6574727947 -:1075E0005F7377697463680074656C656D65747248 -:1075F000795F696E76657273696F6E006672736B20 -:10760000795F64656661756C745F6C6174746974CC -:10761000756465006672736B795F64656661756C2D -:10762000745F6C6F6E676974756465006672736B06 -:10763000795F636F6F7264696E617465735F666FA3 -:10764000726D6174006672736B795F756E69740038 -:10765000626174746572795F636170616369747982 -:1076600000766261745F7363616C65007662617459 -:107670005F6D61785F63656C6C5F766F6C7461677A -:107680006500766261745F6D696E5F63656C6C5FE7 -:10769000766F6C746167650063757272656E745F96 -:1076A0006D657465725F7363616C6500637572729A -:1076B000656E745F6D657465725F6F666673657421 -:1076C000006D756C74697769695F63757272656E58 -:1076D000745F6D657465725F6F7574707574006149 -:1076E0006C69676E5F6779726F00616C69676E5F66 -:1076F00061636300616C69676E5F6D616700616CF7 -:1077000069676E5F626F6172645F726F6C6C00615B -:107710006C69676E5F626F6172645F7069746368E1 -:1077200000616C69676E5F626F6172645F79617737 -:10773000006D61785F616E676C655F696E636C692F -:107740006E6174696F6E006779726F5F6C7066004E -:107750006D6F726F6E5F7468726573686F6C6400D2 -:107760006779726F5F636D70665F666163746F7275 -:10777000006779726F5F636D70666D5F66616374D9 -:107780006F7200616C745F686F6C645F64656164E4 -:1077900062616E6400616C745F686F6C645F6661E7 -:1077A00073745F6368616E6765007961775F6465B4 -:1077B000616462616E64007468726F74746C655F9A -:1077C000636F7272656374696F6E5F76616C756505 -:1077D000007468726F74746C655F636F7272656356 -:1077E00074696F6E5F616E676C65007961775F6366 -:1077F0006F6E74726F6C5F646972656374696F6ECB -:10780000007961775F646972656374696F6E007493 -:1078100072695F756E61726D65645F736572766FB4 -:107820000064656661756C745F726174655F707227 -:107830006F66696C650072635F7261746500726384 -:107840005F6578706F007468725F6D69640074685A -:10785000725F6578706F00726F6C6C5F70697463D3 -:10786000685F72617465007961775F726174650049 -:107870007470615F72617465007470615F627265DB -:10788000616B706F696E74006661696C73616665C7 -:107890005F64656C6179006661696C736166655FE0 -:1078A0006F66665F64656C6179006661696C7361BF -:1078B00066655F7468726F74746C65006661696C8C -:1078C000736166655F6D696E5F75736563006661A0 -:1078D000696C736166655F6D61785F757365630080 -:1078E00067696D62616C5F666C6167730061636399 -:1078F0005F6861726477617265006163635F6C7079 -:10790000665F666163746F720061636378795F6458 -:1079100065616462616E64006163637A5F6465617E -:107920006462616E64006163637A5F6C70665F635A -:1079300075746F6666006163635F756E61726D6515 -:107940006463616C006163635F7472696D5F706929 -:10795000746368006163635F7472696D5F726F6CFA -:107960006C006261726F5F7461625F73697A650057 -:107970006261726F5F6E6F6973655F6C70660062E3 -:1079800061726F5F63665F76656C006261726F5FE4 -:1079900063665F616C74006D61675F6465636C69E9 -:1079A0006E6174696F6E007069645F636F6E74728C -:1079B0006F6C6C657200705F706974636800695FFA -:1079C000706974636800705F726F6C6C00695F72DD -:1079D0006F6C6C00705F79617700695F7961770027 -:1079E000705F70697463686600695F70697463686A -:1079F0006600645F70697463686600705F726F6CC4 -:107A00006C6600695F726F6C6C6600645F726F6CAD -:107A10006C6600705F7961776600695F796177668F -:107A200000645F79617766006C6576656C5F686F8E -:107A300072697A6F6E006C6576656C5F616E676CFB -:107A40006500705F616C7400695F616C7400645FF5 -:107A5000616C7400705F6C6576656C00695F6C6565 -:107A600076656C00645F6C6576656C00705F76654A -:107A70006C00695F76656C00645F76656C00002061 -:107A800020202020202020202828282828202020CE -:107A9000202020202020202020202020202020887E -:107AA00010101010101010101010101010101004E2 -:107AB0000404040404040404041010101010101032 -:107AC0004141414141410101010101010101010126 -:107AD000010101010101010101011010101010103C -:107AE00042424242424202020202020202020202F6 -:107AF0000202020202020202020210101010200012 -:107B00000000000000000000000000000000000075 -:107B10000000000000000000000000000000000065 -:107B20000000000000000000000000000000000055 -:107B30000000000000000000000000000000000045 -:107B40000000000000000000000000000000000035 -:107B50000000000000000000000000000000000025 -:107B60000000000000000000000000000000000015 -:107B70000000000000000000000000000000000005 -:107B80000000004B000000CB61636F7366000000D3 -:107B9000706F7766000000007371727466000000F9 -:107BA0000000000000C0153F00000000DCCFD13510 -:107BB0000000803F0000C03F000FC93F000F494058 -:107BC00000CB9640000FC9400053FB4000CB16414C -:107BD00000ED2F41000F49410031624100537B41CC -:107BE000003A8A4100CB9641005CA34100EDAF41D1 -:107BF000007EBC41000FC94100A0D5410031E241E7 -:107C000000C2EE410053FB4100F20342003A0A4237 -:107C10000083104200CB164200141D42005C234238 -:107C200000A5294200ED2F4200363642007E3C423C -:107C300000C74242000F4942A2000000F9000000C4 -:107C4000830000006E0000004E00000044000000B1 -:107C50001500000029000000FC00000027000000C3 -:107C600057000000D1000000F500000034000000C3 -:107C7000DD000000C0000000DB000000620000002A -:107C800095000000990000003C0000004300000047 -:107C90009000000041000000FE00000051000000C4 -:107CA00063000000AB000000DE000000BB0000002D -:107CB000C500000061000000B700000024000000C3 -:107CC0006E0000003A000000420000004D0000007D -:107CD000D2000000E00000000600000049000000A3 -:107CE0002E000000EA00000009000000D1000000A2 -:107CF000920000001C000000FE0000001D000000BB -:107D0000EB0000001C000000B10000002900000092 -:107D1000A70000003E000000E80000008200000014 -:107D200035000000F50000002E000000BB00000040 -:107D30004400000084000000E90000009C000000F6 -:107D40007000000026000000B40000005F0000008A -:107D50007E0000004100000039000000910000009A -:107D6000D60000003900000083000000530000002E -:107D700039000000F40000009C00000084000000B6 -:107D80005F0000008B000000BD000000F900000053 -:107D9000280000003B0000001F000000F800000069 -:107DA00097000000FF000000DE000000050000005A -:107DB000980000000F000000EF0000002F000000FE -:107DC000110000008B0000005A0000000A000000B3 -:107DD0006D0000001F0000006D0000003600000074 -:107DE0007E000000CF00000027000000CB00000054 -:107DF00009000000B70000004F000000460000002E -:107E00003F000000660000009E0000005F000000D0 -:107E1000EA0000002D0000007500000027000000AF -:107E2000BA000000C7000000EB000000E500000001 -:107E3000F10000007B0000003D0000000700000092 -:107E400039000000F70000008A0000005200000026 -:107E500092000000EA0000006B000000FB00000040 -:107E60005F000000B10000001F0000008D00000056 -:107E70005D00000008000000560000000300000044 -:107E80003000000046000000FC0000007B00000005 -:107E90006B000000AB000000F0000000CF0000000D -:107EA000BC000000200000009A000000F400000068 -:107EB000360000001D000000A9000000E3000000E3 -:107EC00091000000610000005E000000E60000007C -:107ED0001B00000008000000650000009900000081 -:107EE000850000005F00000014000000A0000000FA -:107EF00068000000400000008D000000FF0000004E -:107F0000D8000000800000004D0000007300000059 -:107F100027000000310000000600000006000000FD -:107F20001500000056000000CA00000073000000A9 -:107F3000A8000000C900000060000000E20000008E -:107F40007B000000C00000008C0000006B000000FF -:107F50000400000007000000090000000000C93F05 -:107F60000000F0390000DA370000A2330000842E50 -:107F70000000502B0000C2270000D0220000C41FC8 -:107F80000000C61B00004417000000000000304342 -:107F900000000000000030C36937AC316821223393 -:107FA000B40F14336821A2333863ED3EDA0F493F32 -:087FB0005E987B3FDA0FC93F28 -:087FB800B473FF7F010000001B -:107FC000000100000000803F0000000000000000F1 -:107FD0000100DC05DC05DC05DC05DC05DC05DC0579 -:107FE000DC05000000127A00000000000000000024 -:107FF0000102030406070809010303000000803F93 -:108000000000803F0000803F010100000000803F31 -:10801000000000000102030401020304060708092E -:10802000020406080100000000000000000000003B -:10803000000000000100000000000000000000003F -:108040000300000000000000000000000400000029 -:10805000000000000000000003000000056E0008A2 -:108060000F270000FFFFFFFF00A24A04CE670108B0 -:10807000536C01085F6C0108656C01086D6C0108A8 -:10808000756C0108786C0108806C01087E7A010823 -:1080900000000000000000000000000000000000E0 -:1080A00000000000000000000000000000000000D0 -:1080B000EF72010800000000000000000000000056 -:1080C00000000000000000000000000000000000B0 -:1080D00000000000000000000000000000000000A0 -:1080E0000000000000000000000000000000000090 -:0880F000D00000200100000097 +:100000003C318A4215D3C3F8F421D3F8FC615E4A2F +:100010005E4CC3F8F82133880B202361F6F708FC07 +:100020003388636105E0564A93689B0301D5FDF769 +:10003000CCF9DBF8F830052B03DD504B0022C3F878 +:10004000F820F6F71FFB4E4928608B892BB1DBF8AF +:100050000022821A002AC1F29182494A474C184470 +:100060005279DBF80C32CBF8000204F506700592E9 +:10007000DBF80452984704F5067001469BF81E22EF +:10008000F6F716F9424B1B88002B00F0A380D4F83A +:10009000203200271B7804F5097403933E463C4B3D +:1000A000B3F800903B4BB9F57A7F02D10022DA51C8 +:1000B0002261394A905FDA590244DA51FEF798FF1B +:1000C000236984460133012B236104D1002360603E +:1000D0002060A36028E022688DE808101146029293 +:1000E000FEF7D0FE009B82461846FEF781FF0146D0 +:1000F0005046FFF785F8029A01461046FEF7C4FE07 +:10010000DDF804C003461946606060460093FEF7C0 +:10011000B9FE01465046FEF7BFFFA168FEF7B4FEE8 +:10012000009BE0602360A0601B4A002302F1540A98 +:10013000B9F1010FB35226F80A30DFF854903CD1E0 +:100140002069012807DD0138FEF752FF0146E0680B +:10015000FFF756F800E0002002F00AFC039903467E +:10016000E1B108460093FEF743FF009B01461846A5 +:10017000FFF74EF990B14FF47A7329E0380100206F +:100180003420002030200020A4000020000C01407A +:10019000CC2700209803002050030020B24B4FF4DE +:1001A0007A72FB580A2003F5FA7393FBF2F32AF8EC +:1001B00006300F210122F6F757FB0236062E07F113 +:1001C000040704F114047FF46AAFB9F80030013B6E +:1001D000A9F800300023A54C04F5067204F51B7144 +:1001E000985A595A411A99520233062BF3D1D4F82E +:1001F000D03013F0020300F00583D4F8783204F510 +:100200002070984704F52070014694F88622F6F78E +:100210004FF8B4F8883204F52076002B3FD0002246 +:10022000D4F88C021346B8F88812914FB1F5C87F04 +:1002300004BF0021F95036F902E0F9588B4C7144A3 +:10024000F950043300210C2BB152815202F1020209 +:10025000E9D1B4F88832012B1CD1D4F890324FF494 +:10026000C872C83393FBF2F30380D4F89432C833D6 +:1002700093FBF2F34380D4F89832C83393FBF2F245 +:100280007C4B1B88D21A8280A5F85410A5F8561012 +:10029000FBF75AFBBBF88832013BABF88832764A51 +:1002A00093685F0776D5BBF89C22704B322A13D136 +:1002B000D3F88C221188A3F89E1251889288A3F853 +:1002C000A012A3F8A222B5F85420A3F8A422B5F8EE +:1002D0005620A3F8A62201E0002A39D00021DBF83D +:1002E0008C420A46B8F89C32644F322B04BF00237C +:1002F000BB5036F901E0B8585C4B7044B85004323A +:1003000000200C2A7052605201F10201EAD1B3F8C8 +:100310009C22012A17D183F8B522052283F8B62240 +:10032000B3F89E2283F8B4022280B3F8A022628040 +:10033000B3F8A222A280B3F8A422B3F8A632A5F89B +:100340005420A5F85630BBF89C32013BABF89C32E8 +:100350009BF8B722454BEAB1D3F8A802D3F88C1228 +:100360003224002290FBF4F083F8B7220880D3F8FF +:10037000AC0290FBF4F04880D3F8B03293FBF4F475 +:100380003C4B1B88E41A8C80A5F85420A5F8562015 +:10039000FBF7DAFADBF88C32BBF880121A880025FA +:1003A0008A1AABF88022BBF882125A88AA468A1AA7 +:1003B000ABF882229B88BBF88422D31AABF8843234 +:1003C000F6F760F9DBF8B8320446C31A184603930F +:1003D000FEF70AFEDBF8BC120690FEF75DFEDBF8C6 +:1003E000C072CBF8B8423B78079004932C46244E59 +:1003F0000DF12408305FFEF7FBFD0799FEF74CFE78 +:10040000049A48F80500002A3CD01046FEF7F0FD9B +:1004100001464FF07E50FEF7F3FE0346194606F103 +:10042000AC094FF07E500093FEF72CFD55F80910F3 +:10043000FEF732FE06F168028446105FCDF804C074 +:10044000FEF7D6FD009BB8361946FEF725FEDDF80F +:1004500004C001466046FEF717FD49F80500FEF7A7 +:10046000E1FF305313E000BF980300203801002063 +:10047000C80300200000002034200020E0030020FA +:100480005003002006F1B8036836A25BE252AA4886 +:100490000435235E0234062C03FB03AAA7D1642390 +:1004A00003FB0AFAA54B08301B8809A95B439AFB9A +:1004B000F3FAAAF1490A1FFA8AFAF4F7FBFABAF139 +:1004C0003B0F7C6810D9BBF9E402FEF791FDDBF825 +:1004D000E04201462046FEF79BFF994D9BF8E6322D +:1004E00040B343F0080327E04FF07E512046FEF76B +:1004F000CBFC01464FF07E50FEF782FE00260546FB +:10050000DFF85892204659F81610FEF7C5FDA9F1FC +:1005100008038246985FFEF76BFD01465046FEF7E2 +:10052000B3FC2946FEF7B8FD49F816000236062E40 +:10053000E6D1C8E723F008032146DBF8DC0285F8A2 +:10054000E63202F08BF80546CBF8E802DBF8D80279 +:10055000DBF8E09200F10044DBF8DC020146FEF734 +:100560009BFD494606464846FEF796FD0146304645 +:10057000FEF78AFC02F0FCF90146204602F06EF814 +:1005800070490446CBF8EC022846FEF785FD01F0E1 +:1005900099FF6C49ABF8F0022046FEF77DFD01F0B3 +:1005A00091FFDBF8D030ABF8F2021E073BD566486E +:1005B00009A9F4F77FFAD7F808804FF07E5140463A +:1005C000FEF762FC01464FF07E50FEF719FE4FF039 +:1005D000000A81465A4E404606F53D7353F81A10FC +:1005E0000093FEF759FD06F54072844632F90A0081 +:1005F000CDF804C0FEF7FCFCDDF804C001466046FF +:10060000FEF742FC4946FEF747FD009B43F81A00FF +:100610000AF1020ABAF1060FDCD11846F4F702FB20 +:10062000A6F8060342E0DFF81491414609F1040000 +:10063000F4F740FAD9F80400D9F808A00146FEF70B +:100640002BFD514680465046FEF726FD01464046AA +:10065000FEF71AFCD9F80C60804631463046FEF7AA +:100660001BFD01464046FEF70FFC02F081F9002118 +:100670000646FEF7A5FEA0B9D9F804003146FEF7FC +:10068000BFFD3146C9F80400D9F80800FEF7B8FDEF +:100690003146C9F80800D9F80C00FEF7B1FDC9F8D9 +:1006A0000C002A48F4F7BEFAABF80603284906986E +:1006B000FEF7F2FC04F10044064605F10045BBF9E3 +:1006C00006030D940C95FEF793FC224900F10040BF +:1006D000FEF7E2FC0E90BBF9D002FEF789FC109009 +:1006E000BBF9D202FEF784FC1190BBF9D402FEF7ED +:1006F0007FFC0CA9129010A8F4F7DCF97B78104C61 +:10070000012B2DD1144B1B785D070ED4D4F8083380 +:10071000402093FBF0F0181AFEF76AFC1299FEF7DE +:10072000B3FBFEF77FFEC4F80803054BD3F80803BC +:10073000402390FBF3F015E00804002000000020A7 +:10074000380100204C3D0F442C0400200400002000 +:10075000BD37863535FA8E3CD527002010040020A1 +:10076000A94B1888FEF744FC01461298FEF78AFB55 +:10077000DBF8101312903046FEF786FB0146304638 +:10078000FEF73EFDDBF80C43054621461298FEF7C6 +:1007900079FB01462846FEF77FFC01462046FEF71E +:1007A00073FB0546CBF80C031098DBF8146301F0DB +:1007B00089FEDBF820432178F4F7CEFB3044CBF8F8 +:1007C00014031198DBF8186301F07CFE2178F4F72C +:1007D000C3FB3044CBF818032846DBF81C6301F058 +:1007E00071FE6178F4F7B8FB884B03991A683044BE +:1007F0000A441A60DBF82433CBF81C030133CBF82E +:10080000243305E0A4F88032A4F88232A4F88432BC +:100810007F4CB4F818322746A4F82833B4F81A32BB +:10082000A4F82A33059B012B0ED1B4F92E23B4F979 +:100830001C3203EB4203032293FBF2F39BB2A4F8B6 +:100840002C33A4F82E3303E0B4F81C32A4F82C3374 +:10085000F5F718FF6F4B01261860D4F83433C4F84D +:100860003403C31AA4F83033F2F762F8D4F8D43062 +:10087000674D13F4801384F8CC6000F08D80B5F8D8 +:10088000D830180600F1EA80634B1B78590770D501 +:1008900095F838235C4B12B195F839233AB1002210 +:1008A000C4F83C2301221A74002284F839231B7CEB +:1008B000D4F80452032B95F80090554E05F1040826 +:1008C00084F8383306D1404606F550714C2201F0C9 +:1008D0008BFB44E0012B07D106F5507041464C22BA +:1008E00001F082FB002302E0022B02D1012386F8F3 +:1008F0008C3301238BF88D338BF88E330023CBF8A8 +:100900009033CBF89433454A9BF88C33CBF89883DB +:1009100013441B7C424A1D448BF89D33CBF83C2387 +:1009200028798BF89C93FEF763FB3E49FEF768FC41 +:10093000CBF8A003A87BFEF75BFB3B49FEF760FC0E +:10094000CBF8A403287EFEF753FB3849FEF7A4FB3F +:10095000CBF8A803FEF78CFD00232876AB73B4F820 +:10096000D83043F08003A4F8D830012384F8AC33A6 +:1009700074E04FF00008D5F83C034146FEF720FD37 +:10098000814600286AD1FAF7DFFF1F4BC5F83C8388 +:1009900085F838931E7461E0B5F8D8A01AF0800F7E +:1009A00051D095F83823DFF86080511E012924D8F2 +:1009B0001D49D5F8A403FEF76FFBFEF759FDD5F8E6 +:1009C000986395F89D931A49B14489F80A00D5F8BF +:1009D000A803FEF761FBFEF74BFD89F814003078A1 +:1009E000FEF706FB0146FEF74FFAFEF741FDB37A2C +:1009F000B0703373337DB3751CE0032A1AD185F8C8 +:100A0000383388F810601AE000000020C827002062 +:100A100038010020C4270020D5270020684601089F +:100A20000000A0410000204100007A445555553F88 +:100A30009A99993F98F81030013388F810302AF0CD +:100A4000800AA4F8D8A0944B1B785A0706D494F8CF +:100A5000AC331BB1914B012283F83923D4F8D090E9 +:100A60008E4A19F0080F8E4E38D0B2F8EA1001F114 +:100A700045039BB28A2B2DD8B2F8D8305B0729D515 +:100A8000B2F80603B2F8AE3394F8E652C21A92B244 +:100A900093B218B2B330BCBF02F5B4739BB21AB2B2 +:100AA000B32AC4BFA3F5B4739BB22D0796F8EC002C +:100AB0007A4A13D540B240424343D2F804021BB2F3 +:100AC000007B43436FF01D0093FBF0F31944A2F841 +:100AD000EA1003E0B4F80633A4F8AE3319F0140FAB +:100AE0007ED0B4F8D8206D4B02F40272002A77D081 +:100AF00093F8E62202F0100202F0FF0052B1B3F8C0 +:100B0000E81096F92701D3F8F42000FB0212A3F8AD +:100B1000E82065E0D3F8B023D178927881B3B3F8B8 +:100B2000ECE0B3F9E4100FFA8EF5C1EB050CBCF163 +:100B3000000FB8BFCCF1000C94450FDD8D42C8BF4B +:100B400052421FFA8EFEC8BF92B2C3F8F000724440 +:100B5000012083F8B403A4F8EC2041E093F8B42317 +:100B60002AB1D3F8E02083F8B403C3F8DC20D4F82A +:100B7000F430D4F8B823194413885288994228E0F5 +:100B8000B3F9E450B3F9EC00401B80EAE07EAEEB31 +:100B9000E07E96450ADD022290FBF2F0414A1060A9 +:100BA000012283F8BC2383F8B4230AE093F8B4232A +:100BB0003AB1D3F8E00083F8BC13C3F8DC0083F843 +:100BC000B413D4F8B813D4F8F4200B882A44498815 +:100BD0009A4203DB8A42B4BF13460B46A4F8EC30BA +:100BE000D4F804822D4D98F864210392002A64D031 +:100BF000B5F8D830990760D0D5F8D802B5F8EC3000 +:100C0000D5F8DC220146D5F8E0A204930292FEF763 +:100C100043FA029A0346114610460093FEF73CFA47 +:100C2000009B01461846FEF72FF9514603465046F1 +:100C30000093FEF731FA009B01461846FEF724F9AF +:100C400001F096FE01465046FEF7DAFA1649824652 +:100C5000FEF7CAFB60BB504601F0B0FCD5F8C013EC +:100C6000FEF71AFA01F02EFCB0F5617FA8BF4FF431 +:100C70006170FEF7BDF90D49FEF7C2FA01F060FCA4 +:100C800005460398FEF7B4F92946FEF705FA01F088 +:100C900019FC80B20DE000BFD527002038010020EC +:100CA00034200020D02700208FC2753CEFB6B0441E +:100CB0000020049A1044A4F8EC0019F0200F0BD087 +:100CC000B4F8D83003F0300333B1A54B93F8E632D3 +:100CD000DA0701D5F5F79AF8A24B08F104001D6870 +:100CE000D4F8C41308F15403B6F8F620A847FBF76C +:100CF00095FDD4F8C833002B4BD0994B93F8CC33E7 +:100D0000013B142B40D8DFE803F00B3F3F27423F65 +:100D10003F1F3F3F3F3F3F2F3F3F3F3F3F272F007A +:100D2000D4F8D0335B782BB18F4B0020998BF4F73C +:100D30009CFB2EE08D4B1B7803F0040303F0FF00B7 +:100D4000002BF1D10146F2E7874D0020298BF4F703 +:100D50008CFB0120698BEAE7834D0020698BF4F757 +:100D600084FB0120A98BE2E77F4D0020298BF4F75B +:100D70007CFB0120698BF4F778FB0220A98BF4F748 +:100D800074FB0320E98BD2E7B3689B0601D5F5F726 +:100D900071FFFBF7F3FC764B1B78002B40F0EE83E2 +:100DA000B268150340F1EA8394F8D433023B042B74 +:100DB00000F2E483DFE813F0070032000500B00022 +:100DC0000B0110258FE06B4B1A68D4F8D8336433CD +:100DD0009A4240F2D3831025674BD7F8DC23604E4C +:100DE0001A44907C984648B1F5F75AFED6F8DC23B1 +:100DF000013D02F10102C6F8DC23EDD1D4F8DC2379 +:100E0000574B4244927C002A40F0B883032183F878 +:100E1000D413C3F8DC23C3F8E023AFE3D4F8DC53E6 +:100E2000564B052D93F800A04D4B4AD8DFF848816A +:100E3000CAF1080908EB8503D3F8880001F01EF910 +:100E4000002D14BF0223092309FB1309D4F8E05332 +:100E5000D7F8E0330F33AB4202DA4D452ED10DE027 +:100E60004D45FADA3E4BD3F8DC3308EB8303D3F875 +:100E70008830585DF5F714FE0135E9E77379012BE9 +:100E80000BD00A20F5F70CFED4F8DC330133C4F89C +:100E9000DC330023C4F8E03370E32C20F5F700FEC8 +:100EA000D4F8DC3308EB8303D3F8A050013D15F8E8 +:100EB000010F0028E5D0F5F7F3FDF8E7C4F8E0539B +:100EC0005CE310064CBF0422052283F8D4230023E0 +:100ED0007AE0F5F7E5FDD6F8DC23013D02F10102E9 +:100EE000C6F8DC2309D0244BD7F8DC231C4E1A4467 +:100EF00092F8B80098460028EBD1D4F8DC23184BC0 +:100F0000424492F8B820002A40F03883052183F843 +:100F1000D413C3F8DC2331E3D4F8DC330B2B4DD8E6 +:100F2000DFE803F0064F0A4F0D4F133C4044484F93 +:100F30001348FBF7D7F944E0124813490DE0134872 +:100F40001349144AFBF7CEF93BE096F854370A22CE +:100F500002FB0366104896F85617FBF7C3F930E01A +:100F6000380100209C00002000000020D527002030 +:100F7000D42700203020002068460108E727002001 +:100F8000C4620108E1620108F96201080163010815 +:100F900018630108246301082D630108C648B6F8E8 +:100FA000D010DAE7C548B6F8D210D6E7C448D4F86E +:100FB0001412D2E7C34BC4481988CEE7062384F83D +:100FC000D433D4F8DC330133C4F8DC33D6E2D4F8BC +:100FD000E433BE4F13F01F020393049240F090805D +:100FE000F3F7D2FFD7F8E8534920F5F759FDD7F8C2 +:100FF000E403F5F75BFD2868F5F758FD6868F5F739 +:1010000064FDA868F5F761FDE868F5F75EFD2869FD +:10101000F5F75BFD6869F5F758FDA869F5F755FD2B +:10102000E869F5F752FD286AF5F74FFD686AF5F7AC +:101030004CFDB5F92800F5F748FDB5F92A00F5F79C +:1010400044FDB5F92C00F5F740FDA149B5F92E0096 +:10105000B1F8D0300127C01AF5F728FDB5F93000F6 +:10106000F5F733FDB5F93200F5F72FFDB5F934008A +:10107000F5F72BFDB5F93600F5F727FDB5F9380082 +:10108000F5F723FDB5F93A00F5F71FFD904AB5F9DC +:101090003C00B2F8D030C01AF5F708FD8D4B1B7834 +:1010A0009F420ADA05EB4703B3F93C00B5F93C303F +:1010B0000137C01AF5F709FDF0E77379012B07D165 +:1010C000D4F8E833B3F95E00A0F2DC50F5F7FDFC8C +:1010D000DBF8E833804A8149CBF8EC33CBF8F033C6 +:1010E0009B1A9B104B430321013393FBF1F101EB5E +:1010F00041015B1A642101FB0322CBF8E82338E2AB +:1011000096F87437049996F875271944013991FBBC +:10111000F2F002FB10129A4280F2DF81F3F734FF03 +:101120005020D7F8E893D7F8EC83F5F7B9FCD7F857 +:10113000F023D7F8E83310681B6800251844D7F867 +:10114000EC331B68A0EB4300F5F7BFFC09EB05028D +:1011500008EB050350685B680435C01AF5F7B5FC69 +:101160000C2DF3D1002309EB030108EB03020969FD +:1011700012690CAD8A1A5A5104330C2BF3D1002298 +:101180001346A95801F120003F2820D801F108009A +:101190000F2806D80231032904D9002B08BF0123E8 +:1011A00000E0022304320C2AEBD1012B0C9813D05F +:1011B000022B1FD00D9B00F0030003F003039B00E4 +:1011C00043EA00100E9B03F0030318431EE00EAA2F +:1011D0000BA84FF0000A1DE000F00F0040F04000A7 +:1011E000F5F75EFC0E9B03F00F020D9B42EA031025 +:1011F000C0B20BE000F03F0040F08000F5F750FC7B +:101200009DF83400F5F74CFC9DF83800F5F748FCE4 +:10121000002765E052F804194FEA8A0A01F18007B5 +:10122000FF2F10D901F50047B7F5803F02D24AF0F1 +:10123000010A08E001F50001B1F1807F34BF4AF0F6 +:10124000020A4AF0030A8242E4D16AF03F00C0B2C7 +:10125000F5F726FC00270AF00302022AE85D09D010 +:10126000032A12D0012A1ED1F5F71AFCE859C0F35F +:10127000072018E0F5F714FCE859C0F30720F5F74C +:101280000FFCE859C0F307400DE0F5F709FCE859F9 +:10129000C0F30720F5F704FCE859C0F30740F5F761 +:1012A000FFFBE859000E0437F5F7FAFB0C2F4FEA65 +:1012B000AA0AD0D1ACE700BF3A6301084C63010829 +:1012C0005E630108000000207163010838010020FE +:1012D00034200020E72700202C050020295C8FC245 +:1012E00009EB070208EB0703D069DB690437C01A72 +:1012F000F5F7EBFB0C2FF3D1002309EB0302B2F956 +:10130000281008EB0302B2F928208A1A45F81320A6 +:101310000233082BF1D1864B10AF03F1100E186881 +:1013200059683A4603C2083373451746F7D10FAAE6 +:101330000BA8002352F804199B00DBB269B101F13C +:1013400008070F2F02D843F0010306E08031FF2980 +:1013500094BF43F0020343F003038242EAD114A98D +:1013600001EB131203F00F030B4412F8107C13F877 +:10137000103C4FF0000A43EA0717FFB23846F5F772 +:101380008FFB07F00302022A15D0032A19D0012A85 +:1013900021D114AB03EB8A0252F8200C52F81C1C2A +:1013A00000F00F0040EA0110C0B2F5F779FB0AF136 +:1013B000010ABF080FE014A901EB8A0212F8200C01 +:1013C00007E015F82A00F5F76BFB55F82A00C0F383 +:1013D0000720F5F765FB0AF1010ABAF1030F4FEA9E +:1013E0009707CEDD0027534D07F11803D5F8E82302 +:1013F000013732F91300D5F8EC2332F91310D5F880 +:10140000F02332F9133002220B4493FBF2F3C01A9B +:10141000F5F75BFB032FE6D10027D5F8E82307F1AA +:1014200018035B001A44B2F90600D5F8EC23013723 +:101430001A44B2F90610D5F8F0231344B3F9063074 +:1014400002220B4493FBF2F3C01AF5F73EFB032F85 +:10145000E3D10027384B1B789F421ADAD5F8E823EE +:1014600007F11C035B001A44B2F90400D5F8EC2321 +:1014700001371A44B2F90410D5F8F0231344B3F934 +:10148000043002220B4493FBF2F3C01AF5F71DFB64 +:10149000E0E72A4B5B79012B06D1B9F95E00B8F978 +:1014A0005E30C01AF5F711FBD5F8EC33D5F8E82318 +:1014B000C5F8F033224B2349C5F8EC23D21A921019 +:1014C0004A430321013292FBF1F101EB4101521A2F +:1014D000642101FB0233C5F8E833B368190648D527 +:1014E000D4F82015D4F82825124B91420CD1D3F80A +:1014F0002425D3F82C359A4206D1049A102A23D1F8 +:10150000039B13F47E6F1FD14820F5F7C9FAD4F876 +:101510002005F5F7DAFAD4F82405F5F7D6FAD4F869 +:101520002035C4F82835D4F82435C4F82C351EE00D +:101530002D48010838010020E72700203420002032 +:101540002C050020295C8FC294F83C1594F83825AE +:10155000CB4B91420BD1D3F84015D3F830259142B3 +:1015600005D1D3F84425D3F834359A4201D0F5F7A4 +:10157000B0FAD4F8E4330133C4F8E433C14BC04CBF +:101580001B78DFF82083002B40F09582D8F80830D4 +:101590005A0540F1908294F84835002B00F08B8278 +:1015A000F3F74CFD002800F0868294F84935002BB3 +:1015B00000F08182D4F84C351B78002B40F00F826C +:1015C000D4F85005F5F7ACF9002840F00882AE4F8A +:1015D000D4F854253B689A1A7C2A40F20082C4F859 +:1015E000543594F858350546013384F8583505F1DB +:1015F0002400A34EC0B2F5F7BDFA06F5347333F9F3 +:101600001500FDF7F5FCA14B81461888FDF7F0FCAD +:1016100001464846FDF7F4FD9D49FDF73DFDFDF708 +:1016200001FF013500B2F5F7D1FA032DDFD13020EB +:10163000F5F7A0FAB6F95C05F5F7C8FAF5F7A8FAD8 +:1016400096F858359B0716D1D6F8542541F28833C1 +:101650009A4201D9F5F7C5FA1420F5F78BFAB4F9D7 +:101660000603F5F7B3FA1C20F5F784FA0020F5F726 +:10167000ADFAF5F78DFA94F85835814D5E0740F0D4 +:1016800089810220F5F776FAD5F8203164223233C9 +:1016900093FBF2F000B2F5F799FA0320F5F76AFA36 +:1016A0007C4B1B7813F0040F4FF0050304D0B5F901 +:1016B000EC0090FBF3F005E0D5F860255289B2FB11 +:1016C000F3F000B2F5F782FAD8F80830980764D53D +:1016D000714D9BF864252B7840F63401B2FBF3F290 +:1016E0004A432A21B2FBF1F2BBF86615062091FBB2 +:1016F000F3F603FB16163601B6B246EA0226B6B278 +:10170000C2F303221643F5F735FA30B2F5F75EFA65 +:10171000BBF866252B78013292B292FBF3F103FB02 +:101720001123ABF866359BF864356E255D431523B0 +:1017300095FBF3F53A204FF06409F5F71BFAB5FB7A +:10174000F9F63046F5F742FA3B20F5F713FA09FBB4 +:10175000165080B20A26053090FBF6F000B2F5F77D +:1017600035FA2820F5F706FADBF8680590FBF6F065 +:1017700000B2F5F72BFA0420F5F7FCF9DBF8603539 +:101780005B8913B1F4F7F4FA04E03D4BD3F86C0530 +:1017900080F3100000B2F5F719FAD4F8D030384DC4 +:1017A000990640F18B8095F8E6329A071AD51120F8 +:1017B000F5F7E0F9B5F87005FDF750F82CA3D3E97B +:1017C0000023FDF7B1F80022344BFCF7FBFEFDF7D8 +:1017D000BDFA00B2F5F7FAF91920F5F7CBF90020B8 +:1017E000F5F7F4F994F8E632B4F8725513F0020FF5 +:1017F00008BF00250120F5F7BDF928B2F5F7E6F995 +:101800000920F5F7B7F90020F5F7E0F9244B94F833 +:101810003C551B88B3F5967F0BD9194A92F8582589 +:1018200002F00F02072A04D842F20F75AB42B8BF8C +:101830001D460520F5F79EF9D4F874355B7B0BB98E +:1018400028B239E0A5F12000FDF708F80AA3D3E992 +:101850000023FDF793F9FDF7C1FA00210546FDF7D6 +:10186000B9FD08B34FF03F4120E000BFAFF3008067 +:101870007B14AE47E17A843FCDCCCCCCCCCCFC3FC2 +:1018800038010020D4270020302000200000002054 +:1018900000007A44D5270020980000200000E03F97 +:1018A000A0000020342000204FF07C512846FDF796 +:1018B000EBFAFDF7B7FD00B2F5F788F9D4F8D030B0 +:1018C0009B060ED4BC4B0021D3F874556868FDF715 +:1018D00077FD00285CD1A8680021FDF771FD002884 +:1018E00056D194F8E622B44B960703D493F87825A2 +:1018F000012A07D10123D4F84065D4F8445584F86F +:1019000078350FE0D3F87455AC496868FDF7C4FB2F +:10191000FDF788FDA9490646A868FDF7BDFBFDF760 +:1019200081FD054610A93046F3F7B0FB1320F5F70B +:1019300021F9BDF94000F5F749F91B20F5F71AF92F +:10194000BDF94200F5F742F92320F5F713F9002E0F +:10195000ACBF4E205320F5F739F910A92846F3F70C +:1019600095FB1220F5F706F9BDF94000F5F72EF9C1 +:101970001A20F5F7FFF8BDF94200F5F727F9222004 +:10198000F5F7F8F8002DACBF45205720F5F71EF904 +:10199000F5F7FEF894F85835282B20D1864B002215 +:1019A0003F6883F858254FF47A73B7FBF3F73C256B +:1019B0001720F5F7DFF8B7FBF5F6B6FBF5F005FBFA +:1019C0001060000200B2F5F701F91820F5F7D2F81F +:1019D00005FB167000B2F5F7F9F8F5F7D9F8D4F869 +:1019E0004C351B78012B01D1F7F703FDD4F84C35AA +:1019F000714D1B78022B1CD1D5F87C35CBB1C5F8C5 +:101A000080351B686E4AC5F88435D5F8883513448F +:101A100093F8D501F8F76CFED5F880359879F4F78E +:101A200096FFD5F888350133092B88BF0023C5F808 +:101A30008835F3F755FB00283DD094F88C35013BF1 +:101A4000012B38D8D4F89005F4F76AFF5A4D5D4E53 +:101A5000D8B1D5F89005F4F75EFF95F89425336872 +:101A60007E2A0FD102221B2885F88C25C5F89835CF +:101A700005D00D2803D0342801D0672802D10123D6 +:101A800084F89C3584F89405DCE73368D5F898250C +:101A900041F658319A1A8A4203D9032385F88C35C6 +:101AA00009E0D5F8A0259B1A042B04D995F89C359C +:101AB0000BB1F8F70FFAD8F80830DD037EF5C5A8AA +:101AC00094F8A4353C4D002B3EF4BFA83E4B1B7848 +:101AD000002B7EF4BAA8F4F7D5FDD5F8AC35D5F8CF +:101AE000A875C31A6FEA030AD5F8B035C71BC3EB54 +:101AF00000096FEA0909FF434FEAD9790646FF0F4B +:101B00004FEADA7AB9F1000F05D1BAF1000F02D12C +:101B1000002F3EF49AA84FF0000B94F838365FFA85 +:101B20008BF59D42DFF890C062D22849DCF8B435CD +:101B3000AA00096813446244C2F8B8155988C80558 +:101B40000BD48B0535D5224B1B785D0754BF1C4B3E +:101B5000204B1B68C2F8B8352BE019461E4A2846B0 +:101B60008DE80810FBF77EF9DDF804C0009BBCF897 +:101B7000D82012F0400F03D028461946174A16E025 +:101B8000500703D528461946154A10E0110703D51A +:101B900028461946134A0AE0900703D528461946F5 +:101BA000114A04E0D10704D5104A28461946FBF72C +:101BB00059F90BF1010BB0E7380100208096184B62 +:101BC0006846010830200020CE270020C0620108AE +:101BD000D527002074460108474801084D480108F0 +:101BE00053480108594801085F4801086548010841 +:101BF0009D000023AB421FD0D4F8B425B3491A444A +:101C00005288520516D501F5B762D0580890B1F93F +:101C100040067821A0F57A7048434FF47A7190FB22 +:101C2000F1F000F22B1040F2671190FBF1FE01FB86 +:101C30001E0199520433DDE7B9F1000F2CD006F5EF +:101C4000C333A033C4F8B03594F85E369F4D1BBB48 +:101C500085F85F36D8F808309B0705D5F4F7E0FB28 +:101C600010B1012385F85F36D4F86036974D1B68B4 +:101C70009B68984728B195F85F3643F0020385F8D2 +:101C80005F36934B1B7813F0050F05D194F85F3640 +:101C900043F0040384F85F3694F85F2622B98B4B37 +:101CA00093F85E36002B4ED094F85E1611F0010FBB +:101CB000A1F10C001AD1032906D8864B864D12F0EB +:101CC000040F18BF2B4600E0824B0439072904D8C3 +:101CD000824912F0010F18BF0B46C0B2032810D87A +:101CE0007F4912F0020F18BF0B460AE0C0B203286A +:101CF00006D8784B7B4912F0020F18BF0B4600E064 +:101D0000744B002194F83806CDB2A842DFF8BCE14C +:101D10000CD9DEF8B405AD0028444088000603D590 +:101D200018687544C5F8B8050131EBE7B9F1000F43 +:101D300013D05AB194F85E26644B0132D2B2142A01 +:101D400009D1002207E0B9F1000F06D094F85E3601 +:101D5000002BEFD101E083F85E26BAF1000F23D00B +:101D6000B4F9E830B4F9E6203221002AB8BF524273 +:101D7000002BB8BF5B4293FBF1F392FBF1F1DBB2B6 +:101D8000C9B28B4238BF0B46574A0BB192FBF3F2F4 +:101D90003244C4F8AC2594F864264C4B0AB90122AD +:101DA00000E0002283F8642694F86426474B22B9A9 +:101DB0004E4AC3F8682600200CE0464AF9E7D3F8FB +:101DC000B415950001EB050EBEF802E01EF0400FC1 +:101DD00007D1013094F83816C2B291423B4BEED88D +:101DE000B2E0B3F9E6E0BEF1190F22DD11F822C02E +:101DF00093F86C860CF00F09C145D3F868E609DC4E +:101E000093F86D86B8EB1C1F04DC2B44DEF8005001 +:101E1000C3F8B85511F8225094F86EC605F00F08B3 +:101E2000E0452A4B30DB93F86DC6BCEB151F2BDC6D +:101E300024E01EF1190F27DA11F822C093F86C86FE +:101E40000CF00F09C145D3F868E609DC93F86F86FA +:101E5000B8EB1C1F04DB2B44DEF80050C3F8B85568 +:101E600011F8225094F86EC605F00F08E045174BA4 +:101E70000ADB93F86FC6BCEB151F05DBDEF80050DC +:101E800003EB8203C3F8B855B4F9E8500F4B192D92 +:101E90002EDD11F822C093F86CE60CF00F08F04527 +:101EA000D3F868560ADC93F86D86B8EB1C1F05DC86 +:101EB000D5F800C003EB8203C3F8B8C511F822308F +:101EC00003F00F01714532DD83E700BF38010020C8 +:101ED000D5270020C0620108684601086C46010849 +:101EE0007046010874460108400D03006C48010863 +:101EF0001935BFF66EAF11F822C093F86EE60CF0FC +:101F00000F08F045D3F868560ADB93F86D86B8EBF6 +:101F10001C1F05DCD5F800C003EB8203C3F8B8C56D +:101F200011F8223003F00F017145FFF652AF94F81B +:101F30006F16B1EB131FFFF64CAF294B03EB820278 +:101F40002B68C2F8B83544E7E7B193F8712693F8E7 +:101F5000701606F543468818013890FBF2F402FB30 +:101F6000140083F87316013183F8720691FBF2F0C6 +:101F700002FB10125036D2B2C3F8A86583F874265B +:101F800083F87026F3F75AFDFDF75FBECB067EF5AA +:101F900058A8DBF8D420124B920207D4B3F8D8200B +:101FA00022F40072A3F8D820FEF74BB8B3F8D8108B +:101FB00001F4007292B2002A7EF443A841F4007149 +:101FC000A3F8D810D3F8E010C3F8F020C3F8DC1061 +:101FD000B3F8EC10C3F8F420A3F8E410FEF731B81E +:101FE00038010020AFF3008010B50023934203D0E6 +:101FF000CC5CC4540133F9E710BD0244034693425C +:1020000002D003F8011BFAE7704700000D4B70B5D2 +:102010001D680022845C2B195B7803F00303012BFD +:102020008B5C08BF2034EE18767806F00306012E8C +:1020300008BF2033E41A02D10132002BEAD1204636 +:1020400070BD00BFCC00002010B5044622461378B6 +:102050000134002BFAD1CC5CD4540133002CFAD1DA +:1020600010BDC9B2024610F8013B1BB18B42F9D139 +:10207000104670470029FBD018467047034613F8F6 +:10208000012B002AFBD1181A013870470F4BF0B50D +:102090001E680023934215D0C55C7419647804F05F +:1020A0000304012CCC5C08BF203537197F7807F07A +:1020B0000307012F08BF20342D1B04D10133002C4E +:1020C000E8D100E000252846F0BD00BFCC0000208C +:1020D00010B5034632B111F8014B013A03F8014B38 +:1020E000002CF7D11A44934203D0002103F8011BBE +:1020F000F9E710BD30B503780BB1044604E00B7866 +:10210000002B18BF002030BD22461078013438B1B2 +:102110000023C85C28B1D55C8542F5D10133F8E7CE +:1021200030BD104630BD00210A2200F001B92DE972 +:10213000F04E82468B461F46144612B90020BDE879 +:10214000F08E002BFAD00026A642F7D2A5196D0812 +:1021500007FB05B950464946089B9847002802DB13 +:1021600003D06E1C25462C46EEE74846BDE8F08EAF +:10217000174B2DE9F0411D680646AC6D0F46FCB9C2 +:10218000502000F0E3F8A8658460AB6D0460446003 +:102190001C61DC60AB6D9C615C61AB6DDC629C6260 +:1021A000AB6D5C631C63AB6DDC639C63AB6D5C64AB +:1021B0001C64AB6DDC649C64AB6D1C77AB6D5C62C6 +:1021C00030463946AA6D0123BDE8F04100F002B85F +:1021D00030010020F0B508B9106828B3044614F89F +:1021E000015B0F4617F8016B3EB1B542FAD10BB156 +:1021F0002046F3E714600370F0BD4DB91560284622 +:10220000F0BD17F8016BAE4207D0002EF9D11C4685 +:10221000234613F8015B0F46F3E715B10021217047 +:1022200000E02B461360F0BDF0BD000084463F483F +:102230002DE9F04FD0F800800E46344614F8015BCB +:1022400008EB0500407800F0080000F0FF0708B137 +:102250002646F2E72D2D03D1B41C7578012703E043 +:102260002B2D04BF7578B41C33F010000DD1302D28 +:1022700008D1207800F0DF00582851D1657810236C +:10228000023402E0002B08BF0A23002F0CBF6FF0BE +:10229000004A4FF0004ABAFBF3F903FB19AA0026E3 +:1022A000304608EB050B9BF801B01BF0040F01D082 +:1022B000303D0BE01BF0030B1BD0BBF1010F14BF33 +:1022C0004FF0570B4FF0370BCBEB05059D4210DA63 +:1022D000B6F1FF3F0AD0484506D801D1554503DC89 +:1022E00003FB0050012601E04FF0FF3614F8015BBC +:1022F000D7E7731C0CD1002F4FF022030CBF6FF0F7 +:1023000000404FF00040CCF800302AB9BDE8F08F13 +:1023100007B1404242B106B1611E1160BDE8F08FC5 +:10232000002B08BF0823B0E7BDE8F08FCC000020E9 +:1023300030B51346044A05460C4610682946224625 +:10234000BDE83040FFF772BF30010020024B01466C +:10235000186800F003B800BF3001002070B5CD1C34 +:1023600025F0030508350C2D38BF0C25002D064639 +:102370003FDB8D423DD3214B1C6818462146A1B15D +:102380000B685B1B0ED40B2B03D90B60CC18CD5004 +:102390001FE08C4202D1626802601AE04B68636001 +:1023A0000C4616E00C464968E9E7154C23681BB952 +:1023B000304600F027F820602946304600F022F829 +:1023C000431C014615D0C41C24F0030484420AD1E6 +:1023D000256004F10B00231D20F00700C31A0BD069 +:1023E0005A42E25070BD3046611A00F00BF80130DD +:1023F000EED10C233360002070BD00BFEC2700201D +:10240000E827002038B5064C00230546084623601F +:1024100000F008F8431C02D1236803B12B6038BDDB +:10242000F4270020094A136863B1184469468842BA +:1024300002D8106018467047054B0C221A604FF006 +:10244000FF307047034B1360EFE700BFF027002019 +:10245000F4270020F827002000B5194A20F0004397 +:10246000934283B0014617DDB3F1FF4F04DBFCF765 +:1024700009FD03B05DF804FB694601F03BF800F08C +:102480000302012A0098019911D0022A0AD09AB1B8 +:10249000012201F0F3FDECE7002101F0F3F903B0B4 +:1024A0005DF804FB01F0EEF900F10040E1E701F016 +:1024B000E5FD00F10040DCE701F0E4F9D9E700BFF9 +:1024C000D80F493F30B5C0F3C754A4F17F031E2B8A +:1024D00083B0014620DC581C1BDB162B4FEAD1755C +:1024E00009DDC1F3160040F40000963CA04005B1A0 +:1024F000404203B030BD114B53F825402046FCF755 +:10250000C3FC019001982146FCF7BCFC20F000437D +:1025100033B9002003B030BDFCF784FF03B030BDF9 +:10252000C0F31604C0F3C75044F40004C0F1960091 +:1025300024FA00F0002DDCD0DAE700BFF87C0108B7 +:1025400000B51D4A20F00043934283B0014618DDD8 +:10255000B3F1FF4F04DBFCF795FC03B05DF804FB1F +:10256000694600F0C7FF00F00300012818D00228D8 +:102570000ED0D0B10098019901F084F900F100402B +:10258000EBE70021002201F079FD03B05DF804FBC8 +:1025900000980199012201F071FD00F10040DCE793 +:1025A0000098019901F06EF9D7E70098019901228E +:1025B00001F064FDD1E700BFD80F493F70B58AB084 +:1025C000054600F023FA224C064694F90030013308 +:1025D00003D0284601F0C4FF10B930460AB070BDE0 +:1025E000284601F06BFF4FF07E51FCF711FF0028E9 +:1025F000F3D0184901220023284600920893019144 +:10260000FCF73EF902460B461348CDE90423CDE919 +:10261000022301F0ABFD94F90030CDE90601022B55 +:102620000BD0684601F0A0FD38B1089B53B9DDE935 +:102630000601FCF7D3FB0AB070BD02F00FF82123AE +:102640000360F2E702F00AF8089B0360EFE700BFBF +:1026500034010020007D01080C7D010800F03EBB24 +:102660002DE9F0418AB007460C4600F0C7FB9B4EAF +:10267000054696F90030013303D0204601F070FF83 +:1026800018B928460AB0BDE8F081384601F068FF65 +:102690008046002832D120460021FCF791FE002818 +:1026A000EFD08F4A0123384601920093CDF8208065 +:1026B000FCF7E6F8CDE902012046FCF7E1F8894B8A +:1026C00096F900400022CDE90623631CCDE9040100 +:1026D0000DD0022C0BD0684601F046FD002800F01A +:1026E0009A80089B1BB101F0B9FF089B0360DDE9EC +:1026F0000601FCF773FB0AB0BDE8F0813846002103 +:10270000FCF75EFE18B320460021FCF759FE804618 +:10271000002855D0724901220023384600920893C0 +:102720000191FCF7ADF8CDE902012046FCF7A8F8CD +:1027300096F9004000220023CDE90401CDE90623EB +:10274000002CC8D0674B0022CDE90623CFE72846EE +:1027500001F0B8FE8046002862D028460021FCF730 +:102760002FFE00288DD0384601F0ACFE002888D01E +:10277000204601F0A7FE002883D0594904220023F7 +:102780003846009208930191FCF77AF8CDE90201EE +:102790002046FCF775F896F9004000220023022C31 +:1027A000CDE90401CDE9062300F08880684601F0F8 +:1027B000DBFC002800F08280089B002B97D092E77A +:1027C000204601F07FFE00283FF45BAF2046002149 +:1027D000FCF700FE00283FF454AF414A012338467D +:1027E00001920093CDF82080FCF74AF8CDE9020170 +:1027F0002046FCF745F83478CDE904010022002C8E +:1028000030D0394B022CCDE906232ED101F026FF22 +:1028100021230360D0E701F021FF2123036060E75B +:10282000384601F04FFE002897D0204601F04AFEBE +:10283000002892D0284601F093FE0346D8B92849D3 +:1028400001223846089300920191FCF719F8CDE96E +:1028500002012046FCF714F83478CDE90401002C7D +:1028600031D100220023CDE90623684601F07CFC2B +:102870000028A1D1CAE71A4A0323384600930192DF +:10288000CDF82080FBF7FCFFCDE902012046FBF7E5 +:10289000F7FF96F90030CDE90401384643BB134BEE +:1028A0004FF060420021CDE90623FCF793FD00289C +:1028B0003FD196F90030022B7FF478AF01F0CEFEC5 +:1028C0002223036078E70020002102460B46FCF734 +:1028D00055F9022CCDE9060198D0C6E73401002055 +:1028E000087D01080000F03F0000F0FFFFFFEF4708 +:1028F0001C4B00220021CDE90623FCF76BFD0028CC +:10290000D7D020464FF07C51FCF7C6FBFBF7B8FF51 +:1029100004460D4601F030FC02460B46204629468F +:10292000FDF702F90028C4D10F4B0022CDE90623A0 +:10293000BFE720464FF07C51FCF7AEFBFBF7A0FF52 +:1029400004460D4601F018FC02460B462046294677 +:10295000FDF7EAF80028ACD1044B4FF06042CDE916 +:102960000623A6E70000F07F0000F0FFFFFFEFC79F +:1029700070B58AB0054600F031FF224C064694F946 +:102980000030013308D0284601F0EAFD20B1284686 +:102990000021FCF71FFD10B930460AB070BD1A497E +:1029A000012200232846019100920893FBF768FF5B +:1029B0002478CDE90401CDE902017CB9002200238D +:1029C000CDE90623684601F0CFFB88B1089BA3B987 +:1029D000DDE90601FCF702FA0AB070BD0020002113 +:1029E00002460B46FCF7CAF8022CCDE90601E9D1F4 +:1029F00001F034FE21230360E8E701F02FFE089B7D +:102A00000360E5E734010020107D0108F8B520F0EF +:102A10000043B3F17E5F044610D008DCB3F17C5F65 +:102A200011DAB3F10C5F00F384809D48F8BD0146D4 +:102A3000FCF728FA0146FCF7E3FBF8BD002840F359 +:102A4000CD800020F8BD0028C0F2CA8001464FF0BA +:102A50007E50FCF717FA4FF07C51FCF71DFB044643 +:102A600000F0BCFE8F4906462046FCF715FB8E4958 +:102A7000FCF70AFA2146FCF70FFB8C49FCF702FA37 +:102A80002146FCF709FB8A49FCF7FEF92146FCF7D1 +:102A900003FB8849FCF7F6F92146FCF7FDFA864965 +:102AA000FCF7F2F92146FCF7F7FA8449054620467F +:102AB000FCF7F2FA8249FCF7E5F92146FCF7ECFA5B +:102AC0008049FCF7E1F92146FCF7E6FA7E49FCF77C +:102AD000D9F92146FCF7E0FA4FF07E51FCF7D4F922 +:102AE00001462846FCF78CFB3146FCF7D5FA26F464 +:102AF0007F6525F00F05074629462846FCF7CCFAE6 +:102B000001462046FCF7BEF9294604463046FCF74C +:102B1000BBF901462046FCF773FB01463846FCF73B +:102B2000B3F901462846FCF7AFF90146FCF7ACF9CA +:102B3000F8BD0146FCF7B0FA5A490546FCF7ACFA75 +:102B40005949FCF7A1F92946FCF7A6FA5749FCF7C1 +:102B500099F92946FCF7A0FA5549FCF795F9294659 +:102B6000FCF79AFA5349FCF78DF92946FCF794FAD9 +:102B70005149FCF789F92946FCF78EFA4F49064678 +:102B80002846FCF789FA4E49FCF77CF92946FCF700 +:102B900083FA4C49FCF778F92946FCF77DFA4A4953 +:102BA000FCF770F92946FCF777FA4FF07E51FCF7F5 +:102BB0006BF901463046FCF723FB01462046FCF743 +:102BC0006BFA01464148FCF75DF901462046FCF7E7 +:102BD00059F901463E48FCF755F9F8BD3D48F8BDA6 +:102BE0004FF07E51FCF750F94FF07C51FCF754FA4E +:102BF0002C490446FCF750FA2B49FCF745F92146CD +:102C0000FCF74AFA2949FCF73DF92146FCF744FA5A +:102C10002749FCF739F92146FCF73EFA2549FCF72C +:102C200031F92146FCF738FA2349FCF72DF9214602 +:102C3000FCF732FA0646204600F0D0FD1F49054653 +:102C40002046FCF729FA1E49FCF71CF92146FCF73F +:102C500023FA1C49FCF718F92146FCF71DFA1A491A +:102C6000FCF710F92146FCF717FA4FF07E51FCF7FC +:102C70000BF901463046FCF7C3FA2946FCF70CFA7B +:102C80001249FCF7FFF801462846FCF7FDF801461B +:102C9000FCF7FAF801461048FCF7F4F8F8BD00BF5D +:102CA000DB0FC93F08EF1138047F4F3A4611243D2E +:102CB000A80A4E3E90B0A63EABAA2A3E2EC69D3D27 +:102CC0006133303F2D57014039D119406821A2337B +:102CD000DA0FC93FDB0F4940DA0F494021F00042CB +:102CE000B2F1FF4FF8B5044614DC20F00045B5F111 +:102CF000FF4F06460EDCB1F17E5F3AD08F1707F02A +:102D0000020747EAD07755B9022F2FD0032F2FD1D2 +:102D10003148F8BD08462146FCF7B6F8F8BDFAB1CF +:102D2000B2F1FF4F29D0B5F1FF4F19D0AA1AD21531 +:102D30003C2A19DC002938DB2046FCF761FA01F057 +:102D4000BDFB01F0A5FA012F2CD0022F22D0002FBD +:102D50002FD02249FCF798F82149FCF793F8F8BDE9 +:102D6000002E15DB1F48F8BD1E48ECE71C48F8BDD7 +:102D7000F8BDBDE8F84001F08BBAB5F1FF4F19D0AE +:102D8000022FF3D0032FC3D0012F1BD00020F8BD9A +:102D90001548F8BD1149FCF777F801461048FCF7D3 +:102DA00071F8F8BD00F10040F8BD3C32C4DA0020F3 +:102DB000C9E7F8BD022F0CD0032F08D0012F04D093 +:102DC0000A48F8BD4FF00040F8BD0948F8BD094871 +:102DD000F8BD0948F8BD00BFDB0F49C02EBDBB33AD +:102DE000DB0F4940DB0FC93FDB0FC9BFDB0F493F9A +:102DF000DB0F49BFE4CB16C0E4CB16402DE9F04F02 +:102E000031F0004987B00D460C46074611D020F03E +:102E1000004ABAF1FF4F804605DD514807B0BDE8D2 +:102E2000F04F01F0B7BBB9F1FF4F07DDBAF17E5F9C +:102E3000F3D14FF07E5007B0BDE8F08F002840DBA3 +:102E40000026B9F1FF4F34D0B9F17E5F4CD0B4F118 +:102E5000804F384655D0B4F17C5F1BD001F02EFB7B +:102E60000146BAF1000F1DD028F04043B3F17E5F58 +:102E700018D04FEAD87808F1FF3856EA080166D032 +:102E8000B9F19A4F74DD374B9A4533DC002C37DBB0 +:102E90000020D0E7B8F1000FE0DB07B0BDE8F04F4D +:102EA00000F09CBC002C41DBB8F1000F32DB08467F +:102EB000C1E7BAF17E5FBCD027DD002CE8DB2846F5 +:102EC000B9E7B9F1974F13DAB9F17E5F0ADB4FEA40 +:102ED000E953C3F1960349FA03F202FA03F34B45AF +:102EE00000F044820026AFE7002C25DB3846A2E73D +:102EF0000226A6E71C4B9A4540F39D82002CC7DDB5 +:102F00001A480146FCF7C8F895E7002CC0DA05F12D +:102F1000004090E7AAF17E5A56EA0A0A12D1084602 +:102F2000FBF7B0FF0146FCF76BF984E74FF07E50EA +:102F3000FCF766F90146B7E739464FF07E50FCF7DB +:102F40005FF978E7012EB2D101F1004073E739460D +:102F50003846FBF797FF0146FCF752F96BE700BFD5 +:102F60000C7D0108F7FF7F3F0700803FCAF24971DF +:102F7000BAF5000F80F202824FF09741FCF78CF80F +:102F80006FF017028246B34B4FEAEA51CAF3160AB2 +:102F90007F399A4501EB020C4AF07E5740F3EB81F2 +:102FA000AD4B9A4540F3428200220CF1010CA7F58B +:102FB000000705920599A94B384653F82130CDF802 +:102FC00004C0194603920493FBF75CFF0499814601 +:102FD0003846FBF759FF01464FF07E50FCF710F9D9 +:102FE0000346194648460293FCF756F87910039AAF +:102FF00041F00051BB4601F5802120F47F6727F0A6 +:103000000F070A448246114638460392FCF744F8FB +:1030100001464846FBF736FF039A8146049910465D +:10302000FBF730FF01465846FBF72CFF01463846B8 +:10303000FCF732F801464846FBF724FF029B19468D +:10304000FCF72AF8514683465046FCF725F801461E +:103050008146FCF721F88249034648460293FCF773 +:103060001BF88049FBF710FF4946FCF715F87E492D +:10307000FBF70AFF4946FCF70FF87C49FBF704FF12 +:103080004946FCF709F87A49FBF7FEFE4946FCF78A +:1030900003F87849FBF7F8FE029B01461846FBF758 +:1030A000FBFF394681465046FBF7EEFE5946FBF7DB +:1030B000F3FF4946FBF7E8FE394604903846FBF734 +:1030C000EBFF6D490390FBF7DFFE0499FBF7DCFE95 +:1030D00020F47F6929F00F0949463846FBF7DCFFE9 +:1030E000494607465846FBF7D7FF6349834648469B +:1030F000FBF7C8FE039A1146FBF7C4FE014604988D +:10310000FBF7C0FE5146FBF7C7FF01465846FBF7E9 +:10311000BBFE834659463846FBF7B6FE20F47F6A6D +:103120002AF00F0A50465549FBF7B6FF544981462D +:103130005046FBF7B1FF3946034650460293FBF772 +:10314000A1FE01465846FBF79DFE4E49FBF7A4FF42 +:10315000029B01461846FBF797FE4B4B059A53F826 +:103160002210FBF791FEDDF804C007466046FBF72E +:103170003FFF464B059A049053F822B03946484623 +:10318000FBF782FE5946FBF77FFE0499FBF77CFEB6 +:1031900020F47F6A2AF00F0A04995046FBF772FE6A +:1031A0005946FBF76FFE4946FBF76CFE0146384671 +:1031B000FBF768FE24F47F6424F00F04013E56EA16 +:1031C00008068146214628460CBF314F4FF07E57F6 +:1031D000FBF758FE5146FBF75FFF49460646284677 +:1031E000FBF75AFF01463046FBF74EFE21460646E6 +:1031F0005046FBF751FF054601463046FBF744FEBB +:1032000000288146044620F00048AA4640F3F88092 +:10321000B8F1864F00F3C28000F0B280B8F17C5F55 +:1032200000F3C4804FF00009C84624F47F6424F002 +:103230000F0420461749FBF72FFF5146054620464D +:10324000FBF720FE01463046FBF71CFE1249FBF758 +:1032500023FF23E071C41C00D6B35D00287D010864 +:1032600042F1533E55326C3E05A38B3EABAAAA3EBB +:10327000B76DDB3E9A99193F000040400038763F19 +:10328000A0C39D364F38763F207D0108187D010888 +:10329000000080BF0072313F1872313F86490646F8 +:1032A0002046FBF7F9FE01463046FBF7EDFD0646EA +:1032B00031462846FBF7E8FD29460446FBF7E2FDC8 +:1032C00001463046FBF7DEFD214606462046FBF769 +:1032D000E3FE7A490546FBF7DFFE7949FBF7D2FDAD +:1032E0002946FBF7D9FE7749FBF7CEFD2946FBF7C8 +:1032F000D3FE7549FBF7C6FD2946FBF7CDFE7349A2 +:10330000FBF7C2FD2946FBF7C7FE01462046FBF747 +:10331000B9FD054629462046FBF7BEFE4FF0804129 +:1033200082462846FBF7AEFD01465046FBF768FF94 +:10333000314605462046FBF7AFFE3146FBF7A4FDBC +:1033400001462846FBF79EFD2146FBF79BFD014603 +:103350004FF07E50FBF796FD8144B9F5000FC0F2A7 +:10336000A58049463846FBF797FE64E502F0010266 +:10337000C2F1020668E5002205921BE6002202E681 +:1033800053493046FBF780FD294682464846FBF705 +:1033900079FD01465046FCF73BF838B138464D49B7 +:1033A000FBF77AFE4B49FBF777FE44E54FEAE85816 +:1033B000A8F17E084FF4000343FA08F32344C3F353 +:1033C000C7524548C3F31608A2F17F0140FA01F144 +:1033D000C2F1960248F4000848FA02F8002C23EAE9 +:1033E00001012846B8BFC8F10008FBF74BFD824633 +:1033F00051463046FBF748FD4FEAC859044614E7EA +:10340000364B98450ADC7FF409AF2946FBF73AFDB5 +:1034100001463046FBF7E8FF0028C7D03846304960 +:10342000FBF73AFE2E49FBF737FE04E501234FF484 +:1034300000120593BEE54FF07E51FBF723FD2949AD +:103440000746FBF729FE284981463846FBF724FE4C +:10345000394682463846FBF71FFE4FF07A518346C5 +:103460003846FBF719FE01462048FBF70BFD3946AD +:10347000FBF712FE01464FF07C50FBF703FD0146BF +:103480005846FBF709FE1A49FBF706FE014650466F +:10349000FBF7F8FC074639464846FBF7F5FC20F4F5 +:1034A0007F6A2AF00F0A494650467DE6414601F000 +:1034B00075F8014656E700BF8CBEBF354CBB3133B3 +:1034C0000EEADD3555B38A38610B363BABAA2A3E8E +:1034D0003CAA3833CAF24971FFFF7F00000016434F +:1034E0006042A20D00AAB83F70A5EC36ABAAAA3E76 +:1034F0003BAAB83F2DE9F04FAB4A20F0004494427C +:1035000089B006460D4664DDA84A94421CDC0028BA +:10351000A74940F3EC80FBF7B5FCA64B24F00F0461 +:103520009C42064664D0A449FBF7ACFC01462860E7 +:103530003046FBF7A7FCA049FBF7A4FC0123686019 +:10354000184609B0BDE8F08F9C4A944262DDB4F1A0 +:10355000FF4F46DAE715863FA4EBC7542046FBF73A +:1035600061FFFBF745FD0346014620460593FBF747 +:1035700089FC4FF08741FBF78FFD8046FBF752FF38 +:10358000FBF736FD0146044640460694FBF77AFCFD +:103590004FF08741FBF780FD00210790FBF710FFFC +:1035A000002800F0C58020460021FBF709FF002815 +:1035B00014BF0123022382480221019000913A4660 +:1035C00005A8294600F022FA002EC0F2A780034683 +:1035D00003E00022286000234A60184609B0BDE8D5 +:1035E000F08F0146FBF74EFC002368602860F4E78B +:1035F0007449FBF747FC74490446FBF743FC01465A +:1036000028602046FBF73EFC6F49FBF73BFC01239B +:103610006860E2E700F052FF6C490746FBF73CFDAB +:103620004FF07C51FBF730FCFBF7FCFE8246FBF7CA +:10363000DFFC5F498346FBF72FFD01463846FBF769 +:1036400021FC5D4980465846FBF726FDBAF11F0F65 +:1036500081464946404618DC5D4B0AF1FF3253F87B +:10366000223024F0FF029A420FD0FBF70BFC0746F2 +:103670002F6039464046FBF705FC4946FBF702FC44 +:10368000002E686056DB5346A7E7FBF7FBFBE3150C +:10369000C0F3C7529A1A082A0746E9DD4949584635 +:1036A0000393FBF7F9FC074639464046FBF7EAFB74 +:1036B000044621464046FBF7E5FB3946FBF7E2FBB3 +:1036C000414907465846FBF7E7FC3946FBF7DAFB6A +:1036D000814649462046FBF7D5FB039BC0F3C75202 +:1036E0009B1A192B074641DC2860A046C1E7FBF76F +:1036F000CBFB304B24F00F049C42064623D02E49CE +:10370000FBF7C2FB014628603046FBF7BBFB2A49AA +:10371000FBF7BAFB4FF0FF3368605EE795E80C00FB +:1037200003F1004102F1004243422A60696054E71C +:10373000032340E707F1004700F100402F60686075 +:10374000CAF1000349E71F49FBF79EFB1E490446E7 +:10375000FBF79AFB014628602046FBF793FB1A49CA +:10376000FBF792FB4FF0FF33686036E71949584684 +:10377000FBF792FC074639462046FBF783FB804661 +:1037800041462046FBF77EFB3946FBF77BFB12499F +:1037900004465846FBF780FC2146FBF773FB814645 +:1037A0004946404661E700BFD80F493FE3CB16408A +:1037B000800FC93FD00FC93F43443537800F49437D +:1037C000B07D01080044353708A3852E84F9223FD7 +:1037D000307D010800A3852E32318D2420F0004277 +:1037E000B2F1FF4FF8B5044603462DD25AB3002874 +:1037F0003DDBB2F5000F4FEAE0502CD37F38C3F326 +:103800001603C20743F4000348BF5B0000274010C3 +:103810005B003E4619244FF08072B5189D4202DCD1 +:103820005B1BAE181744013C4FEA43034FEA5202B8 +:10383000F3D113B107F001031F447F1007F17C5748 +:1038400007EBC050F8BDF8BD0146FBF725FC21464B +:10385000FBF71AFBF8BD14F400020FD15B0019024C +:1038600002F10102FAD5C2F101021044C6E7014695 +:10387000FBF708FB0146FBF7C3FCF8BD012210442F +:10388000BCE700BF2DE9F84320F00046B6F1485FE1 +:1038900005460F4649DAFBF7C5FD002800F09D807C +:1038A00029462846FBF7F8FB4E490446FBF7F4FB94 +:1038B0004D49FBF7E9FA2146FBF7EEFB4B49FBF7D5 +:1038C000E1FA2146FBF7E8FB4949FBF7DDFA21461F +:1038D000FBF7E2FB4749FBF7D5FA2146FBF7DCFB98 +:1038E0004549FBF7D1FA2146FBF7D6FB8046204637 +:1038F0004FF07C51FBF7D0FB414606462046FBF7D4 +:10390000CBFB394604462846FBF7C6FB014620465A +:10391000FBF7B8FA01463046FBF7B4FA01464FF020 +:103920007E50FBF7AFFABDE8F8830146FBF7B4FB26 +:103930002C490446FBF7B0FB2B49FBF7A5FA2146BF +:10394000FBF7AAFB2949FBF79DFA2146FBF7A4FBED +:103950002749FBF799FA2146FBF79EFB2549FBF720 +:1039600091FA2146FBF798FB2349FBF78DFA214694 +:10397000FBF792FB214B80469E42B8DD204B9E42D6 +:1039800027DC06F17F4631464FF07E50FBF77AFA8E +:10399000814620464FF07C51FBF77EFB3146FBF71A +:1039A00071FA414606462046FBF776FB3946044647 +:1039B0002846FBF771FB01462046FBF763FA0146F8 +:1039C0003046FBF75FFA01464846FBF75BFABDE875 +:1039D000F883DFF834900B4EDBE74FF07E50BDE804 +:1039E000F88300BF4ED747ADF6740F317CF29334A5 +:1039F000010DD037610BB63AABAA2A3D9999993E91 +:103A00000000483F0000903E0000383F2DE9F04F95 +:103A1000DFB00B93013B0293D31E48BF131DB84C7C +:103A200006466898DB1054F8204023EAE3730C93B1 +:103A3000DB4302EBC30308940693089C029B0C9A99 +:103A40001D190991C3EB02071DD4699C3D4404EB89 +:103A5000870901354FF0000822AC0AE059F8080048 +:103A6000FBF7C6FA0137AF4244F8080008F1040832 +:103A700009D0002FF2DA01370020AF4244F80800E5 +:103A800008F10408F5D1089A002AC0F2DF82089AEA +:103A90000B9B02F101089C0022AF4FEA88082744E3 +:103AA0000025029A002AC0F2F28105EB070B4FF0C5 +:103AB00000094FF0000A56F809005BF8041DFBF7F7 +:103AC000EBFA01465046FBF7DFF909F10409A1457D +:103AD0008246F0D14AA840F805A004354545E0D11A +:103AE000089A0EAB03EB82030D9391464FEA8903CC +:103AF0000793079A5EAB1344B9F1000F53F850AC2B +:103B000023DD0DF134084AAF174490440DAD4FF05A +:103B10006E515046FBF7C0FAFBF784FCFBF768FADE +:103B20004FF087418346FBF7B7FA01465046FBF753 +:103B3000A9F9FBF777FC594645F8040F57F8040D2F +:103B4000FBF7A2F945458246E1D15046069900F0BF +:103B500025FD4FF078510546FBF79EFA00F0BAFCC0 +:103B60004FF08241FBF798FA01462846FBF78AF9A5 +:103B70000546FBF757FC8246FBF73AFA0146284612 +:103B8000FBF780F9069A8046002A40F3678109F125 +:103B9000FF310EA850F82130C2F1080043FA00F2BC +:103BA00002FA00F01B1A06989244C0F1070743FA84 +:103BB00007F70EA840F82130002F32DDB9F1000FD1 +:103BC0000AF1010A40F375810EAB079A19461144B8 +:103BD000002507E0C2F5807012B143F8040C0125FE +:103BE0008B420BD053F8042B002DF3D0C2F1FF020F +:103BF0008B4243F8042C4FF00105F3D1069B002BB8 +:103C00000DDD012B00F03281022B08D109F1FF33C9 +:103C10000EA951F8232002F03F0241F82320022F81 +:103C200070D040460021FBF7CBFB002800F08380DA +:103C3000089A09F1FF35AA420DDC079A0EAB0D98E0 +:103C40001344002253F8041D834242EA0102F9D1D1 +:103C5000002A40F0E481089B0EA85A1E50F822303A +:103C6000002B40F0F18100EB8202012352F8041D89 +:103C700001330029FAD04B4499450A933DDADDF827 +:103C80002CA022AACA44DDF8308002EB8A02C84484 +:103C9000C9EB0309131D03920593699A079B4FEA29 +:103CA00089094AAF02EB8808CDF810901F4400251F +:103CB00058F8040FFBF79CF9029B039A002B505114 +:103CC0004FF0000B13DBDDF814A04FF00009AA44FD +:103CD00056F809005AF8041DFBF7DEF9014658466C +:103CE000FBF7D2F809F10409A1458346F0D1049A03 +:103CF0000435954247F804BFDAD1DDF82890F5E69F +:103D0000C880010841464FF07E50FBF7BBF8804663 +:103D1000002D86D006994FF07E5000F03FFC014602 +:103D20004046FBF7AFF8804640460021FBF748FBD2 +:103D300000287FF47DAF069B40465942CDF808A08D +:103D400000F02CFC4FF087410446FBF757FB00289E +:103D500000F07F814FF06E512046FBF79DF9FBF795 +:103D600061FBFBF745F94FF087410546FBF794F9F6 +:103D700001462046FBF786F8FBF754FB0EAB43F8F1 +:103D800029002846FBF74EFB069C09F10105083483 +:103D90000EA9069441F8250006994FF07E5000F0D8 +:103DA000FDFB002D04464FDB6E1C4FEA8508C6EB79 +:103DB000867A0DF138094AABC1444FEA8A0A984421 +:103DC0004FF0000B59F80B00FBF712F92146FBF7F7 +:103DD00063F94FF06E5148F80B002046FBF75CF991 +:103DE000ABF1040BD3450446ECD1DFF88C92DDF83F +:103DF00020A00024B34603950497BAF1000FB8BF82 +:103E0000002515DB00263746002501E0A7420FDC20 +:103E100058F8061059F80600FBF73EF90146284607 +:103E2000FBF732F80137BA45054606F10406EDDA2C +:103E30005EA800EB84030134A345A8F1040843F80D +:103E4000A05CDAD1039D049F689C032C00F298804B +:103E5000DFE814F0CB009C009C00310010D109F188 +:103E6000FF330EA951F823703F12A5E609F1FF3385 +:103E70000EA850F8232002F07F0240F82320CEE65F +:103E80004FF07C51FBF7BAFA58B90746C9E64FF034 +:103E9000000A4AA840F805A0043545457FF401AE64 +:103EA0001EE6B9F1000F4FF002070AF1010A3FF7D1 +:103EB0008BAE0025A2E6002D40F3DC804FEA850B97 +:103EC0005EAB36AE05F1FF3A5B4406EB8A0A53F867 +:103ED000A08C54465B4635AABB462F4600E0C84638 +:103EE00054F804594146284601920093FAF7CCFF52 +:103EF000814649462846FAF7C5FF4146FAF7C4FF0E +:103F0000019AC4F804909442A060009BE7D13D461A +:103F1000012D5F469B4640F3AD805EAB9B445BF852 +:103F2000A04C00E044465AF8049921464846FAF766 +:103F3000ABFF804641464846FAF7A4FF2146FAF710 +:103F4000A3FF5645CAF80480CAF80800EAD16C1CE1 +:103F500006EB84040020083654F8041DFAF794FF99 +:103F6000B442F9D1002F7ED0369A379B099C00F1DC +:103F7000004002F1004203F10043A0602260636050 +:103F8000029A02F007005FB0BDE8F08F002DB8BFC5 +:103F900000200ADB36AE6C1C002006EB840454F8CB +:103FA000041DFAF771FFB442F9D1002F35D000F1AA +:103FB0000043099C014623603698FAF763FF002D01 +:103FC00008DD36AC04EB850554F8041FFAF75CFFF6 +:103FD000AC42F9D10FB100F10040099A5060029A49 +:103FE00002F007005FB0BDE8F08F002D39DB6C1CDC +:103FF00036AE002006EB840454F8041DFAF744FFA3 +:10400000B442F9D10FB100F10040099A1060029A50 +:1040100002F007005FB0BDE8F08F0346C9E7069ADB +:104020000EAC54F82530083ACDF808A00692002BC3 +:104030007FF4B2AE04EB850353F8041D013D083A4A +:104040000029F9D00692A7E6012314E60B9B9C00F9 +:1040500046E52046FBF7E6F90EAA4D4642F8290050 +:104060009AE60020CEE7099C369A379BA060226032 +:10407000636085E7002075E7D48001082DE9F843E7 +:1040800020F00043B3F1485F04460F46904603DA40 +:10409000FBF7C8F9002857D021462046FAF7FCFF65 +:1040A00021460546FAF7F8FF294906462846FAF759 +:1040B000F3FF2849FAF7E6FE2946FAF7EDFF26490D +:1040C000FAF7E2FE2946FAF7E7FF2449FAF7DAFEA3 +:1040D0002946FAF7E1FF2249FAF7D6FE8146B8F100 +:1040E000000F22D038464FF07C51FAF7D5FF4946F1 +:1040F00080463046FAF7D0FF01464046FAF7C2FE46 +:104100002946FAF7C9FF3946FAF7BCFE15490546B4 +:104110003046FAF7C1FF01462846FAF7B5FE0146D8 +:104120002046FAF7AFFEBDE8F88349462846FAF77D +:10413000B3FF0C49FAF7A6FE3146FAF7ADFF214668 +:10414000FAF7A2FEBDE8F8832046BDE8F88300BF79 +:10415000D3C92E2F342FD7321BEF3836010D5039EB +:104160008988083CABAA2A3E0020704700200149FC +:10417000704700BF0000F87F2DE9F043C1F30A5CEF +:10418000ACF2FF37132F83B002460B460D4689462B +:1041900080464FEAD17630DC002F4CDB3A4939417A +:1041A00001EA030010432DD0490801EA030858EA48 +:1041B00002080CD04FF480233B41132F25EA010164 +:1041C00041EA030914BF4FF000084FF000482F499F +:1041D0004B4601EBC606D6E9004542462046294635 +:1041E000FAF7F0F9CDE90001DDE9000122462B469E +:1041F000FAF7E6F903B0BDE8F083332F07DDB7F532 +:10420000806F3ED01046194603B0BDE8F083ACF293 +:10421000134C4FF0FF3121FA0CF10142F2D0490862 +:104220000142D4D04FF0804848FA0CFC20EA01014A +:1042300041EA0C08CBE721F000410143E2D0C3F38F +:10424000130101434C420C431048590C240B490400 +:1042500004F4002444EA010300EBC601D1E900455F +:1042600020462946FAF7AEF9CDE90001DDE9000163 +:104270002B462246FAF7A4F921F0004343EAC6711F +:10428000C2E7FAF79FF9BFE7FFFF0F0000810108BF +:104290002DE9F04120F00045B5F1A14F0446064656 +:1042A00008DBB5F1FF4F6FDC002840F3A0806F48BA +:1042B000BDE8F0816E4B9D4277DCB5F1445F68DB71 +:1042C0004FF0FF3721462046FAF7E6FE01468046CA +:1042D000FAF7E2FE67490546FAF7DEFE6649FAF7A5 +:1042E000D3FD2946FAF7D8FE6449FAF7CDFD2946F1 +:1042F000FAF7D2FE6249FAF7C7FD2946FAF7CCFE73 +:104300006049FAF7C1FD2946FAF7C6FE5E49FAF799 +:10431000BBFD4146FAF7C0FE5C4980462846FAF7E5 +:10432000BBFE5B49FAF7AEFD2946FAF7B5FE5949DF +:10433000FAF7A8FD2946FAF7AFFE5749FAF7A2FDAA +:104340002946FAF7A9FE5549FAF79CFD2946FAF7DE +:10435000A3FE7B1C014640464CD0FAF795FD214652 +:10436000FAF79AFE4E4B4F4D53F82710FAF78AFD95 +:104370002146FAF787FD014655F82700FAF782FD36 +:10438000002E30DBBDE8F0810146FAF77DFDBDE887 +:10439000F0814549FAF778FD4FF07E51FBF738F888 +:1043A00000288DD02046BDE8F08100F087F83F4B13 +:1043B00004469D4229DCA3F5D0039D4244DC01461E +:1043C000FAF762FD4FF07E51FAF75CFD4FF0804145 +:1043D00005462046FAF758FD01462846FAF710FF31 +:1043E000002704466EE700F10040BDE8F081304848 +:1043F000BDE8F081FAF748FD2146FAF74DFE014687 +:104400002046FAF73FFDBDE8F0812A4B9D4214DCBF +:104410004FF07F51FAF736FD4FF07F5105462046A9 +:10442000FAF73AFE4FF07E51FAF72EFD0146284684 +:10443000FAF7E6FE0227044644E701461E48FAF76B +:10444000DFFE032704463DE74FF07E51FAF71AFDE1 +:104450004FF07E5105462046FAF716FD01462846E4 +:10446000FAF7CEFE012704462CE700BFDB0FC93F59 +:10447000FFFFDF3ED769853C59DA4B3D356B883D00 +:104480006E2EBA3D2549123EABAAAA3E21A215BD09 +:104490006BF16E3D95879D3D388EE33DCDCC4C3E16 +:1044A0001081010820810108CAF24971FFFF973F7E +:1044B000DB0FC9BFFFFF1B40000080BF20F00040A2 +:1044C000704700BF20F00040B0F1FF4FACBF0020AC +:1044D000012070472DE9F04120F00047FD0D7F3DA0 +:1044E000162D064613DC002D80461BDB194F2F418D +:1044F000074214D01849FAF7C7FC0021FAF788FFE1 +:1045000068B1002E1BDB28EA0700BDE8F081B7F197 +:10451000FF4F04D30146FAF7B7FCBDE8F0813046FF +:10452000BDE8F0810C49FAF7AFFC0021FAF770FF03 +:104530000028F4D0002E08DB0020BDE8F0814FF405 +:10454000000343FA05F5A844DDE7002FE7D0034850 +:10455000BDE8F081FFFF7F00CAF24971000080BF13 +:1045600030F0004001D102207047A0F50003B3F104 +:10457000FE4F01D204207047054B421E9A4201D8DB +:1045800003207047B0F1FF4358425841704700BFC5 +:10459000FEFF7F00004870470000C07F38B530F054 +:1045A0000044024603460D4614D0B4F1FF4F0DD22D +:1045B000B4F5000F0FD3E40D2C44FE2C2EDC002CA0 +:1045C0001DDD23F0FF4343EAC45038BD0146FAF72E +:1045D0005BFC38BD38BD4FF09841FAF75DFD194BD3 +:1045E00002469D4207DBC0F3C7540346193CE3E78C +:1045F000154800F02DF81449FAF74EFD38BD14F1B6 +:10460000160F13DA4CF250339D421146F0DD0F487D +:1046100000F01EF80D49FAF73FFD38BD11460B4872 +:1046200000F016F80949FAF737FD38BD04F1190012 +:1046300023F0FF4343EAC0504FF04C51FAF72CFDF2 +:1046400038BD00BFB03CFFFF6042A20DCAF2497105 +:1046500001F0004120F0004008437047014B18680A +:10466000704700BF30010020780000FF000000FF0D +:104670003C0000FFF00000FF0001482050726F6412 +:104680007563743A426C61636B626F7820666C6923 +:104690006768742064617461207265636F72646519 +:1046A00072206279204E6963686F6C617320536871 +:1046B00065726C6F636B0A4820426C61636B626F5A +:1046C000782076657273696F6E3A310A48204461CA +:1046D00074612076657273696F6E3A310A482049B9 +:1046E00020696E74657276616C3A33320A0000009C +:1046F00089630108C36401080E6501085C6501084F +:10470000A9650108F76501087E6301084266010892 +:104710002B630108426601088763010842660108AD +:1047200048204669656C642047206E616D653A4794 +:1047300050535F6E756D5361742C4750535F636FB8 +:104740006F72645B305D2C4750535F636F6F7264B0 +:104750005B315D2C4750535F616C7469747564659F +:104760002C4750535F73706565640A48204669653D +:104770006C642047207369676E65643A302C312C75 +:10478000312C302C300A48204669656C6420472063 +:10479000707265646963746F723A302C372C372CF1 +:1047A000302C300A48204669656C64204720656ECD +:1047B000636F64696E673A312C302C302C312C31A8 +:1047C0000A48204669656C642048206E616D653A30 +:1047D0004750535F686F6D655B305D2C4750535F8A +:1047E000686F6D655B315D0A48204669656C6420C1 +:1047F00048207369676E65643A312C310A48204657 +:1048000069656C64204820707265646963746F72B6 +:104810003A302C300A48204669656C64204820658F +:104820006E636F64696E673A302C300A00000202D2 +:104830000308050A0B080A0A0B0C0E0E0F746564B8 +:10484000666D6A69736C67010B020D0A03050B0341 +:104850000D0A03070B030D0A03090B020D0A030AD5 +:104860000B040D0A03080B040D0A03001E0000FFD1 +:104870004A0100FF2C0100FF0E0100FFD20000FFE3 +:10488000B40000FF960000FF5A0000FF0000FFFF89 +:10489000C06201088C4801086C4601086C48010898 +:1048A00070460108884801086846010884480108E4 +:1048B000804801087C4801087446010878480108CE +:1048C000744801087048010824630108186301084E +:1048D000F96201080800000000200000000C0140FF +:1048E000100000000020000000100140000C0140FA +:1048F00008001002000C014010001002000C0140E2 +:104900000400140200000000000000000301000089 +:10491000084F010804000000C84E01080400000010 +:10492000884E010802010000684E010800010000E5 +:104930000000000006000000084E0108060000000C +:10494000A84D010801010000000000000400000063 +:10495000684D010806000000084D0108080000002D +:10496000884C010808000000084C010808000000FD +:10497000884B010801010000000000000001000058 +:104980000000000000010000000000000400000022 +:10499000484B010806000000E84A01080001000039 +:1049A0000000000002010000C84A010801010000E7 +:1049B000000000000000000000000000AA4A0108FA +:1049C000924A0108744A01085C4A010845460008F9 +:1049D00001460008DD450008B5450008A54500086A +:1049E000BDE400083146000855450008254600088A +:1049F000174600080000000000C2010024670108FB +:104A0000476701080100000000E100005C67010841 +:104A10007E6701080200000000960000926701080E +:104A2000B467010803000000004B0000C8670108DC +:104A3000EA6701080400000080250000DE6B010821 +:104A4000DE6B0108000100020002000009170000EF +:104A5000010002000200000001070000000108033D +:104A600009030A040B040C040D04040405040604E1 +:104A70000704FFFF00020102020203020402050212 +:104A800006020702080309030A040B040C040D04C0 +:104A9000FFFF0001080309030A030B030C030D03C6 +:104AA0000403050306030703FFFF000201020202DD +:104AB00003020402050206020702080309030A03AF +:104AC0000B030C030D03FFFF0000803F00000000FC +:104AD00000000000000080BF0000803F00000000D8 +:104AE000000000000000803F0000803F000080BF09 +:104AF0000000803F000080BF0000803F000080BFBA +:104B0000000080BF0000803F0000803F0000803F29 +:104B10000000803F0000803F0000803F0000803F99 +:104B2000000080BF000080BF0000803F0000000048 +:104B300000000000000000000000803F00000000B6 +:104B400000000000000000000000803F00000000A6 +:104B50000000803F0000803F0000803F000080BFD9 +:104B6000000080BF000000000000803F0000000047 +:104B70000000803F000080BF0000803F0000803FB9 +:104B8000000080BF000000800000803F0000803FE8 +:104B9000000000BF0000803F0000803F000000BF19 +:104BA000000080BF0000803F0000803F000080BF09 +:104BB0000000003F0000803F0000803F0000003FF9 +:104BC0000000803F0000803F0000803F0000003F69 +:104BD000000080BF000080BF0000803F000080BF59 +:104BE000000000BF000080BF0000803F000000BF49 +:104BF0000000803F000080BF0000803F0000803F39 +:104C00000000003F000080BF0000803FF704353FF8 +:104C1000F70435BF0000803F0000803FF70435BF38 +:104C2000F70435BF0000803F0000803FF70435BF28 +:104C3000F704353F0000803F0000803FF704353F18 +:104C4000F704353F0000803F0000803F0000000077 +:104C5000000080BF000080BF0000803F000080BFD8 +:104C600000000000000080BF0000803F0000000046 +:104C70000000803F000080BF0000803F0000803FB8 +:104C800000000000000080BF0000803F000080BFE7 +:104C90000000803F000080BF0000803F000080BF18 +:104CA000000080BF0000803F0000803F0000803F88 +:104CB0000000803F0000803F0000803F0000803FF8 +:104CC000000080BF000080BF0000803F000080BF68 +:104CD0000000803F0000803F0000803F000080BF58 +:104CE000000080BF000080BF0000803F0000803FC8 +:104CF0000000803F000080BF0000803F0000803F38 +:104D0000000080BF0000803F0000803F000000BF27 +:104D1000D0B35D3F0000803F0000803F000000BF37 +:104D2000D0B35DBF0000803F0000803F0000003F27 +:104D3000D0B35D3F000080BF0000803F0000003F17 +:104D4000D0B35DBF000080BF0000803F000080BF87 +:104D500000000000000080BF0000803F0000803F96 +:104D6000000000000000803F0000803F00000000C5 +:104D70000000803F000080BF0000803F000080BF37 +:104D8000000080BF000000000000803F0000000025 +:104D90000000803F0000803F0000803F0000803F17 +:104DA000000080BF000000000000803FD0B35DBF66 +:104DB0000000003F0000803F0000803FD0B35DBF97 +:104DC000000000BF000080BF0000803FD0B35D3F07 +:104DD0000000003F0000803F0000803FD0B35D3FF7 +:104DE000000000BF000080BF0000803F0000000006 +:104DF000000080BF0000803F0000803F00000000F6 +:104E00000000803F000080BF0000803F00000000E5 +:104E1000A8AAAA3F0000803F0000803F000080BF9A +:104E2000B0AA2ABF000080BF0000803F0000803F82 +:104E3000B0AA2ABF000080BF0000803F0000000031 +:104E4000A8AAAA3F000080BF0000803F000080BFEA +:104E5000B0AA2ABF0000803F0000803F0000803FD2 +:104E6000B0AA2ABF0000803F0000803F0000803FC2 +:104E700000000000000000000000803F000080BF34 +:104E800000000000000000000000803F000080BF24 +:104E90000000803F000080BF0000803F000080BF16 +:104EA000000080BF0000803F0000803F0000803F86 +:104EB0000000803F0000803F0000803F0000803FF6 +:104EC000000080BF000080BF0000803F00000000A5 +:104ED0000000803F000080BF0000803F000080BFD6 +:104EE000000000000000803F0000803F0000803F85 +:104EF000000000000000803F0000803F0000000034 +:104F0000000080BF000080BF0000803F0000000064 +:104F1000A8AAAA3F000000000000803F000080BF58 +:104F2000B0AA2ABF000000000000803F0000803FC0 +:104F3000B0AA2ABF000000001000000000200000FE +:104F4000001001400040000000100140010001027B +:104F50000001030001040001050001060001070033 +:104F6000010800010900010A00010B00010C010306 +:104F700000000000FE6701080000000001000000C2 +:104F80000368010801000000020000000A6801082F +:104F90000200000003000000136801080300000085 +:104FA0000400000019680108050000000500000069 +:104FB0001E680108060000000600000028680108BD +:104FC0000700000007000000316801080800000029 +:104FD000080000003A68010809000000090000000C +:104FE000436801080A0000000A0000004D6801083B +:104FF0000B0000000B000000576801080C000000C7 +:105000000C000000616801080D0000000D000000A8 +:10501000696801080E0000000E00000071680108B8 +:105020000F0000000F000000796801081000000068 +:10503000100000008268010811000000110000004B +:10504000896801081200000012000000936801083E +:1050500013000000130000009B680108140000000A +:1050600014000000A66801081500000015000000EB +:10507000B0680108160000001600000000000000E3 +:10508000FF000000B56206010300F00500FF19B53E +:105090006206010300F00300FD15B562060103007E +:1050A000F00100FB11B56206010300F00000FA0FE9 +:1050B000B56206010300F00200FC13B562060103AD +:1050C00000F00400FE17B562060103000102010EA4 +:1050D00047B562060103000103010F49B5620601ED +:1050E0000300010601124FB562060103000112011F +:1050F0001E67B56206080600C80001000100DE6AEE +:1051000000B5620616080003070300000000003126 +:10511000E501B56206160800030703005108000008 +:105120008A4102B562061608000307030004E00482 +:1051300000199D03B562061608000307030000026C +:10514000020035EF04B5620616080003070300806D +:10515000010000B2E8009001C800C800C800C80003 +:10516000C800C800C800C80064000000C800C8002B +:10517000C800C800320000011E1E646464646464D8 +:10518000220046022100820120004302100001019A +:10519000000049020100880102004C021200840153 +:1051A00011009001110090011100A0011100A00157 +:1051B00000540040000C0140400080001F2000000F +:1051C0000000200000580040000C014000040008CE +:1051D0002122000000004000BF460008DD46000814 +:1051E000F94600085999000825470008314700088A +:1051F000020000008025000000C201000000000045 +:10520000200000008025000000C201000100000015 +:10521000400000008025000000C2010000000000E6 +:10522000010000008025000000C201000000000015 +:10523000100000008025000000C2010000030000F3 +:105240000400000080250000004B0000000000006A +:105250000800000000E1000000E100000004000080 +:105260008000000000C2010000C201000000000038 +:10527000106D0108156D0108196D01082C6D0108EC +:105280001E6D0108246D0108286D01080000000052 +:10529000DE6B0108CC6C0108D46C0108DC6C0108E1 +:1052A000E46C0108EB6C0108F66C0108FE6C010867 +:1052B000066D01080B6D010800000000524F4C4CB8 +:1052C0003B50495443483B5941573B414C543B5058 +:1052D0006F733B506F73523B4E6176523B4C455659 +:1052E000454C3B4D41473B56454C3B00BD93000868 +:1052F0008D4600085B460008E1BF0008A94600088B +:10530000DDBF00084E6F0108526F0108586F010899 +:105310005E6F0108616F0108686F01086B6F01081B +:10532000706F01087C6F01087F6F0108856F0108AD +:105330008C6F0108966F0108A06F0108A96F010822 +:10534000B76F0108C36F0108CA6F0108D06F010869 +:10535000DD6F0108E86F0108F56F0108000000002B +:105360009C6E0108A36E0108A86E0108B96E0108C1 +:10537000C36E0108CE6E0108D96E0108246D0108C4 +:10538000E46E01081E6D0108ED6E0108F76E01085C +:10539000056F0108086F0108186F01081F6F0108E9 +:1053A000286F0108326F01083A6F0108456F010844 +:1053B0000000000040008000000100020004495786 +:1053C0004641540102040810204E45535755442CC1 +:1053D0003A3A0000000000008025000000C20100F1 +:1053E00006000000010000008025000000C201004E +:1053F000070000000300000080250000004B0000B3 +:10540000090000000400000080250000004B00009F +:1054100009000000000000000000004F000000072D +:10542000000700147F147F14242A7F2A12231308F4 +:10543000646236495522500005030000001C2241D9 +:10544000000041221C0014083E081408083E080809 +:1054500000503000000808080808006060000020C4 +:10546000100804023E5149453E00427F400042611F +:105470005149462141454B311814127F10274545AB +:1054800045393C4A494930017109050336494949C2 +:1054900036064949291E00363600000056360000FF +:1054A0000814224100141414141400412214080298 +:1054B00001510906324979413E7E1111117E7F4921 +:1054C0004949363E414141227F4141221C7F4949A1 +:1054D00049417F090909013E4149497A7F08080885 +:1054E0007F00417F41002040413F017F081422415D +:1054F0007F404040407F020C027F7F0408107F3EC7 +:105500004141413E7F090909063E4151215E7F0923 +:10551000192946464949493101017F01013F40406F +:10552000403F1F2040201F3F4038403F6314081475 +:105530006307087008076151494543007F414100F6 +:1055400002040810200041417F00040201020440CF +:1055500040404040010204000020545454787F48E9 +:105560004444383844444420384444487F385454F0 +:105570005418087E090102064949493F7F0804047E +:105580007800447D40002040443D007F10284400C6 +:1055900000417F40007C0418047C7C0804047838B7 +:1055A000444444387C14141408081414187C7C08EF +:1055B0000404084854545420043F4440203C4040D4 +:1055C000207C1C2040201C3C4030403C44281028BB +:1055D000440C5050503C4464544C44000836410044 +:1055E00000007F0000004136080002010204023E74 +:1055F00055554122000000000000007900001824E9 +:10560000742E24487E4942405D2222225D15167C7C +:10561000161500007700000A5555552800010001B5 +:1056200000000A0D0A0408142A1422040404041CAD +:105630000008080800010101010100020502004400 +:10564000445F444400000402017E2020103E060F07 +:105650007F007F00181800000040502000000A0D55 +:105660000A0022142A14081708342A7D1708046A2D +:1056700059304845402042004200427E42004200EC +:105680007E7E0042007E7E7E42007E7E7E7E007EAA +:105690007E7E7E7E05040203557201085E7201085B +:1056A000755500088272010886720108A956000823 +:1056B0009C720108A172010811720008B5720108FC +:1056C000BB720108956F0008F56B0108CC720108E8 +:1056D00089870008E9720108EE72010831B50008F7 +:1056E0001D730108DE6B0108E57A000822730108CA +:1056F0002A730108FDA500083E73010842730108E2 +:10570000B1BB00085573010864730108F1D70008A4 +:105710007E730108DE6B0108B9BA000883730108C3 +:105720008773010835C30008967301089A7301084E +:10573000A9BD0008AF720108B6730108596E0008D0 +:10574000C9730108CF730108F56E00087F7901085D +:10575000EA730108E5B40008F9730108EA73010867 +:1057600085910008057401080A740108117B00087E +:10577000B86A01081A74010811BC000848740108CD +:105780003C740108E19A000845770108DE6B0108C6 +:1057900089BA00084F74010844000000402000202E +:1057A0000000000028230000587401084100000098 +:1057B0004220002000000000010000006674010883 +:1057C000440000004E210020B0040000A4060000A8 +:1057D0006D7401084400000050210020000000000A +:1057E000D007000077740108440000005221002017 +:1057F00000000000D0070000817401084200000092 +:105800005421002000000000120000008E740108E6 +:10581000420000005521002001000000FF000000B0 +:105820009974010842000000562100200000000089 +:1058300001000000AE7401084400000004210020B3 +:1058400000000000D0070000BB7401084400000005 +:105850000621002000000000D0070000C8740108E5 +:10586000440000000821002000000000D0070000D4 +:10587000D4740108440000000A2100200000000048 +:10588000D0070000E4740108440000000C2100204F +:1058900000000000D0070000F5740108440000007B +:1058A0000E21002000000000D00700000075010854 +:1058B000440000001021002000000000D00700007C +:1058C000157501084400000012210020320000007C +:1058D000007D000024750108440000001421002010 +:1058E00032000000F20100003375010841000000A1 +:1058F0005721002000000000010000004075010851 +:1059000041000000582100200000000001000000BC +:1059100053750108410000005921002000000000DB +:10592000B40000005F750108410000005A2100200A +:1059300000000000640000006B75010842000000D8 +:105940005B210020FFFFFFFF0100000081750108BF +:105950004100000060210020000000000B0000005A +:10596000987501084100000061210020000000003E +:105970000B000000AF75010841000000622100200B +:10598000000000000B000000C67501084100000087 +:1059900063210020000000000B000000DD750108FD +:1059A0004100000074210020300000007E00000053 +:1059B000EE7501085000000064210020B0040000D2 +:1059C00000C20100FB7501085000000068210020A2 +:1059D000B004000000C20100087601085000000079 +:1059E0006C2100200000000000C2010015760108B3 +:1059F0005000000070210020B004000000C201002F +:105A00002E760108410000005C210020000000000B +:105A1000010000003B760108410000005D210020EC +:105A20000000000004000000497601084100000069 +:105A30005E210020000000000100000059760108EE +:105A4000810000005022002000000000C80000007B +:105A500063760108810000005A2200200000000047 +:105A6000C80000006D76010881000000642200205B +:105A700000000000C80000007776010881000000E7 +:105A80005122002000000000C800000082760108BA +:105A9000810000005B22002000000000C800000020 +:105AA0008D760108810000006522002000000000C2 +:105AB000C8000000987601088100000052220020F2 +:105AC00000000000C8000000A2760108810000006C +:105AD0005C22002000000000C8000000AC76010835 +:105AE000810000006622002000000000C8000000C5 +:105AF000B676010884000000FA23002000000000B0 +:105B0000D0070000C476010881000000FE230020B9 +:105B10000000000001000000D976010884000000A8 +:105B2000002400200A000000D0070000E7760108EA +:105B300084000000022400200A000000D0070000BA +:105B4000F576010881000000FD2300200000000020 +:105B50006400000003770108410000004C21002090 +:105B6000000000000300000015770108410000005C +:105B700078210020000000000300000028770108C1 +:105B80004100000079210020000000000100000019 +:105B900039770108410000007A2100200000000050 +:105BA000010000004D770108600000007C2100200A +:105BB000A6FFFFFF5A0000006577010860000000A3 +:105BC000802100204CFFFFFFB40000007D7701081A +:105BD00041000000842100200000000001000000BE +:105BE0009677010841000000852100200000000098 +:105BF00001000000A17701084400000042210020BC +:105C000000000000204E0000B277010841000000B3 +:105C10003821002000000000FF000000BD770108CF +:105C200041000000392100200A000000320000007D +:105C3000D3770108410000003A2100200A0000004B +:105C400032000000E9770108440000003C210020F8 +:105C50000100000010270000FD770108440000004B +:105C60003E210020000000007206000012780108AA +:105C70004100000040210020000000000100000061 +:105C800030780108410000001621002000000000CB +:105C9000080000003B7801084100000017210020A7 +:105CA00000000000080000004578010841000000E5 +:105CB0001821002000000000080000004F780108B3 +:105CC000480000001A2100204CFFFFFF680100007F +:105CD00060780108480000001C2100204CFFFFFFF5 +:105CE0006801000072780108480000001E210020B1 +:105CF0004CFFFFFF680100008278010844000000AB +:105D00002A21002064000000840300009878010824 +:105D100044000000222100200000000000010000DB +:105D2000A1780108410000002821002000000000A7 +:105D300080000000B1780108440000002421002008 +:105D400064000000E8030000C2780108440000007D +:105D50002621002064000000E8030000D478010838 +:105D600081000000A723002001000000FA000000CD +:105D7000E678010881000000A82300200000000050 +:105D800001000000DD78010881000000A52300204B +:105D90000000000020000000FB78010881000000E6 +:105DA000A62300200000000064000000087901081C +:105DB00081000000AC2300200000000096000000DD +:105DC0002279010884000000AA23002001000000BD +:105DD000840300003C7901084200000020210020DB +:105DE000FFFFFFFF01000000527901088200000060 +:105DF000F6230020FFFFFFFF01000000607901088B +:105E000082000000F72300200000000001000000D5 +:105E10007279010881000000982200200000000033 +:105E20000200000087790108010100008A27002094 +:105E300000000000FA0000008F7901080101000055 +:105E40008B27002000000000640000009779010803 +:105E5000010100008C270020000000006400000009 +:105E60009F790108010100008D270020000000003B +:105E700064000000A8790108010100008E270020BD +:105E80000000000064000000B87901080101000072 +:105E90008F2700200000000064000000C179010885 +:105EA00001010000902700200000000064000000B5 +:105EB000CA7901080401000092270020E8030000CD +:105EC000D0070000D979010881000000EE230020EE +:105ED00000000000C8000000E8790108810000000F +:105EE000EF23002000000000C8000000FB7901083B +:105EF00084000000F0230020E8030000D007000029 +:105F00000D7A010884000000F223002064000000E4 +:105F1000D00700001F7A010884000000F42300204D +:105F200064000000B80B0000317A01088100000015 +:105F3000F823002000000000FF0000003E7A010866 +:105F400041000000212100200000000009000000A5 +:105F50004B7A010881000000A02200200000000010 +:105F6000FA0000005A7A010881000000A8220020EF +:105F70000000000064000000697A01088100000050 +:105F8000A92200200000000064000000777A0108C8 +:105F9000A0000000A4220020010000001400000066 +:105FA000877A010881000000BC2200200000000068 +:105FB00001000000967A0108880000009E2200205F +:105FC000D4FEFFFF2C010000A57A01088800000024 +:105FD0009C220020D4FEFFFF2C010000B37A0108B0 +:105FE00081000000AC220020000000003000000012 +:105FF000C17A0108A0000000B022002000000000CB +:1060000001000000D07A0108A0000000B4220020A6 +:106010000000000001000000DC7A0108A000000080 +:10602000B82200200000000001000000E87A01080A +:10603000880000009A220020B0B9FFFF50460000FF +:10604000F87A0108810000004822002000000000CA +:1060500002000000077B0108810000004D220020A3 +:1060600000000000C80000000F7B01088100000054 +:106070005722002000000000C80000006A780108D4 +:10608000810000006122002000000000C800000024 +:10609000177B0108810000004C2200200000000056 +:1060A000C80000001E7B010881000000562200206D +:1060B00000000000C80000005978010881000000BD +:1060C0006022002000000000C8000000257B0108BD +:1060D000810000004E22002000000000C8000000E7 +:1060E0002B7B0108810000005822002000000000E6 +:1060F000C80000007C7801088100000062220020B6 +:1061000000000000C8000000317B0108A000000072 +:106110007022002000000000640000003A7B0108AB +:10612000A00000007C2200200000000064000000AD +:10613000437B0108A000000088220020000000002E +:10614000640000004C7B0108A00000006C220020CD +:106150000000000064000000547B0108A000000063 +:106160007822002000000000640000005C7B010831 +:10617000A000000084220020000000006400000055 +:10618000647B0108A00000007422002000000000D1 +:10619000640000006B7B0108A0000000802200204A +:1061A0000000000064000000727B0108A0000000F5 +:1061B0008C2200200000000064000000797B0108B0 +:1061C000A000000094220020000000000A0000004F +:1061D000877B0108A0000000902200200000000042 +:1061E0000A000000937B0108810000004F2200207C +:1061F00000000000C8000000997B01088100000039 +:106200005922002000000000C80000009F7B010808 +:10621000810000006322002000000000C800000090 +:10622000A57B01088100000053220020000000002F +:10623000C8000000AD7B0108810000005D22002045 +:1062400000000000C8000000B57B010881000000CC +:106250006722002000000000C8000000BD7B01088C +:10626000810000005522002000000000C80000004E +:10627000C37B0108810000005F22002000000000B5 +:10628000C8000000C97B01088100000069220020CD +:1062900000000000C8000000CF7B010841000000A2 +:1062A000A82700200100000020000000E17B010879 +:1062B00041000000A927002001000000200000008C +:1062C0000000000048204669726D77617265207495 +:1062D0007970653A436C65616E666C696768740ACB +:1062E0000048204669726D77617265207265766933 +:1062F00073696F6E3A25730A00653437613832610D +:106300000048204669726D7761726520646174652A +:106310003A25732025730A00446563203137203203 +:106320003031340031373A30343A33380048207253 +:1063300063526174653A25640A0048206D696E7481 +:1063400068726F74746C653A25640A0048206D6148 +:10635000787468726F74746C653A25640A0048201A +:106360006779726F2E7363616C653A307825780AAD +:106370000048206163635F31473A25750A00736501 +:1063800072766F5B355D00310048204669656C644C +:106390002049206E616D653A6C6F6F70497465724B +:1063A0006174696F6E2C74696D652C6178697350C6 +:1063B0005B305D2C61786973505B315D2C6178696D +:1063C00073505B325D2C61786973495B305D2C6181 +:1063D000786973495B315D2C61786973495B325D23 +:1063E0002C61786973445B305D2C61786973445B20 +:1063F000315D2C61786973445B325D2C7263436F4D +:106400006D6D616E645B305D2C7263436F6D6D61A9 +:106410006E645B315D2C7263436F6D6D616E645BA6 +:10642000325D2C7263436F6D6D616E645B335D2C06 +:106430006779726F446174615B305D2C6779726F4C +:10644000446174615B315D2C6779726F4461746182 +:106450005B325D2C616363536D6F6F74685B305D9D +:106460002C616363536D6F6F74685B315D2C616386 +:1064700063536D6F6F74685B325D2C6D6F746F72F8 +:106480005B305D2C6D6F746F725B315D2C6D6F7462 +:106490006F725B325D2C6D6F746F725B335D2C6D50 +:1064A0006F746F725B345D2C6D6F746F725B355DF2 +:1064B0002C6D6F746F725B365D2C6D6F746F725BD9 +:1064C000375D0048204669656C6420492073696720 +:1064D0006E65643A302C302C312C312C312C312C1F +:1064E000312C312C312C312C312C312C312C312CC4 +:1064F000302C312C312C312C312C312C312C302CB6 +:10650000302C302C302C302C302C302C30004820CB +:106510004669656C64204920707265646963746FB4 +:10652000723A302C302C302C302C302C302C302C3B +:10653000302C302C302C302C302C302C302C342C77 +:10654000302C302C302C302C302C302C342C352C62 +:10655000352C352C352C352C352C3500482046690A +:10656000656C64204920656E636F64696E673A31BB +:106570002C312C302C302C302C302C302C302C303A +:106580002C302C302C302C302C302C312C302C302A +:106590002C302C302C302C302C312C302C302C301A +:1065A0002C302C302C302C300048204669656C642F +:1065B000205020707265646963746F723A362C32B1 +:1065C0002C312C312C312C312C312C312C312C31E3 +:1065D0002C312C312C312C312C312C332C332C33CD +:1065E0002C332C332C332C332C332C332C332C33B3 +:1065F0002C332C332C330048204669656C642050C2 +:1066000020656E636F64696E673A302C302C302CD5 +:10661000302C302C372C372C372C302C302C302C85 +:10662000382C382C382C382C302C302C302C302C6A +:10663000302C302C302C302C302C302C302C302C7A +:10664000302C300000000040000801400100000034 +:10665000001C00280000004000080140020000006B +:10666000041C002800000040000801400400000055 +:10667000081C00280000004000080140080000003D +:106680000C1C0028000400400008014040000000ED +:10669000001D0028000400400008014080000000A8 +:1066A000041D002800040040000C0140010000000F +:1066B000081D002800040040000C014002000000FA +:1066C0000C1D0028002C01400008014000010000C2 +:1066D000001B0128002C01400008014000080000B8 +:1066E0000C1B012800080040000C01404000000085 +:1066F000001E002800080040000C0140800000003F +:10670000041E002800080040000C014000010000A9 +:10671000081E002800080040000C01400002000094 +:106720000C1E002824505542582C34312C312C306A +:106730003030332C303030312C3131353230302C58 +:10674000302A31450D0A0024504D544B3235312C3E +:106750003131353230302A31460D0A00245055424D +:10676000582C34312C312C303030332C3030303107 +:106770002C35373630302C302A32440D0A00245064 +:106780004D544B3235312C35373630302A32430DAB +:106790000A0024505542582C34312C312C303030E2 +:1067A000332C303030312C33383430302C302A32E6 +:1067B000360D0A0024504D544B3235312C333834C9 +:1067C00030302A32370D0A0024505542582C3431CB +:1067D0002C312C303030332C303030312C313932B8 +:1067E00030302C302A32330D0A0024504D544B32B5 +:1067F00035312C31393230302A32320D0A004152D3 +:106800004D3B00414E474C453B00484F52495A4F83 +:106810004E3B004241524F3B004D41473B004845F3 +:106820004144465245453B004845414441444A3B6A +:106830000043414D535441423B0043414D54524962 +:10684000473B0047505320484F4D453B004750536E +:1068500020484F4C443B0050415353544852553B01 +:10686000004245455045523B004C45444D41583B44 +:10687000004C45444C4F573B004C4C4947485453FF +:106880003B0043414C49423B00474F5645524E4F17 +:10689000523B004F53442053573B0054454C454D09 +:1068A000455452593B004155544F54554E453B00B9 +:1068B000534F4E41523B0030313233343536373846 +:1068C000394142434445464748494A4B4C4D4E4F57 +:1068D000505152535455565758595A0061646A7270 +:1068E000616E676520257520257520257520257525 +:1068F0002025752025752025750D0A0061757820E5 +:1069000025752025752025752025752025750D0AEE +:1069100000004F201004430240010880C3437572F9 +:1069200072656E74206D697865723A2025730D0A60 +:1069300000417661696C61626C65206D6978657291 +:10694000733A200025732000496E76616C696420DB +:106950006D6978657220747970650D0A004D6978EB +:1069600065722073657420746F2025730D0A0055BD +:10697000736167653A0D0A6D6F746F7220696E649A +:106980006578205B76616C75655D202D2073686F7E +:1069900077205B6F72207365745D206D6F746F720A +:1069A0002076616C75650D0A004E6F207375636803 +:1069B000206D6F746F722C207573652061206E7569 +:1069C0006D626572205B302C2025645D0D0A004DE0 +:1069D0006F746F7220256420697320736574206161 +:1069E000742025640D0A00496E76616C6964206D1F +:1069F0006F746F722076616C75652C203130303089 +:106A00002E2E323030300D0A0053657474696E6773 +:106A1000206D6F746F7220256420746F2025640DC3 +:106A20000A00636F6C6F722025752025642C257514 +:106A30002C25750D0A00496E76616C696420636FC0 +:106A40006C6F7220696E6465783A206D757374207E +:106A50006265203C2025750D0A0050617273652027 +:106A60006572726F720D0A002E004E4709004F4B7F +:106A70000900437573746F6D206D697865723A20F3 +:106A80000D0A4D6F746F720954687209526F6C6C05 +:106A9000095069746368095961770D0A00232564F8 +:106AA0003A09002573090053616E6974792063689F +:106AB00065636B3A09007265736574006C6F61649D +:106AC000004C6F61646564202573206D69780D0A40 +:106AD0000057726F6E67206E756D626572206F660B +:106AE00020617267756D656E74732C206E656564C8 +:106AF00073206964782074687220726F6C6C2070E7 +:106B000069746368207961770D0A004D6F746F7244 +:106B1000206E756D626572206D75737420626520DC +:106B20006265747765656E203120616E642025642E +:106B30000D0A000D0A5265626F6F74696E67000D71 +:106B40000A4C656176696E6720434C49206D6F641D +:106B5000652C20756E7361766564206368616E676D +:106B60006573206C6F73742E0D0A00536176696E25 +:106B700067000D0A456E746572696E6720434C4963 +:106B8000204D6F64652C20747970652027657869C5 +:106B9000742720746F2072657475726E2C206F726A +:106BA000202768656C70270D0A000D0A2320000D50 +:106BB0001B5B4B001B5B324A1B5B313B3148005572 +:106BC0006E6B6E6F776E20636F6D6D616E642C20DF +:106BD000747279202768656C7027000820080041CE +:106BE0004554523132333400526573657474696EA2 +:106BF0006720746F2064656661756C7473007261E0 +:106C0000746570726F66696C652025640D0A0000FA +:106C10003008100200020001000600080008100100 +:106C20004008000710072007000410042008000097 +:106C300053797374656D20557074696D653A2025BC +:106C400064207365636F6E64732C20566F6C74617F +:106C500067653A202564202A20302E3156202825C9 +:106C600064532062617474657279290D0A0043507F +:106C7000552025644D487A2C2064657465637465DD +:106C8000642073656E736F72733A2000414343480A +:106C9000573A202573002E2563004379636C6520E5 +:106CA00054696D653A2025642C2049324320457291 +:106CB000726F72733A2025642C20636F6E66696769 +:106CC0002073697A653A2025640D0A004144584CC6 +:106CD000333435004D505536303530004D4D413848 +:106CE00034357800424D41323830004C534D33300A +:106CF00033444C4843004D505536303030004D50F1 +:106D000055363530300046414B45004E6F6E6500BC +:106D10004759524F00414343004241524F00534FA5 +:106D20004E415200475053004750532B4D414700AE +:106D3000456E61626C656420666561747572657329 +:106D40003A2000417661696C61626C65206665611C +:106D500074757265733A2000496E76616C696420BF +:106D600066656174757265206E616D650D0A00441B +:106D7000697361626C65642000456E61626C656474 +:106D8000200041464E41006D61737465720072616E +:106D9000746573000D0A232076657273696F6E0D3A +:106DA0000A000D0A232064756D70206D617374658F +:106DB000720D0A000D0A23206D697865720D0A00B4 +:106DC0006D697865722025730D0A00636D697820FE +:106DD000256400636D6978202564203020302030E0 +:106DE00020300D0A000D0A0D0A23206665617475B6 +:106DF00072650D0A0066656174757265202D2573D4 +:106E00000D0A00666561747572652025730D0A00B0 +:106E10000D0A0D0A23206D61700D0A006D6170204E +:106E200025730D0A000D0A0D0A23206C65640D0AF6 +:106E3000000D0A0D0A2320636F6C6F720D0A000D9E +:106E40000A232064756D702070726F66696C650D21 +:106E50000A000D0A232070726F66696C650D0A00C6 +:106E60000D0A23206175780D0A000D0A2320616444 +:106E70006A72616E67650D0A000D0A232064756DE4 +:106E8000702072617465730D0A000D0A232072610F +:106E9000746570726F66696C650D0A0052585F50B8 +:106EA000504D005642415400494E464C49474854C3 +:106EB0005F4143435F43414C0052585F5345524941 +:106EC000414C004D4F544F525F53544F5000534567 +:106ED00052564F5F54494C5400534F4654534552F9 +:106EE00049414C004641494C534146450054454CAC +:106EF000454D455452590043555252454E545F4DED +:106F0000455445520033440052585F504152414C61 +:106F10004C454C5F50574D0052585F4D53500052F6 +:106F20005353495F414443004C45445F53545249D5 +:106F30005000444953504C4159004F4E4553484F1F +:106F40005431323500424C41434B424F5800545269 +:106F5000490051554144500051554144580042495F +:106F60000047494D42414C005936004845583600CB +:106F7000464C59494E475F57494E470059340048DF +:106F800045583658004F43544F5838004F43544FDC +:106F9000464C415450004F43544F464C41545800C6 +:106FA000414952504C414E450048454C495F3132B1 +:106FB000305F4343504D0048454C495F39305F4492 +:106FC000454700565441494C34004845583648001E +:106FD00050504D5F544F5F534552564F00445541FA +:106FE0004C434F505445520053494E474C45434F34 +:106FF0005054455200435553544F4D00414552544F +:1070000031323334353637386162636465666768B8 +:1070100000436C65616E666C696768742F25732028 +:107020002573202F202573202825732900417661A0 +:10703000696C61626C6520636F6D6D616E64733A3B +:107040000D0A0025730925730D0A002025642025EB +:107050006400556E6B6E6F776E2076617269616247 +:107060006C65206E616D650D0A0043757272656E08 +:10707000742073657474696E67733A200D0A002575 +:10708000732073657420746F200056616C756520E1 +:1070900061737369676E6D656E74206F7574206FB0 +:1070A000662072616E67650D0A004D75737420620B +:1070B0006520616E79206F72646572206F66204171 +:1070C000455452313233340D0A0043757272656E85 +:1070D000742061737369676E6D656E743A20007316 +:1070E0006574202573203D200025752C25753A25D3 +:1070F000733A2573006C65642025752025730D0A8D +:1071000000496E76616C6964206C656420696E6408 +:1071100065783A206D757374206265203C20257572 +:107120000D0A005265763A20257300546172676536 +:10713000743A20257300566F6C74733A2025642EC0 +:107140002531642043656C6C733A20256400416DE1 +:1071500070733A2025642E253264206D41683A20F0 +:1071600025640020202020202020205820202020BE +:10717000205920202020205A0041203D2025356420 +:1071800020253564202535640047203D20253564C1 +:107190002025356420253564004D203D20253564AB +:1071A00020253564202535640050726F66696C6552 +:1071B0003A20256400526174652070726F66696CB4 +:1071C000653A202564005243204578706F3A2025A7 +:1071D0006400524320526174653A202564005226AF +:1071E0005020526174653A2025640059617720521D +:1071F0006174653A202564007C2F2D5C00434C456A +:10720000414E464C494748540041524D4544004286 +:107210004154544552590053454E534F5253005216 +:10722000580050524F46494C45004E415A45004582 +:1072300072726F723A20456E61626C6520616E6495 +:1072400020706C756720696E204750532066697204 +:1072500073740D0A0061646A72616E676500736819 +:107260006F772F7365742061646A7573746D656ED2 +:10727000742072616E6765732073657474696E67DC +:1072800073006175780073686F772F736574206180 +:1072900075782073657474696E677300636D6978BF +:1072A0000064657369676E20637573746F6D206D1C +:1072B0006978657200636F6C6F7200636F6E6669E8 +:1072C0006775726520636F6C6F72730072657365AA +:1072D0007420746F2064656661756C747320616ED0 +:1072E00064207265626F6F740064756D70007072F7 +:1072F000696E7420636F6E666967757261626C6532 +:107300002073657474696E677320696E20612070E4 +:1073100061737461626C6520666F726D0065786977 +:10732000740066656174757265006C697374206FB2 +:1073300072202D76616C206F722076616C0067651B +:107340007400676574207661726961626C6520768D +:10735000616C756500677073706173737468726FC8 +:1073600075676800706173737468726F7567682001 +:1073700067707320746F2073657269616C00686553 +:107380006C70006C656400636F6E6669677572652A +:10739000206C656473006D6170006D617070696E62 +:1073A00067206F66207263206368616E6E656C2073 +:1073B0006F72646572006D69786572206E616D65CB +:1073C000206F72206C697374006D6F746F72006748 +:1073D00065742F736574206D6F746F72206F757490 +:1073E0007075742076616C756500696E64657820CF +:1073F000283020746F203229007261746570726FBA +:1074000066696C65007361766500736176652061FD +:107410006E64207265626F6F74006E616D653D769B +:10742000616C7565206F7220626C616E6B206F728B +:10743000202A20666F72206C6973740073686F77FE +:107440002073797374656D20737461747573006C47 +:107450006F6F7074696D6500656D665F61766F69E9 +:1074600064616E6365006D69645F7263006D696E6F +:107470005F636865636B006D61785F636865636B0C +:1074800000727373695F6368616E6E656C0072731E +:1074900073695F7363616C6500696E7075745F66B4 +:1074A000696C746572696E675F6D6F6465006D69A4 +:1074B0006E5F7468726F74746C65006D61785F7470 +:1074C00068726F74746C65006D696E5F636F6D6D6B +:1074D000616E640033645F6465616462616E645F01 +:1074E0006C6F770033645F6465616462616E645FD2 +:1074F000686967680033645F6E65757472616C00FB +:1075000033645F6465616462616E645F7468726F46 +:1075100074746C65006D6F746F725F70776D5F72FD +:1075200061746500736572766F5F70776D5F72610D +:1075300074650072657461726465645F61726D0088 +:1075400064697361726D5F6B696C6C5F737769748A +:10755000636800736D616C6C5F616E676C6500667B +:107560006C6170735F7370656564006669786564EB +:1075700077696E675F616C74686F6C645F64697271 +:107580000073657269616C5F706F72745F315F73F5 +:1075900063656E6172696F0073657269616C5F70BB +:1075A0006F72745F325F7363656E6172696F0073CF +:1075B000657269616C5F706F72745F335F7363656E +:1075C0006E6172696F0073657269616C5F706F7272 +:1075D000745F345F7363656E6172696F00726562B8 +:1075E0006F6F745F636861726163746572006D735D +:1075F000705F626175647261746500636C695F627B +:1076000061756472617465006770735F626175644F +:1076100072617465006770735F7061737374687210 +:107620006F7567685F626175647261746500677029 +:10763000735F70726F7669646572006770735F73F1 +:107640006261735F6D6F6465006770735F6175740D +:107650006F5F636F6E666967006770735F706F73EB +:107660005F70006770735F706F735F69006770733E +:107670005F706F735F64006770735F706F73725FCA +:1076800070006770735F706F73725F69006770730B +:107690005F706F73725F64006770735F6E61765FB7 +:1076A00070006770735F6E61765F69006770735F0B +:1076B0006E61765F64006770735F77705F7261649C +:1076C000697573006E61765F636F6E74726F6C7351 +:1076D0005F68656164696E67006E61765F7370658F +:1076E00065645F6D696E006E61765F737065656479 +:1076F0005F6D6178006E61765F736C65775F726154 +:1077000074650073657269616C72785F70726F7610 +:10771000696465720074656C656D657472795F701B +:10772000726F76696465720074656C656D657472FC +:10773000795F7377697463680074656C656D6574EF +:1077400072795F696E76657273696F6E00667273C7 +:107750006B795F64656661756C745F6C6174746984 +:1077600074756465006672736B795F6465666175D4 +:107770006C745F6C6F6E67697475646500667273B4 +:107780006B795F636F6F7264696E617465735F6656 +:107790006F726D6174006672736B795F756E697478 +:1077A00000626174746572795F63617061636974AA +:1077B0007900766261745F7363616C650076626103 +:1077C000745F6D61785F63656C6C5F766F6C74611C +:1077D000676500766261745F6D696E5F63656C6C8E +:1077E0005F766F6C746167650063757272656E7445 +:1077F0005F6D657465725F7363616C65006375725C +:1078000072656E745F6D657465725F6F66667365D1 +:1078100074006D756C74697769695F637572726500 +:107820006E745F6D657465725F6F757470757400EA +:10783000616C69676E5F6779726F00616C69676E12 +:107840005F61636300616C69676E5F6D61670061B2 +:107850006C69676E5F626F6172645F726F6C6C00FF +:10786000616C69676E5F626F6172645F7069746397 +:107870006800616C69676E5F626F6172645F7961F5 +:1078800077006D61785F616E676C655F696E636CD0 +:10789000696E6174696F6E006779726F5F6C706694 +:1078A000006D6F726F6E5F7468726573686F6C6481 +:1078B000006779726F5F636D70665F666163746F96 +:1078C00072006779726F5F636D70666D5F6661638A +:1078D000746F7200616C745F686F6C645F64656183 +:1078E0006462616E6400616C745F686F6C645F6693 +:1078F0006173745F6368616E6765007961775F6467 +:1079000065616462616E64007468726F74746C6542 +:107910005F636F7272656374696F6E5F76616C75B9 +:1079200065007468726F74746C655F636F72726502 +:107930006374696F6E5F616E676C65007961775F14 +:10794000636F6E74726F6C5F646972656374696F84 +:107950006E007961775F646972656374696F6E0048 +:107960007472695F756E61726D65645F736572765E +:107970006F0064656661756C745F726174655F70D9 +:10798000726F66696C650072635F72617465007224 +:10799000635F6578706F007468725F6D696400740E +:1079A00068725F6578706F00726F6C6C5F7069747D +:1079B00063685F72617465007961775F7261746595 +:1079C000007470615F72617465007470615F6272EF +:1079D00065616B706F696E74006661696C73616676 +:1079E000655F64656C6179006661696C7361666589 +:1079F0005F6F66665F64656C6179006661696C7370 +:107A00006166655F7468726F74746C650066616945 +:107A10006C736166655F6D696E5F75736563006643 +:107A200061696C736166655F6D61785F75736563CD +:107A30000067696D62616C5F666C616773006163AA +:107A4000635F6861726477617265006163635F6C34 +:107A500070665F666163746F720061636378795FFB +:107A60006465616462616E64006163637A5F64652A +:107A7000616462616E64006163637A5F6C70665F0B +:107A80006375746F6666006163635F756E61726DC6 +:107A9000656463616C006163635F7472696D5F70DC +:107AA00069746368006163635F7472696D5F726FAC +:107AB0006C6C006261726F5F7461625F73697A659A +:107AC000006261726F5F6E6F6973655F6C706600F4 +:107AD0006261726F5F63665F76656C006261726F90 +:107AE0005F63665F616C74006D61675F6465636CA2 +:107AF000696E6174696F6E007069645F636F6E7444 +:107B0000726F6C6C657200705F7069746368006995 +:107B10005F706974636800705F726F6C6C00695F9E +:107B2000726F6C6C00705F79617700695F79617763 +:107B300000705F70697463686600695F7069746380 +:107B4000686600645F70697463686600705F726F76 +:107B50006C6C6600695F726F6C6C6600645F726F5C +:107B60006C6C6600705F7961776600695F79617738 +:107B70006600645F79617766006C6576656C5F6846 +:107B80006F72697A6F6E006C6576656C5F616E67A7 +:107B90006C6500705F616C7400695F616C74006497 +:107BA0005F616C7400705F6C6576656C00695F6C1A +:107BB0006576656C00645F6C6576656C00705F76F9 +:107BC000656C00695F76656C00645F76656C006269 +:107BD0006C61636B626F785F726174655F6E756D07 +:107BE00000626C61636B626F785F726174655F6481 +:107BF000656E6F6D0000202020202020202020288E +:107C00002828282820202020202020202020202054 +:107C1000202020202020881010101010101010108C +:107C200010101010101004040404040404040404CC +:107C3000101010101010104141414141410101014B +:107C40000101010101010101010101010101010124 +:107C50000110101010101042424242424202020231 +:107C600002020202020202020202020202020202F4 +:107C700002101010102000000000000000000000A2 +:107C800000000000000000000000000000000000F4 +:107C900000000000000000000000000000000000E4 +:107CA00000000000000000000000000000000000D4 +:107CB00000000000000000000000000000000000C4 +:107CC00000000000000000000000000000000000B4 +:107CD00000000000000000000000000000000000A4 +:107CE0000000000000000000000000000000000094 +:107CF00000000000000000000000004B000000CB6E +:107D000061636F7366000000706F776600000000AB +:107D100073717274660000000000000000C0153F1F +:107D200000000000DCCFD1350000803F0000C03FE4 +:107D3000000FC93F000F494000CB9640000FC940DB +:107D40000053FB4000CB164100ED2F41000F49418D +:107D50000031624100537B41003A8A4100CB964199 +:107D6000005CA34100EDAF41007EBC41000FC94162 +:107D700000A0D5410031E24100C2EE410053FB4179 +:107D800000F20342003A0A420083104200CB16423E +:107D900000141D42005C234200A5294200ED2F4241 +:107DA00000363642007E3C4200C74242000F494244 +:107DB000A2000000F9000000830000006E00000037 +:107DC0004E000000440000001500000029000000E3 +:107DD000FC0000002700000057000000D100000058 +:107DE000F500000034000000DD000000C0000000CD +:107DF000DB00000062000000950000009900000018 +:107E00003C00000043000000900000004100000022 +:107E1000FE0000005100000063000000AB00000005 +:107E2000DE000000BB000000C50000006100000093 +:107E3000B7000000240000006E0000003A000000BF +:107E4000420000004D000000D2000000E0000000F1 +:107E500006000000490000002E000000EA000000BB +:107E600009000000D1000000920000001C0000008A +:107E7000FE0000001D000000EB0000001C000000E0 +:107E8000B100000029000000A70000003E00000033 +:107E9000E80000008200000035000000F50000004E +:107EA0002E000000BB000000440000008400000021 +:107EB000E90000009C0000007000000026000000A7 +:107EC000B40000005F0000007E00000041000000E0 +:107ED0003900000091000000D600000039000000C9 +:107EE000830000005300000039000000F40000008F +:107EF0009C000000840000005F0000008B00000078 +:107F0000BD000000F9000000280000003B00000058 +:107F10001F000000F800000097000000FF000000B4 +:107F2000DE00000005000000980000000F000000C7 +:107F3000EF0000002F000000110000008B00000087 +:107F40005A0000000A0000006D0000001F00000041 +:107F50006D000000360000007E000000CF00000031 +:107F600027000000CB00000009000000B70000005F +:107F70004F000000460000003F00000066000000C7 +:107F80009E0000005F000000EA0000002D000000DD +:107F90007500000027000000BA000000C7000000C4 +:107FA000EB000000E5000000F10000007B00000095 +:107FB0003D0000000700000039000000F70000004D +:107FC0008A0000005200000092000000EA00000059 +:107FD0006B000000FB0000005F000000B10000002B +:107FE0001F0000008D0000005D0000000800000080 +:107FF00056000000030000003000000046000000B2 +:10800000FC0000007B0000006B000000AB000000E3 +:10801000F0000000CF000000BC00000020000000C5 +:108020009A000000F4000000360000001D0000006F +:10803000A9000000E30000009100000061000000C2 +:108040005E000000E60000001B00000008000000C9 +:108050006500000099000000850000005F0000003E +:1080600014000000A00000006800000040000000B4 +:108070008D000000FF000000D8000000800000001C +:108080004D000000730000002700000031000000D8 +:108090000600000006000000150000005600000069 +:1080A000CA00000073000000A8000000C900000022 +:1080B00060000000E20000007B000000C000000043 +:1080C0008C0000006B0000000400000007000000AE +:1080D000090000000000C93F0000F0390000DA3755 +:1080E0000000A2330000842E0000502B0000C227A5 +:1080F0000000D0220000C41F0000C61B000044176F +:10810000000000000000304300000000000030C309 +:108110006937AC3168212233B40F14336821A2339C +:108120003863ED3EDA0F493F5E987B3FDA0FC93F77 +:088130001C74FF7F0100000038 +:10813800000100000000803F000000000000000077 +:108148000100DC05DC05DC05DC05DC05DC05DC05FF +:10815800DC05000000127A000000000000000000AA +:108168000102030406070809010303000000803F19 +:108178000000803F0000803F010100000000803FB8 +:1081880000000000010203040102030406070809B5 +:1081980002040608010000000000000000000000C2 +:1081A80000000000010000000000000000000000C6 +:1081B80003000000000000000000000004000000B0 +:1081C800000000000000000003000000D17C00084F +:1081D8000F270000FFFFFFFF00A24A04826D01087D +:1081E800FD710108097201080F7201081772010870 +:1081F8001F720108227201082A720108F57B010822 +:108208000000000000000000000000000000000066 +:108218000000000000000000000000000000000056 +:10822800176D0108000000000000000000000000B9 +:108238000000000000000000000000000000000036 +:108248000000000000000000000000000000000026 +:108258000000000000000000000000000000000016 +:08826800D0000020010000001D :0400000508000000EF :00000001FF diff --git a/src/main/blackbox/blackbox.c b/src/main/blackbox/blackbox.c index b5cd03eaf5..eadd8621b8 100644 --- a/src/main/blackbox/blackbox.c +++ b/src/main/blackbox/blackbox.c @@ -77,11 +77,7 @@ #define BLACKBOX_BAUDRATE 115200 #define BLACKBOX_INITIAL_PORT_MODE MODE_TX - -static const char blackboxHeader[] = - "H Product:Blackbox flight data recorder by Nicholas Sherlock\n" - "H Blackbox version:1\n" - "H Data version:1\n"; +#define BLACKBOX_I_INTERVAL 32 // Some macros to make writing FLIGHT_LOG_FIELD_PREDICTOR_* constants shorter: #define STR_HELPER(x) #x @@ -93,6 +89,12 @@ static const char blackboxHeader[] = #define PREDICT(x) STR(CONCAT(FLIGHT_LOG_FIELD_PREDICTOR_, x)) #define ENCODING(x) STR(CONCAT(FLIGHT_LOG_FIELD_ENCODING_, x)) +static const char blackboxHeader[] = + "H Product:Blackbox flight data recorder by Nicholas Sherlock\n" + "H Blackbox version:1\n" + "H Data version:1\n" + "H I interval:" STR(BLACKBOX_I_INTERVAL) "\n"; + /* These headers have info for all 8 motors on them, we'll trim the final fields off to match the number of motors in the mixer: */ static const char * const blackboxHeaderFields[] = { "H Field I name:" @@ -288,10 +290,10 @@ static uint32_t previousBaudRate; static gpsState_t gpsHistory; // Keep a history of length 2, plus a buffer for MW to store the new values into -static blackbox_values_t blackboxHistoryRing[3]; +static blackboxValues_t blackboxHistoryRing[3]; // These point into blackboxHistoryRing, use them to know where to store history of a given age (0, 1 or 2 generations old) -static blackbox_values_t* blackboxHistory[3]; +static blackboxValues_t* blackboxHistory[3]; static int isTricopter() { @@ -536,7 +538,7 @@ static void writeTag8_4S16(int32_t *values) { static void writeIntraframe(void) { - blackbox_values_t *blackboxCurrent = blackboxHistory[0]; + blackboxValues_t *blackboxCurrent = blackboxHistory[0]; int x; blackboxWrite('I'); @@ -589,8 +591,8 @@ static void writeInterframe(void) int x; int32_t deltas[4]; - blackbox_values_t *blackboxCurrent = blackboxHistory[0]; - blackbox_values_t *blackboxLast = blackboxHistory[1]; + blackboxValues_t *blackboxCurrent = blackboxHistory[0]; + blackboxValues_t *blackboxLast = blackboxHistory[1]; blackboxWrite('P'); @@ -645,6 +647,28 @@ static void writeInterframe(void) blackboxHistory[0] = ((blackboxHistory[0] - blackboxHistoryRing + 1) % 3) + blackboxHistoryRing; } +static int gcd(int num, int denom) +{ + if (denom == 0) + return num; + return gcd(denom, num % denom); +} + +static void validateBlackboxConfig() +{ + int div; + + if (masterConfig.blackbox_rate_num >= masterConfig.blackbox_rate_denom) { + masterConfig.blackbox_rate_num = 1; + masterConfig.blackbox_rate_denom = 1; + } else { + div = gcd(masterConfig.blackbox_rate_num, masterConfig.blackbox_rate_denom); + + masterConfig.blackbox_rate_num /= div; + masterConfig.blackbox_rate_denom /= div; + } +} + static void configureBlackboxPort(void) { blackboxPort = findOpenSerialPort(FUNCTION_BLACKBOX); @@ -676,6 +700,8 @@ static void releaseBlackboxPort(void) void startBlackbox(void) { if (blackboxState == BLACKBOX_STATE_STOPPED) { + validateBlackboxConfig(); + configureBlackboxPort(); if (!blackboxPort) { @@ -739,7 +765,7 @@ static void writeGPSFrame() */ static void loadBlackboxState(void) { - blackbox_values_t *blackboxCurrent = blackboxHistory[0]; + blackboxValues_t *blackboxCurrent = blackboxHistory[0]; int i; blackboxCurrent->time = currentTime; @@ -774,6 +800,8 @@ void handleBlackbox(void) const int SERIAL_CHUNK_SIZE = 16; static int charXmitIndex = 0; int motorsToRemove, endIndex; + int blackboxIntercycleIndex, blackboxIntracycleIndex; + union floatConvert_t { float f; uint32_t u; @@ -894,17 +922,19 @@ void handleBlackbox(void) headerXmitIndex++; break; case BLACKBOX_STATE_RUNNING: - // Copy current system values into the blackbox - loadBlackboxState(); - // Write a keyframe every 32 frames so we can resynchronise upon missing frames - int blackboxIntercycleIndex = blackboxIteration % 32; - int blackboxIntracycleIndex = blackboxIteration / 32; + blackboxIntercycleIndex = blackboxIteration % BLACKBOX_I_INTERVAL; + blackboxIntracycleIndex = blackboxIteration / BLACKBOX_I_INTERVAL; - if (blackboxIntercycleIndex == 0) + if (blackboxIntercycleIndex == 0) { + // Copy current system values into the blackbox + loadBlackboxState(); writeIntraframe(); - else { - writeInterframe(); + } else { + if ((blackboxIntercycleIndex + masterConfig.blackbox_rate_num - 1) % masterConfig.blackbox_rate_denom < masterConfig.blackbox_rate_num) { + loadBlackboxState(); + writeInterframe(); + } if (feature(FEATURE_GPS)) { /* @@ -915,7 +945,7 @@ void handleBlackbox(void) * still be interpreted correctly. */ if (GPS_home[0] != gpsHistory.GPS_home[0] || GPS_home[1] != gpsHistory.GPS_home[1] - || (blackboxIntercycleIndex == 15 && blackboxIntracycleIndex % 128 == 0)) { + || (blackboxIntercycleIndex == BLACKBOX_I_INTERVAL / 2 && blackboxIntracycleIndex % 128 == 0)) { writeGPSHomeFrame(); writeGPSFrame(); @@ -934,7 +964,7 @@ void handleBlackbox(void) } } -bool canUseBlackboxWithCurrentConfiguration(void) +static bool canUseBlackboxWithCurrentConfiguration(void) { if (!feature(FEATURE_BLACKBOX)) return false; diff --git a/src/main/blackbox/blackbox.h b/src/main/blackbox/blackbox.h index cd8f326c34..de5cc344d7 100644 --- a/src/main/blackbox/blackbox.h +++ b/src/main/blackbox/blackbox.h @@ -19,7 +19,7 @@ #include -typedef struct blackbox_values_t { +typedef struct blackboxValues_t { uint32_t time; int32_t axisP[3], axisI[3], axisD[3]; @@ -29,7 +29,7 @@ typedef struct blackbox_values_t { int16_t accSmooth[3]; int16_t motor[MAX_SUPPORTED_MOTORS]; int16_t servo[MAX_SUPPORTED_SERVOS]; -} blackbox_values_t; +} blackboxValues_t; void initBlackbox(void); void handleBlackbox(void); diff --git a/src/main/config/config.c b/src/main/config/config.c index bc96cdc189..1c4ff1a027 100644 --- a/src/main/config/config.c +++ b/src/main/config/config.c @@ -435,6 +435,11 @@ static void resetConf(void) applyDefaultLedStripConfig(masterConfig.ledConfigs); #endif +#ifdef BLACKBOX + masterConfig.blackbox_rate_num = 1; + masterConfig.blackbox_rate_denom = 1; +#endif + // copy first profile into remaining profile for (i = 1; i < MAX_PROFILE_COUNT; i++) { memcpy(&masterConfig.profile[i], currentProfile, sizeof(profile_t)); diff --git a/src/main/config/config_master.h b/src/main/config/config_master.h index c354d9e58a..f1aeac24a1 100644 --- a/src/main/config/config_master.h +++ b/src/main/config/config_master.h @@ -82,6 +82,8 @@ typedef struct master_t { uint8_t current_profile_index; controlRateConfig_t controlRateProfiles[MAX_CONTROL_RATE_PROFILE_COUNT]; + uint8_t blackbox_rate_num; + uint8_t blackbox_rate_denom; uint8_t magic_ef; // magic number, should be 0xEF uint8_t chk; // XOR checksum diff --git a/src/main/io/serial_cli.c b/src/main/io/serial_cli.c index e18370e0c0..4716572dee 100644 --- a/src/main/io/serial_cli.c +++ b/src/main/io/serial_cli.c @@ -386,6 +386,9 @@ const clivalue_t valueTable[] = { { "p_vel", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[PIDVEL], 0, 200 }, { "i_vel", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[PIDVEL], 0, 200 }, { "d_vel", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[PIDVEL], 0, 200 }, + + { "blackbox_rate_num", VAR_UINT8 | MASTER_VALUE, &masterConfig.blackbox_rate_num, 1, 32 }, + { "blackbox_rate_denom", VAR_UINT8 | MASTER_VALUE, &masterConfig.blackbox_rate_denom, 1, 32 }, }; #define VALUE_COUNT (sizeof(valueTable) / sizeof(clivalue_t)) From 172256c91e6614bb2e84f2efc7aec06e2d744f1a Mon Sep 17 00:00:00 2001 From: Nicholas Sherlock Date: Wed, 17 Dec 2014 21:31:28 +1300 Subject: [PATCH 06/24] Update readme --- README.md | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/README.md b/README.md index 9ddd494400..974296ec2f 100644 --- a/README.md +++ b/README.md @@ -2,8 +2,8 @@ ![Rendered flight log frame](http://i.imgur.com/FBphB8c.jpg) -WARNING - This firmware is experimental, and may cause your craft to suddenly fall out of the sky. This port to -Cleanflight has only had 3 test flights! No warranty is offered: if your craft breaks, you get to keep both pieces. +WARNING - This firmware is experimental, and may cause your craft to suddenly fall out of the sky. No warranty is +offered: if your craft breaks, you get to keep both pieces. ## Introduction This is a modified version of Cleanflight which adds a flight data recorder function ("Blackbox"). Flight data @@ -18,7 +18,8 @@ use the Cleanflight firmware from this repository instead of the Baseflight firm https://github.com/thenickdude/blackbox -Instructions which are specific to Cleanflight are included here. +You will also find the tools to turn your logs into CSV logs or PNG image files. Instructions which are specific to +Cleanflight are included here. ## Installation of firmware Before installing the new firmware onto your Naze32, back up your configuration: Connect to your flight controller From 5aa8e61c6ede5daf70d8c0a9b2534bbb80837c02 Mon Sep 17 00:00:00 2001 From: Nicholas Sherlock Date: Thu, 18 Dec 2014 17:39:09 +1300 Subject: [PATCH 07/24] Be defensive and don't mod by zero if denominator somehow gets set to zero --- src/main/blackbox/blackbox.c | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/src/main/blackbox/blackbox.c b/src/main/blackbox/blackbox.c index eadd8621b8..87fc45a08f 100644 --- a/src/main/blackbox/blackbox.c +++ b/src/main/blackbox/blackbox.c @@ -658,7 +658,8 @@ static void validateBlackboxConfig() { int div; - if (masterConfig.blackbox_rate_num >= masterConfig.blackbox_rate_denom) { + if (masterConfig.blackbox_rate_num == 0 || masterConfig.blackbox_rate_denom == 0 + || masterConfig.blackbox_rate_num >= masterConfig.blackbox_rate_denom) { masterConfig.blackbox_rate_num = 1; masterConfig.blackbox_rate_denom = 1; } else { From 0ed47d5e6df18ee14f20bdc1110fcce6e6d9a482 Mon Sep 17 00:00:00 2001 From: Nicholas Sherlock Date: Thu, 18 Dec 2014 18:42:22 +1300 Subject: [PATCH 08/24] Use spaces instead of tabs --- src/main/blackbox/blackbox.c | 1964 +++++++++++++++++----------------- src/main/blackbox/blackbox.h | 74 +- src/main/flight/flight.c | 6 +- src/main/mw.c | 10 +- 4 files changed, 1027 insertions(+), 1027 deletions(-) diff --git a/src/main/blackbox/blackbox.c b/src/main/blackbox/blackbox.c index 87fc45a08f..baad91d3fc 100644 --- a/src/main/blackbox/blackbox.c +++ b/src/main/blackbox/blackbox.c @@ -1,982 +1,982 @@ -/* - * This file is part of Cleanflight. - * - * Cleanflight is free software: you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * Cleanflight is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with Cleanflight. If not, see . - */ - -#include -#include -#include - -#include "platform.h" -#include "version.h" - -#include "common/maths.h" -#include "common/axis.h" -#include "common/color.h" - -#include "drivers/accgyro.h" -#include "drivers/light_led.h" - -#include "drivers/gpio.h" -#include "drivers/system.h" -#include "drivers/serial.h" -#include "drivers/timer.h" -#include "drivers/pwm_rx.h" - -#include "common/printf.h" - -#include "flight/flight.h" -#include "sensors/sensors.h" -#include "sensors/boardalignment.h" -#include "sensors/sonar.h" -#include "sensors/compass.h" -#include "sensors/acceleration.h" -#include "sensors/barometer.h" -#include "sensors/gyro.h" -#include "sensors/battery.h" -#include "io/beeper.h" -#include "io/display.h" -#include "io/escservo.h" -#include "rx/rx.h" -#include "io/rc_controls.h" -#include "flight/mixer.h" -#include "flight/altitudehold.h" -#include "flight/failsafe.h" -#include "flight/imu.h" -#include "flight/autotune.h" -#include "flight/navigation.h" -#include "io/gimbal.h" -#include "io/gps.h" -#include "io/ledstrip.h" -#include "io/serial.h" -#include "io/serial_cli.h" -#include "io/serial_msp.h" -#include "io/statusindicator.h" -#include "rx/msp.h" -#include "telemetry/telemetry.h" - -#include "config/runtime_config.h" -#include "config/config.h" -#include "config/config_profile.h" -#include "config/config_master.h" - -#include "blackbox_fielddefs.h" -#include "blackbox.h" - -#define BLACKBOX_BAUDRATE 115200 -#define BLACKBOX_INITIAL_PORT_MODE MODE_TX -#define BLACKBOX_I_INTERVAL 32 - -// Some macros to make writing FLIGHT_LOG_FIELD_PREDICTOR_* constants shorter: -#define STR_HELPER(x) #x -#define STR(x) STR_HELPER(x) - -#define CONCAT_HELPER(x,y) x ## y -#define CONCAT(x,y) CONCAT_HELPER(x, y) - -#define PREDICT(x) STR(CONCAT(FLIGHT_LOG_FIELD_PREDICTOR_, x)) -#define ENCODING(x) STR(CONCAT(FLIGHT_LOG_FIELD_ENCODING_, x)) - -static const char blackboxHeader[] = - "H Product:Blackbox flight data recorder by Nicholas Sherlock\n" - "H Blackbox version:1\n" - "H Data version:1\n" - "H I interval:" STR(BLACKBOX_I_INTERVAL) "\n"; - -/* These headers have info for all 8 motors on them, we'll trim the final fields off to match the number of motors in the mixer: */ -static const char * const blackboxHeaderFields[] = { - "H Field I name:" - "loopIteration,time," - "axisP[0],axisP[1],axisP[2]," - "axisI[0],axisI[1],axisI[2]," - "axisD[0],axisD[1],axisD[2]," - "rcCommand[0],rcCommand[1],rcCommand[2],rcCommand[3]," - "gyroData[0],gyroData[1],gyroData[2]," - "accSmooth[0],accSmooth[1],accSmooth[2]," - "motor[0],motor[1],motor[2],motor[3]," - "motor[4],motor[5],motor[6],motor[7]", - - "H Field I signed:" - /* loopIteration, time: */ - "0,0," - /* PIDs: */ - "1,1,1,1,1,1,1,1,1," - /* rcCommand[0..2] */ - "1,1,1," - /* rcCommand[3] (Throttle): */ - "0," - /* gyroData[0..2]: */ - "1,1,1," - /* accSmooth[0..2]: */ - "1,1,1," - /* Motor[0..7]: */ - "0,0,0,0,0,0,0,0", - - "H Field I predictor:" - /* loopIteration, time: */ - PREDICT(0) "," PREDICT(0) "," - /* PIDs: */ - PREDICT(0) "," PREDICT(0) "," PREDICT(0) "," - PREDICT(0) "," PREDICT(0) "," PREDICT(0) "," - PREDICT(0) "," PREDICT(0) "," PREDICT(0) "," - /* rcCommand[0..2] */ - PREDICT(0) "," PREDICT(0) "," PREDICT(0) "," - /* rcCommand[3] (Throttle): */ - PREDICT(MINTHROTTLE) "," - /* gyroData[0..2]: */ - PREDICT(0) "," PREDICT(0) "," PREDICT(0) "," - /* accSmooth[0..2]: */ - PREDICT(0) "," PREDICT(0) "," PREDICT(0) "," - /* Motor[0]: */ - PREDICT(MINTHROTTLE) "," - /* Motor[1..7]: */ - PREDICT(MOTOR_0) "," PREDICT(MOTOR_0) "," PREDICT(MOTOR_0) "," - PREDICT(MOTOR_0) "," PREDICT(MOTOR_0) "," PREDICT(MOTOR_0) "," - PREDICT(MOTOR_0), - - "H Field I encoding:" - /* loopIteration, time: */ - ENCODING(UNSIGNED_VB) "," ENCODING(UNSIGNED_VB) "," - /* PIDs: */ - ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," - ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," - ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," - /* rcCommand[0..2] */ - ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," - /* rcCommand[3] (Throttle): */ - ENCODING(UNSIGNED_VB) "," - /* gyroData[0..2]: */ - ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," - /* accSmooth[0..2]: */ - ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," - /* Motor[0]: */ - ENCODING(UNSIGNED_VB) "," - /* Motor[1..7]: */ - ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," - ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," - ENCODING(SIGNED_VB), - - //Motors and gyros predict an average of the last two measurements (to reduce the impact of noise): - "H Field P predictor:" - /* loopIteration, time: */ - PREDICT(INC) "," PREDICT(STRAIGHT_LINE) "," - /* PIDs: */ - PREDICT(PREVIOUS) "," PREDICT(PREVIOUS) "," PREDICT(PREVIOUS) "," - PREDICT(PREVIOUS) "," PREDICT(PREVIOUS) "," PREDICT(PREVIOUS) "," - PREDICT(PREVIOUS) "," PREDICT(PREVIOUS) "," PREDICT(PREVIOUS) "," - /* rcCommand[0..2] */ - PREDICT(PREVIOUS) "," PREDICT(PREVIOUS) "," PREDICT(PREVIOUS) "," - /* rcCommand[3] (Throttle): */ - PREDICT(PREVIOUS) "," - /* gyroData[0..2]: */ - PREDICT(AVERAGE_2) "," PREDICT(AVERAGE_2) "," PREDICT(AVERAGE_2) "," - /* accSmooth[0..2]: */ - PREDICT(AVERAGE_2) "," PREDICT(AVERAGE_2) "," PREDICT(AVERAGE_2) "," - /* Motor[0]: */ - PREDICT(AVERAGE_2) "," - /* Motor[1..7]: */ - PREDICT(AVERAGE_2) "," PREDICT(AVERAGE_2) "," PREDICT(AVERAGE_2) "," - PREDICT(AVERAGE_2) "," PREDICT(AVERAGE_2) "," PREDICT(AVERAGE_2) "," - PREDICT(AVERAGE_2), - - /* RC fields are encoded together as a group, everything else is signed since they're diffs: */ - "H Field P encoding:" - /* loopIteration, time: */ - ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," - /* PIDs: */ - ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," - ENCODING(TAG2_3S32) "," ENCODING(TAG2_3S32) "," ENCODING(TAG2_3S32) "," - ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," - /* rcCommand[0..3] */ - ENCODING(TAG8_4S16) "," ENCODING(TAG8_4S16) "," ENCODING(TAG8_4S16) "," - ENCODING(TAG8_4S16) "," - /* gyroData[0..2]: */ - ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," - /* accSmooth[0..2]: */ - ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," - /* Motor[0]: */ - ENCODING(SIGNED_VB) "," - /* Motor[1..7]: */ - ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," - ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," - ENCODING(SIGNED_VB) -}; - -/** - * Additional fields to tack on to those above for tricopters (to record tail servo position) - */ -static const char * const blackboxAdditionalFieldsTricopter[] = { - //Field I name - "servo[5]", - - //Field I signed - "0", - - //Field I predictor - PREDICT(1500), - - //Field I encoding: - ENCODING(SIGNED_VB), - - //Field P predictor: - PREDICT(PREVIOUS), - - //Field P encoding: - ENCODING(SIGNED_VB) -}; - -static const char blackboxGpsHeader[] = - "H Field G name:" - "GPS_numSat,GPS_coord[0],GPS_coord[1],GPS_altitude,GPS_speed\n" - "H Field G signed:" - "0,1,1,0,0\n" - "H Field G predictor:" - PREDICT(0) "," PREDICT(HOME_COORD) "," PREDICT(HOME_COORD) "," PREDICT(0) "," PREDICT(0) "\n" - "H Field G encoding:" - ENCODING(UNSIGNED_VB) "," ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," - ENCODING(UNSIGNED_VB) "," ENCODING(UNSIGNED_VB) "\n" - - "H Field H name:" - "GPS_home[0],GPS_home[1]\n" - "H Field H signed:" - "1,1\n" - "H Field H predictor:" - PREDICT(0) "," PREDICT(0) "\n" - "H Field H encoding:" - ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "\n"; - -typedef enum BlackboxState { - BLACKBOX_STATE_DISABLED = 0, - BLACKBOX_STATE_STOPPED, - BLACKBOX_STATE_SEND_HEADER, - BLACKBOX_STATE_SEND_FIELDINFO, - BLACKBOX_STATE_SEND_GPS_HEADERS, - BLACKBOX_STATE_SEND_SYSINFO, - BLACKBOX_STATE_RUNNING -} BlackboxState; - -typedef struct gpsState_t { - int32_t GPS_home[2], GPS_coord[2]; - uint8_t GPS_numSat; -} gpsState_t; - -//From mixer.c: -extern uint8_t motorCount; - -//From mw.c: -extern uint32_t currentTime; - -static BlackboxState blackboxState = BLACKBOX_STATE_DISABLED; -static uint32_t startTime; -static unsigned int headerXmitIndex; -static uint32_t blackboxIteration; - -static serialPort_t *blackboxPort; -static portMode_t previousPortMode; -static uint32_t previousBaudRate; - -static gpsState_t gpsHistory; - -// Keep a history of length 2, plus a buffer for MW to store the new values into -static blackboxValues_t blackboxHistoryRing[3]; - -// These point into blackboxHistoryRing, use them to know where to store history of a given age (0, 1 or 2 generations old) -static blackboxValues_t* blackboxHistory[3]; - -static int isTricopter() -{ - return masterConfig.mixerConfiguration == MULTITYPE_TRI; -} - -static void blackboxWrite(uint8_t value) -{ - serialWrite(blackboxPort, value); -} - -static void _putc(void *p, char c) -{ - (void)p; - serialWrite(blackboxPort, c); -} - -//printf() to the blackbox serial port with no blocking shenanigans (so it's caller's responsibility to not write too fast!) -static void blackboxPrintf(char *fmt, ...) -{ - va_list va; - va_start(va, fmt); - tfp_format(NULL, _putc, fmt, va); - va_end(va); -} - -/** - * Write an unsigned integer to the blackbox serial port using variable byte encoding. - */ -static void writeUnsignedVB(uint32_t value) -{ - //While this isn't the final byte (we can only write 7 bits at a time) - while (value > 127) { - blackboxWrite((uint8_t) (value | 0x80)); // Set the high bit to mean "more bytes follow" - value >>= 7; - } - blackboxWrite(value); -} - -/** - * Write a signed integer to the blackbox serial port using ZigZig and variable byte encoding. - */ -static void writeSignedVB(int32_t value) -{ - //ZigZag encode to make the value always positive - writeUnsignedVB((uint32_t)((value << 1) ^ (value >> 31))); -} - -/** - * Write a 2 bit tag followed by 3 signed fields of 2, 4, 6 or 32 bits - */ -static void writeTag2_3S32(int32_t *values) { - static const int NUM_FIELDS = 3; - - //Need to be enums rather than const ints if we want to switch on them (due to being C) - enum { BITS_2 = 0}; - enum { BITS_4 = 1}; - enum { BITS_6 = 2}; - enum { BITS_32 = 3}; - - enum { BYTES_1 = 0}; - enum { BYTES_2 = 1}; - enum { BYTES_3 = 2}; - enum { BYTES_4 = 3}; - - int x; - int selector = BITS_2, selector2; - - /* - * Find out how many bits the largest value requires to encode, and use it to choose one of the packing schemes - * below: - * - * Selector possibilities - * - * 2 bits per field ss11 2233, - * 4 bits per field ss00 1111 2222 3333 - * 6 bits per field ss11 1111 0022 2222 0033 3333 - * 32 bits per field sstt tttt followed by fields of various byte counts - */ - for (x = 0; x < NUM_FIELDS; x++) { - //Require more than 6 bits? - if (values[x] >= 32 || values[x] < -32) { - selector = BITS_32; - break; - } - - //Require more than 4 bits? - if (values[x] >= 8 || values[x] < -8) { - if (selector < BITS_6) - selector = BITS_6; - } else if (values[x] >= 2 || values[x] < -2) { //Require more than 2 bits? - if (selector < BITS_4) - selector = BITS_4; - } - } - - switch (selector) { - case BITS_2: - blackboxWrite((selector << 6) | ((values[0] & 0x03) << 4) | ((values[1] & 0x03) << 2) | (values[2] & 0x03)); - break; - case BITS_4: - blackboxWrite((selector << 6) | (values[0] & 0x0F)); - blackboxWrite((values[1] << 4) | (values[2] & 0x0F)); - break; - case BITS_6: - blackboxWrite((selector << 6) | (values[0] & 0x3F)); - blackboxWrite((uint8_t)values[1]); - blackboxWrite((uint8_t)values[2]); - break; - case BITS_32: - /* - * Do another round to compute a selector for each field, assuming that they are at least 8 bits each - * - * Selector2 field possibilities - * 0 - 8 bits - * 1 - 16 bits - * 2 - 24 bits - * 3 - 32 bits - */ - selector2 = 0; - - //Encode in reverse order so the first field is in the low bits: - for (x = NUM_FIELDS - 1; x >= 0; x--) { - selector2 <<= 2; - - if (values[x] < 128 && values[x] >= -128) - selector2 |= BYTES_1; - else if (values[x] < 32768 && values[x] >= -32768) - selector2 |= BYTES_2; - else if (values[x] < 8388608 && values[x] >= -8388608) - selector2 |= BYTES_3; - else - selector2 |= BYTES_4; - } - - //Write the selectors - blackboxWrite((selector << 6) | selector2); - - //And now the values according to the selectors we picked for them - for (x = 0; x < NUM_FIELDS; x++, selector2 >>= 2) { - switch (selector2 & 0x03) { - case BYTES_1: - blackboxWrite(values[x]); - break; - case BYTES_2: - blackboxWrite(values[x]); - blackboxWrite(values[x] >> 8); - break; - case BYTES_3: - blackboxWrite(values[x]); - blackboxWrite(values[x] >> 8); - blackboxWrite(values[x] >> 16); - break; - case BYTES_4: - blackboxWrite(values[x]); - blackboxWrite(values[x] >> 8); - blackboxWrite(values[x] >> 16); - blackboxWrite(values[x] >> 24); - break; - } - } - break; - } -} - -/** - * Write an 8-bit selector followed by four signed fields of size 0, 4, 8 or 16 bits. - */ -static void writeTag8_4S16(int32_t *values) { - - //Need to be enums rather than const ints if we want to switch on them (due to being C) - enum { FIELD_ZERO = 0}; - enum { FIELD_4BIT = 1}; - enum { FIELD_8BIT = 2}; - enum { FIELD_16BIT = 3}; - - uint8_t selector; - int x; - - /* - * 4-bit fields can only be combined with their paired neighbor (there are two pairs), so choose a - * larger encoding if that's not possible. - */ - const uint8_t rcSelectorCleanup[16] = { - // Output selectors <- Input selectors - FIELD_ZERO << 2 | FIELD_ZERO, // zero, zero - FIELD_ZERO << 2 | FIELD_8BIT, // zero, 4-bit - FIELD_ZERO << 2 | FIELD_8BIT, // zero, 8-bit - FIELD_ZERO << 2 | FIELD_16BIT, // zero, 16-bit - FIELD_8BIT << 2 | FIELD_ZERO, // 4-bit, zero - FIELD_4BIT << 2 | FIELD_4BIT, // 4-bit, 4-bit - FIELD_8BIT << 2 | FIELD_8BIT, // 4-bit, 8-bit - FIELD_8BIT << 2 | FIELD_16BIT, // 4-bit, 16-bit - FIELD_8BIT << 2 | FIELD_ZERO, // 8-bit, zero - FIELD_8BIT << 2 | FIELD_8BIT, // 8-bit, 4-bit - FIELD_8BIT << 2 | FIELD_8BIT, // 8-bit, 8-bit - FIELD_8BIT << 2 | FIELD_16BIT, // 8-bit, 16-bit - FIELD_16BIT << 2 | FIELD_ZERO, // 16-bit, zero - FIELD_16BIT << 2 | FIELD_8BIT, // 16-bit, 4-bit - FIELD_16BIT << 2 | FIELD_8BIT, // 16-bit, 8-bit - FIELD_16BIT << 2 | FIELD_16BIT, // 16-bit, 16-bit - }; - - selector = 0; - //Encode in reverse order so the first field is in the low bits: - for (x = 3; x >= 0; x--) { - selector <<= 2; - - if (values[x] == 0) - selector |= FIELD_ZERO; - else if (values[x] <= 7 && values[x] >= -8) - selector |= FIELD_4BIT; - else if (values[x] <= 127 && values[x] >= -128) - selector |= FIELD_8BIT; - else - selector |= FIELD_16BIT; - } - - selector = rcSelectorCleanup[selector & 0x0F] | (rcSelectorCleanup[selector >> 4] << 4); - - blackboxWrite(selector); - - for (x = 0; x < 4; x++, selector >>= 2) { - switch (selector & 0x03) { - case FIELD_4BIT: - blackboxWrite((values[x] & 0x0F) | (values[x + 1] << 4)); - - //We write two selector fields: - x++; - selector >>= 2; - break; - case FIELD_8BIT: - blackboxWrite(values[x]); - break; - case FIELD_16BIT: - blackboxWrite(values[x]); - blackboxWrite(values[x] >> 8); - break; - } - } -} - -static void writeIntraframe(void) -{ - blackboxValues_t *blackboxCurrent = blackboxHistory[0]; - int x; - - blackboxWrite('I'); - - writeUnsignedVB(blackboxIteration); - writeUnsignedVB(blackboxCurrent->time); - - for (x = 0; x < 3; x++) - writeSignedVB(blackboxCurrent->axisP[x]); - - for (x = 0; x < 3; x++) - writeSignedVB(blackboxCurrent->axisI[x]); - - for (x = 0; x < 3; x++) - writeSignedVB(blackboxCurrent->axisD[x]); - - for (x = 0; x < 3; x++) - writeSignedVB(blackboxCurrent->rcCommand[x]); - - writeUnsignedVB(blackboxCurrent->rcCommand[3] - masterConfig.escAndServoConfig.minthrottle); //Throttle lies in range [minthrottle..maxthrottle] - - for (x = 0; x < 3; x++) - writeSignedVB(blackboxCurrent->gyroData[x]); - - for (x = 0; x < 3; x++) - writeSignedVB(blackboxCurrent->accSmooth[x]); - - //Motors can be below minthrottle when disarmed, but that doesn't happen much - writeUnsignedVB(blackboxCurrent->motor[0] - masterConfig.escAndServoConfig.minthrottle); - - //Motors tend to be similar to each other - for (x = 1; x < motorCount; x++) - writeSignedVB(blackboxCurrent->motor[x] - blackboxCurrent->motor[0]); - - if (isTricopter()) - writeSignedVB(blackboxHistory[0]->servo[5] - 1500); - - //Rotate our history buffers: - - //The current state becomes the new "before" state - blackboxHistory[1] = blackboxHistory[0]; - //And since we have no other history, we also use it for the "before, before" state - blackboxHistory[2] = blackboxHistory[0]; - //And advance the current state over to a blank space ready to be filled - blackboxHistory[0] = ((blackboxHistory[0] - blackboxHistoryRing + 1) % 3) + blackboxHistoryRing; -} - -static void writeInterframe(void) -{ - int x; - int32_t deltas[4]; - - blackboxValues_t *blackboxCurrent = blackboxHistory[0]; - blackboxValues_t *blackboxLast = blackboxHistory[1]; - - blackboxWrite('P'); - - //No need to store iteration count since its delta is always 1 - - /* - * Since the difference between the difference between successive times will be nearly zero, use - * second-order differences. - */ - writeSignedVB((int32_t) (blackboxHistory[0]->time - 2 * blackboxHistory[1]->time + blackboxHistory[2]->time)); - - for (x = 0; x < 3; x++) - writeSignedVB(blackboxCurrent->axisP[x] - blackboxLast->axisP[x]); - - for (x = 0; x < 3; x++) - deltas[x] = blackboxCurrent->axisI[x] - blackboxLast->axisI[x]; - - /* - * The PID I field changes very slowly, most of the time +-2, so use an encoding - * that can pack all three fields into one byte in that situation. - */ - writeTag2_3S32(deltas); - - for (x = 0; x < 3; x++) - writeSignedVB(blackboxCurrent->axisD[x] - blackboxLast->axisD[x]); - - for (x = 0; x < 4; x++) - deltas[x] = blackboxCurrent->rcCommand[x] - blackboxLast->rcCommand[x]; - - /* - * RC tends to stay the same or fairly small for many frames at a time, so use an encoding that - * can pack multiple values per byte: - */ - writeTag8_4S16(deltas); - - //Since gyros, accs and motors are noisy, base the prediction on the average of the history: - for (x = 0; x < 3; x++) - writeSignedVB(blackboxHistory[0]->gyroData[x] - (blackboxHistory[1]->gyroData[x] + blackboxHistory[2]->gyroData[x]) / 2); - - for (x = 0; x < 3; x++) - writeSignedVB(blackboxHistory[0]->accSmooth[x] - (blackboxHistory[1]->accSmooth[x] + blackboxHistory[2]->accSmooth[x]) / 2); - - for (x = 0; x < motorCount; x++) - writeSignedVB(blackboxHistory[0]->motor[x] - (blackboxHistory[1]->motor[x] + blackboxHistory[2]->motor[x]) / 2); - - if (isTricopter()) - writeSignedVB(blackboxCurrent->servo[5] - blackboxLast->servo[5]); - - //Rotate our history buffers - blackboxHistory[2] = blackboxHistory[1]; - blackboxHistory[1] = blackboxHistory[0]; - blackboxHistory[0] = ((blackboxHistory[0] - blackboxHistoryRing + 1) % 3) + blackboxHistoryRing; -} - -static int gcd(int num, int denom) -{ - if (denom == 0) - return num; - return gcd(denom, num % denom); -} - -static void validateBlackboxConfig() -{ - int div; - - if (masterConfig.blackbox_rate_num == 0 || masterConfig.blackbox_rate_denom == 0 - || masterConfig.blackbox_rate_num >= masterConfig.blackbox_rate_denom) { - masterConfig.blackbox_rate_num = 1; - masterConfig.blackbox_rate_denom = 1; - } else { - div = gcd(masterConfig.blackbox_rate_num, masterConfig.blackbox_rate_denom); - - masterConfig.blackbox_rate_num /= div; - masterConfig.blackbox_rate_denom /= div; - } -} - -static void configureBlackboxPort(void) -{ - blackboxPort = findOpenSerialPort(FUNCTION_BLACKBOX); - if (blackboxPort) { - previousPortMode = blackboxPort->mode; - previousBaudRate = blackboxPort->baudRate; - - serialSetBaudRate(blackboxPort, BLACKBOX_BAUDRATE); - serialSetMode(blackboxPort, BLACKBOX_INITIAL_PORT_MODE); - beginSerialPortFunction(blackboxPort, FUNCTION_BLACKBOX); - } else { - blackboxPort = openSerialPort(FUNCTION_BLACKBOX, NULL, BLACKBOX_BAUDRATE, BLACKBOX_INITIAL_PORT_MODE, SERIAL_NOT_INVERTED); - - if (blackboxPort) { - previousPortMode = blackboxPort->mode; - previousBaudRate = blackboxPort->baudRate; - } - } -} - -static void releaseBlackboxPort(void) -{ - serialSetMode(blackboxPort, previousPortMode); - serialSetBaudRate(blackboxPort, previousBaudRate); - - endSerialPortFunction(blackboxPort, FUNCTION_BLACKBOX); -} - -void startBlackbox(void) -{ - if (blackboxState == BLACKBOX_STATE_STOPPED) { - validateBlackboxConfig(); - - configureBlackboxPort(); - - if (!blackboxPort) { - blackboxState = BLACKBOX_STATE_DISABLED; - return; - } - - startTime = millis(); - headerXmitIndex = 0; - blackboxIteration = 0; - blackboxState = BLACKBOX_STATE_SEND_HEADER; - - memset(&gpsHistory, 0, sizeof(gpsHistory)); - - //No need to clear the content of blackboxHistoryRing since our first frame will be an intra which overwrites it - - blackboxHistory[0] = &blackboxHistoryRing[0]; - blackboxHistory[1] = &blackboxHistoryRing[1]; - blackboxHistory[2] = &blackboxHistoryRing[2]; - } -} - -void finishBlackbox(void) -{ - if (blackboxState != BLACKBOX_STATE_DISABLED && blackboxState != BLACKBOX_STATE_STOPPED) { - blackboxState = BLACKBOX_STATE_STOPPED; - - releaseBlackboxPort(); - } -} - -static void writeGPSHomeFrame() -{ - blackboxWrite('H'); - - writeSignedVB(GPS_home[0]); - writeSignedVB(GPS_home[1]); - //TODO it'd be great if we could grab the GPS current time and write that too - - gpsHistory.GPS_home[0] = GPS_home[0]; - gpsHistory.GPS_home[1] = GPS_home[1]; -} - -static void writeGPSFrame() -{ - blackboxWrite('G'); - - writeUnsignedVB(GPS_numSat); - writeSignedVB(GPS_coord[0] - gpsHistory.GPS_home[0]); - writeSignedVB(GPS_coord[1] - gpsHistory.GPS_home[1]); - writeUnsignedVB(GPS_altitude); - writeUnsignedVB(GPS_speed); - - gpsHistory.GPS_numSat = GPS_numSat; - gpsHistory.GPS_coord[0] = GPS_coord[0]; - gpsHistory.GPS_coord[1] = GPS_coord[1]; -} - -/** - * Fill the current state of the blackbox using values read from the flight controller - */ -static void loadBlackboxState(void) -{ - blackboxValues_t *blackboxCurrent = blackboxHistory[0]; - int i; - - blackboxCurrent->time = currentTime; - - for (i = 0; i < 3; i++) - blackboxCurrent->axisP[i] = axisP[i]; - for (i = 0; i < 3; i++) - blackboxCurrent->axisI[i] = axisI[i]; - for (i = 0; i < 3; i++) - blackboxCurrent->axisD[i] = axisD[i]; - - for (i = 0; i < 4; i++) - blackboxCurrent->rcCommand[i] = rcCommand[i]; - - for (i = 0; i < 3; i++) - blackboxCurrent->gyroData[i] = gyroData[i]; - - for (i = 0; i < 3; i++) - blackboxCurrent->accSmooth[i] = accSmooth[i]; - - for (i = 0; i < motorCount; i++) - blackboxCurrent->motor[i] = motor[i]; - - //Tail servo for tricopters - blackboxCurrent->servo[5] = servo[5]; -} - -void handleBlackbox(void) -{ - int i; - const char *additionalHeader; - const int SERIAL_CHUNK_SIZE = 16; - static int charXmitIndex = 0; - int motorsToRemove, endIndex; - int blackboxIntercycleIndex, blackboxIntracycleIndex; - - union floatConvert_t { - float f; - uint32_t u; - } floatConvert; - - switch (blackboxState) { - case BLACKBOX_STATE_SEND_HEADER: - /* - * Once the UART has had time to init, transmit the header in chunks so we don't overflow our transmit - * buffer. - */ - if (millis() > startTime + 100) { - for (i = 0; i < SERIAL_CHUNK_SIZE && blackboxHeader[headerXmitIndex] != '\0'; i++, headerXmitIndex++) - blackboxWrite(blackboxHeader[headerXmitIndex]); - - if (blackboxHeader[headerXmitIndex] == '\0') { - blackboxState = BLACKBOX_STATE_SEND_FIELDINFO; - headerXmitIndex = 0; - charXmitIndex = 0; - } - } - break; - case BLACKBOX_STATE_SEND_FIELDINFO: - /* - * Send information about the fields we're recording to the log. - * - * Once again, we're chunking up the data so we don't exceed our datarate. This time we're trimming the - * excess field defs off the end of the header for motors we don't have. - */ - motorsToRemove = 8 - motorCount; - - if (headerXmitIndex < sizeof(blackboxHeaderFields) / sizeof(blackboxHeaderFields[0])){ - endIndex = strlen(blackboxHeaderFields[headerXmitIndex]) - (headerXmitIndex == 0 ? strlen(",motor[x]") : strlen(",x")) * motorsToRemove; - - for (i = charXmitIndex; i < charXmitIndex + SERIAL_CHUNK_SIZE && i < endIndex; i++) - blackboxWrite(blackboxHeaderFields[headerXmitIndex][i]); - - // Did we complete this line? - if (i == endIndex) { - if (isTricopter()) { - //Add fields to the end for the tail servo - blackboxWrite(','); - - for (additionalHeader = blackboxAdditionalFieldsTricopter[headerXmitIndex]; *additionalHeader; additionalHeader++) - blackboxWrite(*additionalHeader); - } - - blackboxWrite('\n'); - headerXmitIndex++; - charXmitIndex = 0; - } else { - charXmitIndex = i; - } - } else { - //Completed sending field information - - if (feature(FEATURE_GPS)) { - blackboxState = BLACKBOX_STATE_SEND_GPS_HEADERS; - } else { - blackboxState = BLACKBOX_STATE_SEND_SYSINFO; - } - headerXmitIndex = 0; - } - break; - case BLACKBOX_STATE_SEND_GPS_HEADERS: - for (i = 0; i < SERIAL_CHUNK_SIZE && blackboxGpsHeader[headerXmitIndex] != '\0'; i++, headerXmitIndex++) - blackboxWrite(blackboxGpsHeader[headerXmitIndex]); - - if (blackboxGpsHeader[headerXmitIndex] == '\0') { - blackboxState = BLACKBOX_STATE_SEND_SYSINFO; - headerXmitIndex = 0; - } - break; - case BLACKBOX_STATE_SEND_SYSINFO: - - switch (headerXmitIndex) { - case 0: - blackboxPrintf("H Firmware type:Cleanflight\n"); - break; - case 1: - // Pause to allow more time for previous to transmit (it exceeds our chunk size) - break; - case 2: - blackboxPrintf("H Firmware revision:%s\n", shortGitRevision); - break; - case 3: - // Pause to allow more time for previous to transmit - break; - case 4: - blackboxPrintf("H Firmware date:%s %s\n", buildDate, buildTime); - break; - case 5: - // Pause to allow more time for previous to transmit - break; - case 6: - blackboxPrintf("H rcRate:%d\n", masterConfig.controlRateProfiles[masterConfig.current_profile_index].rcRate8); - break; - case 7: - blackboxPrintf("H minthrottle:%d\n", masterConfig.escAndServoConfig.minthrottle); - break; - case 8: - blackboxPrintf("H maxthrottle:%d\n", masterConfig.escAndServoConfig.maxthrottle); - break; - case 9: - floatConvert.f = gyro.scale; - blackboxPrintf("H gyro.scale:0x%x\n", floatConvert.u); - break; - case 10: - blackboxPrintf("H acc_1G:%u\n", acc_1G); - break; - case 11: - // One more pause for good luck - break; - default: - blackboxState = BLACKBOX_STATE_RUNNING; - } - - headerXmitIndex++; - break; - case BLACKBOX_STATE_RUNNING: - // Write a keyframe every 32 frames so we can resynchronise upon missing frames - blackboxIntercycleIndex = blackboxIteration % BLACKBOX_I_INTERVAL; - blackboxIntracycleIndex = blackboxIteration / BLACKBOX_I_INTERVAL; - - if (blackboxIntercycleIndex == 0) { - // Copy current system values into the blackbox - loadBlackboxState(); - writeIntraframe(); - } else { - if ((blackboxIntercycleIndex + masterConfig.blackbox_rate_num - 1) % masterConfig.blackbox_rate_denom < masterConfig.blackbox_rate_num) { - loadBlackboxState(); - writeInterframe(); - } - - if (feature(FEATURE_GPS)) { - /* - * If the GPS home point has been updated, or every 128 intraframes (~10 seconds), write the - * GPS home position. - * - * We write it periodically so that if one Home Frame goes missing, the GPS coordinates can - * still be interpreted correctly. - */ - if (GPS_home[0] != gpsHistory.GPS_home[0] || GPS_home[1] != gpsHistory.GPS_home[1] - || (blackboxIntercycleIndex == BLACKBOX_I_INTERVAL / 2 && blackboxIntracycleIndex % 128 == 0)) { - - writeGPSHomeFrame(); - writeGPSFrame(); - } else if (GPS_numSat != gpsHistory.GPS_numSat || GPS_coord[0] != gpsHistory.GPS_coord[0] - || GPS_coord[1] != gpsHistory.GPS_coord[1]) { - //We could check for velocity changes as well but I doubt it changes independent of position - writeGPSFrame(); - } - } - } - - blackboxIteration++; - break; - default: - break; - } -} - -static bool canUseBlackboxWithCurrentConfiguration(void) -{ - if (!feature(FEATURE_BLACKBOX)) - return false; - - return true; -} - -void initBlackbox(void) -{ - if (canUseBlackboxWithCurrentConfiguration()) - blackboxState = BLACKBOX_STATE_STOPPED; - else - blackboxState = BLACKBOX_STATE_DISABLED; -} +/* + * This file is part of Cleanflight. + * + * Cleanflight is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * Cleanflight is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with Cleanflight. If not, see . + */ + +#include +#include +#include + +#include "platform.h" +#include "version.h" + +#include "common/maths.h" +#include "common/axis.h" +#include "common/color.h" + +#include "drivers/accgyro.h" +#include "drivers/light_led.h" + +#include "drivers/gpio.h" +#include "drivers/system.h" +#include "drivers/serial.h" +#include "drivers/timer.h" +#include "drivers/pwm_rx.h" + +#include "common/printf.h" + +#include "flight/flight.h" +#include "sensors/sensors.h" +#include "sensors/boardalignment.h" +#include "sensors/sonar.h" +#include "sensors/compass.h" +#include "sensors/acceleration.h" +#include "sensors/barometer.h" +#include "sensors/gyro.h" +#include "sensors/battery.h" +#include "io/beeper.h" +#include "io/display.h" +#include "io/escservo.h" +#include "rx/rx.h" +#include "io/rc_controls.h" +#include "flight/mixer.h" +#include "flight/altitudehold.h" +#include "flight/failsafe.h" +#include "flight/imu.h" +#include "flight/autotune.h" +#include "flight/navigation.h" +#include "io/gimbal.h" +#include "io/gps.h" +#include "io/ledstrip.h" +#include "io/serial.h" +#include "io/serial_cli.h" +#include "io/serial_msp.h" +#include "io/statusindicator.h" +#include "rx/msp.h" +#include "telemetry/telemetry.h" + +#include "config/runtime_config.h" +#include "config/config.h" +#include "config/config_profile.h" +#include "config/config_master.h" + +#include "blackbox_fielddefs.h" +#include "blackbox.h" + +#define BLACKBOX_BAUDRATE 115200 +#define BLACKBOX_INITIAL_PORT_MODE MODE_TX +#define BLACKBOX_I_INTERVAL 32 + +// Some macros to make writing FLIGHT_LOG_FIELD_PREDICTOR_* constants shorter: +#define STR_HELPER(x) #x +#define STR(x) STR_HELPER(x) + +#define CONCAT_HELPER(x,y) x ## y +#define CONCAT(x,y) CONCAT_HELPER(x, y) + +#define PREDICT(x) STR(CONCAT(FLIGHT_LOG_FIELD_PREDICTOR_, x)) +#define ENCODING(x) STR(CONCAT(FLIGHT_LOG_FIELD_ENCODING_, x)) + +static const char blackboxHeader[] = + "H Product:Blackbox flight data recorder by Nicholas Sherlock\n" + "H Blackbox version:1\n" + "H Data version:1\n" + "H I interval:" STR(BLACKBOX_I_INTERVAL) "\n"; + +/* These headers have info for all 8 motors on them, we'll trim the final fields off to match the number of motors in the mixer: */ +static const char * const blackboxHeaderFields[] = { + "H Field I name:" + "loopIteration,time," + "axisP[0],axisP[1],axisP[2]," + "axisI[0],axisI[1],axisI[2]," + "axisD[0],axisD[1],axisD[2]," + "rcCommand[0],rcCommand[1],rcCommand[2],rcCommand[3]," + "gyroData[0],gyroData[1],gyroData[2]," + "accSmooth[0],accSmooth[1],accSmooth[2]," + "motor[0],motor[1],motor[2],motor[3]," + "motor[4],motor[5],motor[6],motor[7]", + + "H Field I signed:" + /* loopIteration, time: */ + "0,0," + /* PIDs: */ + "1,1,1,1,1,1,1,1,1," + /* rcCommand[0..2] */ + "1,1,1," + /* rcCommand[3] (Throttle): */ + "0," + /* gyroData[0..2]: */ + "1,1,1," + /* accSmooth[0..2]: */ + "1,1,1," + /* Motor[0..7]: */ + "0,0,0,0,0,0,0,0", + + "H Field I predictor:" + /* loopIteration, time: */ + PREDICT(0) "," PREDICT(0) "," + /* PIDs: */ + PREDICT(0) "," PREDICT(0) "," PREDICT(0) "," + PREDICT(0) "," PREDICT(0) "," PREDICT(0) "," + PREDICT(0) "," PREDICT(0) "," PREDICT(0) "," + /* rcCommand[0..2] */ + PREDICT(0) "," PREDICT(0) "," PREDICT(0) "," + /* rcCommand[3] (Throttle): */ + PREDICT(MINTHROTTLE) "," + /* gyroData[0..2]: */ + PREDICT(0) "," PREDICT(0) "," PREDICT(0) "," + /* accSmooth[0..2]: */ + PREDICT(0) "," PREDICT(0) "," PREDICT(0) "," + /* Motor[0]: */ + PREDICT(MINTHROTTLE) "," + /* Motor[1..7]: */ + PREDICT(MOTOR_0) "," PREDICT(MOTOR_0) "," PREDICT(MOTOR_0) "," + PREDICT(MOTOR_0) "," PREDICT(MOTOR_0) "," PREDICT(MOTOR_0) "," + PREDICT(MOTOR_0), + + "H Field I encoding:" + /* loopIteration, time: */ + ENCODING(UNSIGNED_VB) "," ENCODING(UNSIGNED_VB) "," + /* PIDs: */ + ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," + ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," + ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," + /* rcCommand[0..2] */ + ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," + /* rcCommand[3] (Throttle): */ + ENCODING(UNSIGNED_VB) "," + /* gyroData[0..2]: */ + ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," + /* accSmooth[0..2]: */ + ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," + /* Motor[0]: */ + ENCODING(UNSIGNED_VB) "," + /* Motor[1..7]: */ + ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," + ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," + ENCODING(SIGNED_VB), + + //Motors and gyros predict an average of the last two measurements (to reduce the impact of noise): + "H Field P predictor:" + /* loopIteration, time: */ + PREDICT(INC) "," PREDICT(STRAIGHT_LINE) "," + /* PIDs: */ + PREDICT(PREVIOUS) "," PREDICT(PREVIOUS) "," PREDICT(PREVIOUS) "," + PREDICT(PREVIOUS) "," PREDICT(PREVIOUS) "," PREDICT(PREVIOUS) "," + PREDICT(PREVIOUS) "," PREDICT(PREVIOUS) "," PREDICT(PREVIOUS) "," + /* rcCommand[0..2] */ + PREDICT(PREVIOUS) "," PREDICT(PREVIOUS) "," PREDICT(PREVIOUS) "," + /* rcCommand[3] (Throttle): */ + PREDICT(PREVIOUS) "," + /* gyroData[0..2]: */ + PREDICT(AVERAGE_2) "," PREDICT(AVERAGE_2) "," PREDICT(AVERAGE_2) "," + /* accSmooth[0..2]: */ + PREDICT(AVERAGE_2) "," PREDICT(AVERAGE_2) "," PREDICT(AVERAGE_2) "," + /* Motor[0]: */ + PREDICT(AVERAGE_2) "," + /* Motor[1..7]: */ + PREDICT(AVERAGE_2) "," PREDICT(AVERAGE_2) "," PREDICT(AVERAGE_2) "," + PREDICT(AVERAGE_2) "," PREDICT(AVERAGE_2) "," PREDICT(AVERAGE_2) "," + PREDICT(AVERAGE_2), + + /* RC fields are encoded together as a group, everything else is signed since they're diffs: */ + "H Field P encoding:" + /* loopIteration, time: */ + ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," + /* PIDs: */ + ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," + ENCODING(TAG2_3S32) "," ENCODING(TAG2_3S32) "," ENCODING(TAG2_3S32) "," + ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," + /* rcCommand[0..3] */ + ENCODING(TAG8_4S16) "," ENCODING(TAG8_4S16) "," ENCODING(TAG8_4S16) "," + ENCODING(TAG8_4S16) "," + /* gyroData[0..2]: */ + ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," + /* accSmooth[0..2]: */ + ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," + /* Motor[0]: */ + ENCODING(SIGNED_VB) "," + /* Motor[1..7]: */ + ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," + ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," + ENCODING(SIGNED_VB) +}; + +/** + * Additional fields to tack on to those above for tricopters (to record tail servo position) + */ +static const char * const blackboxAdditionalFieldsTricopter[] = { + //Field I name + "servo[5]", + + //Field I signed + "0", + + //Field I predictor + PREDICT(1500), + + //Field I encoding: + ENCODING(SIGNED_VB), + + //Field P predictor: + PREDICT(PREVIOUS), + + //Field P encoding: + ENCODING(SIGNED_VB) +}; + +static const char blackboxGpsHeader[] = + "H Field G name:" + "GPS_numSat,GPS_coord[0],GPS_coord[1],GPS_altitude,GPS_speed\n" + "H Field G signed:" + "0,1,1,0,0\n" + "H Field G predictor:" + PREDICT(0) "," PREDICT(HOME_COORD) "," PREDICT(HOME_COORD) "," PREDICT(0) "," PREDICT(0) "\n" + "H Field G encoding:" + ENCODING(UNSIGNED_VB) "," ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," + ENCODING(UNSIGNED_VB) "," ENCODING(UNSIGNED_VB) "\n" + + "H Field H name:" + "GPS_home[0],GPS_home[1]\n" + "H Field H signed:" + "1,1\n" + "H Field H predictor:" + PREDICT(0) "," PREDICT(0) "\n" + "H Field H encoding:" + ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "\n"; + +typedef enum BlackboxState { + BLACKBOX_STATE_DISABLED = 0, + BLACKBOX_STATE_STOPPED, + BLACKBOX_STATE_SEND_HEADER, + BLACKBOX_STATE_SEND_FIELDINFO, + BLACKBOX_STATE_SEND_GPS_HEADERS, + BLACKBOX_STATE_SEND_SYSINFO, + BLACKBOX_STATE_RUNNING +} BlackboxState; + +typedef struct gpsState_t { + int32_t GPS_home[2], GPS_coord[2]; + uint8_t GPS_numSat; +} gpsState_t; + +//From mixer.c: +extern uint8_t motorCount; + +//From mw.c: +extern uint32_t currentTime; + +static BlackboxState blackboxState = BLACKBOX_STATE_DISABLED; +static uint32_t startTime; +static unsigned int headerXmitIndex; +static uint32_t blackboxIteration; + +static serialPort_t *blackboxPort; +static portMode_t previousPortMode; +static uint32_t previousBaudRate; + +static gpsState_t gpsHistory; + +// Keep a history of length 2, plus a buffer for MW to store the new values into +static blackboxValues_t blackboxHistoryRing[3]; + +// These point into blackboxHistoryRing, use them to know where to store history of a given age (0, 1 or 2 generations old) +static blackboxValues_t* blackboxHistory[3]; + +static int isTricopter() +{ + return masterConfig.mixerConfiguration == MULTITYPE_TRI; +} + +static void blackboxWrite(uint8_t value) +{ + serialWrite(blackboxPort, value); +} + +static void _putc(void *p, char c) +{ + (void)p; + serialWrite(blackboxPort, c); +} + +//printf() to the blackbox serial port with no blocking shenanigans (so it's caller's responsibility to not write too fast!) +static void blackboxPrintf(char *fmt, ...) +{ + va_list va; + va_start(va, fmt); + tfp_format(NULL, _putc, fmt, va); + va_end(va); +} + +/** + * Write an unsigned integer to the blackbox serial port using variable byte encoding. + */ +static void writeUnsignedVB(uint32_t value) +{ + //While this isn't the final byte (we can only write 7 bits at a time) + while (value > 127) { + blackboxWrite((uint8_t) (value | 0x80)); // Set the high bit to mean "more bytes follow" + value >>= 7; + } + blackboxWrite(value); +} + +/** + * Write a signed integer to the blackbox serial port using ZigZig and variable byte encoding. + */ +static void writeSignedVB(int32_t value) +{ + //ZigZag encode to make the value always positive + writeUnsignedVB((uint32_t)((value << 1) ^ (value >> 31))); +} + +/** + * Write a 2 bit tag followed by 3 signed fields of 2, 4, 6 or 32 bits + */ +static void writeTag2_3S32(int32_t *values) { + static const int NUM_FIELDS = 3; + + //Need to be enums rather than const ints if we want to switch on them (due to being C) + enum { BITS_2 = 0}; + enum { BITS_4 = 1}; + enum { BITS_6 = 2}; + enum { BITS_32 = 3}; + + enum { BYTES_1 = 0}; + enum { BYTES_2 = 1}; + enum { BYTES_3 = 2}; + enum { BYTES_4 = 3}; + + int x; + int selector = BITS_2, selector2; + + /* + * Find out how many bits the largest value requires to encode, and use it to choose one of the packing schemes + * below: + * + * Selector possibilities + * + * 2 bits per field ss11 2233, + * 4 bits per field ss00 1111 2222 3333 + * 6 bits per field ss11 1111 0022 2222 0033 3333 + * 32 bits per field sstt tttt followed by fields of various byte counts + */ + for (x = 0; x < NUM_FIELDS; x++) { + //Require more than 6 bits? + if (values[x] >= 32 || values[x] < -32) { + selector = BITS_32; + break; + } + + //Require more than 4 bits? + if (values[x] >= 8 || values[x] < -8) { + if (selector < BITS_6) + selector = BITS_6; + } else if (values[x] >= 2 || values[x] < -2) { //Require more than 2 bits? + if (selector < BITS_4) + selector = BITS_4; + } + } + + switch (selector) { + case BITS_2: + blackboxWrite((selector << 6) | ((values[0] & 0x03) << 4) | ((values[1] & 0x03) << 2) | (values[2] & 0x03)); + break; + case BITS_4: + blackboxWrite((selector << 6) | (values[0] & 0x0F)); + blackboxWrite((values[1] << 4) | (values[2] & 0x0F)); + break; + case BITS_6: + blackboxWrite((selector << 6) | (values[0] & 0x3F)); + blackboxWrite((uint8_t)values[1]); + blackboxWrite((uint8_t)values[2]); + break; + case BITS_32: + /* + * Do another round to compute a selector for each field, assuming that they are at least 8 bits each + * + * Selector2 field possibilities + * 0 - 8 bits + * 1 - 16 bits + * 2 - 24 bits + * 3 - 32 bits + */ + selector2 = 0; + + //Encode in reverse order so the first field is in the low bits: + for (x = NUM_FIELDS - 1; x >= 0; x--) { + selector2 <<= 2; + + if (values[x] < 128 && values[x] >= -128) + selector2 |= BYTES_1; + else if (values[x] < 32768 && values[x] >= -32768) + selector2 |= BYTES_2; + else if (values[x] < 8388608 && values[x] >= -8388608) + selector2 |= BYTES_3; + else + selector2 |= BYTES_4; + } + + //Write the selectors + blackboxWrite((selector << 6) | selector2); + + //And now the values according to the selectors we picked for them + for (x = 0; x < NUM_FIELDS; x++, selector2 >>= 2) { + switch (selector2 & 0x03) { + case BYTES_1: + blackboxWrite(values[x]); + break; + case BYTES_2: + blackboxWrite(values[x]); + blackboxWrite(values[x] >> 8); + break; + case BYTES_3: + blackboxWrite(values[x]); + blackboxWrite(values[x] >> 8); + blackboxWrite(values[x] >> 16); + break; + case BYTES_4: + blackboxWrite(values[x]); + blackboxWrite(values[x] >> 8); + blackboxWrite(values[x] >> 16); + blackboxWrite(values[x] >> 24); + break; + } + } + break; + } +} + +/** + * Write an 8-bit selector followed by four signed fields of size 0, 4, 8 or 16 bits. + */ +static void writeTag8_4S16(int32_t *values) { + + //Need to be enums rather than const ints if we want to switch on them (due to being C) + enum { FIELD_ZERO = 0}; + enum { FIELD_4BIT = 1}; + enum { FIELD_8BIT = 2}; + enum { FIELD_16BIT = 3}; + + uint8_t selector; + int x; + + /* + * 4-bit fields can only be combined with their paired neighbor (there are two pairs), so choose a + * larger encoding if that's not possible. + */ + const uint8_t rcSelectorCleanup[16] = { + // Output selectors <- Input selectors + FIELD_ZERO << 2 | FIELD_ZERO, // zero, zero + FIELD_ZERO << 2 | FIELD_8BIT, // zero, 4-bit + FIELD_ZERO << 2 | FIELD_8BIT, // zero, 8-bit + FIELD_ZERO << 2 | FIELD_16BIT, // zero, 16-bit + FIELD_8BIT << 2 | FIELD_ZERO, // 4-bit, zero + FIELD_4BIT << 2 | FIELD_4BIT, // 4-bit, 4-bit + FIELD_8BIT << 2 | FIELD_8BIT, // 4-bit, 8-bit + FIELD_8BIT << 2 | FIELD_16BIT, // 4-bit, 16-bit + FIELD_8BIT << 2 | FIELD_ZERO, // 8-bit, zero + FIELD_8BIT << 2 | FIELD_8BIT, // 8-bit, 4-bit + FIELD_8BIT << 2 | FIELD_8BIT, // 8-bit, 8-bit + FIELD_8BIT << 2 | FIELD_16BIT, // 8-bit, 16-bit + FIELD_16BIT << 2 | FIELD_ZERO, // 16-bit, zero + FIELD_16BIT << 2 | FIELD_8BIT, // 16-bit, 4-bit + FIELD_16BIT << 2 | FIELD_8BIT, // 16-bit, 8-bit + FIELD_16BIT << 2 | FIELD_16BIT, // 16-bit, 16-bit + }; + + selector = 0; + //Encode in reverse order so the first field is in the low bits: + for (x = 3; x >= 0; x--) { + selector <<= 2; + + if (values[x] == 0) + selector |= FIELD_ZERO; + else if (values[x] <= 7 && values[x] >= -8) + selector |= FIELD_4BIT; + else if (values[x] <= 127 && values[x] >= -128) + selector |= FIELD_8BIT; + else + selector |= FIELD_16BIT; + } + + selector = rcSelectorCleanup[selector & 0x0F] | (rcSelectorCleanup[selector >> 4] << 4); + + blackboxWrite(selector); + + for (x = 0; x < 4; x++, selector >>= 2) { + switch (selector & 0x03) { + case FIELD_4BIT: + blackboxWrite((values[x] & 0x0F) | (values[x + 1] << 4)); + + //We write two selector fields: + x++; + selector >>= 2; + break; + case FIELD_8BIT: + blackboxWrite(values[x]); + break; + case FIELD_16BIT: + blackboxWrite(values[x]); + blackboxWrite(values[x] >> 8); + break; + } + } +} + +static void writeIntraframe(void) +{ + blackboxValues_t *blackboxCurrent = blackboxHistory[0]; + int x; + + blackboxWrite('I'); + + writeUnsignedVB(blackboxIteration); + writeUnsignedVB(blackboxCurrent->time); + + for (x = 0; x < 3; x++) + writeSignedVB(blackboxCurrent->axisP[x]); + + for (x = 0; x < 3; x++) + writeSignedVB(blackboxCurrent->axisI[x]); + + for (x = 0; x < 3; x++) + writeSignedVB(blackboxCurrent->axisD[x]); + + for (x = 0; x < 3; x++) + writeSignedVB(blackboxCurrent->rcCommand[x]); + + writeUnsignedVB(blackboxCurrent->rcCommand[3] - masterConfig.escAndServoConfig.minthrottle); //Throttle lies in range [minthrottle..maxthrottle] + + for (x = 0; x < 3; x++) + writeSignedVB(blackboxCurrent->gyroData[x]); + + for (x = 0; x < 3; x++) + writeSignedVB(blackboxCurrent->accSmooth[x]); + + //Motors can be below minthrottle when disarmed, but that doesn't happen much + writeUnsignedVB(blackboxCurrent->motor[0] - masterConfig.escAndServoConfig.minthrottle); + + //Motors tend to be similar to each other + for (x = 1; x < motorCount; x++) + writeSignedVB(blackboxCurrent->motor[x] - blackboxCurrent->motor[0]); + + if (isTricopter()) + writeSignedVB(blackboxHistory[0]->servo[5] - 1500); + + //Rotate our history buffers: + + //The current state becomes the new "before" state + blackboxHistory[1] = blackboxHistory[0]; + //And since we have no other history, we also use it for the "before, before" state + blackboxHistory[2] = blackboxHistory[0]; + //And advance the current state over to a blank space ready to be filled + blackboxHistory[0] = ((blackboxHistory[0] - blackboxHistoryRing + 1) % 3) + blackboxHistoryRing; +} + +static void writeInterframe(void) +{ + int x; + int32_t deltas[4]; + + blackboxValues_t *blackboxCurrent = blackboxHistory[0]; + blackboxValues_t *blackboxLast = blackboxHistory[1]; + + blackboxWrite('P'); + + //No need to store iteration count since its delta is always 1 + + /* + * Since the difference between the difference between successive times will be nearly zero, use + * second-order differences. + */ + writeSignedVB((int32_t) (blackboxHistory[0]->time - 2 * blackboxHistory[1]->time + blackboxHistory[2]->time)); + + for (x = 0; x < 3; x++) + writeSignedVB(blackboxCurrent->axisP[x] - blackboxLast->axisP[x]); + + for (x = 0; x < 3; x++) + deltas[x] = blackboxCurrent->axisI[x] - blackboxLast->axisI[x]; + + /* + * The PID I field changes very slowly, most of the time +-2, so use an encoding + * that can pack all three fields into one byte in that situation. + */ + writeTag2_3S32(deltas); + + for (x = 0; x < 3; x++) + writeSignedVB(blackboxCurrent->axisD[x] - blackboxLast->axisD[x]); + + for (x = 0; x < 4; x++) + deltas[x] = blackboxCurrent->rcCommand[x] - blackboxLast->rcCommand[x]; + + /* + * RC tends to stay the same or fairly small for many frames at a time, so use an encoding that + * can pack multiple values per byte: + */ + writeTag8_4S16(deltas); + + //Since gyros, accs and motors are noisy, base the prediction on the average of the history: + for (x = 0; x < 3; x++) + writeSignedVB(blackboxHistory[0]->gyroData[x] - (blackboxHistory[1]->gyroData[x] + blackboxHistory[2]->gyroData[x]) / 2); + + for (x = 0; x < 3; x++) + writeSignedVB(blackboxHistory[0]->accSmooth[x] - (blackboxHistory[1]->accSmooth[x] + blackboxHistory[2]->accSmooth[x]) / 2); + + for (x = 0; x < motorCount; x++) + writeSignedVB(blackboxHistory[0]->motor[x] - (blackboxHistory[1]->motor[x] + blackboxHistory[2]->motor[x]) / 2); + + if (isTricopter()) + writeSignedVB(blackboxCurrent->servo[5] - blackboxLast->servo[5]); + + //Rotate our history buffers + blackboxHistory[2] = blackboxHistory[1]; + blackboxHistory[1] = blackboxHistory[0]; + blackboxHistory[0] = ((blackboxHistory[0] - blackboxHistoryRing + 1) % 3) + blackboxHistoryRing; +} + +static int gcd(int num, int denom) +{ + if (denom == 0) + return num; + return gcd(denom, num % denom); +} + +static void validateBlackboxConfig() +{ + int div; + + if (masterConfig.blackbox_rate_num == 0 || masterConfig.blackbox_rate_denom == 0 + || masterConfig.blackbox_rate_num >= masterConfig.blackbox_rate_denom) { + masterConfig.blackbox_rate_num = 1; + masterConfig.blackbox_rate_denom = 1; + } else { + div = gcd(masterConfig.blackbox_rate_num, masterConfig.blackbox_rate_denom); + + masterConfig.blackbox_rate_num /= div; + masterConfig.blackbox_rate_denom /= div; + } +} + +static void configureBlackboxPort(void) +{ + blackboxPort = findOpenSerialPort(FUNCTION_BLACKBOX); + if (blackboxPort) { + previousPortMode = blackboxPort->mode; + previousBaudRate = blackboxPort->baudRate; + + serialSetBaudRate(blackboxPort, BLACKBOX_BAUDRATE); + serialSetMode(blackboxPort, BLACKBOX_INITIAL_PORT_MODE); + beginSerialPortFunction(blackboxPort, FUNCTION_BLACKBOX); + } else { + blackboxPort = openSerialPort(FUNCTION_BLACKBOX, NULL, BLACKBOX_BAUDRATE, BLACKBOX_INITIAL_PORT_MODE, SERIAL_NOT_INVERTED); + + if (blackboxPort) { + previousPortMode = blackboxPort->mode; + previousBaudRate = blackboxPort->baudRate; + } + } +} + +static void releaseBlackboxPort(void) +{ + serialSetMode(blackboxPort, previousPortMode); + serialSetBaudRate(blackboxPort, previousBaudRate); + + endSerialPortFunction(blackboxPort, FUNCTION_BLACKBOX); +} + +void startBlackbox(void) +{ + if (blackboxState == BLACKBOX_STATE_STOPPED) { + validateBlackboxConfig(); + + configureBlackboxPort(); + + if (!blackboxPort) { + blackboxState = BLACKBOX_STATE_DISABLED; + return; + } + + startTime = millis(); + headerXmitIndex = 0; + blackboxIteration = 0; + blackboxState = BLACKBOX_STATE_SEND_HEADER; + + memset(&gpsHistory, 0, sizeof(gpsHistory)); + + //No need to clear the content of blackboxHistoryRing since our first frame will be an intra which overwrites it + + blackboxHistory[0] = &blackboxHistoryRing[0]; + blackboxHistory[1] = &blackboxHistoryRing[1]; + blackboxHistory[2] = &blackboxHistoryRing[2]; + } +} + +void finishBlackbox(void) +{ + if (blackboxState != BLACKBOX_STATE_DISABLED && blackboxState != BLACKBOX_STATE_STOPPED) { + blackboxState = BLACKBOX_STATE_STOPPED; + + releaseBlackboxPort(); + } +} + +static void writeGPSHomeFrame() +{ + blackboxWrite('H'); + + writeSignedVB(GPS_home[0]); + writeSignedVB(GPS_home[1]); + //TODO it'd be great if we could grab the GPS current time and write that too + + gpsHistory.GPS_home[0] = GPS_home[0]; + gpsHistory.GPS_home[1] = GPS_home[1]; +} + +static void writeGPSFrame() +{ + blackboxWrite('G'); + + writeUnsignedVB(GPS_numSat); + writeSignedVB(GPS_coord[0] - gpsHistory.GPS_home[0]); + writeSignedVB(GPS_coord[1] - gpsHistory.GPS_home[1]); + writeUnsignedVB(GPS_altitude); + writeUnsignedVB(GPS_speed); + + gpsHistory.GPS_numSat = GPS_numSat; + gpsHistory.GPS_coord[0] = GPS_coord[0]; + gpsHistory.GPS_coord[1] = GPS_coord[1]; +} + +/** + * Fill the current state of the blackbox using values read from the flight controller + */ +static void loadBlackboxState(void) +{ + blackboxValues_t *blackboxCurrent = blackboxHistory[0]; + int i; + + blackboxCurrent->time = currentTime; + + for (i = 0; i < 3; i++) + blackboxCurrent->axisP[i] = axisP[i]; + for (i = 0; i < 3; i++) + blackboxCurrent->axisI[i] = axisI[i]; + for (i = 0; i < 3; i++) + blackboxCurrent->axisD[i] = axisD[i]; + + for (i = 0; i < 4; i++) + blackboxCurrent->rcCommand[i] = rcCommand[i]; + + for (i = 0; i < 3; i++) + blackboxCurrent->gyroData[i] = gyroData[i]; + + for (i = 0; i < 3; i++) + blackboxCurrent->accSmooth[i] = accSmooth[i]; + + for (i = 0; i < motorCount; i++) + blackboxCurrent->motor[i] = motor[i]; + + //Tail servo for tricopters + blackboxCurrent->servo[5] = servo[5]; +} + +void handleBlackbox(void) +{ + int i; + const char *additionalHeader; + const int SERIAL_CHUNK_SIZE = 16; + static int charXmitIndex = 0; + int motorsToRemove, endIndex; + int blackboxIntercycleIndex, blackboxIntracycleIndex; + + union floatConvert_t { + float f; + uint32_t u; + } floatConvert; + + switch (blackboxState) { + case BLACKBOX_STATE_SEND_HEADER: + /* + * Once the UART has had time to init, transmit the header in chunks so we don't overflow our transmit + * buffer. + */ + if (millis() > startTime + 100) { + for (i = 0; i < SERIAL_CHUNK_SIZE && blackboxHeader[headerXmitIndex] != '\0'; i++, headerXmitIndex++) + blackboxWrite(blackboxHeader[headerXmitIndex]); + + if (blackboxHeader[headerXmitIndex] == '\0') { + blackboxState = BLACKBOX_STATE_SEND_FIELDINFO; + headerXmitIndex = 0; + charXmitIndex = 0; + } + } + break; + case BLACKBOX_STATE_SEND_FIELDINFO: + /* + * Send information about the fields we're recording to the log. + * + * Once again, we're chunking up the data so we don't exceed our datarate. This time we're trimming the + * excess field defs off the end of the header for motors we don't have. + */ + motorsToRemove = 8 - motorCount; + + if (headerXmitIndex < sizeof(blackboxHeaderFields) / sizeof(blackboxHeaderFields[0])){ + endIndex = strlen(blackboxHeaderFields[headerXmitIndex]) - (headerXmitIndex == 0 ? strlen(",motor[x]") : strlen(",x")) * motorsToRemove; + + for (i = charXmitIndex; i < charXmitIndex + SERIAL_CHUNK_SIZE && i < endIndex; i++) + blackboxWrite(blackboxHeaderFields[headerXmitIndex][i]); + + // Did we complete this line? + if (i == endIndex) { + if (isTricopter()) { + //Add fields to the end for the tail servo + blackboxWrite(','); + + for (additionalHeader = blackboxAdditionalFieldsTricopter[headerXmitIndex]; *additionalHeader; additionalHeader++) + blackboxWrite(*additionalHeader); + } + + blackboxWrite('\n'); + headerXmitIndex++; + charXmitIndex = 0; + } else { + charXmitIndex = i; + } + } else { + //Completed sending field information + + if (feature(FEATURE_GPS)) { + blackboxState = BLACKBOX_STATE_SEND_GPS_HEADERS; + } else { + blackboxState = BLACKBOX_STATE_SEND_SYSINFO; + } + headerXmitIndex = 0; + } + break; + case BLACKBOX_STATE_SEND_GPS_HEADERS: + for (i = 0; i < SERIAL_CHUNK_SIZE && blackboxGpsHeader[headerXmitIndex] != '\0'; i++, headerXmitIndex++) + blackboxWrite(blackboxGpsHeader[headerXmitIndex]); + + if (blackboxGpsHeader[headerXmitIndex] == '\0') { + blackboxState = BLACKBOX_STATE_SEND_SYSINFO; + headerXmitIndex = 0; + } + break; + case BLACKBOX_STATE_SEND_SYSINFO: + + switch (headerXmitIndex) { + case 0: + blackboxPrintf("H Firmware type:Cleanflight\n"); + break; + case 1: + // Pause to allow more time for previous to transmit (it exceeds our chunk size) + break; + case 2: + blackboxPrintf("H Firmware revision:%s\n", shortGitRevision); + break; + case 3: + // Pause to allow more time for previous to transmit + break; + case 4: + blackboxPrintf("H Firmware date:%s %s\n", buildDate, buildTime); + break; + case 5: + // Pause to allow more time for previous to transmit + break; + case 6: + blackboxPrintf("H rcRate:%d\n", masterConfig.controlRateProfiles[masterConfig.current_profile_index].rcRate8); + break; + case 7: + blackboxPrintf("H minthrottle:%d\n", masterConfig.escAndServoConfig.minthrottle); + break; + case 8: + blackboxPrintf("H maxthrottle:%d\n", masterConfig.escAndServoConfig.maxthrottle); + break; + case 9: + floatConvert.f = gyro.scale; + blackboxPrintf("H gyro.scale:0x%x\n", floatConvert.u); + break; + case 10: + blackboxPrintf("H acc_1G:%u\n", acc_1G); + break; + case 11: + // One more pause for good luck + break; + default: + blackboxState = BLACKBOX_STATE_RUNNING; + } + + headerXmitIndex++; + break; + case BLACKBOX_STATE_RUNNING: + // Write a keyframe every 32 frames so we can resynchronise upon missing frames + blackboxIntercycleIndex = blackboxIteration % BLACKBOX_I_INTERVAL; + blackboxIntracycleIndex = blackboxIteration / BLACKBOX_I_INTERVAL; + + if (blackboxIntercycleIndex == 0) { + // Copy current system values into the blackbox + loadBlackboxState(); + writeIntraframe(); + } else { + if ((blackboxIntercycleIndex + masterConfig.blackbox_rate_num - 1) % masterConfig.blackbox_rate_denom < masterConfig.blackbox_rate_num) { + loadBlackboxState(); + writeInterframe(); + } + + if (feature(FEATURE_GPS)) { + /* + * If the GPS home point has been updated, or every 128 intraframes (~10 seconds), write the + * GPS home position. + * + * We write it periodically so that if one Home Frame goes missing, the GPS coordinates can + * still be interpreted correctly. + */ + if (GPS_home[0] != gpsHistory.GPS_home[0] || GPS_home[1] != gpsHistory.GPS_home[1] + || (blackboxIntercycleIndex == BLACKBOX_I_INTERVAL / 2 && blackboxIntracycleIndex % 128 == 0)) { + + writeGPSHomeFrame(); + writeGPSFrame(); + } else if (GPS_numSat != gpsHistory.GPS_numSat || GPS_coord[0] != gpsHistory.GPS_coord[0] + || GPS_coord[1] != gpsHistory.GPS_coord[1]) { + //We could check for velocity changes as well but I doubt it changes independent of position + writeGPSFrame(); + } + } + } + + blackboxIteration++; + break; + default: + break; + } +} + +static bool canUseBlackboxWithCurrentConfiguration(void) +{ + if (!feature(FEATURE_BLACKBOX)) + return false; + + return true; +} + +void initBlackbox(void) +{ + if (canUseBlackboxWithCurrentConfiguration()) + blackboxState = BLACKBOX_STATE_STOPPED; + else + blackboxState = BLACKBOX_STATE_DISABLED; +} diff --git a/src/main/blackbox/blackbox.h b/src/main/blackbox/blackbox.h index de5cc344d7..84804b3828 100644 --- a/src/main/blackbox/blackbox.h +++ b/src/main/blackbox/blackbox.h @@ -1,37 +1,37 @@ -/* - * This file is part of Cleanflight. - * - * Cleanflight is free software: you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * Cleanflight is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with Cleanflight. If not, see . - */ - -#pragma once - -#include - -typedef struct blackboxValues_t { - uint32_t time; - - int32_t axisP[3], axisI[3], axisD[3]; - - int16_t rcCommand[4]; - int16_t gyroData[3]; - int16_t accSmooth[3]; - int16_t motor[MAX_SUPPORTED_MOTORS]; - int16_t servo[MAX_SUPPORTED_SERVOS]; -} blackboxValues_t; - -void initBlackbox(void); -void handleBlackbox(void); -void startBlackbox(void); -void finishBlackbox(void); +/* + * This file is part of Cleanflight. + * + * Cleanflight is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * Cleanflight is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with Cleanflight. If not, see . + */ + +#pragma once + +#include + +typedef struct blackboxValues_t { + uint32_t time; + + int32_t axisP[3], axisI[3], axisD[3]; + + int16_t rcCommand[4]; + int16_t gyroData[3]; + int16_t accSmooth[3]; + int16_t motor[MAX_SUPPORTED_MOTORS]; + int16_t servo[MAX_SUPPORTED_SERVOS]; +} blackboxValues_t; + +void initBlackbox(void); +void handleBlackbox(void); +void startBlackbox(void); +void finishBlackbox(void); diff --git a/src/main/flight/flight.c b/src/main/flight/flight.c index ca1812ca9c..faafe90ef2 100644 --- a/src/main/flight/flight.c +++ b/src/main/flight/flight.c @@ -339,9 +339,9 @@ static void pidRewrite(pidProfile_t *pidProfile, controlRateConfig_t *controlRat axisPID[axis] = PTerm + ITerm + DTerm; #ifdef BLACKBOX - axisP[axis] = PTerm; - axisI[axis] = ITerm; - axisD[axis] = DTerm; + axisP[axis] = PTerm; + axisI[axis] = ITerm; + axisD[axis] = DTerm; #endif } } diff --git a/src/main/mw.c b/src/main/mw.c index e6607cbccb..f6fbee39dc 100644 --- a/src/main/mw.c +++ b/src/main/mw.c @@ -307,7 +307,7 @@ void mwDisarm(void) #ifdef BLACKBOX if (feature(FEATURE_BLACKBOX)) { - finishBlackbox(); + finishBlackbox(); if (isSerialPortFunctionShared(FUNCTION_BLACKBOX, FUNCTION_MSP)) { mspAllocateSerialPorts(&masterConfig.serialConfig); } @@ -341,7 +341,7 @@ void mwArm(void) if (sharedBlackboxAndMspPort) { mspReleasePortIfAllocated(sharedBlackboxAndMspPort); } - startBlackbox(); + startBlackbox(); } #endif return; @@ -700,9 +700,9 @@ void loop(void) writeMotors(); #ifdef BLACKBOX - if (!cliMode && feature(FEATURE_BLACKBOX)) { - handleBlackbox(); - } + if (!cliMode && feature(FEATURE_BLACKBOX)) { + handleBlackbox(); + } #endif } From 8226922d46ca2ca7231886e67dbd9b919f3c5996 Mon Sep 17 00:00:00 2001 From: Nicholas Sherlock Date: Thu, 18 Dec 2014 18:44:56 +1300 Subject: [PATCH 09/24] Note supported flight controllers --- docs/Blackbox.md | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/docs/Blackbox.md b/docs/Blackbox.md index 6ee4e6e717..5933b1afaa 100644 --- a/docs/Blackbox.md +++ b/docs/Blackbox.md @@ -41,6 +41,10 @@ data rate. The default looptime on Cleanflight is 3500. If you're using a loopti need to reduce the sampling rate in the Blackbox settings, see the later section on configuring the Blackbox feature for details. +The Blackbox feature is currently available on the Naze32 and Naze32Pro targets. It may work on other targets, but you +will need to enable those manually in `/src/main/target/xxx/target.h` by adding a `#define BLACKBOX` statement and +recompile Cleanflight. + ## Hardware The blackbox software is designed to be used with an [OpenLog serial data logger][] and a microSDHC card. You need a little prep to get the OpenLog ready for use, so here are the details: @@ -58,7 +62,7 @@ The original OpenLog firmware may work with acceptable error rates if you use lo [OpenLog serial data logger]: https://www.sparkfun.com/products/9530 [OpenLog Lite firmware]: https://github.com/sparkfun/OpenLog/tree/master/firmware/OpenLog_v3_Light -[this version][]: https://raw.githubusercontent.com/thenickdude/blackbox/blackbox/tools/blackbox/openlog/OpenLog_v3_Light.cpp.hex +[this version]: https://raw.githubusercontent.com/thenickdude/blackbox/blackbox/tools/blackbox/openlog/OpenLog_v3_Light.cpp.hex [Required libraries]: https://code.google.com/p/beta-lib/downloads/detail?name=SerialLoggerBeta20120108.zip&can=4&q= [FTDI Basic Breakout]: https://www.sparkfun.com/products/9716 [FTDI crossover]: https://www.sparkfun.com/products/10660 From cdb3cc0dd3ed39b24122914f3f08583f289f7540 Mon Sep 17 00:00:00 2001 From: Nicholas Sherlock Date: Thu, 18 Dec 2014 18:47:13 +1300 Subject: [PATCH 10/24] Whitespace --- src/main/flight/flight.c | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/src/main/flight/flight.c b/src/main/flight/flight.c index faafe90ef2..1f4eb4c4b4 100644 --- a/src/main/flight/flight.c +++ b/src/main/flight/flight.c @@ -250,9 +250,9 @@ static void pidMultiWii(pidProfile_t *pidProfile, controlRateConfig_t *controlRa axisPID[axis] = PTerm + ITerm - DTerm; #ifdef BLACKBOX - axisP[axis] = PTerm; - axisI[axis] = ITerm; - axisD[axis] = -DTerm; + axisP[axis] = PTerm; + axisI[axis] = ITerm; + axisD[axis] = -DTerm; #endif } } From 54ead59791aa656f0ae13845d1776ebf6a2f1b05 Mon Sep 17 00:00:00 2001 From: Nicholas Sherlock Date: Fri, 19 Dec 2014 00:24:51 +1300 Subject: [PATCH 11/24] Rename axisP to less-cryptic axisPID_P (same for I and D) --- src/main/blackbox/blackbox.c | 20 ++++++++++---------- src/main/blackbox/blackbox.h | 2 +- src/main/flight/flight.c | 14 +++++++------- src/main/flight/flight.h | 2 +- 4 files changed, 19 insertions(+), 19 deletions(-) diff --git a/src/main/blackbox/blackbox.c b/src/main/blackbox/blackbox.c index baad91d3fc..2736b6d00c 100644 --- a/src/main/blackbox/blackbox.c +++ b/src/main/blackbox/blackbox.c @@ -191,7 +191,7 @@ static const char * const blackboxHeaderFields[] = { PREDICT(AVERAGE_2) "," PREDICT(AVERAGE_2) "," PREDICT(AVERAGE_2) "," PREDICT(AVERAGE_2), - /* RC fields are encoded together as a group, everything else is signed since they're diffs: */ + /* PID_I terms and RC fields are encoded together as groups, everything else is signed since they're diffs: */ "H Field P encoding:" /* loopIteration, time: */ ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," @@ -547,13 +547,13 @@ static void writeIntraframe(void) writeUnsignedVB(blackboxCurrent->time); for (x = 0; x < 3; x++) - writeSignedVB(blackboxCurrent->axisP[x]); + writeSignedVB(blackboxCurrent->axisPID_P[x]); for (x = 0; x < 3; x++) - writeSignedVB(blackboxCurrent->axisI[x]); + writeSignedVB(blackboxCurrent->axisPID_I[x]); for (x = 0; x < 3; x++) - writeSignedVB(blackboxCurrent->axisD[x]); + writeSignedVB(blackboxCurrent->axisPID_D[x]); for (x = 0; x < 3; x++) writeSignedVB(blackboxCurrent->rcCommand[x]); @@ -605,10 +605,10 @@ static void writeInterframe(void) writeSignedVB((int32_t) (blackboxHistory[0]->time - 2 * blackboxHistory[1]->time + blackboxHistory[2]->time)); for (x = 0; x < 3; x++) - writeSignedVB(blackboxCurrent->axisP[x] - blackboxLast->axisP[x]); + writeSignedVB(blackboxCurrent->axisPID_P[x] - blackboxLast->axisPID_P[x]); for (x = 0; x < 3; x++) - deltas[x] = blackboxCurrent->axisI[x] - blackboxLast->axisI[x]; + deltas[x] = blackboxCurrent->axisPID_I[x] - blackboxLast->axisPID_I[x]; /* * The PID I field changes very slowly, most of the time +-2, so use an encoding @@ -617,7 +617,7 @@ static void writeInterframe(void) writeTag2_3S32(deltas); for (x = 0; x < 3; x++) - writeSignedVB(blackboxCurrent->axisD[x] - blackboxLast->axisD[x]); + writeSignedVB(blackboxCurrent->axisPID_D[x] - blackboxLast->axisPID_D[x]); for (x = 0; x < 4; x++) deltas[x] = blackboxCurrent->rcCommand[x] - blackboxLast->rcCommand[x]; @@ -772,11 +772,11 @@ static void loadBlackboxState(void) blackboxCurrent->time = currentTime; for (i = 0; i < 3; i++) - blackboxCurrent->axisP[i] = axisP[i]; + blackboxCurrent->axisPID_P[i] = axisPID_P[i]; for (i = 0; i < 3; i++) - blackboxCurrent->axisI[i] = axisI[i]; + blackboxCurrent->axisPID_I[i] = axisPID_I[i]; for (i = 0; i < 3; i++) - blackboxCurrent->axisD[i] = axisD[i]; + blackboxCurrent->axisPID_D[i] = axisPID_D[i]; for (i = 0; i < 4; i++) blackboxCurrent->rcCommand[i] = rcCommand[i]; diff --git a/src/main/blackbox/blackbox.h b/src/main/blackbox/blackbox.h index 84804b3828..8f88fec526 100644 --- a/src/main/blackbox/blackbox.h +++ b/src/main/blackbox/blackbox.h @@ -22,7 +22,7 @@ typedef struct blackboxValues_t { uint32_t time; - int32_t axisP[3], axisI[3], axisD[3]; + int32_t axisPID_P[3], axisPID_I[3], axisPID_D[3]; int16_t rcCommand[4]; int16_t gyroData[3]; diff --git a/src/main/flight/flight.c b/src/main/flight/flight.c index 1f4eb4c4b4..9da2c24742 100644 --- a/src/main/flight/flight.c +++ b/src/main/flight/flight.c @@ -44,7 +44,7 @@ int16_t heading, magHold; int16_t axisPID[3]; #ifdef BLACKBOX -int32_t axisP[3], axisI[3], axisD[3]; +int32_t axisPID_P[3], axisPID_I[3], axisPID_D[3]; #endif uint8_t dynP8[3], dynI8[3], dynD8[3]; @@ -250,9 +250,9 @@ static void pidMultiWii(pidProfile_t *pidProfile, controlRateConfig_t *controlRa axisPID[axis] = PTerm + ITerm - DTerm; #ifdef BLACKBOX - axisP[axis] = PTerm; - axisI[axis] = ITerm; - axisD[axis] = -DTerm; + axisPID_P[axis] = PTerm; + axisPID_I[axis] = ITerm; + axisPID_D[axis] = -DTerm; #endif } } @@ -339,9 +339,9 @@ static void pidRewrite(pidProfile_t *pidProfile, controlRateConfig_t *controlRat axisPID[axis] = PTerm + ITerm + DTerm; #ifdef BLACKBOX - axisP[axis] = PTerm; - axisI[axis] = ITerm; - axisD[axis] = DTerm; + axisPID_P[axis] = PTerm; + axisPID_I[axis] = ITerm; + axisPID_D[axis] = DTerm; #endif } } diff --git a/src/main/flight/flight.h b/src/main/flight/flight.h index ebccf21906..158ac23a79 100644 --- a/src/main/flight/flight.h +++ b/src/main/flight/flight.h @@ -127,7 +127,7 @@ extern int16_t gyroADC[XYZ_AXIS_COUNT], accADC[XYZ_AXIS_COUNT], accSmooth[XYZ_AX extern int32_t accSum[XYZ_AXIS_COUNT]; extern int16_t axisPID[XYZ_AXIS_COUNT]; -extern int32_t axisP[3], axisI[3], axisD[3]; +extern int32_t axisPID_P[3], axisPID_I[3], axisPID_D[3]; extern int16_t heading, magHold; From 50c81aa00e808902e64a92f70b59aee7dd6dec0d Mon Sep 17 00:00:00 2001 From: Nicholas Sherlock Date: Fri, 19 Dec 2014 02:06:44 +1300 Subject: [PATCH 12/24] Make tag8_4S16 encoding more space efficent. This replaces the older encoding variant, so the data version number has been bumped. --- src/main/blackbox/blackbox.c | 111 +++++++++++++++++++---------------- 1 file changed, 60 insertions(+), 51 deletions(-) diff --git a/src/main/blackbox/blackbox.c b/src/main/blackbox/blackbox.c index 2736b6d00c..a32d9f09c1 100644 --- a/src/main/blackbox/blackbox.c +++ b/src/main/blackbox/blackbox.c @@ -92,7 +92,7 @@ static const char blackboxHeader[] = "H Product:Blackbox flight data recorder by Nicholas Sherlock\n" "H Blackbox version:1\n" - "H Data version:1\n" + "H Data version:2\n" "H I interval:" STR(BLACKBOX_I_INTERVAL) "\n"; /* These headers have info for all 8 motors on them, we'll trim the final fields off to match the number of motors in the mixer: */ @@ -349,15 +349,19 @@ static void writeTag2_3S32(int32_t *values) { static const int NUM_FIELDS = 3; //Need to be enums rather than const ints if we want to switch on them (due to being C) - enum { BITS_2 = 0}; - enum { BITS_4 = 1}; - enum { BITS_6 = 2}; - enum { BITS_32 = 3}; + enum { + BITS_2 = 0, + BITS_4 = 1, + BITS_6 = 2, + BITS_32 = 3 + }; - enum { BYTES_1 = 0}; - enum { BYTES_2 = 1}; - enum { BYTES_3 = 2}; - enum { BYTES_4 = 3}; + enum { + BYTES_1 = 0, + BYTES_2 = 1, + BYTES_3 = 2, + BYTES_4 = 3 + }; int x; int selector = BITS_2, selector2; @@ -465,38 +469,17 @@ static void writeTag2_3S32(int32_t *values) { static void writeTag8_4S16(int32_t *values) { //Need to be enums rather than const ints if we want to switch on them (due to being C) - enum { FIELD_ZERO = 0}; - enum { FIELD_4BIT = 1}; - enum { FIELD_8BIT = 2}; - enum { FIELD_16BIT = 3}; - - uint8_t selector; - int x; - - /* - * 4-bit fields can only be combined with their paired neighbor (there are two pairs), so choose a - * larger encoding if that's not possible. - */ - const uint8_t rcSelectorCleanup[16] = { - // Output selectors <- Input selectors - FIELD_ZERO << 2 | FIELD_ZERO, // zero, zero - FIELD_ZERO << 2 | FIELD_8BIT, // zero, 4-bit - FIELD_ZERO << 2 | FIELD_8BIT, // zero, 8-bit - FIELD_ZERO << 2 | FIELD_16BIT, // zero, 16-bit - FIELD_8BIT << 2 | FIELD_ZERO, // 4-bit, zero - FIELD_4BIT << 2 | FIELD_4BIT, // 4-bit, 4-bit - FIELD_8BIT << 2 | FIELD_8BIT, // 4-bit, 8-bit - FIELD_8BIT << 2 | FIELD_16BIT, // 4-bit, 16-bit - FIELD_8BIT << 2 | FIELD_ZERO, // 8-bit, zero - FIELD_8BIT << 2 | FIELD_8BIT, // 8-bit, 4-bit - FIELD_8BIT << 2 | FIELD_8BIT, // 8-bit, 8-bit - FIELD_8BIT << 2 | FIELD_16BIT, // 8-bit, 16-bit - FIELD_16BIT << 2 | FIELD_ZERO, // 16-bit, zero - FIELD_16BIT << 2 | FIELD_8BIT, // 16-bit, 4-bit - FIELD_16BIT << 2 | FIELD_8BIT, // 16-bit, 8-bit - FIELD_16BIT << 2 | FIELD_16BIT, // 16-bit, 16-bit + enum { + FIELD_ZERO = 0, + FIELD_4BIT = 1, + FIELD_8BIT = 2, + FIELD_16BIT = 3 }; + uint8_t selector, buffer; + int nibbleIndex; + int x; + selector = 0; //Encode in reverse order so the first field is in the low bits: for (x = 3; x >= 0; x--) { @@ -504,36 +487,62 @@ static void writeTag8_4S16(int32_t *values) { if (values[x] == 0) selector |= FIELD_ZERO; - else if (values[x] <= 7 && values[x] >= -8) + else if (values[x] < 8 && values[x] >= -8) selector |= FIELD_4BIT; - else if (values[x] <= 127 && values[x] >= -128) + else if (values[x] < 128 && values[x] >= -128) selector |= FIELD_8BIT; else selector |= FIELD_16BIT; } - selector = rcSelectorCleanup[selector & 0x0F] | (rcSelectorCleanup[selector >> 4] << 4); - blackboxWrite(selector); + nibbleIndex = 0; + buffer = 0; for (x = 0; x < 4; x++, selector >>= 2) { switch (selector & 0x03) { + case FIELD_ZERO: + //No-op + break; case FIELD_4BIT: - blackboxWrite((values[x] & 0x0F) | (values[x + 1] << 4)); - - //We write two selector fields: - x++; - selector >>= 2; + if (nibbleIndex == 0) { + //We fill high-bits first + buffer = values[x] << 4; + nibbleIndex = 1; + } else { + blackboxWrite(buffer | (values[x] & 0x0F)); + nibbleIndex = 0; + } break; case FIELD_8BIT: - blackboxWrite(values[x]); + if (nibbleIndex == 0) + blackboxWrite(values[x]); + else { + //Write the high bits of the value first (mask to avoid sign extension) + blackboxWrite(buffer | ((values[x] >> 4) & 0x0F)); + //Now put the leftover low bits into the top of the next buffer entry + buffer = values[x] << 4; + } break; case FIELD_16BIT: - blackboxWrite(values[x]); - blackboxWrite(values[x] >> 8); + if (nibbleIndex == 0) { + //Write high byte first + blackboxWrite(values[x] >> 8); + blackboxWrite(values[x]); + } else { + //First write the highest 4 bits + blackboxWrite(buffer | ((values[x] >> 12) & 0x0F)); + // Then the middle 8 + blackboxWrite(values[x] >> 4); + //Only the smallest 4 bits are still left to write + buffer = values[x] << 4; + } break; } } + //Anything left over to write? + if (nibbleIndex == 1) + blackboxWrite(buffer); } static void writeIntraframe(void) From 9b9474250ee9cb079c1a4528e1766612093e1908 Mon Sep 17 00:00:00 2001 From: Nicholas Sherlock Date: Sat, 20 Dec 2014 16:51:38 +1300 Subject: [PATCH 13/24] Header definitions now provided by a struct instead of lots of strings Introduce mechanism for disabling log fields at logging-start Remove a div/mod from handleBlackbox() Bring code required to be executed upon state transitions into a central setState() routine. --- src/main/blackbox/blackbox.c | 538 ++++++++++++++----------- src/main/blackbox/blackbox_fielddefs.h | 127 +++--- 2 files changed, 374 insertions(+), 291 deletions(-) diff --git a/src/main/blackbox/blackbox.c b/src/main/blackbox/blackbox.c index a32d9f09c1..1623f5afaf 100644 --- a/src/main/blackbox/blackbox.c +++ b/src/main/blackbox/blackbox.c @@ -79,6 +79,8 @@ #define BLACKBOX_INITIAL_PORT_MODE MODE_TX #define BLACKBOX_I_INTERVAL 32 +#define ARRAY_LENGTH(x) (sizeof((x))/sizeof((x)[0])) + // Some macros to make writing FLIGHT_LOG_FIELD_PREDICTOR_* constants shorter: #define STR_HELPER(x) #x #define STR(x) STR_HELPER(x) @@ -86,8 +88,11 @@ #define CONCAT_HELPER(x,y) x ## y #define CONCAT(x,y) CONCAT_HELPER(x, y) -#define PREDICT(x) STR(CONCAT(FLIGHT_LOG_FIELD_PREDICTOR_, x)) -#define ENCODING(x) STR(CONCAT(FLIGHT_LOG_FIELD_ENCODING_, x)) +#define PREDICT(x) CONCAT(FLIGHT_LOG_FIELD_PREDICTOR_, x) +#define ENCODING(x) CONCAT(FLIGHT_LOG_FIELD_ENCODING_, x) +#define CONDITION(x) CONCAT(FLIGHT_LOG_FIELD_CONDITION_, x) +#define UNSIGNED FLIGHT_LOG_FIELD_UNSIGNED +#define SIGNED FLIGHT_LOG_FIELD_SIGNED static const char blackboxHeader[] = "H Product:Blackbox flight data recorder by Nicholas Sherlock\n" @@ -95,174 +100,115 @@ static const char blackboxHeader[] = "H Data version:2\n" "H I interval:" STR(BLACKBOX_I_INTERVAL) "\n"; -/* These headers have info for all 8 motors on them, we'll trim the final fields off to match the number of motors in the mixer: */ -static const char * const blackboxHeaderFields[] = { - "H Field I name:" - "loopIteration,time," - "axisP[0],axisP[1],axisP[2]," - "axisI[0],axisI[1],axisI[2]," - "axisD[0],axisD[1],axisD[2]," - "rcCommand[0],rcCommand[1],rcCommand[2],rcCommand[3]," - "gyroData[0],gyroData[1],gyroData[2]," - "accSmooth[0],accSmooth[1],accSmooth[2]," - "motor[0],motor[1],motor[2],motor[3]," - "motor[4],motor[5],motor[6],motor[7]", - - "H Field I signed:" - /* loopIteration, time: */ - "0,0," - /* PIDs: */ - "1,1,1,1,1,1,1,1,1," - /* rcCommand[0..2] */ - "1,1,1," - /* rcCommand[3] (Throttle): */ - "0," - /* gyroData[0..2]: */ - "1,1,1," - /* accSmooth[0..2]: */ - "1,1,1," - /* Motor[0..7]: */ - "0,0,0,0,0,0,0,0", - - "H Field I predictor:" - /* loopIteration, time: */ - PREDICT(0) "," PREDICT(0) "," - /* PIDs: */ - PREDICT(0) "," PREDICT(0) "," PREDICT(0) "," - PREDICT(0) "," PREDICT(0) "," PREDICT(0) "," - PREDICT(0) "," PREDICT(0) "," PREDICT(0) "," - /* rcCommand[0..2] */ - PREDICT(0) "," PREDICT(0) "," PREDICT(0) "," - /* rcCommand[3] (Throttle): */ - PREDICT(MINTHROTTLE) "," - /* gyroData[0..2]: */ - PREDICT(0) "," PREDICT(0) "," PREDICT(0) "," - /* accSmooth[0..2]: */ - PREDICT(0) "," PREDICT(0) "," PREDICT(0) "," - /* Motor[0]: */ - PREDICT(MINTHROTTLE) "," - /* Motor[1..7]: */ - PREDICT(MOTOR_0) "," PREDICT(MOTOR_0) "," PREDICT(MOTOR_0) "," - PREDICT(MOTOR_0) "," PREDICT(MOTOR_0) "," PREDICT(MOTOR_0) "," - PREDICT(MOTOR_0), - - "H Field I encoding:" - /* loopIteration, time: */ - ENCODING(UNSIGNED_VB) "," ENCODING(UNSIGNED_VB) "," - /* PIDs: */ - ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," - ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," - ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," - /* rcCommand[0..2] */ - ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," - /* rcCommand[3] (Throttle): */ - ENCODING(UNSIGNED_VB) "," - /* gyroData[0..2]: */ - ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," - /* accSmooth[0..2]: */ - ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," - /* Motor[0]: */ - ENCODING(UNSIGNED_VB) "," - /* Motor[1..7]: */ - ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," - ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," - ENCODING(SIGNED_VB), - - //Motors and gyros predict an average of the last two measurements (to reduce the impact of noise): - "H Field P predictor:" - /* loopIteration, time: */ - PREDICT(INC) "," PREDICT(STRAIGHT_LINE) "," - /* PIDs: */ - PREDICT(PREVIOUS) "," PREDICT(PREVIOUS) "," PREDICT(PREVIOUS) "," - PREDICT(PREVIOUS) "," PREDICT(PREVIOUS) "," PREDICT(PREVIOUS) "," - PREDICT(PREVIOUS) "," PREDICT(PREVIOUS) "," PREDICT(PREVIOUS) "," - /* rcCommand[0..2] */ - PREDICT(PREVIOUS) "," PREDICT(PREVIOUS) "," PREDICT(PREVIOUS) "," - /* rcCommand[3] (Throttle): */ - PREDICT(PREVIOUS) "," - /* gyroData[0..2]: */ - PREDICT(AVERAGE_2) "," PREDICT(AVERAGE_2) "," PREDICT(AVERAGE_2) "," - /* accSmooth[0..2]: */ - PREDICT(AVERAGE_2) "," PREDICT(AVERAGE_2) "," PREDICT(AVERAGE_2) "," - /* Motor[0]: */ - PREDICT(AVERAGE_2) "," - /* Motor[1..7]: */ - PREDICT(AVERAGE_2) "," PREDICT(AVERAGE_2) "," PREDICT(AVERAGE_2) "," - PREDICT(AVERAGE_2) "," PREDICT(AVERAGE_2) "," PREDICT(AVERAGE_2) "," - PREDICT(AVERAGE_2), - - /* PID_I terms and RC fields are encoded together as groups, everything else is signed since they're diffs: */ - "H Field P encoding:" - /* loopIteration, time: */ - ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," - /* PIDs: */ - ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," - ENCODING(TAG2_3S32) "," ENCODING(TAG2_3S32) "," ENCODING(TAG2_3S32) "," - ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," - /* rcCommand[0..3] */ - ENCODING(TAG8_4S16) "," ENCODING(TAG8_4S16) "," ENCODING(TAG8_4S16) "," - ENCODING(TAG8_4S16) "," - /* gyroData[0..2]: */ - ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," - /* accSmooth[0..2]: */ - ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," - /* Motor[0]: */ - ENCODING(SIGNED_VB) "," - /* Motor[1..7]: */ - ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," - ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," - ENCODING(SIGNED_VB) +static const char* const blackboxMainHeaderNames[] = { + "I name", + "I signed", + "I predictor", + "I encoding", + "P predictor", + "P encoding" }; -/** - * Additional fields to tack on to those above for tricopters (to record tail servo position) - */ -static const char * const blackboxAdditionalFieldsTricopter[] = { - //Field I name - "servo[5]", - - //Field I signed - "0", - - //Field I predictor - PREDICT(1500), - - //Field I encoding: - ENCODING(SIGNED_VB), - - //Field P predictor: - PREDICT(PREVIOUS), - - //Field P encoding: - ENCODING(SIGNED_VB) +static const char* const blackboxGPSGHeaderNames[] = { + "G name", + "G signed", + "G predictor", + "G encoding" }; -static const char blackboxGpsHeader[] = - "H Field G name:" - "GPS_numSat,GPS_coord[0],GPS_coord[1],GPS_altitude,GPS_speed\n" - "H Field G signed:" - "0,1,1,0,0\n" - "H Field G predictor:" - PREDICT(0) "," PREDICT(HOME_COORD) "," PREDICT(HOME_COORD) "," PREDICT(0) "," PREDICT(0) "\n" - "H Field G encoding:" - ENCODING(UNSIGNED_VB) "," ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "," - ENCODING(UNSIGNED_VB) "," ENCODING(UNSIGNED_VB) "\n" +static const char* const blackboxGPSHHeaderNames[] = { + "H name", + "H signed", + "H predictor", + "H encoding" +}; - "H Field H name:" - "GPS_home[0],GPS_home[1]\n" - "H Field H signed:" - "1,1\n" - "H Field H predictor:" - PREDICT(0) "," PREDICT(0) "\n" - "H Field H encoding:" - ENCODING(SIGNED_VB) "," ENCODING(SIGNED_VB) "\n"; +/* All field definition structs should look like this (but with longer arrs): */ +typedef struct blackboxFieldDefinition_t { + const char *name; + uint8_t arr[1]; +} blackboxFieldDefinition_t; + +typedef struct blackboxMainFieldDefinition_t { + const char *name; + uint8_t isSigned; + uint8_t Ipredict; + uint8_t Iencode; + uint8_t Ppredict; + uint8_t Pencode; + uint8_t condition; // Decide whether this field should appear in the log +} blackboxMainFieldDefinition_t; + +typedef struct blackboxGPSFieldDefinition_t { + const char *name; + uint8_t isSigned; + uint8_t predict; + uint8_t encode; +} blackboxGPSFieldDefinition_t; + +static const blackboxMainFieldDefinition_t blackboxMainFields[] = { + /* loopIteration doesn't appear in P frames since it always increments */ + {"loopIteration", UNSIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(UNSIGNED_VB), .Ppredict = PREDICT(INC), .Pencode = FLIGHT_LOG_FIELD_ENCODING_NULL, CONDITION(ALWAYS)}, + /* Time advances pretty steadily so the P-frame prediction is a straight line */ + {"time", UNSIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(UNSIGNED_VB), .Ppredict = PREDICT(STRAIGHT_LINE), .Pencode = ENCODING(SIGNED_VB), CONDITION(ALWAYS)}, + {"axisP[0]", SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(SIGNED_VB), CONDITION(ALWAYS)}, + {"axisP[1]", SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(SIGNED_VB), CONDITION(ALWAYS)}, + {"axisP[2]", SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(SIGNED_VB), CONDITION(ALWAYS)}, + /* I terms get special packed encoding in P frames: */ + {"axisI[0]", SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(TAG2_3S32), CONDITION(ALWAYS)}, + {"axisI[1]", SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(TAG2_3S32), CONDITION(ALWAYS)}, + {"axisI[2]", SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(TAG2_3S32), CONDITION(ALWAYS)}, + {"axisD[0]", SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(SIGNED_VB), CONDITION(ALWAYS)}, + {"axisD[1]", SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(SIGNED_VB), CONDITION(ALWAYS)}, + {"axisD[2]", SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(SIGNED_VB), CONDITION(ALWAYS)}, + /* rcCommands are encoded together as a group in P-frames: */ + {"rcCommand[0]", SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(TAG8_4S16), CONDITION(ALWAYS)}, + {"rcCommand[1]", SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(TAG8_4S16), CONDITION(ALWAYS)}, + {"rcCommand[2]", SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(TAG8_4S16), CONDITION(ALWAYS)}, + /* Throttle is always in the range [minthrottle..maxthrottle]: */ + {"rcCommand[3]", UNSIGNED, .Ipredict = PREDICT(MINTHROTTLE), .Iencode = ENCODING(UNSIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(TAG8_4S16), CONDITION(ALWAYS)}, + /* Gyros and accelerometers base their P-predictions on the average of the previous 2 frames to reduce noise impact */ + {"gyroData[0]", SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(ALWAYS)}, + {"gyroData[1]", SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(ALWAYS)}, + {"gyroData[2]", SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(ALWAYS)}, + {"accSmooth[0]", SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(ALWAYS)}, + {"accSmooth[1]", SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(ALWAYS)}, + {"accSmooth[2]", SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(ALWAYS)}, + /* Motors only rarely drops under minthrottle (when stick falls below mincommand), so predict minthrottle for it and use *unsigned* encoding (which is large for negative numbers but more compact for positive ones): */ + {"motor[0]", UNSIGNED, .Ipredict = PREDICT(MINTHROTTLE), .Iencode = ENCODING(UNSIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_MOTORS_1)}, + /* Subsequent motors base their I-frame values on the first one, P-frame values on the average of last two frames: */ + {"motor[1]", UNSIGNED, .Ipredict = PREDICT(MOTOR_0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_MOTORS_2)}, + {"motor[2]", UNSIGNED, .Ipredict = PREDICT(MOTOR_0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_MOTORS_3)}, + {"motor[3]", UNSIGNED, .Ipredict = PREDICT(MOTOR_0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_MOTORS_4)}, + {"motor[4]", UNSIGNED, .Ipredict = PREDICT(MOTOR_0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_MOTORS_5)}, + {"motor[5]", UNSIGNED, .Ipredict = PREDICT(MOTOR_0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_MOTORS_6)}, + {"motor[6]", UNSIGNED, .Ipredict = PREDICT(MOTOR_0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_MOTORS_7)}, + {"motor[7]", UNSIGNED, .Ipredict = PREDICT(MOTOR_0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_MOTORS_8)}, + {"servo[5]", UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(SIGNED_VB), CONDITION(TRICOPTER)} +}; + +// GPS position/vel frame +static const blackboxGPSFieldDefinition_t blackboxGpsGFields[] = { + {"GPS_numSat", UNSIGNED, PREDICT(0), ENCODING(UNSIGNED_VB)}, + {"GPS_coord[0]", SIGNED, PREDICT(HOME_COORD), ENCODING(SIGNED_VB)}, + {"GPS_coord[1]", SIGNED, PREDICT(HOME_COORD), ENCODING(SIGNED_VB)}, + {"GPS_altitude", UNSIGNED, PREDICT(0), ENCODING(UNSIGNED_VB)}, + {"GPS_speed", UNSIGNED, PREDICT(0), ENCODING(UNSIGNED_VB)} +}; + +// GPS home frame +static const blackboxGPSFieldDefinition_t blackboxGpsHFields[] = { + {"GPS_home[0]", SIGNED, PREDICT(0), ENCODING(SIGNED_VB)}, + {"GPS_home[1]", SIGNED, PREDICT(0), ENCODING(SIGNED_VB)} +}; typedef enum BlackboxState { BLACKBOX_STATE_DISABLED = 0, BLACKBOX_STATE_STOPPED, BLACKBOX_STATE_SEND_HEADER, BLACKBOX_STATE_SEND_FIELDINFO, - BLACKBOX_STATE_SEND_GPS_HEADERS, + BLACKBOX_STATE_SEND_GPS_H_HEADERS, + BLACKBOX_STATE_SEND_GPS_G_HEADERS, BLACKBOX_STATE_SEND_SYSINFO, BLACKBOX_STATE_RUNNING } BlackboxState; @@ -278,10 +224,16 @@ extern uint8_t motorCount; //From mw.c: extern uint32_t currentTime; +static const int SERIAL_CHUNK_SIZE = 16; + static BlackboxState blackboxState = BLACKBOX_STATE_DISABLED; + static uint32_t startTime; static unsigned int headerXmitIndex; +static int fieldXmitIndex; + static uint32_t blackboxIteration; +static uint32_t blackboxPFrameIndex, blackboxIFrameIndex; static serialPort_t *blackboxPort; static portMode_t previousPortMode; @@ -295,11 +247,6 @@ static blackboxValues_t blackboxHistoryRing[3]; // These point into blackboxHistoryRing, use them to know where to store history of a given age (0, 1 or 2 generations old) static blackboxValues_t* blackboxHistory[3]; -static int isTricopter() -{ - return masterConfig.mixerConfiguration == MULTITYPE_TRI; -} - static void blackboxWrite(uint8_t value) { serialWrite(blackboxPort, value); @@ -320,6 +267,19 @@ static void blackboxPrintf(char *fmt, ...) va_end(va); } +// Print the null-terminated string 's' to the serial port and return the number of bytes written +static int blackboxPrint(const char *s) +{ + const char *pos = s; + + while (*pos) { + serialWrite(blackboxPort, *pos); + pos++; + } + + return pos - s; +} + /** * Write an unsigned integer to the blackbox serial port using variable byte encoding. */ @@ -545,6 +505,64 @@ static void writeTag8_4S16(int32_t *values) { blackboxWrite(buffer); } +static bool testBlackboxCondition(FlightLogFieldCondition condition) +{ + switch (condition) { + case FLIGHT_LOG_FIELD_CONDITION_ALWAYS: + return true; + case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_1: + return motorCount >= 1; + case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_2: + return motorCount >= 2; + case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_3: + return motorCount >= 3; + case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_4: + return motorCount >= 4; + case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_5: + return motorCount >= 5; + case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_6: + return motorCount >= 6; + case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_7: + return motorCount >= 7; + case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_8: + return motorCount >= 8; + case FLIGHT_LOG_FIELD_CONDITION_TRICOPTER: + return masterConfig.mixerConfiguration == MULTITYPE_TRI; + case FLIGHT_LOG_FIELD_CONDITION_NEVER: + return false; + default: + return false; + } +} + +static void blackboxSetState(BlackboxState newState) +{ + //Perform initial setup required for the new state + switch (newState) { + case BLACKBOX_STATE_SEND_HEADER: + startTime = millis(); + headerXmitIndex = 0; + break; + case BLACKBOX_STATE_SEND_FIELDINFO: + case BLACKBOX_STATE_SEND_GPS_G_HEADERS: + case BLACKBOX_STATE_SEND_GPS_H_HEADERS: + headerXmitIndex = 0; + fieldXmitIndex = -1; + break; + case BLACKBOX_STATE_SEND_SYSINFO: + headerXmitIndex = 0; + break; + case BLACKBOX_STATE_RUNNING: + blackboxIteration = 0; + blackboxPFrameIndex = 0; + blackboxIFrameIndex = 0; + break; + default: + ; + } + blackboxState = newState; +} + static void writeIntraframe(void) { blackboxValues_t *blackboxCurrent = blackboxHistory[0]; @@ -582,7 +600,7 @@ static void writeIntraframe(void) for (x = 1; x < motorCount; x++) writeSignedVB(blackboxCurrent->motor[x] - blackboxCurrent->motor[0]); - if (isTricopter()) + if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_TRICOPTER)) writeSignedVB(blackboxHistory[0]->servo[5] - 1500); //Rotate our history buffers: @@ -647,7 +665,7 @@ static void writeInterframe(void) for (x = 0; x < motorCount; x++) writeSignedVB(blackboxHistory[0]->motor[x] - (blackboxHistory[1]->motor[x] + blackboxHistory[2]->motor[x]) / 2); - if (isTricopter()) + if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_TRICOPTER)) writeSignedVB(blackboxCurrent->servo[5] - blackboxLast->servo[5]); //Rotate our history buffers @@ -715,29 +733,26 @@ void startBlackbox(void) configureBlackboxPort(); if (!blackboxPort) { - blackboxState = BLACKBOX_STATE_DISABLED; + blackboxSetState(BLACKBOX_STATE_DISABLED); return; } - startTime = millis(); - headerXmitIndex = 0; - blackboxIteration = 0; - blackboxState = BLACKBOX_STATE_SEND_HEADER; - memset(&gpsHistory, 0, sizeof(gpsHistory)); - //No need to clear the content of blackboxHistoryRing since our first frame will be an intra which overwrites it - blackboxHistory[0] = &blackboxHistoryRing[0]; blackboxHistory[1] = &blackboxHistoryRing[1]; blackboxHistory[2] = &blackboxHistoryRing[2]; + + //No need to clear the content of blackboxHistoryRing since our first frame will be an intra which overwrites it + + blackboxSetState(BLACKBOX_STATE_SEND_HEADER); } } void finishBlackbox(void) { if (blackboxState != BLACKBOX_STATE_DISABLED && blackboxState != BLACKBOX_STATE_STOPPED) { - blackboxState = BLACKBOX_STATE_STOPPED; + blackboxSetState(BLACKBOX_STATE_STOPPED); releaseBlackboxPort(); } @@ -803,14 +818,81 @@ static void loadBlackboxState(void) blackboxCurrent->servo[5] = servo[5]; } +/** + * Transmit the header information for the given field definitions. Transmitted header lines look like: + * + * H Field I name:a,b,c + * H Field I predictor:0,1,2 + * + * Provide an array 'conditions' of FlightLogFieldCondition enums if you want these conditions to decide whether a field + * should be included or not. Otherwise provide NULL for this parameter and NULL for secondCondition. + * + * Set headerXmitIndex to 0 and fieldXmitIndex to -1 before calling for the first time. + * + * secondFieldDefinition and secondCondition element pointers need to be provided in order to compute the stride of the + * fieldDefinition and secondCondition arrays. + * + * Returns true if there is still header left to transmit (so call again to continue transmission). + */ +static bool sendFieldDefinition(const char * const *headerNames, unsigned int headerCount, const void *fieldDefinitions, + const void *secondFieldDefinition, int fieldCount, const uint8_t *conditions, const uint8_t *secondCondition) +{ + const blackboxFieldDefinition_t *def; + int charsWritten; + static bool needComma = false; + size_t definitionStride = (char*) secondFieldDefinition - (char*) fieldDefinitions; + size_t conditionsStride = (char*) secondCondition - (char*) conditions; + + /* + * Send information about the fields we're recording to the log. Once again, we're chunking up the data so we don't exceed our datarate. + */ + if (fieldXmitIndex == -1) { + if (headerXmitIndex >= headerCount) + return false; //Someone probably called us again after we had already completed transmission + + charsWritten = blackboxPrint("H Field "); + charsWritten += blackboxPrint(headerNames[headerXmitIndex]); + charsWritten += blackboxPrint(":"); + + fieldXmitIndex++; + needComma = false; + } else + charsWritten = 0; + + for (; fieldXmitIndex < fieldCount && charsWritten < SERIAL_CHUNK_SIZE; fieldXmitIndex++) { + def = (const blackboxFieldDefinition_t*) ((const char*)fieldDefinitions + definitionStride * fieldXmitIndex); + + if (!conditions || testBlackboxCondition(conditions[conditionsStride * fieldXmitIndex])) { + if (needComma) { + blackboxWrite(','); + charsWritten++; + } else + needComma = true; + + // The first header is a field name + if (headerXmitIndex == 0) { + charsWritten += blackboxPrint(def->name); + } else { + //The other headers are integers (format as single digit for now): + blackboxWrite(def->arr[headerXmitIndex - 1] + '0'); + charsWritten++; + } + } + } + + // Did we complete this line? + if (fieldXmitIndex == fieldCount) { + blackboxWrite('\n'); + headerXmitIndex++; + fieldXmitIndex = -1; + } + + return headerXmitIndex < headerCount; +} + void handleBlackbox(void) { int i; - const char *additionalHeader; - const int SERIAL_CHUNK_SIZE = 16; - static int charXmitIndex = 0; - int motorsToRemove, endIndex; - int blackboxIntercycleIndex, blackboxIntracycleIndex; union floatConvert_t { float f; @@ -819,6 +901,8 @@ void handleBlackbox(void) switch (blackboxState) { case BLACKBOX_STATE_SEND_HEADER: + //On entry of this state, headerXmitIndex is 0 and startTime is intialised + /* * Once the UART has had time to init, transmit the header in chunks so we don't overflow our transmit * buffer. @@ -828,65 +912,36 @@ void handleBlackbox(void) blackboxWrite(blackboxHeader[headerXmitIndex]); if (blackboxHeader[headerXmitIndex] == '\0') { - blackboxState = BLACKBOX_STATE_SEND_FIELDINFO; - headerXmitIndex = 0; - charXmitIndex = 0; + blackboxSetState(BLACKBOX_STATE_SEND_FIELDINFO); } } break; case BLACKBOX_STATE_SEND_FIELDINFO: - /* - * Send information about the fields we're recording to the log. - * - * Once again, we're chunking up the data so we don't exceed our datarate. This time we're trimming the - * excess field defs off the end of the header for motors we don't have. - */ - motorsToRemove = 8 - motorCount; - - if (headerXmitIndex < sizeof(blackboxHeaderFields) / sizeof(blackboxHeaderFields[0])){ - endIndex = strlen(blackboxHeaderFields[headerXmitIndex]) - (headerXmitIndex == 0 ? strlen(",motor[x]") : strlen(",x")) * motorsToRemove; - - for (i = charXmitIndex; i < charXmitIndex + SERIAL_CHUNK_SIZE && i < endIndex; i++) - blackboxWrite(blackboxHeaderFields[headerXmitIndex][i]); - - // Did we complete this line? - if (i == endIndex) { - if (isTricopter()) { - //Add fields to the end for the tail servo - blackboxWrite(','); - - for (additionalHeader = blackboxAdditionalFieldsTricopter[headerXmitIndex]; *additionalHeader; additionalHeader++) - blackboxWrite(*additionalHeader); - } - - blackboxWrite('\n'); - headerXmitIndex++; - charXmitIndex = 0; - } else { - charXmitIndex = i; - } - } else { - //Completed sending field information - - if (feature(FEATURE_GPS)) { - blackboxState = BLACKBOX_STATE_SEND_GPS_HEADERS; - } else { - blackboxState = BLACKBOX_STATE_SEND_SYSINFO; - } - headerXmitIndex = 0; + //On entry of this state, headerXmitIndex is 0 and fieldXmitIndex is -1 + if (!sendFieldDefinition(blackboxMainHeaderNames, ARRAY_LENGTH(blackboxMainHeaderNames), blackboxMainFields, &blackboxMainFields[1], + ARRAY_LENGTH(blackboxMainFields), &blackboxMainFields[0].condition, &blackboxMainFields[1].condition)) { + if (feature(FEATURE_GPS)) + blackboxSetState(BLACKBOX_STATE_SEND_GPS_H_HEADERS); + else + blackboxSetState(BLACKBOX_STATE_SEND_SYSINFO); } break; - case BLACKBOX_STATE_SEND_GPS_HEADERS: - for (i = 0; i < SERIAL_CHUNK_SIZE && blackboxGpsHeader[headerXmitIndex] != '\0'; i++, headerXmitIndex++) - blackboxWrite(blackboxGpsHeader[headerXmitIndex]); - - if (blackboxGpsHeader[headerXmitIndex] == '\0') { - blackboxState = BLACKBOX_STATE_SEND_SYSINFO; - headerXmitIndex = 0; + case BLACKBOX_STATE_SEND_GPS_H_HEADERS: + //On entry of this state, headerXmitIndex is 0 and fieldXmitIndex is -1 + if (!sendFieldDefinition(blackboxGPSHHeaderNames, ARRAY_LENGTH(blackboxGPSHHeaderNames), blackboxGpsHFields, &blackboxGpsHFields[1], + ARRAY_LENGTH(blackboxGpsHFields), NULL, 0)) { + blackboxSetState(BLACKBOX_STATE_SEND_GPS_G_HEADERS); + } + break; + case BLACKBOX_STATE_SEND_GPS_G_HEADERS: + //On entry of this state, headerXmitIndex is 0 and fieldXmitIndex is -1 + if (!sendFieldDefinition(blackboxGPSGHeaderNames, ARRAY_LENGTH(blackboxGPSGHeaderNames), blackboxGpsGFields, &blackboxGpsGFields[1], + ARRAY_LENGTH(blackboxGpsGFields), NULL, 0)) { + blackboxSetState(BLACKBOX_STATE_SEND_SYSINFO); } break; case BLACKBOX_STATE_SEND_SYSINFO: - + //On entry of this state, headerXmitIndex is 0 switch (headerXmitIndex) { case 0: blackboxPrintf("H Firmware type:Cleanflight\n"); @@ -926,22 +981,21 @@ void handleBlackbox(void) // One more pause for good luck break; default: - blackboxState = BLACKBOX_STATE_RUNNING; + blackboxSetState(BLACKBOX_STATE_RUNNING); } headerXmitIndex++; break; case BLACKBOX_STATE_RUNNING: - // Write a keyframe every 32 frames so we can resynchronise upon missing frames - blackboxIntercycleIndex = blackboxIteration % BLACKBOX_I_INTERVAL; - blackboxIntracycleIndex = blackboxIteration / BLACKBOX_I_INTERVAL; + // On entry to this state, blackboxIteration, blackboxPFrameIndex and blackboxIFrameIndex are reset to 0 - if (blackboxIntercycleIndex == 0) { + // Write a keyframe every BLACKBOX_I_INTERVAL frames so we can resynchronise upon missing frames + if (blackboxPFrameIndex == 0) { // Copy current system values into the blackbox loadBlackboxState(); writeIntraframe(); } else { - if ((blackboxIntercycleIndex + masterConfig.blackbox_rate_num - 1) % masterConfig.blackbox_rate_denom < masterConfig.blackbox_rate_num) { + if ((blackboxPFrameIndex + masterConfig.blackbox_rate_num - 1) % masterConfig.blackbox_rate_denom < masterConfig.blackbox_rate_num) { loadBlackboxState(); writeInterframe(); } @@ -955,7 +1009,7 @@ void handleBlackbox(void) * still be interpreted correctly. */ if (GPS_home[0] != gpsHistory.GPS_home[0] || GPS_home[1] != gpsHistory.GPS_home[1] - || (blackboxIntercycleIndex == BLACKBOX_I_INTERVAL / 2 && blackboxIntracycleIndex % 128 == 0)) { + || (blackboxPFrameIndex == BLACKBOX_I_INTERVAL / 2 && blackboxIFrameIndex % 128 == 0)) { writeGPSHomeFrame(); writeGPSFrame(); @@ -968,6 +1022,12 @@ void handleBlackbox(void) } blackboxIteration++; + blackboxPFrameIndex++; + + if (blackboxPFrameIndex == BLACKBOX_I_INTERVAL) { + blackboxPFrameIndex = 0; + blackboxIFrameIndex++; + } break; default: break; @@ -985,7 +1045,7 @@ static bool canUseBlackboxWithCurrentConfiguration(void) void initBlackbox(void) { if (canUseBlackboxWithCurrentConfiguration()) - blackboxState = BLACKBOX_STATE_STOPPED; + blackboxSetState(BLACKBOX_STATE_STOPPED); else - blackboxState = BLACKBOX_STATE_DISABLED; + blackboxSetState(BLACKBOX_STATE_DISABLED); } diff --git a/src/main/blackbox/blackbox_fielddefs.h b/src/main/blackbox/blackbox_fielddefs.h index 1e0dbce1e7..bdea5cbd32 100644 --- a/src/main/blackbox/blackbox_fielddefs.h +++ b/src/main/blackbox/blackbox_fielddefs.h @@ -1,52 +1,75 @@ -/* - * This file is part of Cleanflight. - * - * Cleanflight is free software: you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * Cleanflight is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with Cleanflight. If not, see . - */ - -#pragma once - -//No prediction: -#define FLIGHT_LOG_FIELD_PREDICTOR_0 0 - -//Predict that the field is the same as last frame: -#define FLIGHT_LOG_FIELD_PREDICTOR_PREVIOUS 1 - -//Predict that the slope between this field and the previous item is the same as that between the past two history items: -#define FLIGHT_LOG_FIELD_PREDICTOR_STRAIGHT_LINE 2 - -//Predict that this field is the same as the average of the last two history items: -#define FLIGHT_LOG_FIELD_PREDICTOR_AVERAGE_2 3 - -//Predict that this field is minthrottle -#define FLIGHT_LOG_FIELD_PREDICTOR_MINTHROTTLE 4 - -//Predict that this field is the same as motor 0 -#define FLIGHT_LOG_FIELD_PREDICTOR_MOTOR_0 5 - -//This field always increments -#define FLIGHT_LOG_FIELD_PREDICTOR_INC 6 - -//Predict this GPS co-ordinate is the GPS home co-ordinate (or no prediction if that coordinate is not set) -#define FLIGHT_LOG_FIELD_PREDICTOR_HOME_COORD 7 - -//Predict 1500 -#define FLIGHT_LOG_FIELD_PREDICTOR_1500 8 - - -#define FLIGHT_LOG_FIELD_ENCODING_SIGNED_VB 0 -#define FLIGHT_LOG_FIELD_ENCODING_UNSIGNED_VB 1 -#define FLIGHT_LOG_FIELD_ENCODING_TAG2_3S32 7 -#define FLIGHT_LOG_FIELD_ENCODING_TAG8_4S16 8 -#define FLIGHT_LOG_FIELD_ENCODING_NULL 9 +/* + * This file is part of Cleanflight. + * + * Cleanflight is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * Cleanflight is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with Cleanflight. If not, see . + */ + +#pragma once + +typedef enum FlightLogFieldCondition { + FLIGHT_LOG_FIELD_CONDITION_ALWAYS = 0, + FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_1, + FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_2, + FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_3, + FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_4, + FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_5, + FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_6, + FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_7, + FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_8, + FLIGHT_LOG_FIELD_CONDITION_TRICOPTER, + FLIGHT_LOG_FIELD_CONDITION_NEVER = 255, +} FlightLogFieldCondition; + +typedef enum FlightLogFieldPredictor { + //No prediction: + FLIGHT_LOG_FIELD_PREDICTOR_0 = 0, + + //Predict that the field is the same as last frame: + FLIGHT_LOG_FIELD_PREDICTOR_PREVIOUS = 1, + + //Predict that the slope between this field and the previous item is the same as that between the past two history items: + FLIGHT_LOG_FIELD_PREDICTOR_STRAIGHT_LINE = 2, + + //Predict that this field is the same as the average of the last two history items: + FLIGHT_LOG_FIELD_PREDICTOR_AVERAGE_2 = 3, + + //Predict that this field is minthrottle + FLIGHT_LOG_FIELD_PREDICTOR_MINTHROTTLE = 4, + + //Predict that this field is the same as motor 0 + FLIGHT_LOG_FIELD_PREDICTOR_MOTOR_0 = 5, + + //This field always increments + FLIGHT_LOG_FIELD_PREDICTOR_INC = 6, + + //Predict this GPS co-ordinate is the GPS home co-ordinate (or no prediction if that coordinate is not set) + FLIGHT_LOG_FIELD_PREDICTOR_HOME_COORD = 7, + + //Predict 1500 + FLIGHT_LOG_FIELD_PREDICTOR_1500 = 8 +} FlightLogFieldPredictor; + +typedef enum FlightLogFieldEncoding { + FLIGHT_LOG_FIELD_ENCODING_SIGNED_VB = 0, + FLIGHT_LOG_FIELD_ENCODING_UNSIGNED_VB = 1, + FLIGHT_LOG_FIELD_ENCODING_TAG2_3S32 = 7, + FLIGHT_LOG_FIELD_ENCODING_TAG8_4S16 = 8, + FLIGHT_LOG_FIELD_ENCODING_NULL = 9 +} FlightLogFieldEncoding; + +typedef enum FlightLogFieldSign { + FLIGHT_LOG_FIELD_UNSIGNED = 0, + FLIGHT_LOG_FIELD_SIGNED = 1 +} FlightLogFieldSign; + From 2889f5904ee5dc6d94d38bd234bae3ea07337d8b Mon Sep 17 00:00:00 2001 From: Nicholas Sherlock Date: Mon, 22 Dec 2014 23:42:28 +1300 Subject: [PATCH 14/24] Update includes to add new required headers --- src/main/blackbox/blackbox.c | 19 ++++++++++--------- 1 file changed, 10 insertions(+), 9 deletions(-) diff --git a/src/main/blackbox/blackbox.c b/src/main/blackbox/blackbox.c index 1623f5afaf..2d3cae3c4d 100644 --- a/src/main/blackbox/blackbox.c +++ b/src/main/blackbox/blackbox.c @@ -26,14 +26,15 @@ #include "common/axis.h" #include "common/color.h" -#include "drivers/accgyro.h" -#include "drivers/light_led.h" - #include "drivers/gpio.h" +#include "drivers/sensor.h" #include "drivers/system.h" #include "drivers/serial.h" +#include "drivers/compass.h" #include "drivers/timer.h" #include "drivers/pwm_rx.h" +#include "drivers/accgyro.h" +#include "drivers/light_led.h" #include "common/printf.h" @@ -844,7 +845,8 @@ static bool sendFieldDefinition(const char * const *headerNames, unsigned int he size_t conditionsStride = (char*) secondCondition - (char*) conditions; /* - * Send information about the fields we're recording to the log. Once again, we're chunking up the data so we don't exceed our datarate. + * We're chunking up the header data so we don't exceed our datarate. So we'll be called multiple times to transmit + * the whole header. */ if (fieldXmitIndex == -1) { if (headerXmitIndex >= headerCount) @@ -911,14 +913,13 @@ void handleBlackbox(void) for (i = 0; i < SERIAL_CHUNK_SIZE && blackboxHeader[headerXmitIndex] != '\0'; i++, headerXmitIndex++) blackboxWrite(blackboxHeader[headerXmitIndex]); - if (blackboxHeader[headerXmitIndex] == '\0') { + if (blackboxHeader[headerXmitIndex] == '\0') blackboxSetState(BLACKBOX_STATE_SEND_FIELDINFO); - } } break; case BLACKBOX_STATE_SEND_FIELDINFO: //On entry of this state, headerXmitIndex is 0 and fieldXmitIndex is -1 - if (!sendFieldDefinition(blackboxMainHeaderNames, ARRAY_LENGTH(blackboxMainHeaderNames), blackboxMainFields, &blackboxMainFields[1], + if (!sendFieldDefinition(blackboxMainHeaderNames, ARRAY_LENGTH(blackboxMainHeaderNames), blackboxMainFields, blackboxMainFields + 1, ARRAY_LENGTH(blackboxMainFields), &blackboxMainFields[0].condition, &blackboxMainFields[1].condition)) { if (feature(FEATURE_GPS)) blackboxSetState(BLACKBOX_STATE_SEND_GPS_H_HEADERS); @@ -928,14 +929,14 @@ void handleBlackbox(void) break; case BLACKBOX_STATE_SEND_GPS_H_HEADERS: //On entry of this state, headerXmitIndex is 0 and fieldXmitIndex is -1 - if (!sendFieldDefinition(blackboxGPSHHeaderNames, ARRAY_LENGTH(blackboxGPSHHeaderNames), blackboxGpsHFields, &blackboxGpsHFields[1], + if (!sendFieldDefinition(blackboxGPSHHeaderNames, ARRAY_LENGTH(blackboxGPSHHeaderNames), blackboxGpsHFields, blackboxGpsHFields + 1, ARRAY_LENGTH(blackboxGpsHFields), NULL, 0)) { blackboxSetState(BLACKBOX_STATE_SEND_GPS_G_HEADERS); } break; case BLACKBOX_STATE_SEND_GPS_G_HEADERS: //On entry of this state, headerXmitIndex is 0 and fieldXmitIndex is -1 - if (!sendFieldDefinition(blackboxGPSGHeaderNames, ARRAY_LENGTH(blackboxGPSGHeaderNames), blackboxGpsGFields, &blackboxGpsGFields[1], + if (!sendFieldDefinition(blackboxGPSGHeaderNames, ARRAY_LENGTH(blackboxGPSGHeaderNames), blackboxGpsGFields, blackboxGpsGFields + 1, ARRAY_LENGTH(blackboxGpsGFields), NULL, 0)) { blackboxSetState(BLACKBOX_STATE_SEND_SYSINFO); } From 80082660ce7ae5d9beab8764882e6aa3e65c7a61 Mon Sep 17 00:00:00 2001 From: Nicholas Sherlock Date: Fri, 26 Dec 2014 11:38:48 +1300 Subject: [PATCH 15/24] Add blackbox scenarios to serial documentation --- docs/Serial.md | 2 ++ 1 file changed, 2 insertions(+) diff --git a/docs/Serial.md b/docs/Serial.md index f35944f864..fcf1d89d75 100644 --- a/docs/Serial.md +++ b/docs/Serial.md @@ -46,6 +46,8 @@ To make configuration easier common usage scenarios are listed below. 7 GPS-PASSTHROUGH ONLY 8 MSP ONLY 9 SMARTPORT TELEMETRY ONLY +10 BLACKBOX ONLY +11 MSP, CLI, BLACKBOX, GPS-PASSTHROUGH ``` ### Constraints From 5a51ca8d62d06201d9d15d39fe7f5e4e6fdb9764 Mon Sep 17 00:00:00 2001 From: Nicholas Sherlock Date: Fri, 26 Dec 2014 12:06:13 +1300 Subject: [PATCH 16/24] Update references for renamed mixer constants --- src/main/blackbox/blackbox.c | 10 ++++++++-- 1 file changed, 8 insertions(+), 2 deletions(-) diff --git a/src/main/blackbox/blackbox.c b/src/main/blackbox/blackbox.c index 2d3cae3c4d..0ba5c56f1f 100644 --- a/src/main/blackbox/blackbox.c +++ b/src/main/blackbox/blackbox.c @@ -82,7 +82,7 @@ #define ARRAY_LENGTH(x) (sizeof((x))/sizeof((x)[0])) -// Some macros to make writing FLIGHT_LOG_FIELD_PREDICTOR_* constants shorter: +// Some macros to make writing FLIGHT_LOG_FIELD_* constants shorter: #define STR_HELPER(x) #x #define STR(x) STR_HELPER(x) @@ -147,6 +147,12 @@ typedef struct blackboxGPSFieldDefinition_t { uint8_t encode; } blackboxGPSFieldDefinition_t; +/** + * Description of the blackbox fields we are writing in our main intra (I) and inter (P) frames. This description is + * written into the flight log header so the log can be properly interpreted (but these definitions don't actually cause + * the encoding to happen, we have to encode the flight log ourselves in write{Inter|Intra}frame() in a way that matches + * the encoding we've promised here). + */ static const blackboxMainFieldDefinition_t blackboxMainFields[] = { /* loopIteration doesn't appear in P frames since it always increments */ {"loopIteration", UNSIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(UNSIGNED_VB), .Ppredict = PREDICT(INC), .Pencode = FLIGHT_LOG_FIELD_ENCODING_NULL, CONDITION(ALWAYS)}, @@ -528,7 +534,7 @@ static bool testBlackboxCondition(FlightLogFieldCondition condition) case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_8: return motorCount >= 8; case FLIGHT_LOG_FIELD_CONDITION_TRICOPTER: - return masterConfig.mixerConfiguration == MULTITYPE_TRI; + return masterConfig.mixerMode == MIXER_TRI; case FLIGHT_LOG_FIELD_CONDITION_NEVER: return false; default: From ff9dad067c83990be71e60cab44212a2af410e97 Mon Sep 17 00:00:00 2001 From: Nicholas Sherlock Date: Fri, 26 Dec 2014 19:00:09 +1300 Subject: [PATCH 17/24] Give access to raw battery ADC readings for blackbox --- src/main/sensors/battery.c | 3 ++- src/main/sensors/battery.h | 1 + 2 files changed, 3 insertions(+), 1 deletion(-) diff --git a/src/main/sensors/battery.c b/src/main/sensors/battery.c index 186c6804e7..9766d40130 100644 --- a/src/main/sensors/battery.c +++ b/src/main/sensors/battery.c @@ -31,6 +31,7 @@ uint16_t batteryWarningVoltage; uint16_t batteryCriticalVoltage; uint8_t vbat = 0; // battery voltage in 0.1V steps +uint16_t vbatLatest = 0; // most recent unsmoothed raw reading from vbat adc int32_t amperage = 0; // amperage read by current sensor in centiampere (1/100th A) int32_t mAhDrawn = 0; // milliampere hours drawn from the battery since start @@ -54,7 +55,7 @@ void updateBatteryVoltage(void) uint16_t vbatSampleTotal = 0; // store the battery voltage with some other recent battery voltage readings - vbatSamples[(currentSampleIndex++) % BATTERY_SAMPLE_COUNT] = adcGetChannel(ADC_BATTERY); + vbatSamples[(currentSampleIndex++) % BATTERY_SAMPLE_COUNT] = vbatLatest = adcGetChannel(ADC_BATTERY); // calculate vbat based on the average of recent readings for (index = 0; index < BATTERY_SAMPLE_COUNT; index++) { diff --git a/src/main/sensors/battery.h b/src/main/sensors/battery.h index 6288f9f108..f90395f5fc 100644 --- a/src/main/sensors/battery.h +++ b/src/main/sensors/battery.h @@ -42,6 +42,7 @@ typedef enum { } batteryState_e; extern uint8_t vbat; +extern uint16_t vbatLatest; extern uint8_t batteryCellCount; extern uint16_t batteryWarningVoltage; extern int32_t amperage; From d195880bb84ba8b78cb93f993ec1e55f3c4a5715 Mon Sep 17 00:00:00 2001 From: Nicholas Sherlock Date: Sat, 27 Dec 2014 19:17:44 +1300 Subject: [PATCH 18/24] Support logging Vbat, baro, mag Don't bother logging PID "D" results if the corresponding D setting is zero --- src/main/blackbox/blackbox.c | 320 ++++++++++++++++++------- src/main/blackbox/blackbox.h | 16 +- src/main/blackbox/blackbox_fielddefs.h | 28 ++- 3 files changed, 276 insertions(+), 88 deletions(-) diff --git a/src/main/blackbox/blackbox.c b/src/main/blackbox/blackbox.c index 0ba5c56f1f..7895d4b601 100644 --- a/src/main/blackbox/blackbox.c +++ b/src/main/blackbox/blackbox.c @@ -165,15 +165,26 @@ static const blackboxMainFieldDefinition_t blackboxMainFields[] = { {"axisI[0]", SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(TAG2_3S32), CONDITION(ALWAYS)}, {"axisI[1]", SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(TAG2_3S32), CONDITION(ALWAYS)}, {"axisI[2]", SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(TAG2_3S32), CONDITION(ALWAYS)}, - {"axisD[0]", SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(SIGNED_VB), CONDITION(ALWAYS)}, - {"axisD[1]", SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(SIGNED_VB), CONDITION(ALWAYS)}, - {"axisD[2]", SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(SIGNED_VB), CONDITION(ALWAYS)}, + {"axisD[0]", SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(SIGNED_VB), CONDITION(NONZERO_PID_D_0)}, + {"axisD[1]", SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(SIGNED_VB), CONDITION(NONZERO_PID_D_1)}, + {"axisD[2]", SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(SIGNED_VB), CONDITION(NONZERO_PID_D_2)}, /* rcCommands are encoded together as a group in P-frames: */ {"rcCommand[0]", SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(TAG8_4S16), CONDITION(ALWAYS)}, {"rcCommand[1]", SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(TAG8_4S16), CONDITION(ALWAYS)}, {"rcCommand[2]", SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(TAG8_4S16), CONDITION(ALWAYS)}, /* Throttle is always in the range [minthrottle..maxthrottle]: */ {"rcCommand[3]", UNSIGNED, .Ipredict = PREDICT(MINTHROTTLE), .Iencode = ENCODING(UNSIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(TAG8_4S16), CONDITION(ALWAYS)}, + + {"vbatLatest", UNSIGNED, .Ipredict = PREDICT(VBATREF), .Iencode = ENCODING(NEG_14BIT), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(TAG8_8SVB), CONDITION(ALWAYS)}, +#ifdef MAG + {"magADC[0]", SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(TAG8_8SVB), FLIGHT_LOG_FIELD_CONDITION_MAG}, + {"magADC[1]", SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(TAG8_8SVB), FLIGHT_LOG_FIELD_CONDITION_MAG}, + {"magADC[2]", SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(TAG8_8SVB), FLIGHT_LOG_FIELD_CONDITION_MAG}, +#endif +#ifdef BARO + {"BaroAlt", SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(TAG8_8SVB), FLIGHT_LOG_FIELD_CONDITION_BARO}, +#endif + /* Gyros and accelerometers base their P-predictions on the average of the previous 2 frames to reduce noise impact */ {"gyroData[0]", SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(ALWAYS)}, {"gyroData[1]", SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(ALWAYS)}, @@ -246,6 +257,12 @@ static serialPort_t *blackboxPort; static portMode_t previousPortMode; static uint32_t previousBaudRate; +/* + * We store voltages in I-frames relative to this, which was the voltage when the blackbox was activated. + * This helps out since the voltage is only expected to fall from that point and we can reduce our diffs + * to encode: + */ +static uint16_t vbatReference; static gpsState_t gpsHistory; // Keep a history of length 2, plus a buffer for MW to store the new values into @@ -512,29 +529,89 @@ static void writeTag8_4S16(int32_t *values) { blackboxWrite(buffer); } +/** + * Write `valueCount` fields from `values` to the Blackbox using signed variable byte encoding. A 1-byte header is + * written first which specifies which fields are non-zero (so this encoding is compact when most fields are zero). + * + * valueCount must be 8 or less. + */ +static void writeTag8_8SVB(int32_t *values, int valueCount) +{ + uint8_t header; + int i; + + if (valueCount > 0) { + //If we're only writing one field then we can skip the header + if (valueCount == 1) { + writeSignedVB(values[0]); + } else { + //First write a one-byte header that marks which fields are non-zero + header = 0; + + // First field should be in low bits of header + for (i = valueCount - 1; i >= 0; i--) { + header <<= 1; + + if (values[i] != 0) + header |= 0x01; + } + + blackboxWrite(header); + + for (i = 0; i < valueCount; i++) + if (values[i] != 0) + writeSignedVB(values[i]); + } + } +} + static bool testBlackboxCondition(FlightLogFieldCondition condition) { switch (condition) { case FLIGHT_LOG_FIELD_CONDITION_ALWAYS: return true; + case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_1: - return motorCount >= 1; case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_2: - return motorCount >= 2; case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_3: - return motorCount >= 3; case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_4: - return motorCount >= 4; case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_5: - return motorCount >= 5; case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_6: - return motorCount >= 6; case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_7: - return motorCount >= 7; case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_8: - return motorCount >= 8; + return motorCount >= condition - FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_1 + 1; case FLIGHT_LOG_FIELD_CONDITION_TRICOPTER: return masterConfig.mixerMode == MIXER_TRI; + + case FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_P_0: + case FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_P_1: + case FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_P_2: + return currentProfile->pidProfile.P8[condition - FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_P_0] != 0; + + case FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_I_0: + case FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_I_1: + case FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_I_2: + return currentProfile->pidProfile.I8[condition - FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_I_0] != 0; + + case FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_0: + case FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_1: + case FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_2: + return currentProfile->pidProfile.D8[condition - FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_0] != 0; + + case FLIGHT_LOG_FIELD_CONDITION_MAG: +#ifdef MAG + return sensors(SENSOR_MAG); +#else + return false; +#endif + + case FLIGHT_LOG_FIELD_CONDITION_BARO: +#ifdef BARO + return sensors(SENSOR_BARO); +#else + return false; +#endif + case FLIGHT_LOG_FIELD_CONDITION_NEVER: return false; default: @@ -580,24 +657,45 @@ static void writeIntraframe(void) writeUnsignedVB(blackboxIteration); writeUnsignedVB(blackboxCurrent->time); - for (x = 0; x < 3; x++) + for (x = 0; x < XYZ_AXIS_COUNT; x++) writeSignedVB(blackboxCurrent->axisPID_P[x]); - for (x = 0; x < 3; x++) + for (x = 0; x < XYZ_AXIS_COUNT; x++) writeSignedVB(blackboxCurrent->axisPID_I[x]); - for (x = 0; x < 3; x++) - writeSignedVB(blackboxCurrent->axisPID_D[x]); + for (x = 0; x < XYZ_AXIS_COUNT; x++) + if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_0 + x)) + writeSignedVB(blackboxCurrent->axisPID_D[x]); for (x = 0; x < 3; x++) writeSignedVB(blackboxCurrent->rcCommand[x]); writeUnsignedVB(blackboxCurrent->rcCommand[3] - masterConfig.escAndServoConfig.minthrottle); //Throttle lies in range [minthrottle..maxthrottle] - for (x = 0; x < 3; x++) + /* + * Our voltage is expected to decrease over the course of the flight, so store our difference from + * the reference: + * + * Write 14 bits even if the number is negative (which would otherwise result in 32 bits) + */ + writeUnsignedVB((vbatReference - blackboxCurrent->vbatLatest) & 0x3FFF); + +#ifdef MAG + if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_MAG)) { + for (x = 0; x < XYZ_AXIS_COUNT; x++) + writeSignedVB(blackboxCurrent->magADC[x]); + } +#endif + +#ifdef BARO + if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_BARO)) + writeSignedVB(blackboxCurrent->BaroAlt); +#endif + + for (x = 0; x < XYZ_AXIS_COUNT; x++) writeSignedVB(blackboxCurrent->gyroData[x]); - for (x = 0; x < 3; x++) + for (x = 0; x < XYZ_AXIS_COUNT; x++) writeSignedVB(blackboxCurrent->accSmooth[x]); //Motors can be below minthrottle when disarmed, but that doesn't happen much @@ -623,7 +721,7 @@ static void writeIntraframe(void) static void writeInterframe(void) { int x; - int32_t deltas[4]; + int32_t deltas[5]; blackboxValues_t *blackboxCurrent = blackboxHistory[0]; blackboxValues_t *blackboxLast = blackboxHistory[1]; @@ -638,10 +736,10 @@ static void writeInterframe(void) */ writeSignedVB((int32_t) (blackboxHistory[0]->time - 2 * blackboxHistory[1]->time + blackboxHistory[2]->time)); - for (x = 0; x < 3; x++) + for (x = 0; x < XYZ_AXIS_COUNT; x++) writeSignedVB(blackboxCurrent->axisPID_P[x] - blackboxLast->axisPID_P[x]); - for (x = 0; x < 3; x++) + for (x = 0; x < XYZ_AXIS_COUNT; x++) deltas[x] = blackboxCurrent->axisPID_I[x] - blackboxLast->axisPID_I[x]; /* @@ -650,23 +748,46 @@ static void writeInterframe(void) */ writeTag2_3S32(deltas); - for (x = 0; x < 3; x++) - writeSignedVB(blackboxCurrent->axisPID_D[x] - blackboxLast->axisPID_D[x]); - - for (x = 0; x < 4; x++) - deltas[x] = blackboxCurrent->rcCommand[x] - blackboxLast->rcCommand[x]; + /* + * The PID D term is frequently set to zero for yaw, which makes the result from the calculation + * always zero. So don't bother recording D results when PID D terms are zero. + */ + for (x = 0; x < XYZ_AXIS_COUNT; x++) + if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_0 + x)) + writeSignedVB(blackboxCurrent->axisPID_D[x] - blackboxLast->axisPID_D[x]); /* * RC tends to stay the same or fairly small for many frames at a time, so use an encoding that * can pack multiple values per byte: */ + for (x = 0; x < 4; x++) + deltas[x] = blackboxCurrent->rcCommand[x] - blackboxLast->rcCommand[x]; + writeTag8_4S16(deltas); + //Check for sensors that are updated periodically (so deltas are normally zero) VBAT, MAG, BARO + int optionalFieldCount = 0; + + deltas[optionalFieldCount++] = (int32_t) blackboxCurrent->vbatLatest - blackboxLast->vbatLatest; + +#ifdef MAG + if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_MAG)) { + for (x = 0; x < XYZ_AXIS_COUNT; x++) + deltas[optionalFieldCount++] = blackboxCurrent->magADC[x] - blackboxLast->magADC[x]; + } +#endif + +#ifdef BARO + if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_BARO)) + deltas[optionalFieldCount++] = blackboxCurrent->BaroAlt - blackboxLast->BaroAlt; +#endif + writeTag8_8SVB(deltas, optionalFieldCount); + //Since gyros, accs and motors are noisy, base the prediction on the average of the history: - for (x = 0; x < 3; x++) + for (x = 0; x < XYZ_AXIS_COUNT; x++) writeSignedVB(blackboxHistory[0]->gyroData[x] - (blackboxHistory[1]->gyroData[x] + blackboxHistory[2]->gyroData[x]) / 2); - for (x = 0; x < 3; x++) + for (x = 0; x < XYZ_AXIS_COUNT; x++) writeSignedVB(blackboxHistory[0]->accSmooth[x] - (blackboxHistory[1]->accSmooth[x] + blackboxHistory[2]->accSmooth[x]) / 2); for (x = 0; x < motorCount; x++) @@ -750,6 +871,8 @@ void startBlackbox(void) blackboxHistory[1] = &blackboxHistoryRing[1]; blackboxHistory[2] = &blackboxHistoryRing[2]; + vbatReference = vbatLatest; + //No need to clear the content of blackboxHistoryRing since our first frame will be an intra which overwrites it blackboxSetState(BLACKBOX_STATE_SEND_HEADER); @@ -802,25 +925,36 @@ static void loadBlackboxState(void) blackboxCurrent->time = currentTime; - for (i = 0; i < 3; i++) + for (i = 0; i < XYZ_AXIS_COUNT; i++) blackboxCurrent->axisPID_P[i] = axisPID_P[i]; - for (i = 0; i < 3; i++) + for (i = 0; i < XYZ_AXIS_COUNT; i++) blackboxCurrent->axisPID_I[i] = axisPID_I[i]; - for (i = 0; i < 3; i++) + for (i = 0; i < XYZ_AXIS_COUNT; i++) blackboxCurrent->axisPID_D[i] = axisPID_D[i]; for (i = 0; i < 4; i++) blackboxCurrent->rcCommand[i] = rcCommand[i]; - for (i = 0; i < 3; i++) + for (i = 0; i < XYZ_AXIS_COUNT; i++) blackboxCurrent->gyroData[i] = gyroData[i]; - for (i = 0; i < 3; i++) + for (i = 0; i < XYZ_AXIS_COUNT; i++) blackboxCurrent->accSmooth[i] = accSmooth[i]; for (i = 0; i < motorCount; i++) blackboxCurrent->motor[i] = motor[i]; + blackboxCurrent->vbatLatest = vbatLatest; + +#ifdef MAG + for (i = 0; i < XYZ_AXIS_COUNT; i++) + blackboxCurrent->magADC[i] = magADC[i]; +#endif + +#ifdef BARO + blackboxCurrent->BaroAlt = BaroAlt; +#endif + //Tail servo for tricopters blackboxCurrent->servo[5] = servo[5]; } @@ -881,9 +1015,15 @@ static bool sendFieldDefinition(const char * const *headerNames, unsigned int he if (headerXmitIndex == 0) { charsWritten += blackboxPrint(def->name); } else { - //The other headers are integers (format as single digit for now): - blackboxWrite(def->arr[headerXmitIndex - 1] + '0'); - charsWritten++; + //The other headers are integers + if (def->arr[headerXmitIndex - 1] >= 10) { + blackboxWrite(def->arr[headerXmitIndex - 1] / 10 + '0'); + blackboxWrite(def->arr[headerXmitIndex - 1] % 10 + '0'); + charsWritten += 2; + } else { + blackboxWrite(def->arr[headerXmitIndex - 1] + '0'); + charsWritten++; + } } } } @@ -898,15 +1038,75 @@ static bool sendFieldDefinition(const char * const *headerNames, unsigned int he return headerXmitIndex < headerCount; } -void handleBlackbox(void) +static int blackboxWriteSysinfo(int xmitIndex) { - int i; - union floatConvert_t { float f; uint32_t u; } floatConvert; + switch (xmitIndex) { + case 0: + blackboxPrintf("H Firmware type:Cleanflight\n"); + break; + case 1: + // Pause to allow more time for previous to transmit (it exceeds our chunk size) + break; + case 2: + blackboxPrintf("H Firmware revision:%s\n", shortGitRevision); + break; + case 3: + // Pause to allow more time for previous to transmit + break; + case 4: + blackboxPrintf("H Firmware date:%s %s\n", buildDate, buildTime); + break; + case 5: + // Pause to allow more time for previous to transmit + break; + case 6: + blackboxPrintf("H rcRate:%d\n", masterConfig.controlRateProfiles[masterConfig.current_profile_index].rcRate8); + break; + case 7: + blackboxPrintf("H minthrottle:%d\n", masterConfig.escAndServoConfig.minthrottle); + break; + case 8: + blackboxPrintf("H maxthrottle:%d\n", masterConfig.escAndServoConfig.maxthrottle); + break; + case 9: + floatConvert.f = gyro.scale; + blackboxPrintf("H gyro.scale:0x%x\n", floatConvert.u); + break; + case 10: + blackboxPrintf("H acc_1G:%u\n", acc_1G); + break; + case 11: + blackboxPrintf("H vbatscale:%u\n", masterConfig.batteryConfig.vbatscale); + break; + case 12: + blackboxPrintf("H vbatcellvoltage:%u,%u,%u\n", masterConfig.batteryConfig.vbatmincellvoltage, + masterConfig.batteryConfig.vbatwarningcellvoltage, masterConfig.batteryConfig.vbatmaxcellvoltage); + break; + case 13: + //Pause + break; + case 14: + blackboxPrintf("H vbatref:%u\n", vbatReference); + break; + case 15: + // One more pause for good luck + break; + default: + blackboxSetState(BLACKBOX_STATE_RUNNING); + } + + return xmitIndex + 1; +} + +void handleBlackbox(void) +{ + int i; + switch (blackboxState) { case BLACKBOX_STATE_SEND_HEADER: //On entry of this state, headerXmitIndex is 0 and startTime is intialised @@ -949,49 +1149,7 @@ void handleBlackbox(void) break; case BLACKBOX_STATE_SEND_SYSINFO: //On entry of this state, headerXmitIndex is 0 - switch (headerXmitIndex) { - case 0: - blackboxPrintf("H Firmware type:Cleanflight\n"); - break; - case 1: - // Pause to allow more time for previous to transmit (it exceeds our chunk size) - break; - case 2: - blackboxPrintf("H Firmware revision:%s\n", shortGitRevision); - break; - case 3: - // Pause to allow more time for previous to transmit - break; - case 4: - blackboxPrintf("H Firmware date:%s %s\n", buildDate, buildTime); - break; - case 5: - // Pause to allow more time for previous to transmit - break; - case 6: - blackboxPrintf("H rcRate:%d\n", masterConfig.controlRateProfiles[masterConfig.current_profile_index].rcRate8); - break; - case 7: - blackboxPrintf("H minthrottle:%d\n", masterConfig.escAndServoConfig.minthrottle); - break; - case 8: - blackboxPrintf("H maxthrottle:%d\n", masterConfig.escAndServoConfig.maxthrottle); - break; - case 9: - floatConvert.f = gyro.scale; - blackboxPrintf("H gyro.scale:0x%x\n", floatConvert.u); - break; - case 10: - blackboxPrintf("H acc_1G:%u\n", acc_1G); - break; - case 11: - // One more pause for good luck - break; - default: - blackboxSetState(BLACKBOX_STATE_RUNNING); - } - - headerXmitIndex++; + headerXmitIndex = blackboxWriteSysinfo(headerXmitIndex); break; case BLACKBOX_STATE_RUNNING: // On entry to this state, blackboxIteration, blackboxPFrameIndex and blackboxIFrameIndex are reset to 0 diff --git a/src/main/blackbox/blackbox.h b/src/main/blackbox/blackbox.h index 8f88fec526..36b006c0ad 100644 --- a/src/main/blackbox/blackbox.h +++ b/src/main/blackbox/blackbox.h @@ -17,18 +17,28 @@ #pragma once +#include "common/axis.h" #include typedef struct blackboxValues_t { uint32_t time; - int32_t axisPID_P[3], axisPID_I[3], axisPID_D[3]; + int32_t axisPID_P[XYZ_AXIS_COUNT], axisPID_I[XYZ_AXIS_COUNT], axisPID_D[XYZ_AXIS_COUNT]; int16_t rcCommand[4]; - int16_t gyroData[3]; - int16_t accSmooth[3]; + int16_t gyroData[XYZ_AXIS_COUNT]; + int16_t accSmooth[XYZ_AXIS_COUNT]; int16_t motor[MAX_SUPPORTED_MOTORS]; int16_t servo[MAX_SUPPORTED_SERVOS]; + + uint16_t vbatLatest; + +#ifdef BARO + int32_t BaroAlt; +#endif +#ifdef MAG + int16_t magADC[XYZ_AXIS_COUNT]; +#endif } blackboxValues_t; void initBlackbox(void); diff --git a/src/main/blackbox/blackbox_fielddefs.h b/src/main/blackbox/blackbox_fielddefs.h index bdea5cbd32..2c888ad3cb 100644 --- a/src/main/blackbox/blackbox_fielddefs.h +++ b/src/main/blackbox/blackbox_fielddefs.h @@ -28,6 +28,20 @@ typedef enum FlightLogFieldCondition { FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_7, FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_8, FLIGHT_LOG_FIELD_CONDITION_TRICOPTER, + + FLIGHT_LOG_FIELD_CONDITION_MAG = 20, + FLIGHT_LOG_FIELD_CONDITION_BARO, + + FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_P_0 = 40, + FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_P_1, + FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_P_2, + FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_I_0, + FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_I_1, + FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_I_2, + FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_0, + FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_1, + FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_2, + FLIGHT_LOG_FIELD_CONDITION_NEVER = 255, } FlightLogFieldCondition; @@ -57,15 +71,21 @@ typedef enum FlightLogFieldPredictor { FLIGHT_LOG_FIELD_PREDICTOR_HOME_COORD = 7, //Predict 1500 - FLIGHT_LOG_FIELD_PREDICTOR_1500 = 8 + FLIGHT_LOG_FIELD_PREDICTOR_1500 = 8, + + //Predict vbatref, the reference ADC level stored in the header + FLIGHT_LOG_FIELD_PREDICTOR_VBATREF = 9 + } FlightLogFieldPredictor; typedef enum FlightLogFieldEncoding { - FLIGHT_LOG_FIELD_ENCODING_SIGNED_VB = 0, - FLIGHT_LOG_FIELD_ENCODING_UNSIGNED_VB = 1, + FLIGHT_LOG_FIELD_ENCODING_SIGNED_VB = 0, // Signed variable-byte + FLIGHT_LOG_FIELD_ENCODING_UNSIGNED_VB = 1, // Unsigned variable-byte + FLIGHT_LOG_FIELD_ENCODING_NEG_14BIT = 3, // Unsigned variable-byte but we negate the value before storing, value is 14 bits + FLIGHT_LOG_FIELD_ENCODING_TAG8_8SVB = 6, FLIGHT_LOG_FIELD_ENCODING_TAG2_3S32 = 7, FLIGHT_LOG_FIELD_ENCODING_TAG8_4S16 = 8, - FLIGHT_LOG_FIELD_ENCODING_NULL = 9 + FLIGHT_LOG_FIELD_ENCODING_NULL = 9 // Nothing is written to the file, take value to be zero } FlightLogFieldEncoding; typedef enum FlightLogFieldSign { From 421ac3d0f7c8713d9e248309f6b5ddd4b728e2e0 Mon Sep 17 00:00:00 2001 From: Nicholas Sherlock Date: Sat, 27 Dec 2014 19:35:28 +1300 Subject: [PATCH 19/24] Only log VBAT if that feature is turned on --- src/main/blackbox/blackbox.c | 25 ++++++++++++++++--------- src/main/blackbox/blackbox_fielddefs.h | 1 + 2 files changed, 17 insertions(+), 9 deletions(-) diff --git a/src/main/blackbox/blackbox.c b/src/main/blackbox/blackbox.c index 7895d4b601..84e3106588 100644 --- a/src/main/blackbox/blackbox.c +++ b/src/main/blackbox/blackbox.c @@ -175,7 +175,7 @@ static const blackboxMainFieldDefinition_t blackboxMainFields[] = { /* Throttle is always in the range [minthrottle..maxthrottle]: */ {"rcCommand[3]", UNSIGNED, .Ipredict = PREDICT(MINTHROTTLE), .Iencode = ENCODING(UNSIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(TAG8_4S16), CONDITION(ALWAYS)}, - {"vbatLatest", UNSIGNED, .Ipredict = PREDICT(VBATREF), .Iencode = ENCODING(NEG_14BIT), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(TAG8_8SVB), CONDITION(ALWAYS)}, + {"vbatLatest", UNSIGNED, .Ipredict = PREDICT(VBATREF), .Iencode = ENCODING(NEG_14BIT), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(TAG8_8SVB), FLIGHT_LOG_FIELD_CONDITION_VBAT}, #ifdef MAG {"magADC[0]", SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(TAG8_8SVB), FLIGHT_LOG_FIELD_CONDITION_MAG}, {"magADC[1]", SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(TAG8_8SVB), FLIGHT_LOG_FIELD_CONDITION_MAG}, @@ -612,6 +612,9 @@ static bool testBlackboxCondition(FlightLogFieldCondition condition) return false; #endif + case FLIGHT_LOG_FIELD_CONDITION_VBAT: + return feature(FEATURE_VBAT); + case FLIGHT_LOG_FIELD_CONDITION_NEVER: return false; default: @@ -672,13 +675,15 @@ static void writeIntraframe(void) writeUnsignedVB(blackboxCurrent->rcCommand[3] - masterConfig.escAndServoConfig.minthrottle); //Throttle lies in range [minthrottle..maxthrottle] - /* - * Our voltage is expected to decrease over the course of the flight, so store our difference from - * the reference: - * - * Write 14 bits even if the number is negative (which would otherwise result in 32 bits) - */ - writeUnsignedVB((vbatReference - blackboxCurrent->vbatLatest) & 0x3FFF); + if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_VBAT)) { + /* + * Our voltage is expected to decrease over the course of the flight, so store our difference from + * the reference: + * + * Write 14 bits even if the number is negative (which would otherwise result in 32 bits) + */ + writeUnsignedVB((vbatReference - blackboxCurrent->vbatLatest) & 0x3FFF); + } #ifdef MAG if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_MAG)) { @@ -768,7 +773,9 @@ static void writeInterframe(void) //Check for sensors that are updated periodically (so deltas are normally zero) VBAT, MAG, BARO int optionalFieldCount = 0; - deltas[optionalFieldCount++] = (int32_t) blackboxCurrent->vbatLatest - blackboxLast->vbatLatest; + if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_VBAT)) { + deltas[optionalFieldCount++] = (int32_t) blackboxCurrent->vbatLatest - blackboxLast->vbatLatest; + } #ifdef MAG if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_MAG)) { diff --git a/src/main/blackbox/blackbox_fielddefs.h b/src/main/blackbox/blackbox_fielddefs.h index 2c888ad3cb..8f9302e43a 100644 --- a/src/main/blackbox/blackbox_fielddefs.h +++ b/src/main/blackbox/blackbox_fielddefs.h @@ -31,6 +31,7 @@ typedef enum FlightLogFieldCondition { FLIGHT_LOG_FIELD_CONDITION_MAG = 20, FLIGHT_LOG_FIELD_CONDITION_BARO, + FLIGHT_LOG_FIELD_CONDITION_VBAT, FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_P_0 = 40, FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_P_1, From 6d3ad4a2de298dcb9257d7f1d5bfc602bedde646 Mon Sep 17 00:00:00 2001 From: Nicholas Sherlock Date: Sun, 28 Dec 2014 21:56:12 +1300 Subject: [PATCH 20/24] Update docs for new OpenLog firmware location --- docs/Blackbox.md | 29 ++++++++++++++++------------- 1 file changed, 16 insertions(+), 13 deletions(-) diff --git a/docs/Blackbox.md b/docs/Blackbox.md index 5933b1afaa..9d00bef9e0 100644 --- a/docs/Blackbox.md +++ b/docs/Blackbox.md @@ -19,9 +19,9 @@ gyroscope data, accelerometer data (after your configured low-pass filtering), a speed controller. This is all stored without any approximation or loss of precision, so even quite subtle problems should be detectable from the fight data log. -Currently, the blackbox attempts to log GPS data whenever new GPS data is available, but this has not been tested yet -as my GPS unit is not functional. The CSV decoder and video renderer do not yet show any of the GPS data (though this -will be added). If you have a working GPS, please send me your logs so I can get the decoding implemented. +Currently, the blackbox attempts to log GPS data whenever new GPS data is available, but this has not been tested yet. +The CSV decoder and video renderer do not yet show any of the GPS data (though this will be added). If you have a working +GPS, please send in your logs so I can get the decoding implemented. The data rate for my quadcopter using a looptime of 2400 is about 10.25kB/s. This allows about 18 days of flight logs to fit on a 16GB MicroSD card, which ought to be enough for anybody :). @@ -50,19 +50,20 @@ The blackbox software is designed to be used with an [OpenLog serial data logger little prep to get the OpenLog ready for use, so here are the details: ### Firmware -The OpenLog should be flashed with the [OpenLog Lite firmware][] using Arduino IDE in order to minimise dropped frames -(target the "Arduino Uno"). Note that the .hex file currently in the OpenLog repository is out of date with respect to -the .ino source file, use [this version][] instead. Or you can build your own hex file if you add the [required libraries][] -to your Arduino libraries directory. +The OpenLog should be flashed with the [OpenLog Lite firmware][] or the special [OpenLog Blackbox variant][] using the Arduino IDE +in order to minimise dropped frames (target the "Arduino Uno"). The Blackbox variant of the firmware ensures that the +OpenLog is running at the correct baud-rate and does away for the need for a `CONFIG.TXT` file to set up the OpenLog. + +If you decide to use the OpenLog Lite firmware instead, note that the .hex file for OpenLog Lite currently in the +OpenLog repository is out of date with respect to their .ino source file, so you'll need to build it yourself after +adding the [required libraries][] to your Arduino libraries directory. To flash the firmware, you'll need to use an FTDI programmer like the [FTDI Basic Breakout][] along with some way of switching the Tx and Rx pins over (since the OpenLog has them switched) like the [FTDI crossover][]. -The original OpenLog firmware may work with acceptable error rates if you use lower data-rates. - [OpenLog serial data logger]: https://www.sparkfun.com/products/9530 [OpenLog Lite firmware]: https://github.com/sparkfun/OpenLog/tree/master/firmware/OpenLog_v3_Light -[this version]: https://raw.githubusercontent.com/thenickdude/blackbox/blackbox/tools/blackbox/openlog/OpenLog_v3_Light.cpp.hex +[OpenLog Blackbox variant]: https://github.com/thenickdude/blackbox/tree/blackbox/tools/blackbox/OpenLog_v3_Blackbox [Required libraries]: https://code.google.com/p/beta-lib/downloads/detail?name=SerialLoggerBeta20120108.zip&can=4&q= [FTDI Basic Breakout]: https://www.sparkfun.com/products/9716 [FTDI crossover]: https://www.sparkfun.com/products/10660 @@ -90,6 +91,9 @@ the best chance of writing at high speed. You must format it with either FAT, or [SD Association's special formatting tool]: https://www.sdcard.org/downloads/formatter_4/ ### OpenLog configuration +This section applies only if you are using the OpenLog or OpenLog Lite original firmware on the OpenLog. If you flashed +it with the special OpenLog Blackbox firmware, you don't need to configure it further. + Power up the OpenLog with a microSD card inside, wait 10 seconds or so, then power it down and plug the microSD card into your computer. You should find a "CONFIG.TXT" file on the card. Edit it in a text editor to set the first number (baud) to 115200. Set esc# to 0, mode to 0, and echo to 0. Save the file and put the card back into your OpenLog, it @@ -97,7 +101,7 @@ should use those settings from now on. If your OpenLog didn't write a CONFIG.TXT file, you can [use this one instead][]. -[use this one instead]: https://raw.githubusercontent.com/thenickdude/blackbox/blackbox/tools/blackbox/openlog/CONFIG.TXT +[use this one instead]: https://raw.githubusercontent.com/thenickdude/blackbox/blackbox/tools/blackbox/OpenLog_v3_Blackbox/CONFIG.TXT ### Protection The OpenLog can be wrapped in black electrical tape in order to insulate it from conductive frames (like carbon fiber), @@ -110,8 +114,7 @@ In the [Cleanflight Configurator][], open up the CLI tab. Enable the Blackbox fe and pressing enter. You also need to assign the Blackbox to one of [your serial ports][] . A 115200 baud port is required (such as serial_port_1 on the Naze32, the two-pin Tx/Rx header in the center of the board). -Use `set serial_port_1_scenario=10` to switch the main serial port to Blackbox-only, or `set serial_port_1_scenario=11` -to switch it to MSP, CLI, Blackbox and GPS Passthrough. +For example, use `set serial_port_1_scenario=11` to switch the main serial port to MSP, CLI, Blackbox and GPS Passthrough. Enter `save`. Your configuration should be saved and the flight controller will reboot. You're ready to go! From 566bd561dc8ff178314a1b3fb0774aef569c8526 Mon Sep 17 00:00:00 2001 From: Nicholas Sherlock Date: Mon, 29 Dec 2014 01:41:13 +1300 Subject: [PATCH 21/24] Beep as logging begins to use as a synchronisation point for video --- docs/Blackbox.md | 4 +++ src/main/blackbox/blackbox.c | 35 +++++++++++++++++++++++++- src/main/blackbox/blackbox_fielddefs.h | 4 +++ 3 files changed, 42 insertions(+), 1 deletion(-) diff --git a/docs/Blackbox.md b/docs/Blackbox.md index 9d00bef9e0..71c11dafb6 100644 --- a/docs/Blackbox.md +++ b/docs/Blackbox.md @@ -143,6 +143,10 @@ power-cycled, it begins a fresh new log file. If you arm and disarm several time several flights), those logs will be combined together into one file. The command line tools will ask you to pick which one of these flights you want to display/decode. +If your craft has a buzzer attached, a short beep will be played when you arm. You can later use this beep to +synchronize your recorded flight video with the rendered flight data log (the beep is shown as a blue line in the flight +data log, which you can sync against the beep in your recorded audio track). + The OpenLog requires a couple of seconds of delay after powerup before it's ready to record, so don't arm your craft immediately after connecting the battery (you'll probably be waiting for the flight controller to become ready during that time anyway!) diff --git a/src/main/blackbox/blackbox.c b/src/main/blackbox/blackbox.c index 84e3106588..2dcfbcf499 100644 --- a/src/main/blackbox/blackbox.c +++ b/src/main/blackbox/blackbox.c @@ -35,6 +35,7 @@ #include "drivers/pwm_rx.h" #include "drivers/accgyro.h" #include "drivers/light_led.h" +#include "drivers/sound_beeper.h" #include "common/printf.h" @@ -228,6 +229,7 @@ typedef enum BlackboxState { BLACKBOX_STATE_SEND_GPS_H_HEADERS, BLACKBOX_STATE_SEND_GPS_G_HEADERS, BLACKBOX_STATE_SEND_SYSINFO, + BLACKBOX_STATE_PRERUN, BLACKBOX_STATE_RUNNING } BlackboxState; @@ -1045,6 +1047,10 @@ static bool sendFieldDefinition(const char * const *headerNames, unsigned int he return headerXmitIndex < headerCount; } +/** + * Transmit a portion of the system information headers. Begin with a xmitIndex of 0. Returns the next xmitIndex to + * call with, or -1 if transmission is complete. + */ static int blackboxWriteSysinfo(int xmitIndex) { union floatConvert_t { @@ -1104,12 +1110,32 @@ static int blackboxWriteSysinfo(int xmitIndex) // One more pause for good luck break; default: - blackboxSetState(BLACKBOX_STATE_RUNNING); + return -1; } return xmitIndex + 1; } +// Beep the buzzer and write the current time to the log as a synchronization point +static void blackboxPlaySyncBeep() +{ + uint32_t now = micros(); + + /* + * The regular beep routines aren't going to work for us, because they queue up the beep to be executed later. + * Our beep is timing sensitive, so start beeping now without setting the beeperIsOn flag. + */ + BEEP_ON; + + // Have the regular beeper code turn off the beep for us eventually, since that's not timing-sensitive + queueConfirmationBeep(1); + + blackboxWrite('E'); + blackboxWrite(FLIGHT_LOG_EVENT_SYNC_BEEP); + + writeUnsignedVB(now); +} + void handleBlackbox(void) { int i; @@ -1157,6 +1183,13 @@ void handleBlackbox(void) case BLACKBOX_STATE_SEND_SYSINFO: //On entry of this state, headerXmitIndex is 0 headerXmitIndex = blackboxWriteSysinfo(headerXmitIndex); + + blackboxSetState(BLACKBOX_STATE_PRERUN); + break; + case BLACKBOX_STATE_PRERUN: + blackboxPlaySyncBeep(); + + blackboxSetState(BLACKBOX_STATE_RUNNING); break; case BLACKBOX_STATE_RUNNING: // On entry to this state, blackboxIteration, blackboxPFrameIndex and blackboxIFrameIndex are reset to 0 diff --git a/src/main/blackbox/blackbox_fielddefs.h b/src/main/blackbox/blackbox_fielddefs.h index 8f9302e43a..68a75439f7 100644 --- a/src/main/blackbox/blackbox_fielddefs.h +++ b/src/main/blackbox/blackbox_fielddefs.h @@ -94,3 +94,7 @@ typedef enum FlightLogFieldSign { FLIGHT_LOG_FIELD_SIGNED = 1 } FlightLogFieldSign; +typedef enum FlightLogEvent { + FLIGHT_LOG_EVENT_SYNC_BEEP = 0, + FLIGHT_LOG_EVENT_LOG_END = 255 +} FlightLogEvent; From 8435989dc1e9d26d85d1eef2a240639119fbf22d Mon Sep 17 00:00:00 2001 From: Nicholas Sherlock Date: Tue, 30 Dec 2014 16:35:54 +1300 Subject: [PATCH 22/24] Logging of P interval was missing for some reason --- src/main/blackbox/blackbox.c | 21 ++++++++++++--------- 1 file changed, 12 insertions(+), 9 deletions(-) diff --git a/src/main/blackbox/blackbox.c b/src/main/blackbox/blackbox.c index 2dcfbcf499..2798275e8f 100644 --- a/src/main/blackbox/blackbox.c +++ b/src/main/blackbox/blackbox.c @@ -1078,35 +1078,38 @@ static int blackboxWriteSysinfo(int xmitIndex) // Pause to allow more time for previous to transmit break; case 6: + blackboxPrintf("H P interval:%d/%d\n", masterConfig.blackbox_rate_num, masterConfig.blackbox_rate_denom); + break; + case 7: blackboxPrintf("H rcRate:%d\n", masterConfig.controlRateProfiles[masterConfig.current_profile_index].rcRate8); break; - case 7: + case 8: blackboxPrintf("H minthrottle:%d\n", masterConfig.escAndServoConfig.minthrottle); break; - case 8: + case 9: blackboxPrintf("H maxthrottle:%d\n", masterConfig.escAndServoConfig.maxthrottle); break; - case 9: + case 10: floatConvert.f = gyro.scale; blackboxPrintf("H gyro.scale:0x%x\n", floatConvert.u); break; - case 10: + case 11: blackboxPrintf("H acc_1G:%u\n", acc_1G); break; - case 11: + case 12: blackboxPrintf("H vbatscale:%u\n", masterConfig.batteryConfig.vbatscale); break; - case 12: + case 13: blackboxPrintf("H vbatcellvoltage:%u,%u,%u\n", masterConfig.batteryConfig.vbatmincellvoltage, masterConfig.batteryConfig.vbatwarningcellvoltage, masterConfig.batteryConfig.vbatmaxcellvoltage); break; - case 13: + case 14: //Pause break; - case 14: + case 15: blackboxPrintf("H vbatref:%u\n", vbatReference); break; - case 15: + case 16: // One more pause for good luck break; default: From 3ef83389e9053b93d2a57d867de74e140185c2b1 Mon Sep 17 00:00:00 2001 From: Nicholas Sherlock Date: Tue, 30 Dec 2014 20:12:30 +1300 Subject: [PATCH 23/24] Fix bug intoduced in 0.1.6 which truncated the header in recorded logs --- src/main/blackbox/blackbox.c | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/src/main/blackbox/blackbox.c b/src/main/blackbox/blackbox.c index 2798275e8f..4f0d422609 100644 --- a/src/main/blackbox/blackbox.c +++ b/src/main/blackbox/blackbox.c @@ -1079,7 +1079,7 @@ static int blackboxWriteSysinfo(int xmitIndex) break; case 6: blackboxPrintf("H P interval:%d/%d\n", masterConfig.blackbox_rate_num, masterConfig.blackbox_rate_denom); - break; + break; case 7: blackboxPrintf("H rcRate:%d\n", masterConfig.controlRateProfiles[masterConfig.current_profile_index].rcRate8); break; @@ -1187,7 +1187,8 @@ void handleBlackbox(void) //On entry of this state, headerXmitIndex is 0 headerXmitIndex = blackboxWriteSysinfo(headerXmitIndex); - blackboxSetState(BLACKBOX_STATE_PRERUN); + if (headerXmitIndex == -1) + blackboxSetState(BLACKBOX_STATE_PRERUN); break; case BLACKBOX_STATE_PRERUN: blackboxPlaySyncBeep(); From a0f3ee6315d25890b13d27a58f8b8c1d4264927f Mon Sep 17 00:00:00 2001 From: Nicholas Sherlock Date: Mon, 5 Jan 2015 10:28:15 +1300 Subject: [PATCH 24/24] Fix signed comparison warning --- src/main/blackbox/blackbox.c | 8 +++++--- 1 file changed, 5 insertions(+), 3 deletions(-) diff --git a/src/main/blackbox/blackbox.c b/src/main/blackbox/blackbox.c index 4f0d422609..cbce7b57da 100644 --- a/src/main/blackbox/blackbox.c +++ b/src/main/blackbox/blackbox.c @@ -1141,7 +1141,7 @@ static void blackboxPlaySyncBeep() void handleBlackbox(void) { - int i; + int i, result; switch (blackboxState) { case BLACKBOX_STATE_SEND_HEADER: @@ -1185,10 +1185,12 @@ void handleBlackbox(void) break; case BLACKBOX_STATE_SEND_SYSINFO: //On entry of this state, headerXmitIndex is 0 - headerXmitIndex = blackboxWriteSysinfo(headerXmitIndex); + result = blackboxWriteSysinfo(headerXmitIndex); - if (headerXmitIndex == -1) + if (result == -1) blackboxSetState(BLACKBOX_STATE_PRERUN); + else + headerXmitIndex = result; break; case BLACKBOX_STATE_PRERUN: blackboxPlaySyncBeep();