From 34b4d628568931b5884ecc7763c6d72bd4822c22 Mon Sep 17 00:00:00 2001 From: caroline Date: Tue, 3 May 2022 16:38:52 +0200 Subject: [PATCH] line extracion from clusters --- CMakeLists.txt | 5 +- cfg/config.cfg | 4 + pcl_methods.odt | Bin 22686 -> 24007 bytes src/initial_processing.cpp | 246 ++++++++++++++++++++++++++++++++++++- src/range_image.cpp | 165 +++++++++++++++++++++++++ 5 files changed, 413 insertions(+), 7 deletions(-) create mode 100644 src/range_image.cpp diff --git a/CMakeLists.txt b/CMakeLists.txt index 1574ff8..54a8596 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -11,10 +11,13 @@ find_package(catkin REQUIRED COMPONENTS roscpp rospy std_msgs + sensor_msgs genmsg pcl_conversions pcl_ros dynamic_reconfigure + cv_bridge + image_transport ) #add dynamic reconfigure api @@ -213,7 +216,7 @@ target_link_libraries(talker ${catkin_LIBRARIES}) add_dependencies(talker pcl_tutorial_generate_messages_cpp) add_executable(initial_processing src/initial_processing.cpp) -target_link_libraries(initial_processing ${catkin_LIBRARIES}) +target_link_libraries(initial_processing ${catkin_LIBRARIES}${OpenCV_LIBRARIES}) add_dependencies(initial_processing pcl_tutorial_generate_messages_cpp) # make sure configure headers are built before any node using them diff --git a/cfg/config.cfg b/cfg/config.cfg index 6cc9a0f..372d14b 100755 --- a/cfg/config.cfg +++ b/cfg/config.cfg @@ -37,4 +37,8 @@ gen.add("green_thresh", int_t, 0, "Green threshold for color filtering", 150, gen.add("cluster_on", bool_t, 0, "determines if Euclidean Clustering is applied", False) +gen.add("create_feature_map", bool_t, 0, "determines if feature map will be created", False) + +gen.add("line_fitting_on", bool_t, 0, "determines line will be searched for clusters", False) + exit(gen.generate(PACKAGE, "pcl_tutorial", "config")) diff --git a/pcl_methods.odt b/pcl_methods.odt index 951ea2645042be5ccfc646fda1adb7c0797035e3..8b5f863c9fc88976687631a9c67be7fc54c39c7b 100644 GIT binary patch delta 20957 zcmZs?Q*dWt)2|)d<|LWe#>D2twrxBA*tTukwr$(Cv*&sC`|WxUzCP)$>twB3_r0pS zx__Nr2RzaN3@;}I3Wf#*1O)_?=$9V{FA4e|7fTf9iSmCV=Kl|z{1+tb0uv?R1Ec+i zCKUgRm4Pw-8~=yL{6EhAKaBOi9t(u?KfXa3gc}&}FHi#dU-s|GK-R`i`gCsAR#6Gk zG3yLS!8c#%6kC@2h<^!HMkRTac&wHrixg}}R~!1QYl%nJW&yeh^sCwkT|>+>TsM=e zV+1oL7Iz@kbIVr5@w;Zgq8dfgZBahgydxQ>b+54-C#JN1)YKcOSOht}fC!P;^xzbk zG7DV%u9`oB+AE}6Om)@5Xa}TJaVR>2^f>J?bEU1JE%Fy|E%|fs?E7HwFYy~VlSX|t zG&dVK(?Zwiq%62J6?xfaTveL0~O~k3plPMV_Q&1Djsk?Yv z@`sZ5xMx(uPGW4Cv$-uw&hHD}16EuA`Pk zpVZW5;cXS{cffRg{BoMA+-Cs+wqK7F(rWcGrvnLWSMEQS3D=6vfL7q=riLB?kHOo4 z5*1ad;)1cJZ8?BXQ4}H%o6dv?!OOm!0FAZfCmT%49ORQk;*I~aoxKNcm903_NG3&A zX^f(OJ>!CUN%3y{-%f4_zsKEbZmE$>=#~}yrjTL`CXOy4iSge`ho?)P0x#cF`vh`Q zkWg1abMo`RKtOAth(JL9_sT&*LH*~-C8U8905o0KIgosIbmIm*VG7$=GD&!X6N72N z5Mqz5b^>|ytc{{#NFZNdxZ;VVp=BsVGg5rxOj%lN>E@SCM1DtS3z$dWw=4X}Rp9x- zG44CKXuD&z#PBKe?tD52El?unA?v4-5>C}Y7@CFg=C2gl1X7e_>Wn5@5iV%4lSuKi z1OBe|q8+|B4PPw5kI(?>k+gWVRSgX1MVmNtX80!geE3-_mg(u~E3Q|b6okFh&CE}@ z93x~cnied+zl@tcnlFY`6xySzczYD4B#um~LYiLLRjJkQ0VA9I2F{L+9#(1Es%8^W zrU(z1Rm#m>FBe=p=H9u!QH)iU0LF<#fDbZ-X;MZ*#QU1^6K&EKrK`S0b9{AD!N({u zsx7IPbLK1EP(`t;E7#sRD z>m!5z?{h`6$LYfu)Z|}|*nJ@RE#vFghS&J_u1%ZLM_Fcu73&l>N!D9$MgT<&z`M@Z z!H_$24_$cjyZV=tZGE~d7#^<%o;tza6%-=uL16yvf-&W~Gz&z+m4KUzy?Y(O9YN?= zs<^d>R^)ghND-Z;fr$o1y|4|$bGQez(s&s=at;E>f!&EFiRGbO?xz;|TO1W&59`zy|LxQ`Ce;WKz*tgGzaTfkpNA@IJO z!+T);Vr+^-hwBM3_S1gMLR?j1(ynKpP}-G`u)W zsJw7(*hmP{fmD3@(N*D;fUqk!2#;Pk{`RjHtqr|X*^=cth|)IY^r}k)`gw{BERnYg z+GLL`B#@V>2wc7OA|{{2`q)A2A){vUtz${tkJsCDxOpX-syLJIBKsK1d%GkC=HU;T zG~fGz1;!>pYT@aNbTS?{08C>5^v7I;r3@hsE$i1VbtrxW23eW!5QP#q>y5+ujzzS5 z?w^G3H7DrUZ%8(8%4EdEAMdqcG7dWC$wy3VEceS9@qksKq9q(mnQ2bchZHLYsB!hLMQ8uDujvRk4lG%`T?vohh;7fJPYq(+(0TQj>@= zq`^JVp#1{+-y`5kh>`nwh(q#u<{eqt4?uj6Pe@>UkXf+^#LC0eQb0344QdkG{F3?7x@Uj>$<8iZa>(i_fA-s$RFb7A~zY7HY0!hdo; z&?3bQc_U&dN93$cU@uULNJaAM1>Mfa)~)P+T%H>`bl4WHeqtCD^`XNPi$J%+)2^`j ztGI&2M5NH2;cZloK%2PUaVgHi`vu6#MD3yqV}e7GtwsVX0P*&G64T9uxmGRj;@T4D zkgAmFJv5_a@nLkzFgFa8bJ|Ctd%pYZ*aiSH;s&(bn>&nR8dP2gr{xUkSnNr^B}E!V zl&$1V3Yr<&3@xUnP15h?Qf>xfArL&D4WTJ^qP3#x1laeAt2ARRL}Y=+;X;MiV+clG z+Lf6|9+%600COmShWV;t9|kN(g6V2huRZ(SZM4hswz-PiSisZQ=QbfLX(FY*T4cWl zg#7PjH66(6`N)PFO5zWb6a05gu%1utj{hJvnNLL_ln~t>$z6A zJuiL?;cn&3J&{3P4I&YD6{+)^2J}5XQ7rwTx4eV^P!`rO$E%{Wuxjt8=K~VfNn=MY z;=UoJbI0VhguiyQz5|@WBmd&WyObtD<)Ayf*k*-)#*AKh-2sP&6HWnBYs~LXoAfN^~^kDuyvi6atno(#{_ePKDOZQpQwgDbxWgT0IHwlL@w{Ta1pm zQm5Q2yOz2@_o;luPuwFy&8~VP#5Br6^6?csKlNFdOggXaumYiPO3t|?)C+yE1>!BI z-l%~?W_P{zNPc(kQsH`212MejXri4jw&a5Z6kwcKqaQT^o!XlpaQBp~X*G9&?ayQ& zVK81*ez~e*N=93DpS1XX)RW46gg*abwojO^k{+v;@TBLLT+D7>CIMRj&Gk(Q&b|2D zl)9n>vjIrw79R zpOpANRhW{NS?H+?6A+LKQ$jDCG&HNQlA0*1gqTbMDm*#B%G%l7*2luZ!^y(X&f3x0 z-rB>?%H7RFRkhm8Imp4q*U7`*%gf)wqS?W^(Zi$L+Iz&yyVu(n;Nlk!2nhBHi0}+e z^6~5U_izmG@s99zi1hY~^EM0g_7Cvx3h?O-_VY>%_6QCN@ePg*ibx2IN{fg}2#-pQ zh)atN^p69C2gOH4rbh*&Mn)z?$0f!^Wyc0(Bt#~}CnO}MC#GekC&i~Fr)8xjWoBdq z`*($=mc<2ir)K77=jCMPmt>aI7oqQbJuvZ8|0;?jSvqN1XpxUR4QP+wTpT2WPBTHRJvS5;ZxQeRn8S5w|~SKV4e3 zSky33(b!+rHdxUlirfp55l7;3AUYAqP=sOoR3ALwZ4 z>uMkGXqf0}UFfNt>uTuh=^gA?o9$j3>Te$G>l_*Fnd)mAALv-oa-L= zXG7ydW5a`ElVd{zqa&k}V}lbD6C;4J<;l6p;kl*3*^SA$#mR;BskM#y$&tm;jpg~t zg@uLrrM2bNrKPpawWYb$mDSC)#f^=P;jzQ<#gnn++l9&fg}I}}rL)D2{e|_*^@XGL z<+Jtez0J+b#m&35z3rLZi|M_G&AsFGlgIt3&EwUv{jHUQ_2a|c&C9)oivz&M+3C*R z?$q7M#@F5U$;rv-#lzL@_3_=y!Trba>-W{&&ZJ(!o%T!iVgIF!DC^i|EBe;2UQ^v*63#50|{n865n)uMi3v1*R3-ei=Wv; z!khHo&xpABe);)nd)aT9ExCKGVqLT>U6HHF(-GE>IeJF{<%c=Ekbu&T1l)NcR;b_ z*ZGe1N5Rfd#m@pI6JlJ6D6q!Dtoy14Nv%KY|1k zBck``IcqcQ-knlC`7$nI?*$L`=)sDrBvL!lpZY12R;oy=oJ6d;^6gxX0Dq)}c&Q7q z^{UD%D)_b)w~Rtyt>Vf|ig@*MK9+t*7G^_&q(qw-3LvL9Yh$PSjNos<|7R^L6lV#j zDlY^`Mg@^&el0n6qim&JGdy5}wJZ-%THn%~OSZdaV@urJ&pj9HNERA=r>@N!ihWV2 zK)qoAq#E^J@}VPUW@ciyz^BsQg6$g;#j1d~v(ecTB0^K!!e%)(-=YgCiZ5Ash2-}R zF_Y-m30To7sj}23;J&7+f56=oteN2FrPy3}*i9I5vTCX}oz+cx!V-Tx_WPwGo3Byu z0UVES;pbk^aq_YF(lmI7H|D?mgqB&u1eJlPO`wyqSw>A9ET)nK^nI@;EAQ?)_LlZi z7TsgtWiQcRqwomhBIM+97w_RPF&4`J{QKHE9Z=hlwwO>f&S@amaC&XcYBP@gCwv82l{+A?QPpp zPgo&9bmmY#zLC6%z)ax?6-pg`_16vyEMf!;qAs+ouEhxz_(NW`%uJ#8Cz38hnz1o2m?r8mpZl!jub zC|?4(7nleXYd|~y6Jglq@cCr*uVr!jk-5t0$46XS3+VnbB9=~sx7uCD7q++t)^2`9 zL!3G^`ABmRkCLu!IXFa6!7uKC-<6$&zOLR<)v3u31;gX${v z75`1wp9kER4gz{?wdN|2-j>Mh<6|>heEk(xF{%i<0(^YqHMyB#n)^7-^m^NKIIvl) z#xr>Jn5}^RbxuP~aNJo?;JVA12K^{Y$A~T7R~MTvIpT^Zv#kgrWw4B{?M@va0sv`B zzqcF=Ag#`I%kv;U@=!}Mn;;HWT%J%5mN(Ss@366Y9P*?wx)uE)OgMLBz#VcX`BcxQ zrZ6v;jI^oU87yo#H(&O|D6~kIymFi0FVce25G@X7aF|v>a7t`<-o(){1&LqMg@+D_ z^}WGDLzets%v{Fhy0Uf8o(e_f(f}n=3OTf@{Ptry64c8)D`xQKsxTAh;6jZ3T@*AWCrTzuF-dWm`!2kqULs?xKicCIRbj23RC& z=G$BCRm$w>cXk7QcEV7Qt`Kk8p&wBw5|g6YG0}uAd>A*-4?}ppJF*^?DLLT4(Sw0d z6lVISy$9R_yo?l3r<*au!P?VxQ1{RQz{xS4SYduAe>^=3oe3QLSSE^oulT-$vJPvJ zxe~)~&(}WMi(MQlkt9!M~1nfnV z4Pj;FUUhY1(ms<}lvr)C%<1MWyn*(z4FVTa~m&ZA| zItrvM3CqavmEESd{o&qC{O5(KBTJt;hWm6FPCYlZ4b4i^seXCmTdgXqPyHIljfx7L zRgjKCFZ3%#e}o9YFoVjip~G>JzkUj-27jUnIfGs+<)X^P+Kni62fnpJ94Qc(2<@}WJlE< zknY|Q6F>!|a*+f={z+kG>|c4l*XM(A2%~_lk=DW7p;b+C9qD(C(0MbI*pD#)d_gR> zg^0G^@>a&PKtqR$DrR1Of55>77vLQ#xLbGC?uy;@`lHxG=mL7!(IX&=@Lm=R)ReKa zU>xi$IouVUcvtjn9lfDWWAmcS1P0}`uOgH|Bz}R8{JbBDN%ev~D!H5>$H+Z>5{(Nh zC2+-2zxGbHeFcWiasl5yZKEx=0l^jP92QWJ!Qqcc{vv+}BRtggOM6WwM@Brc(-cZY z6g7hSgB2l|cmlwvKXGD+j})TVTs-QrYMTryMqZq(f??4*wkhwWtK1!3q3DBFu;!1UGPW>{p$TY;`)^nv@` z#fUQA^z86GX@^3+43xWP#DR@1b50C`a}+Pm*9hu>JqRcY-iy#u$O+=cis~0`f4(A? zv9{n?_TT5g$_$78LpRqmI$j$sC z-~$@QHwzF-0iqQP)KM=a&$X=VF_(*vv=K(uVsCeGYJXVKt)Xcm`2<4=%Md#*AwU_E zmhme>cmX7tv?fGxik1N$^V3cM`IQ9GP!Vb052;v>4vH9NaRZqks8%Tju7of%;-FcD zc~B3c#rbSoNo@*e;?Qo)%*tq6cM_Iiiu|?|DGDIMGDb#p5)$sa-`{lSaVEK!M%S}g zV^DTUF+oTflGv!EFiRcuIZEm=F@&B^MfH<}4nhr!shkpj{~j`S*l&CM8j}CZc);7n z7rljY@$ciShZk!>FPey#k=*T5tD;%KHKjI>gq8T!JTmmz&v`CC^sk-f6K$FCnDgMV zztMp8J`XByni19f;1VZALOGBb*w19q?S%tJf_6rxLvw%d3|>sI3n5Y<{)D($mK7FJ z3JnSr^GIdfmaoR4f{JpB!y-en@oiW*`*SV5~(6m^C^P*|5wia@A{55 zjI-LF6$T>LYkWN&YaIrmshHQel(>OE_cM%D2asPX6(?u}(6@pUDMS$B1fTQg!}58h|+C`KGA(&~?Pm@6{l zPDqxcNeG4w`$duXTaw#zOD=`CCR^KPchUCN_e4UNO+JyU_D}nr$UIbR4TM}M1JcvG zwGbaj;kJ$`Al3mFbR-50$h@3fO%#kt)DO!$*wuASiRcMXX{HOa-#hFAeInv-Zg#r-{XgBA%?$)+LR zh$Jb&U-+ip!`fY`T4-gE3!**1oc9gqBZ|TkAWVP~=h>>coxSd2 zba#qtAz(xZ1x|RIXl`mP-THo{Qwt14EPzcXN4zo|OWL;;@!J7T(&0Cip~WP*zCti8 zlauQ2Cmz;x0euRwdBgh5i8}`+nOyly#PL5wSxRU+VTGWlle~XWWg!~wT7Qc;a1Yj- z0EDN}rTj@sM&!Ji=trTF-Tu%-^^1#UOOwU7o%UnpykXsId_!?}6dgLJ<3>E4dzuLC ztwU+PHs&JOc2*#quD^<+cp*-DSqzIpG4d6_%Kw3X+b;os66vGXjvrDh88?;x-p5Z= zu4Lg;IsP)P=lq$jWNMwKoO2BXMc@*|Ex z@i~k}!XxAmlD8#%8bIuL-yHU>0Dt=ngyveODU^uH`iG}5=CmxyK!%;L4b#7g`GL>N z=~gplS$%T5BU8+^wPcLe(SjXR5pVAYR zM)_PCR(RkwWBnjNrYFWO83Zq>_vs7?TuVN-#wiXhvk7#Q2M%}<4ywdYXiYzr=m!|c8z7a1?3ech zzoACEx;hA=?HIal=5Y(HB-^f?Lo8|n04{HQ`N{8(PLJ$x(glwaRjObXt~-|Bfs$L5 z=`12HmjI*SQSPV_Hp6X3slt5~#RLj2*5!8LahocTTKGjoQZ3He;O4xfm4_5lxfVsS za!5oBre03gYiE)@JLL0B0VrR>Js4cXHZ;r~^H#EqR+%My*VVwu7na z)Z*yr>io^rO>bGL1;agNdjb{i^+0~o zy)9fnjImfwYH3N$0@$Fi>NkeY7xb*M&I0LL{gf5%J+%ytdFuT84#qw{4Xl*5F$0P3$*ExX+H8{^rH^GA^)iN@u0m zw({t@W2sUb6)^H~?ar9I+h-;Tx}JwTA)<0 ziBqcjR|Ht}-pif{7+#QWkx&fCZ%1X)3FEG<%qBgmksl@wuWAO3*^@@m{Z{e-30Ivr>v5j(jIxx7 z6TS`)U+gJLK+n1=4VJ#Nb5!g<;;37d8~j!EG$KXz8r!_0!-S#<6-e!1$)jXw)-3?) zhtQbii}_X7)Q4N)&YrE5)r#KyU_j z%t@`)#Qp307rRKC24~864SLZ#ldcNy18{b`<$}^%!$;5~*1LHWAq`8XUu)1`jfivj zZxmJjz2RNe9*mrD0Xia@H}q-_r`+BV4Ly*1s(>OC@nI+UI5P&+Ndx@AnLu1*@o9?- zVgThPJqmi%oe`2~{%M+k!fG$uEzu&_oII`W81HDzE=-8A%rWtdbwaOle)Q74#;iCx zBu{%^)pc3{{WkGx-I;J(S@NuA%rYoYIn@3czOI8Jvn;y|J~YdUT-Q!DVWWq218Oc` z7zn5x;`zB#Ui<|$kwXu%cR>tOtdh+DBH*STbhnxe*slWj{a)}&SI*<3t*U)LPO{pB z#~!c)!dM6@{nT}sM!*9Rt{Q@~-vK|g_|}R1mSoxh1KXBJ5CtQ5>=V^5NEH_vMRK1B zPR z+MuJLi|M%&AIUYXT&+V*{n~(r7_1KUnyufRZt7{USd*ePU*}!PFsds0TVR`2G2a)! zvinTTlLll>BCfymrymhQYw4LK6mYteDhnSCJiVgH?~ajg=fnWx*226R;f850yJ0Ad zBhKgj8>cKhAlGq{dEHe7(u;=|D4egOq=eL>opbSsZr5fbmpM?t_~P!piVRaFPIHH& z@Fzg@#QxS9PP0Kg|{e(!#K zGr(zYCQ8YFqkEf0*fObf4G8i3uoMoEVt0PzFeBQuxYRu=yHenjSByic z5Cm474t-u-y_-V7-dnPQ2LLHAD(~>Ncp1EZF@zF0-+#Xu1p8`OOOz;Y^r<^|nVK?x ztMPQvnK*M;6rm+ej5gzy_$0(G?V0X644i|I@V>IWD59R%_y^627cOwh4~k;Dy>v^F zF4xjgg{xJ9=NtBZk`3?9M}%FrK#P_9$FF2;G7bc%Jo5x4WKV5c!VL^#X_Ff zU*0X}lR!s>s36c@IHU8dj2*$f)9}R)9%ygw2SpO2(AH#%)fL z$*p!NAe!e@(ORVfr*{Vu!fMFa&WF07yIZe_YwFcs|9SnpGNL)P>d3g@TQNJFC6|jw-#Z2|c4S6*;_-YH5$;hg8-s59`7EIJhuN z$+O?T(FUYT0H8vYr`Ao!Xk3-NXW~4; z0HW-P{!eH01-TFznFzIY9y#qo@X{ zb+b8r&%iv=;65I-m#pvUyGz#G?8kl4ULgGKfg?nFw-5YR;zhL@A)c_w@wE#%;;zU6 z`DnEdCW2M$T}WklDj&I^75Jxdt?9U2P0S?J zfq;*=zBVK*nZo((GBtRMswI(OH~nr*{EcN4)bsuCPDQ><15~YNEmBO_D9%5PwE)I^ z)_irqIyN*+l_G`PAxFmO;MRwCy;Fc(&157O$e8U$%d14Wb*Is1HodSxa)K{Y?((nQ zYOr$?-VvRzYZLzSvMgr3(NR^{k%y`-u%*@G40Q*-A7RBh+Sek1D>h7uV~I_o^1zy| zzbM4x@W!E9ks>)M?i@6*W^A!Dk$`@25Wz{u(A^0`q~lMDk^Vt7xc8J-ClXXGxk8l0 zV==-+*grk{5=5@_bclO`FhlVQa(hIGZMe(J6=<~i{o!40TB+Tew6{LLd}%yR+=YR& zdW0=lAKcBGMlDrKZ&K(Iv7ID2CS;YaxK}L`-jZ!t1bJf3;@(xjlroY z?^Ub+4stYjVB1IOxlcSR+Aqg##9X6rDCN|CqR^r#1Pj_gGx^V!zCP9%b+?lmXVGv@ zqLoU;YBcNySy#!+ywgkXwW@W(>LQnwi>xoSW}*>v#4cx9)Os>q*1Jrza1=FaG#xzExcVB8qv zaY^b8nB*Bb-Wr>ta)=4kQ-iXkO?S28M@h`M6#8+8A|P8OTb4x99i>Pw3?MnLfB(5& z*+{*$L_tIq94K8aDa7B)>HReP+}20P7lMENtVTQvJjQfxA|o$OF#bSLn~pIc1Nu~s z*^uu+4lxIP@|{G7CcrmnO9ODH3$a{^X)nSWWQ?LlRNk&h29(^Ldt(HtO$*;_yB|_| z@b!Z2$J_qgN47f6nd_35_Q?4o>(H%>U_+=yhQID3AnE6~@$YZyZuLDI13rs)dg~nc zog;{*%@ufAxpmvW`0e(@?fKCQ)EkA=N7`?6(=1BKQa9`6vH;4;>)XH|sehlLvby#i zNw3UWvZ^HXXMQ6Bb2i9fcQ`NDy>)!t>5k`s2d0GnT}jn3YN~=|26L&&h5Cy>>nuBX z#oK%#gpc&gY7oK0x1p`1IXe_v8jmPT8d`c&CTm1S0EV~9(>iwNmtB(`8kZHtvTB=9 zA?_s(pVV_;79bUuAF+|Rs61|+kzo@J{2DX|>YTkI3&M{uEDNYLSpAy+g3akN#pOOv z2n-xbIJcmOJCFiM+!?YdOV+sOF6{&ZIE?kd(EDc{AI*Z@2Rrh6H2QnQ8wegJhe+q= z;!ajlQQIL#w^)Y?(|P_Vg6N5_vf4)imwvvpRj?TL9MG9z;O;h(s7nYV!g`)?D`SFg zE+Qx~|LED}JMpzG5teq!XPc4MOvEwWYfrLXJhy3X5{+znYln=(N1Dye69Rdb@Y`Tl z|4BeCnQ|wIgV8ZS4$+B8J6R_EEd3Y9T$5@iE!RtWkV~Vc*`iIe-WN!W-(#;njy_3q z{=oY7HK2*9!*o_E**P+)Zc{~gULSYZBYryH_`R@5kIVe*<$JIrlt!hJfM&b2IU57N zF^E@0mU$8^inS10(=~fZp5T(tSik+a65)6$;9$WdBn2bI7JzgI5DN>xHK8LZ`V0ff1JZe8D zvMhdg^KEqnl2;Y z&Cw2f=^Pp9+V^(@rmcn5JIuENh$P7xYxJ=C@W|IpI>)3Lv{=F|v1-U^<}s=a)U4bT z09cGz`LD+<>dPRSwyr)5lD=G`uJg!Uan4y>l#I>TPFdFvNQDfm@;H4w8;Dx5<{Od5}GqM%lua}7LPl&Z1gSN~_th7~~Q2Lk#&PN7)b|Yarg-|{d{OLbC zK@xcl;fXS9r8Gd~lD1cDwOxJsHw3|R1qAC6&mjxf`ONU(^$oxNLdCtsl5eN%o{Byn zCEPn~-BU6@kqb354{rr5l8LYA>J-GE;8b-!e*CqJ0ifJ#Xnzm{3(Ba88!WZ`NlWQr zcNXAeX9~74Zq0X=g=m*engN<#=YHnVLzt5g8yzb>Tx zG)@fJL7mf+B&`DRokiUeU4n`ABB!iG+W6nC4^dF|W~~VEo`eg+6n-P)LB9`lQA`Ua z%ho}&v9X;;7ss=MK7GU;lg-e504Rt(elnAIpVr^*`ZGzQr4qykQ^@N}Na`psgz>he z45vWD;um>zQn`QDAIlcR(NgTI{Zvmd$WKmx8{p;nM>RXoBBT=Y%?Noy+0LR~e@0j?t0r~^*@ z!=thrXgtK$MJD!b)-4QYJ25Zh)F|`FhpU?Xs#6BL0N?Y!+CNmA?KkjU zGmA$)YH%%ri>Hq1Q#+=%I;K2Vw(N1eHOZ~p9AEIWTIMb|Z5vX#raE5cTduUlGHCI) zIy!DHYn_@GTxVOR*lBmTvL}{{!i1>^iFD%9roI;UVCgC zx*C-xjwx$@cb2bOyF0r{s!7k-O(=Egbrm9#$*au-kS#kVQX~^A6uZzSj>MhSH_MY+ zGQ9~xHkEHZkblt;;<%5LkjsW|N2Bf!lB73?Z%c?aGL|2oTqSmr1Ae6;iQI5#Jj*bb zKyuEyON|s3C>qExKDLhjWnvDk3oceZqK<&Ts!(k#GeU=8-Fv z*D+pAiK~&%g%_D53OGT$XYv|*PxWRdqW3%H7ee}UiZziNcvu~Fsf z9{4G42dUb^*s#ec+ORsycU?F}SSkr_(2LfzvlpecK4WoZ!gzRGx_`$X>dN&9P==wa zNeu~7=F}OxX^Y{;HGCT$yGTi0*e5aBWx=syI9R@MO698DsiVygLuj|0?$^VWe3ao5 zMuru&pC)2-0(jnGU>SGz#3Q(@KD$H`n`pdGS6rcdr=Rr$BZ$z|UM%PK+?IW4n~~BqVg=o~tavgO zw1Bp%pJ%ApZIM5fV_K-zbtZF8ARzmEi5rMQ5x_hf!`k@V7FF37Q@#}?41;gp$c_eS z%CV2vR##&|?NQzwREx_$p!C`*h+LWDsGNWNF@n459RSg6aR(<5SEJq1Ovk>nJNZJj z$thGg{b1T;UGyRUib`aK0%{c@V+`uzTHwO)%d zxea<7{6#Uf0J_l-wiXf!j8o12vhcZMGQi2e`v@iIDKNBLV@O66WO`FTJ79U6vs6{P zkh^^;8u6ulCNl>O7Tl^&z??~wzdltvTQo=zxME#ggAOgRfBwv`1$jK&k(ooKKh56d zlRke;P@mN9cZEtWMqHtTcEY*3G_pOv_Ge(g!cpP_+O;A^l9oS#xC$BLdyBSLY!+y6ZSPzyNYVVxzspv{Ee&vufGD zh`*q#QRK3RY%#x-?jG8Cm)+R|3}D^05FQ0qgLBZ7e8M;zX)Idryov>ZYaY3BY*(s? z+u1lpG=GilGl@bV&&*o_z$q@DcS@hb(_jV@`5UC7C>!GcbbX6 zhNRkLn82>iq2_6D$gZt-3^f6Do;8Xo)%ACAW`S>#`Km63Q3^g)8RJL;hws%Oc2dU) z;{a*u6rE{GojRZ2nMKyH?pWaq3v+Y=Or#lCr z;d;sZeXvjQ%d>=B2mf@Z0av{elD7G5fGxw=^<~iJZ}`?D3+*vrQ`+<_;W1|lkN50~ z*K3=|Idjvot1|)L;OAGxRNtk&IC)2v=W}}9m+e<{=`?(O*+q!m3job}83AujdPBJV ztJbM@VwqH0FXL~g;-%9n)*Zt7@?I8NSBSNW3CIIx4;j|nN9fA@*Jzo|4e@@~7hA>4 zqrm!y_}+VNGQ*BcmckGDGskTcMRxy62sv4aY!0V(@s&BNb5Pzw3AxgAwnD*p5kuXb zx{_>(OiDwR2GIxQ6F}B`?^JOiVIiS}G3w6v*|2~P*GCFn#EG83zaMn|&s5%?x*sBe z;Ko;V9U}+i1;$L8X#Z?Z;4OGt6@5)sbXF*|z5vHhKi&=-Z~Ef>88UAebsFlS{#nqd z+Pg5P!_6Z+p0T8Ic{9u761jX*Mfw*ozwP!5ny%*xb2s~aF~Gk9`GRCo78Af*#EOso zwLomMXIbDqk)8FzZN-$@eB%{9`@kBn2@5p04l)~8<71wBzR{MD%MUNlSsQ zKt-1!OpC@wnKuh7xlOPgMi}`B&XIvFh%MMvSV7;=ffsC{R2}i_tXJ>?3i8jde6nl; z1OmWyFL}^=Xs{J8f7AIRaJ?{F0uVOZxN(hzQaY~2B|zSv@HKcAQNj)}42MeMMMbbD z$Bej{$eUHybhqb^IE00#9Z}aU{Fcx#<_kcf^hEs$l8gxQ4b8?fbr8aJJ?A){bTbsC zpIa3Ak@KJ4uoWw zvsf+t4}d-|iLbJiN>OHJ5;P zc>u#EtefO*WZNfU#3o`hiR(RdcRNz`zNV!_FX%ENNK=|47}BPeaTX86D!c%2n=Sz= zcU(DA_?!0mH(&3;Ag4^}G$t@fgaa59I5?GERq2wq;Bf^D&kI)B;w6Nnlr?L<;S2m* zCMPNge0p+T6?{)+E$A#-g`Q=JgK`cy86d%r1zAM$MxW;rf=VgxyH#LssyA;LrUSV( zRHcfoQpEc3`D)6XiyyJNy>0~_#1)yZ~ zxAopxRKA5$n4=j!HdKY#a6f^bm-?mYcO91bp+YCPb~`~XJj>np{+3d-RR$pdu;DFHH? zdXf!AYr_EIDL9njlYI-3UWt5%lkmS1-3LbfPE0fG&r>lJil{3`{zT$_ zd}#;E&+eWj$doISB?+hN2k~QMbJM4c|ja8$om!27&~AW#fFH0Yf~hV zla<0H+tPpAn@o4PtQ%Keq2 zrat&YN>AWrgbwI(alvH0!sP&**#G~Ur~hi&|F;P0KY)Gz^~acIeb_s+RQ;byA4oz( zMz~r~&;LJ*o6u-L|FgN-kjyy^3b;qxDll84(&=}hQfRscL)Rx=p3&uDA0Brj>WZ9= z;NQH}I4{M;YpekfGm zSmf(_Gf=Ztx2Ogv%%$_~LqSh&+4^XrBtxIri->a{?^)63g7X-y@-HAA~AXkOkb|G|WgY-k4IpJx{G?K9VVO>se*f>6HbDqLav?RU-J1KE{}cm4WQssgK8;0tEKpR z;tKZ)2irr}pu5t^jS%KsMyDdquMLv0)UMvDlWvlyt?O9y*bD0|+`UMGs|#KT_PIs4 z4)_a6o=O*xMh7~_!#OS`Vo?Z^CNPAVyW=Bsw$gsVHYYZ&Y)ZrNXI&uY&#%`jL+RF% zmi?He2?3tsBwlg_ATT~hB+CR%er0;A&*(bfVx&{tiH3?kddit&p4hGgHpApgg}=A2 z)E8ErMlnu-F48x?%UEQ}sRs!={EUF@$cephg4l*%G>uu9@9li7Xu}y1Cu*x}LS(L@ zcg}zw%Jfevy~-SH{n;y{>70G}15cp8pSwp@L%3 z`w)SDE#miFRp`b#eJo>`l)*jEy%1}HYnck&r#ppca((#QsljULjmr&jSr zfpxf^f7B!+1+Lu4VzycAQ3XJt9iq*HReXhTr3T^*=kR!mP&=U0{Xd}Pzu@{mV6z9O za3$6FM-1aE-hi30x;8L5)q1qqo_)nHwmr{hpl!Yt zXd7YJGnK$YacTx|Rs57iM`Uu8>T9INKcn++9aHZ#buI${^YIkqF7a<{-VKLeA8k0V z;kO^p`s>Z->9cH;t(gy@_^4w}2oZAM`u zr+NH9GqL5JP4p_YarE`+q9o)Bh9y^|h4kfK&kmzhhqx>ryN*e7b*UMBg%|O2^eIJuliH}X8l~8L^vE~;vH$H%C0)VL2d2oc4hCU zklR!5Oyml~guy4|+5*87I5XBL7@{JFRR2{t0ZdZe6=v;a^gz>NxpbEU>id7XIP0jW zy0(oEDcvb0QX`VX&?zyfq=1ytJ<=se44nf*g9rmCI7m5kNeU=KNj;QE2s21Z4k7xX z-}^n^^StMuz1Ov`d;f9PI%}PCoqhj`>8MHHN(Sf9+J1s``SV1zJLDD~fs?VB3hFdM&x7JAqos(ZuP z(^skln3QoWEW3>~vFO$eK+fri{o4Ft}ve3E?^agqSv%Ah~-#OY>f- zz+|Alc%tSuVf)2`l}Jv*>E*&jx3+O_i}w4&xN&!BI&zQApq0~i`?z+zW!L`6s=<=+ z%&|MjzntqDKU2OQOoQMT-!jda1bbN)QdUr1Q^N{HPo7z+hZ%U*K7D;-5D&pP_<1Ig zT)N9V8P(Mad0IInsh1W~;xgrcl?$hr9(Lb!SnMHuVvHE>9F*G?x(Qs9AdQZ!fv}c- zUH~(0HR5{-3>|NDHf;2sbKmf}Y-=~_ zYu!6FiW8cfB1%I-XZJYcT%26e8vsybp_ctMTdTtK1W@_|9VLvIpqp6(vtLoxUuF!r zR-&8U7S8ux;5zUf--iNa(_XQ^(HRo+9Sa*Nd!$z4IpnA(Z zNx-k)zY%frH$pw*vYDd#9d%eXws>p}FArA~_D-Bc+jdtzJ6oG5JQSR|J*pdBy^s!< z1ZAJurZ2A@gi>leGKkAnEUbs2o)k~zwAK|bwtR#}Xxi3@i?tY1x{5U=V(AuetV=?> zjVpE@i2kum~HeWrvSV5q(9W1nZP(DbVyp7DQ<6Nh9H#?X0b@84ZeWgZg>7 z9kA>qPr{PQ z(SwHGW8_W6vnBl%?Bld$x^JH4#TcfIgIt?&)KK+AHRE5vLjRY(tLs37U{R-NZP|>E zNOwrA%M&P4YryzdjqBmKc~v%s+b-?{m3F2(K|EEb*qJJom{uFMseXvn}P-QM*8K)jB%U zN2tMjH*zOzU%a<#vh|d(kmArcwZ>&TH5lwR`-zh=brAzy_P7STR5iZFqq!V@xeXUp zUwQ*3*fAQmog!rDIoZ$3bfsW%(x_1>ScL85l*c4kF{t^CRDRuSF|=c_Q~)i=`2K20 zX!i2FTpLMpUDU#^|C74OIi1=`2h!s^EZfSdBnvQ3$`hLcl0*;10dC6I;6`)r?{X~Q zCm#bFcPSuSBpeku`oqqccc68UKjY6H1HS>jLgUSN)ZzdQZ-|m=S+M+frHTCw@|PcK z;q~>(uL#DZJic->^G!ozD=0I{sYb$hcRSv%ajPV_zk=#g^aB$Vt+yrGn zJ+?R?sblF^>DJ6%nFP6({LTkf6`b~Q!7Fd7Vt9byt1HI+$eYLJd5Y05a}3pJRg*e z^>)zoVGEEwYo>(8o!{n=c|YamVefwV;&lN7Wig~e^er%VblnXrDcA#*k;K>n2`MYj zvjTz{fn*?lP0IUv*0<}3H7PxU05uApM-o&dc)2XvG8VmdNXBTjSlbl-8(c1*B;h_w zWHrRo=ad3cGHxGs3=?r1qcP!nYlv6BCaCP?T8(`^r>9LgJYY?>)o$NY8-p@*Vp}B9 zCPB{&p>u4hEf*_X1wA=I^uvoUg7J~BJfNhZa*e->j7jjjxddO~it zRGyTxT25V6&uGqWUg(T6mTUs$%r9>iUX^ajJi7c{3cIRRjcg>YbTNTf!^>n^NQGKJ zEu;C)S`9|2^W7O?FBmP^Eu+JoS{QOP_A%7C-(U^RC#qGm_(b#A7QhM*(;UUSBtbhf z*irD8( zHQ90OvI$JNRuqlC@nOeE5sRZ{y(j=r^Z*ZV`5JP0;*G(eDpXDH;F1G_7z`6|Xm4-$ z;cGeqcReL`FIH2h1L*g%FD(4zGB0_}EH>G!Tw>1Zq`p3Wgph|8xh5Q}-Pd#Y4u-#a zBEs)KZQp-2g8tzO7E>{zefMhuRU2KSoNOm!;F1_9(ZmYU`H51%33m&Dokx?ZU>hq2G%$ladvMtI?woWHIv)CNUc z-|4ehWwVRjLGD|*YKf9l` zX^L`MC5~M!e(VT&x*>#>*Ko8hkqo`t*WmWiE>V+KykO`7WrF;HdZ`hX<1EoOB7%_H}3`Fz_&+SOFTKrr{a6*AwL#9*%az{jO?!^!lY^W5DmSfGZ zCPcCE--1W>C2E?A0J0M3#cY&|!!1951r|pDns(R@2!Zr|<_3mqpDaGs{?L&kNe;av ztiyKi^))@dW39`R6it%Eq)ce<5<*855+>sDn2en#o_G+v6N?qG>qJxb4w#lx;BuT}IIsE)DcCnM~I%@+Z)x~KtLQ%8oqLl|seQFk&V&dBp zsMe1%0SN2Qm)_EkhvGTd$6PrUJI6sOz3`cujQwXJoYz9_bQxv!eUZc}H|*89Vnf}) zJsQ0F9=)vvdTsX|FZhDV50IB6h{5sbUcg&a`Vsp!ZMwm?Tz@whg{4||{PLu6-6z46 zrwP#fXW;Ebxa~C+#VM>SL~X4OkZ0UHj);cIpFZc1$}8ke6mmw7MX=qYz~Def7)lS-K!zfSCiR>p<)S!WC&uFx0y)L^!(rAchP-_I zG62@>x$ww>udQNsb;Hreeeg88FrSz#oe3cxD+#~YQW!uc=y+>{`kdutOm>4sMIa&U z>5+-;ZmrB+P)*$(468mrGciQ0hY(}Ov`p3tCnc+pCzU4}#7~#4UwhB%C|9nqY(qZ; z>pCc*e`YaY-f;-DVvD8@@I zOuyzHMro#TZT`tP-(8z!>7czfE#^VK*?H26*y5#fdc73axvO5+%Wx0wnEt2Q)vNF? zqxMh6yj@@ednx`2J^C2eqTW6vHNWkjF{8RaMFvwL+paC#{f5pB`6c z(Q3As%fvz1))EAC%xWXAR8fv5r-)V%F1*kJCUSk7bX!FUND>s2c0ndAH<86NO*zvN z!6kaud?w4?!93nN|5ZZA2K!WI15fHqAJy3R!q2OnXH)rXw#=i=#ej>g^}+d+E5b2$ar)wB6Qt~bJa(u*`+H069VoZ zk)z0u*(&s`T$rT3#Jw0(O;!1EO7MAT1C}~p7`Oz^Pyebihn%)l@D6t4K?^l<_t;R+ zDyXa@nCrp=O(*#^d1;g_wl#W(xrooaC#NL}2wFlx;(^!+Gf_E{_vsVSPzIb}IKNHe z-2{)|8ZY%}TZ6^ddPK@$VMiMWhaVQY08~3UNTi^P)nz`s#!Z*g9&zBz7Re5QB^Psa zT$6%_4-HFz-a;z;l#Ct$c{(_(q9$5NAkavZKjyJfSe&W6bIq6C`GKGIQl?zR!tF;+ z+1Hn`aX8DE+qK?DkXC};jt@ggE&>(n&ICOnJ60X-T4(Lts+c2p})aT#b zi{PAu>+eG;v;8}o=aQXM>Q9QNcaMf&x-@R8Y%7(V&?<0xfHA3?1AA${YwwC!$matCxRu&&fT-G(Pu1LA$?hFeR(pLhO+DGVg8; zj^-P@c57zVemgGbqaJWbc5_Rb!8*;Kb9zKGrm)K{_}8xVx%Y*2eJNw7KBX`NZ&7!; z7HR4AAT>Wb{4$1-`W*9~1~}Ke?Xhgxc4qVA4+hT9gA2Sz0{~=1|JTQIeYcSp!5>y2 z$m9=kFtf&lBQx3r_(!WT(fH5EkxBdTe>H1Uj?9M-h5zVL54Hb{zct){G$zyk)3pAq zy*B-WHq1OUm8JfTApDz1mnmy@i|4oU4UZq<_l3xWnQ{E_{6Coo0ATxj{r99M zv(-%K#_xUpnFvt)%VVjUVa{gp+w;#GLHRFF!(9Nt!OPR%$EI1+H9;1H{RH`wXw0Wot)UVZQHhOCmY+w-RHUYt9sx1>URIp-SeBN zbE?i%&2Rd254VG6)q*0*OMydRfPlb&fSCHG#Ue_A|Hs4-$M>ki!T(PrhWY;>(i;B@ ziQfSwj>iYZ_zxUk^v_?@K>D96|BLsiL!jI0TN_)_|F7r$o6q*&bvvLe|Fzg)od2=) zDq!58z&}SBXEmcCRy2LFM5(ncJGa}bz4v$y zvzhMRDIq zePT77%4>@@=*j*Sux_GQVTm=|vYkIWBo;M$f zic=H`#dx)^U`$X=^w9>WLgx_4*@ay2QZdfgaIVDrVDydfD}?Z@U`{HTSydrRwOnqx zEYD+TzFNb(E0?$b+**{~`nIr!b>{_e%Gn%C5Uhgzax^i#qj0LZHcY`E6u__qd%Z4j zblCcm*z>}xr1SAIo&?}wf=S-53l$3QPn7q0wo?GN{KhklicGX}0hf1qKYHo>&84#{ z1C+(kZ-l}Q$26N|i;xmnlec}hr|i&X>>?V52P8#~ii5SxFwoAhv5w4xjxH`23LGUg zbZwH&loI_jLT*7-I`C~zriWi3@>0++@>fg2)1V+A%itg&@(BOknJ_Rg|Jj-G8IXj4 zlmiY2O4n7jt(^-))Wtx;1;$QH4X6-kl!XI2Goo3gf}8{n_?LG(%MLp>USAFmsDF{> z$LlMxwpSX(=`n0XVo9}Bq6)u}SJMt2 zZLQdSThk)U!|yrx)L9h_)wMD#*p)IMye!2}r&HCdwe2+ZK<-fTbogv;p|wGSZrY^Y zrT*z^MtUr9e0;p_%cT(mHTxUWg{P_a&B^GfI>*;X$J*DLlc5yV$57I?ZpmSTWBpve zH~;m?=hTF00g>!_sY)K#a@CM~Zx29G6;Kl2{lU3ZyF%LpOFMTLue*0FN{AKb&g zZ{+rQb6fVFHg=h?&fttIk&Ti6Mr6pgDgGQ$p-v_GPBSvUMcXHbBYmqS=s(?(9PJv6(!L$3h z#GXs}Q@lNDO21BhHu)RjYUsx}cTnZA(q&Xa zWUSTdhdGQ`p?c#h3XjtwW9S?rdlWWA9+;Ykv?#M^6lDF&wgib`II4Sqf<)uI*RsDq z*|zE8>W84U4nM5h6Gj%_NQA92%DV*J6{<;FmOy%36L`t${1tdIbq&%AbUq)EKIVI5 zer0PdC3MhA7EGKc&qprNIh;s`?|x8;V6189g2+8PW6DV-E8WQcQb?-H3B&$b7=&3| zmYV5L3VwO8YTaB*9ao3AzvVu{L3NSFii%*#i>|;1$UJM}jlZ%m*_587iARIXpNhZ3 z!OKRpGK+qZzZgj}odbxG*+OlFI>zHrQy4h$6=@oT_dBXe=lzF)vUH_Itn7!V< zIl^4Om3lM1IO-H+5>lln^5T!m!|#g~7@XYcte|sWJw@ecd(CBKfN}w#A}_p6p-#<+D=3zOL`aE2sEz4Cr^mSy5g|w!1t)Xq%((^LH`DAT zA3!6=Fo4Cv?rx!}psY?@|63|PslQ&72%RQjD;^o;{BL$WB%z#l zk!@s~SWy#%)K^uM0T`)NK8b)Rwh3wRolbad>UaVN{ibDL#v@9~+-~By_SXZ7m(UUj zW}d}bMfv3X#BG!;M37-*G-8N7@6#$1LFU-#eTqH8qKVe;ZsZvyZwH0&-9i&MD4&1vP|u^En&C+PA=+))(7 zSfZ6Iv?_CexSx!}TA;_a`ITQ=0tZTsDvfV?lw6~PRRzw5foewkAY|8fkL|kwKn~t4 zuXlBgHAJFB4CQz}S(U^w;macbQweP|VT1A~{nV)1{1*c=ZrxrP700a6ns2`&%L8nT zhuY3$CAYBvFF)V&=+xW+yn1r%b9i5@eDioXh}H)LuACpNZctUv*C5JIghyua4n4G{ zG!LwDuGeoQ-<+L^n$Ht>2jv z>r;z7=B9J)Rj+q?$$aX&l(kILk$@TY^`ne3;KEIwC7?ldHN{<2cETPE78jzON35Js zDxax>E3#3n1JSs46x1slWFC?*JnX3|>1y7d)=3hP*yV4>ghpM{c=?b~f!>SEAdbIj zlh!JT@2nZI)4Bu~kB@P0_lQU&>@@fxNoePF)MZ+#r7SBeyZx;vr8;g6Yx0D1qL=b7 zz^$er0PhpEfOqu5Gx?hLoeTxo3eX$aSAV;zqQk&j_MEl>b#W5PMMS;8-z{>IY|e=D zihoq~!6@NrT_S_1=gIL|j>7Xl`h0ZSQ1f>27D?>E?m{J(h?rOM*L9L%mW_&yxGmQ z!_2wQ)w9>xHw^F(^6-oB3Q6?#?~n4d3~+Jq^KkI<^a%B`5AgEyv1#=4?C|yO3H0%Z z4Rj9<3JwU5_m4~oi;NGAOo@z%h=@yx0RsHu!vo?X!&4&zQX?bdqGA(bBeP-x)8ixJ zGXpvU0OC@`}@oYx9!A@-vcivT}=a zk_vJ%%W@OT^V2I!vTE`YY6>&z%Cb7kQu6;vVOe2GQ9)@%X<>dz(SJ;NIZ&QoR9jG9 zmtWOdURhUC)mm9wSzg;*S5aJBUDHrg)KFX5QCrwvU(wXm6dF1h88;T0HkS}FkeoD@ zk}(sNx154S;2Q+o;cJ_2s^^R5bEjIP`H}sBo_6~IPk9CcXwGAz`_aAi4 z?Df?b_BECdwpLEIR{4wvDydjdr)rcUR1IHuQA&479J#b}bL|H4XH3 z43BhA_BM_6cg*)zFAlZrPPOmPboKZ5_YIB>j0_EqPK*xrjSP=W0HXu{ILPqm()jH7 z(ClLW?8fBm!o>XAEHE}zZBfKZ!A2n#5? zu3dN`I^qs{nO1j3Z<$tKJb1cvl0CHk@l5`eJe2T2281^~2#2EXk;I$`TApbJFtGhf z3#{LhC&vz(lVpPEFF@74qwy|AMaA z63lxE{g%o1fxI5FUHX|_ef@R0{h7}9{Bh-d)4Y3y{`3`0zy0C?JXC93 z;=WDp$pp9k><{=E_5w)O!J#WUt0zGGpz6cR{uWsF8?B(PPYtKC*0;^~bzTTRahC3? zdI4E@ck`JFhE&P#ceEG1Q(c$t(u7KhzQiB8 z_^0v3vzMt!yU@RbQ!Qq92%7vOb_?@LX10b3#Ioi zP8`}b&K3Hn1Scm_81~8(zRq`WQKBZJSz1}^+Zoz}LxFEQX;VT%2u9c*ro~Amo0*M< zP$?6P>M-{gS?WN<%!?!R-%QHT8(DF5nV@l)`lY!nIE|CW+4!Y;DqL$*W^ZVIj^M`JQ-AZ zE1|tZEb4D_bxzby*flEeLcuDUqV$EMXS4Hl-b@T~$@dWn;Jx+Pd=$Zc_Vax%#+z^v z0cUKzt-x%|ayEh!ndZ?|+P<{1+J`yzEH-3HBRLgGUHCiZT%)o&UkKK1Scgtjw3t1% z4taL<3b4i1RT24<*v`Qw1CN{Ljjz{R^Xp3M>p#AH5Fp z$dZIME*B^M$1L3rH@-I`M8lLz@)%lN?##^EUDb`;GYnR>O(^IHhRfujOKQRD(#7B0 z)%~_&G)3c9Ki%;OuxBrSIkGYOvI_F|eO-kqM0&)J?p|Y#%b?zS5YT$)TcS^4RI^pz zJp$43lHb2nOk2hyI?uLn)P7JV*3I1pDEo%RK}!$P2$qKZV}y#B3Tgt6eg%~F^09gb zV1=W0)d*_2%fyQV89zw}Nvp-jPvU<57(b3)QclPdn+#@3q=Bz@772Kv9;2iUj{hN{ zgPEWD^HoLUgNGcgN(cP37_UHL8v=W{GZk3l(Y$`+4@RGu?ROz`He>Af51zn@ zq?!wGvRT{mYH(a8M?=`KC4IGxUekK{^4gEgJDXpZ9vH8>+_y%HP%Z94i zkT$j=g=63n+^e&mXZ1ip#)8w|+Ws#u5RmTL(quJHD$`pvTn+j#uPuR6cT^PAQ4fe~ z&~vh5LvRE)jHEf4Xp3Gy`)iqn9r=^fF_G2O&jiqm4jXbC4d;jE!l==%i?maGbAVOo zd5NVffWY`o0i3 zdRK`$$-1QXESXP&-anv$L258U<*3&EyxFW0Gs$~V=M5Is`+A)$aCc3>x= zU!;0a2jNf$gISt|Z}&@=s`R^sfy84Ti1N6AF?|Mgbh7-#x|+heJQ;`XsID>~Wg_o? z>poR+_E#-DEpw$_0$ig`hLiT3oaOEak=?LcWWEF5**U(peGbK9y?{rSGYzPTJe1+W zN6OO-M>WYus(ww;MwxfnDH4lAPv2%Qq&3C28w$&Sq*EbiNDzSCeI}B)jo^S` zufPYj2Px)v5Ja+<;P2!*L<%_5=|q0bA+?H=NZMX8)UzxN!aa_VhPq|i1aZWPs=dwHI7;weAqVdyodlNE+-9;6<2xpuO>^BZwGy&t}tFJa~HJ4YhXQIRTy5LFBm6f%|o5 zrNd+1jGVZ);c3T+4i#Qx=FQW_pR(A;L`#t_0`CP?4}&IIM4zD7y1+qg8a}jpotgVk zKN~awh0L>RA4GKUuR9wKTXgTQ8hlr+Y}ivpaRg%yI;g+z4u2@Cx`^ykV@7_6aMWI4 zBZThVvSZvyipL1g#se|~!oLZo)wbtC1<8p+wf5^v&yWqvZ;AIcqctnVsK?q8)Dnc>#a95!O2&)e{^R zGu%)nX!;&tyUKko_MJ(*777H4IW_`i;uw-ZR3XFrTp!hm=o7G%_ngiCLv!ec5*a$G zb+$g;(y*%60H1f3h%hPo634gd1#|dZE==oG!t>f|4U`iLpY|PT2ZMIKp)8pTo-($_ zaxVywsJdLbA6`wza6Il{h!%pJ!6;xsNFaoDQQrHdbgwv7 zJj|YmGaCHGh=8h`3=n9KFhj=R*$DhVUgaercJGaybyOb6&h+Y~BmpuJFAW`p4uv@X zz&bJ$2PMIu!{H2^xRbmqKf(;WwI-^swSt7ga5w|W3cLD#-K;v*I#k>a z$J)h3%EkJEt(3`SlCnA~s_~L9aSp;2&0vL}0x#p{1qkCWQf2UC#NI}lio6OI5lpf9 zKS9(P;JI#y7iz7d!AOEQJ5jFi?M-*J+y1sYgL@hlX^N2_6g!bb%hhaY6EBG%^=AqQ z(xnqRw*#ym3ehWyECkDwezuYOuGX4jJjd@jDb4+zcn4rN$~IG4rBW* zN4bTkCA4iyeKzw#AIZ+>jgkLyHuY(mJnF5Il6;H>dlr>3q!G{pHwVr%5$X)$FgjsA z;q@+oT|E$L);J{7%Osgjvp>*6BCZskD*XqJd|;(dAtmPSJM_;%RYO<~ivE@i^t(~w z*lJkGJl9S6<*tIu&7Za>Y;HYw5Wl`l#3B9~zTAWHhjniTN87`$TE4>ZAV9H-Vy%$x zBDFm~VUS2+nC}C;GO>kfG@j@TAFk}8*|eEcuIupQ4EN7 zk^YE3xJ05aclOP-k8a&rB+xwtB$nB_J=P73e>!>26?QOb9aK@47gb=AYm=V7UK?!@ zIEl2mZYP*hqe4l*kocN`TzkfZBM9`4pNTkQy~br~L_INlqSYUzu)V>RaV341i?})` zBO^aqLhJ?5NLxCT2sn-nohuy^`Q3God`hhvm0ouD z$)v9BZKImnvP8WEC7KjoljKJKhA5aR%me_77e7K!bpDYyZFcMGta)Ekg8pG*njLSS zx7soS(lx(r7rs#g{W|zpX%OWnq8G8YoY@27j?AhhLB|xx06q-!Ox@33!>;!12u^FV zQ*Lv=qpngX7N_H*Z>)w;A1<6_@K2F1$QCeW5$4@COWxZ^zHj>Wa!N-XtB?$cWDkJ$ z`MTjFNXuWn%0a!ME*t1fCawu{My>v)N%|P!c{O06ZP#Q@IbSU*!y!9zzr2ExDcUv9 zlRqMPz{P;_dVE|3x%QQ=cW}kM?8!KyvKi(p*ulQjfs*Q$#jFg+>1%`ia*!+3Jb;nM z1x3vbr#T&;7%yg^kIt*%Zup5w9{|en|1`9u@7N8YFd_Yw{wBm3AznSdb72 zP1rM2RPM?@AZHe`wp7(rl-b6U-j3m9ry?&kCj!oNA9uL%>arW

$I`BBgd_bI(lwEn zY^~a{*lhMVH-7ql*R9h<)+y)K?yfP|avUrTgjZ9W!2FhEvl3ZjbdLfiyP#o<@{{gw z8|53e zIIoGjV{lZ|bVTT%`J7_We?F>~wQ*P2y|}i?FSkMXW}mo$UeAWO&8RyheG$^ZZl~mm zl|;cSnzuG1(;EY6Btt1Euao|sqde24m<_wDwnQOJIivek)u+Le_Xx;-4CGZLFsZY^ zi83v!lmy6k#n;zq2*O_Ex@he$)Tf%&X2}Ueb{rlp!;82r7h!5wc65ns@c#1EF zkVr~P7zKLv*s)C7H-MbQ_TH7;#}i~iT6B~KsBZDSo%h=2u2l(!AUd-pw8~1EHE1qZ z7J6B48IMS(PD(%hsc|w04>I`HWBIu2+n>F(Tv`eX?5l2FOWc>>2-9xlIn$76uHU}F z1P--^>_A44!f4?^^Jq~r{+eJcq9owKFioS+cnaqx3+BMu83&++48P@VN+-E|6&#YY z8~uRJ<3MV`%e}1dcodcBT1)Ig*sjieOdDUB6fdnA;&!rzxhl=O zo(>bIWB=$J2I(P0lg>7i}I$BD3HYk0kCU#-yY8+W_% zV$4GDF-wB>xdsOCU5PZflQXaV$#z;oLYc!{9}Wez#Xf5jAPx@swU@1>JiW{Cd<+x^ zo)ud>9y9)sl&zlbY7TG}KSc_b-b8k|vHX=D4yuKr zuN-0YH>f;jS>}{iuwhU1eX^FE_VTc4Z}Cod1b=A5klu=njorL}v3$za@~VyP)yS&3 zKcIiGsk&z8Tj}j`mjo}L^-?x9`nbuY+yx8xR@lEhaK+=1k(g_%Hn>g~dWtQ|s_??) zw)J}#Zwy2dpd7=iHIMdCG_!L2W$dfIn_JT21m@_%<@*EOIq& zMC{q93wr{ho?$n3{BxpyFXk9ie~#WnZ)=+V;Dcnpr6U1$h#foh4U!SQQwf%Ud?;Ca zv}2z-!O!nmks)1z?njnPhy<{j9n&ZU1vu1MNaE(kH%!n_`)t+`K2?w>T1}KH2D~0yxCz22y8?zy--_ z00qEAtRUW(4Grr}I{#^ajU&Qd^p};ny%knjPySZQbD>!ZN-dOgYwQnfM#U>P=eCLS zr%_HSUj>fT&sC=~%i(j7U+LGyp?vzIFU2>ZwLW%S937Rg%cqT*LXT@e)GFh(vix!p z{PKn_qQ4M!$6st~vXR>$!i`ao9_t?w5&kees@6Lh1bc6?LPcda9V--c4IhCtCmEfMS?~Vmqo-~q7Yt@1W zMb?pp(%Qy}`tLk)K_GvHk{uu7+EfSD_INE^l)KN)XEH3P2SPhNo+!cG1KCn}VqP2cpJ5O7E2T_el9f5|#lc5i~V z7-rGNZU0St@%$!_&U%)9hbURLTvPlD-@eGIGr6|G@@&rPBWg^yDgq5E+3u&iy*7~6 zx-mHUF0xUz@T*Ksm0}7c7_jgd<-bd$|k_&UU zCx3wOKf&XeKol$GekJuYNMC^BQ3c^-xctgD6 zbgteChx-eBrvhw#ere@XoU^Ni&EXs5F3?7Y(^27kWyNTOEt_Sk0D`z=R$n5el-Tg6(7*G5IWz=5C z9U6m-ZvQ!d0_2a98f zM^oyMrge;ZuRNnUnM^_lVmP`tqs$;w$*n+1MIG39D*BB^x~lS2LqcLK^%zJ{EodJW z%hXtCUKRJQ?4BB^i4AVZ@SRbqIQ1T_ePrppZ~PIO;Jh!b5t&ldb?&C6791R^5|=r) zeS69O2oE>H=;^&rA

xwTPTsm_27*Kf;nJrPotF4G4-)e3*+e&t z%X$8jqk4k<{?MHu-?;iN7OkGV#n+iBFBA$vzROydeXXln9;xurnY~gtp6)9 z$aH@GE?>$k$uR$oO0u>?RAbRUbY3;xGO^U{S;PE(iQ_D8@MUe}I1tXbQ4wgu z9gLBnXPPi1J_ars z2q#=k^fR7J^0@Rav)m4!<9nrNJR`!dC-5u}Ar6y;KEWcSAzO)WRyXQj?0Bb!o7IxK z2^O7uQM%93{5li@dW%g`Lkn-ShCg1;T#?1ROteZfHwuw09|-GgNNrt~?SVHJ6E0Z1 zhjUAKP-#)|OXASY+R6RDhIa*}k+niT?LxG@ySpmr)+B`c8i;skPqfiHq9u;OQ76Pu z*MB+DL25kBq$xai*ym^RLls;r)3QZ>0B0D?F8?o@5+~l8LtDb!c`w{c&rC$d+BA~f#uZk70 zf7D9uRJ3^H+jkc3JEwWRbMErANpTVhUd3l{tp-Vp)5B}XwvYFoANW@`_}Z#jcLei9 zI}!Bew0L|dTc^GJc}P1L`1WbtwdA+X2tMi}ipYLKiR??;uEFMPrtgyO(f??MZf!qp zeKr$(kqvp;W?P>34X%Qk<)Qt&rD0E|Q8n1Asq9! zmIY1XX|TcXCocY$du!mSgM3)E>@3giAOZn?e(+CgUeYgrvZvKCNl?|Q1!uYdN z-dg%VcU~i(DVZq+)wHbqKb)D8t2$0}#Nn(NK}p_{!b#_|$^c`cWG-E-PVRAi$sM8i zJSpp%qVF4g{(QnAx5LHdTAkVo6k>g<*krPy?S8QQ8%{B+kK?G!Kph? z@*>kAY7YD(q4G#P?Xs4r+^a6Qi>J{gG*5PhXJKSNzp1si!OADEGX7WHM5!at7My3L z42e{rYOU>VFlyfU0HWAsO@H3}*dco%#tHIq@nsiq$-!ikFKYcJ+WS~5eHVSAo}=_j zk#;7?JoZxTK@$MxlOK}>r`oo235t%#n+c?N>MrARPPW_?SR2_{3cNF9*Hr1poj>H& z=%|n^)>j*=Po84Y#**8oQ0A3x+XX!?CL~|u%# zOMhAU{y5?vGf5R%hONc5<3@zeyl*I@((!2mGtMvV(+iU&v@NnM-D=+5$WJf}jPHD_ z$X9i@g~$@`J}gi)6-E6Buelc+EMHbWI%%Dc(NO6W6Q2}Aj1wGN1El!u2Gm`$Wj?P5 zcwwlDCjpbj(n?ru%XG{tcIc-_MXA!Qc?!CBx3xI?KGLtmG~PS0d@AK7k%G+Z6#9qE zqOYfphXG`0`W}^HM3srquR37r_LwsA^S4UDT<5V!E}_RH6M)#^JO^|=F@fcCic}&5 zy1&V@J5eb<6wLB`oM~OEt)6NfwYygpBYVx300QNy3aHJC$jfj%wjQ0U_wp8qh6!z( zWkp)!GMlowA+6=Yl{3lq6*Hw{6MAW~*)p`4yN<7m3C9?GJ0H@K-jez5grV*=Fwy5{ zu-k{ixp9e?0*xm1_bNLgaI13Sr;|cstoFDDr_FC-Sb)8r$1g1M3Cp2z__KR z0Yoj^J_UEC2g(3w6gJUP43$7=%ljVCQ%mNvHBWCk=O$ z{Ie-7$%7LZOy{Vmh$RV6r5x{NrQ$6HyePNZK&j{zSA8A^$m#Cok@1e-8o0^ruO1Rr zq^G8NRpkGEZT{gBQl0t=t@27gnL5>_02+m5!Z$l}MF1%=Jxx2yWQ+DK9}!1b1ZY0$ zM!n{grk&r*+V$DrPa$}H*YSy~E+!#K2DXp3(OI!b8Rt~MA#g7rks$jw2O%?#Bs`k0 z#gU%gUYMrQ6ym|zSFTORVmNuMi#(hG+SB;pxK*t_`3FWw;^f$Zj+}<+Y*IK_;DP*{ zj7h`cJJV=%CR(1oa*&IWfg5U_5H@H&(>9{XI=nj12tkp)X9HjX=~%C_JBoP2`Cy z=VRE#%9+k`u;J_BCyeZLXxHy=z-bk&#xD|qbgUT2(Y5ljkOn%a&=@v}E2q^%RogG_Hl(Qo6~WbrqYe2F2@JW9oT(m&$^ zlx}jVej8HsuxmL&2v!i?`pL_vCgX>O8j)xkJ{M3NA_@oV4bZy2P7IK}HUke_JZ2eG)Fr~e4cqr>R;Tu;#GW^aeCYG>V~Lq8}fA!MW1S8{6^ z1>_p(m`D;)F?q7@M*fJG2Yg1+P*Mk6x$%yy2^P+frCJTV;*nhs_D?Z&wxZYeE!Z6p zv9MV>ZLZ8tEzPanky1e+*U|5#HSh&oSrC(BRIrLN-O8F_M2>o54Vh0C8h%&_Q9p}Q z8&j=h=&QhDWJ1r~M>vdfTqqB}C`mcq^o$&TXGwL?i}H3d8cmg?1tN2pO;1k4AT=^< zecT_K)Mx`WOF!LS)41XPyrx77sv5**HAEG?DlL61k^aG87R0m?DKH{+m<@_3nk6{f z@0b(}ogy6x`d*_BO|_b|7CvEjwqvGiPAK!BwBTsootRfCrr0#^A!cSYQRE4lhp71y|S4*acRWUgVQM5heeI9Gw1#%Txn&2mIh z^^1|SKDlmX;Wzvk%k_4qe>3U0zbM5U)Y4QzwTh1JPaOm88^Ay5(>R}yCh;L9+zIF( zd_6MY@$I;+I%&3Vl{27KG3Mc^(4x?(o`H0?G3T_BD%?HYK_B^VB`lE>URhal~VVB%Af{^nnA|TDd|-s%sk=Q zjL)<3_(LIrUz2$v!7(pI3TbXK!@=a1)>gA$;1M3ex?o0J*p^-)6|(BjSAgmwC3jAU z=VmZC$IK)+ss2b?Xe7C%+sRv^^wHqd<6eL~+hE!~2yo7Lw8!JrY?&*al;I>`wN(?^ z*@J+diCmoZ5GqcA4%i$~GKHNG44A;nY??O`-xwCE+?KVzRUPJ(gso9FVH(dY+jWM@e^3Pg95+#rbv4X=iZ;?o@d5wB{Biu=Z!FQB+y~<0R{W z7U(ijN?g)ZOZcWQQ8CENGVOO*;wDJ1XZ@~+Xj(%YLdB~!)9NNuU?|wz4m*ggSF6tq zde!3$c_BI(18tfW_&R+kkJE5$gj4H&jemTrQBg5Yzk%h;KT;-)g zK3Z|t%Y(|@(a73Ta=+?p%9tII}_lJ^t5`jY1_o(PW(spHjIXZ3XE zii`8tYUg~X?CJfl(~+my?C(M*%E4DXA)E>NN~YIKn|-I!J6qmux|v87S;fmmUr`m4 z_ab)s?%Ag-UC*npFOuVb7FK&4>H#KYKTI*_J&4V$Wn(S0R zT7|NX&rE!zBX1N5=I=6l+l$#CJbx0^?}c4k!cL9c1x?=y;nZk88`P2;t4KI_ zz3R3V$rnU5T|T!-=8$7$$s+MrGf02DHxWH^5z6%&%@Gnkd62+wZO9)r=OGyU(mSha z{CyuLtCehn;!`{ms)EtNkN`1kp8BJ4)E(xQq^#|wIs-u{NRT+Y-m%*g${XCYz|tIXR3Hqhf80o?{;7ruEvXWp=rWdgRBn4N!|it@4GiLxltoWasVr)S zj3w6j)m6HOo%-`&J}*JMR*lBRDK8XXYtfuS@|!V6*aAnyGrZ9-lBW?+n>^{Dr6=c1 z{AQl7vR+3E$)OtQp!J3tW|zNE3W|g}q@X8p{G)!IT?@w}#cKMVH*rl)cD)S@IHR|h zQoS5#wq*y@XqFE~0vh5?vFRGDUgN0V<$u7tFWR*=lz9c3$OkQiwV4R_{UWvpL?G&H z>C%x}!6#y(j|4qK7GCrRp5l)Uu#CoiQujKXu~}@6)S=V$b*n&w?A}3I{J?Pkl5XWv zQ$#tqO>@5%gJKb-y`_YL7_b(bgztzm0fd!`!O`;1=W0mBYm9_7m#%Pi6FRrEVv zn#cX-dtt$L+J)Y)U1DK}&lV;lt=jg&%E{)}Yc^>~uZ;3s($=)rOO0Kw#|{B)=ik5u zW;^9lYh;BzDY^D7yxxMyH|dehUaCdH4E#zkr&S&VA#zWCt`0csEJ! zEWMSW!`%hAAI_$fGK90PpKtChd4NxOPwa}0&VKNPv>X@LoJ;YqXa3h0!#U2n_;)30 z!D~-@R@q*3Eq+R-mzbYcUFg?d&y8G5ToVz&N?~JY?}iX8g+6g%5S!#f?wd7&EJ?X^ zKlH#D;GW;?nVz3zrNDmpo(Sdeb&Re{FVc3(9)uZAd^EwY%~295LajZ+I!(8JJc5YG^9Y9tEe`HMsC$t18rixSI4 zJ5=4>2FjwXd}ByheT!zCKLNP;7kqHu{=Vw*^JNzLXdwgbvT#f^`Q#p>#!Hy07azVUi9L)08ddOFNGoqpTnB@_Xu-zlz2`Nd3x6Os9Mk> zlw;iS`tn|Ss_8@H=uTHw!=!UX>FZ~Y6Uz>xXvY9&nJb?q>>&m0rTA76Mlc;9{#*nP z$n@@}O7q<2TbhnwICf?_lDjFnsrPH2&US`9oQ7|Cwi;Tn3>ZyNhh9?~7uvcjQAbGK z=VnG(Pai_~Y#(#qb zz{y7_n0SgfQyWt3f7R2)&&(y~X&8nA*eI794U2UDmYf4ud=Dt~UuP=%mV+0_SX!$1 z;fyS>0{wNYI$(A2Z6syj2crYCvew=Gz-3-w9!pH_j!mjJJo`Wsv|Y#K9u$;**RXLL z?^+QI`N{~Me;ufk^hGF?dKXTCMNGMxzaygkhj~nufVB?d9Lq@he+S;oV}L4w%m0pi zlnb~=sy_lov2;|d=zrm)%tBX#EOA{N@L@`EPuVhPK0HPYT5;DehQZ`QSbs-fIM3Q7 z^eSFn=ye3Yu%8Anzj*RaTN0bRT+bv-InK6bI64tp+4EhjoSGBnA8|4ixr4& zc7DK&S*p=|mow{1BmSMYmWt`a6lPbe1COjK)^aj-(x#rR5`qzs{dHy-(B9UHGo=2f zz271lJ^}25suI3cDW>-Mds{opF|ns?5hiDYpI^*{izX70-Gz+hU($5b7wz(>FFX*4 zKr;r{$kBRF5P#O!!Z#G7dsfiIFY|)BRQqQ|LJ2f zY_p}qg9QOWWd2Vd%YWKf{!d$HuQ&lPY5%tcwd;sVUUG5CdQl!jV)Qk&vDk!%t90|h zwb;@$E**|c0G5la7bV8%f=VuS!(oItI*~#Goa~2W9@$*dpVe7oQIa-LN8lrvoYwp6 zlJ|NxVIZUKx?eu7edFj}taX!y7thOXl+$te+)LShK97lwAcXjzJBvr9y5$k=ocUzm&5LpinVr!4S ztPf+9fR6+o682#NvLGG`FUl0a510MNJcg8j@`3!@v!im-H*tY&fdI%xuej`i$eW7u zpK)0Hll8-~E1#&wKhoSoX*917P187nGipj4~uSSXG*-$w$_~po=THD}FplV6SfrYJU zA7W5O28p-s>JuGW0>uK825>kdv0PlEKZI%eF2)hVDF0rsf+LVEnp+1YqWBHE zN?{zIWb4U)+?`O{JQ}mKS?_Ly{!!*sCSRZ#n((VU5r4%_9doULv9)*W3hZ5o-!(3B zcrtB+l5|R?fu9%>Q3WT%J$&8sgKqRW)DJeJv-9-6@iNc}AE$hw0}^ewo-u#fav@tn zt$st(6vdPWx>#E>gvsS(`SYJ}u(2L!k+e_odq8vhPA25%-=&&e;(2VWQTqIQ% zX=ss3H?~-SGs4@p0D`CryFSsfppcjd)RsuUbj)q|)eI~`tqJNIS@O%wy|~!ej{G2^ zS2tPErAxuI|K-rzIyc(do%(QGC?ZQX9_JVB ze^(@4^7Jth46@^xg4+rZlq`Is-E9kW2nsiBj+Oa2{)g5N37 zy<4X*Y~W@kdTfTEfB{yLKIl3!4i0l0gGmH={~EM98U2&BymEfunJ9UVXmXc9lYuRz zA{CK>ruuG-X^rA(z4aSJm@Zht{1ehax>(6O${gckw%Et&8ZtCdW-d3x(zqXpCQtu5 zxPauH0g)LW9N?EQQ0$qwGsd0k0OQD64T(QLKu6p@J8Gtbz-js~>~D;$ujlECpXbx!<|^l#Ft?CjJd8ip)K;JZ2z^$lDabhnl!+*4BYQaiKV6)8 zIMh)W$0rrp%ThBDqX~tC6v+}AWZ#=jjIlRmY(3ZMFDR7n}le->Qdo+Oq_T} zNo`q@$+gYkGR(|4=Go1vPkf0(ZNm}mI181lVvt!~^zg7viCxO=a$hCv$#zqVV{Z(m zb?zu_93Lw8+Uo|>lr#o6&Nx|@DT#%%Eo-04Jeo0Z%K;L74r4VtRNkfD7?@TQHv*Tr zj)$?j@Z;0KVeCoy{(^mOiy~o%JqPLTVgV+8DW;C3+h!F3?x}6K*{s|Fg;!pbe3WRZ z6=_QH(W#q4mlk)g1crCl4!(Qa`tW>{m#E%ODYKk`PvYeCw>P8Ye7~hl?P*>utr%OG zV`HV^a)!WF!9$G+>BWir#SDT9#TcR;GaaE~^X(xBtHqz$G%t9!TcNxu@>pHoo2a+8 z9pIL?j_nFVSLMeFPt#2}GEHML16G;uLHArNH?M2|ak?v8n&h;Errr0DR(Mk5N*iezQAwj+IZ=J!Wam~-K_W^>WJYbr)Dv%Y`IGL+RGM#v;w(aUJaA~6MOj+ z&@cR6)>(9ng9KQ*$j{5Ak{mXGtkt0LD&S||t@_8`%nh>{Jf$K58Z9;K4xq{j;q}GS zmNUPwz)Bzm`2L}u!zOq+TSWoRx^-T%AtTGe3X+noU0*Ed^5p6vx!2ar_`oIX9ORl{ zV)&66t;)4C_QA`l|%|uX;OUU^dmwY6`P{Ttd#M z6qk6}fbZ3T%Rt=wyQQIT7~n>{%6=GmO;77JsoZo=^|N4}VxNUJqe}RDV&i}lWbuoo zDaXkh9>SvtLY?NJh8=KYvp8!i7#B`3-F>~b$V6mYl)A^}w{B%eWJs3DOUpU^!fh@q zwVz|iKSXSj*XmN#I9cvPu zsQ;R!4j}Fsb#90D4n=^cXZ<`UiLEQ@hm0bTl5=wBCb*Os#7^ z%dewqP@3{Q-t*D zqzK`N4l8piQ8|!DS!*c#akBXhvv50oRxL9up-ugbyN_aWsTp9co0n^)W9-=K00#pz zx^yyB+Z+$!cm3GxY$s~+MFQ7JyBTh6VVNVvWo#r;hMb{w+hv&=9LzA0wNr7ei0oJ- zoq7V_kEULCyqYYjjR<%bwektjk zLvS0Iy^_9Lm74ma{^hOF<1WxVkinXk_9I%W!Ry!jt)}G(jTd0iD`!3+3V>`pN{qQO^X?2cz5xK7(>@T zQ{vw#eeA-!a6`=Cl?Rt0}*C?k(?jaKEk$JduNK)6OeXIh97d^m>j>-q2 zQ~ci~%jBE~2@(;$Hm?!|LhXN4?iLDC=5@J?4AV|gx?eKU%}24Z>z|6?kcedlD{(nX zG)soudrZLR_BALkB%E(p2&dcVHHGeAgsV;(F0s`WtC0ynTGhfdExJ8%eMCJ}c@$aI z_X!OTsIhq5z)#ILV#}DrRe(H|B8I$<)0#9x=Ex%Ee8ReJ>!K0s-h&*i!F?L(BKT?W;bX3`(#zcI~v4?nZ>BXPMDd?nNU* zSmKq(tlD$$BAq9S!xn}mb@%Tb2eEZ`73lbL8>YrjB!p$9yKuUvqJeGe^4{Yk6m(p? zG}C4{A9C3|``)?d!=KAF99W$|#SixQd=ELZx;nPK6Q8El>R~`%#_Ux%VHNu9Ex$c| zk+k;(i_d!ze%o~Tvln!yPQ6rOA}5K7+0(+6_B1*RG|IkvFXnV|1781>;G_Z^SD2P8 z+=oT%;U2{cG~SZA1IV{CFKQ@s_NciF9;*s@waV+{_VjBxofhy_UZv7mcudGWrLTFn zzY6C0^gL|ZW#wW%HERi5xF4aP=({?sfTZ61w*xxVy4+}GXYm39+r(_bR}(P$?^-vl^z{}B6-g$ zpmamVV)xJqLmasWweRNhON+nM&8dUhd5c%h^9!jOU9*#$xxiif*&8vO5g4J(3Sr_s zDc;@pZ=Y?FCHN+^7jsHHj9% zvXAGzw{0=4(8w)x7BwEJzZJ(L#i(rL;Xhg(^;_dm@U5H{T8!F&QrOZY|Ec)cAj4vi^XRs7{z8s9%}C(Gh%qL9{@i*qtDdpR2#W=Vf=lUnnh0lWiO# zpg#<-zsM3G5cr?ULOyB>-+t-_h7a+p#otps&p*Z(jm;MRL3r1H8vJ+WxBdIfc>k$m b=~J-|kgc7DI*4(USyNLTWI1756tMpQA!(E) diff --git a/src/initial_processing.cpp b/src/initial_processing.cpp index 0d6bbdc..2379b4e 100755 --- a/src/initial_processing.cpp +++ b/src/initial_processing.cpp @@ -1,6 +1,7 @@ #include #include #include +#include #include "ros/ros.h" #include "std_msgs/String.h" @@ -27,7 +28,19 @@ #include #include #include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include /* TBD: get to know typedef such as stringstream @@ -37,10 +50,17 @@ TBD: get to know typedef such as stringstream ros::Publisher pub; ros::Publisher pub2; ros::Publisher pub3; +ros::Publisher pub4; ros::Publisher marker_pub; ros::Publisher marker_pub2; ros::Publisher visual; ros::Publisher steer; +ros::Publisher image_pub; +ros::Publisher line_pub; +ros::Publisher pub4_1; +ros::Publisher pub4_2; +ros::Publisher pub4_3; +ros::Publisher pub4_4; float xbpos = 5.0; float xbneg = 0.0; @@ -49,7 +69,7 @@ float ybneg = -5.0; float zbpos = 5.0; float zbneg = 0.0; float rotx = 0; -float roty = 45; +float roty = 0; float rotz = 0; float movex = 0.0; float movey = 0.0; @@ -64,8 +84,21 @@ float voxel_size = 0.02; float Pseg_dist = 0.025; int green_thresh = 150; bool cluster_on = true; +bool create_feature_map = false; +bool line_fitting_on = false; typedef pcl::PointXYZRGB PointT; +typedef pcl::PointXYZ PointType; +/* +void setViewerPose (pcl::visualization::PCLVisualizer& viewer, const Eigen::Affine3f& viewer_pose) +{ + Eigen::Vector3f pos_vector = viewer_pose * Eigen::Vector3f(0, 0, 0); + Eigen::Vector3f look_at_vector = viewer_pose.rotation () * Eigen::Vector3f(0, 0, 1) + pos_vector; + Eigen::Vector3f up_vector = viewer_pose.rotation () * Eigen::Vector3f(0, -1, 0); + viewer.setCameraPosition (pos_vector[0], pos_vector[1], pos_vector[2], + look_at_vector[0], look_at_vector[1], look_at_vector[2], + up_vector[0], up_vector[1], up_vector[2]); +}*/ void callback(pcl_tutorial::configConfig &config, uint32_t level) { @@ -92,6 +125,7 @@ void callback(pcl_tutorial::configConfig &config, uint32_t level) Pseg_dist = config.Pseg_dist; green_thresh = config.green_thresh; cluster_on = config.cluster_on; + line_fitting_on = config.line_fitting_on; } void cloud_cb (const sensor_msgs::PointCloud2ConstPtr& cloud_msg){ @@ -116,6 +150,20 @@ void cloud_cb (const sensor_msgs::PointCloud2ConstPtr& cloud_msg){ transform.rotate(Eigen::AngleAxisf((rotz*M_PI) / 180, Eigen::Vector3f::UnitZ())); pcl::transformPointCloud(*cloud, *cloud, transform); + /* + sensor_msgs::PointCloud2 transformed_cloud; + pcl::toROSMsg(*cloud, transformed_cloud); + transformed_cloud.header.frame_id = "base_link"; + pub4.publish(transformed_cloud); + */ + + /* // Getting an image from PointCloud + sensor_msgs::Image image_; + pcl::toROSMsg (*cloud, image_); + image_.header.frame_id = "base_link"; + image_pub.publish(image_); + */ + // Create filtering objects for all 3 coordinates pcl::PassThrough passx; passx.setInputCloud (cloud); @@ -233,7 +281,7 @@ void cloud_cb (const sensor_msgs::PointCloud2ConstPtr& cloud_msg){ // apply the filter color_filter.filter(*cloud); - if (cluster_on == true){ + //if (cluster_on == true){ // Creating the KdTree object for the search method of the extraction // https://pcl.readthedocs.io/projects/tutorials/en/master/cluster_extraction.html pcl::search::KdTree::Ptr tree (new pcl::search::KdTree); @@ -251,6 +299,7 @@ void cloud_cb (const sensor_msgs::PointCloud2ConstPtr& cloud_msg){ int count = 0; pcl::PointCloud cluster_vector[cluster_indices.size()]; + pcl::PointCloud::Ptr cluster_vector_ptr[cluster_indices.size()]; for (std::vector::const_iterator it = cluster_indices.begin (); it != cluster_indices.end (); ++it){ pcl::PointCloud::Ptr cloud_cluster (new pcl::PointCloud); @@ -260,6 +309,7 @@ void cloud_cb (const sensor_msgs::PointCloud2ConstPtr& cloud_msg){ cloud_cluster->height = 1; cloud_cluster->is_dense = true; cluster_vector[count] = *cloud_cluster; + cluster_vector_ptr[count] = cloud_cluster; } count++; } @@ -295,7 +345,7 @@ void cloud_cb (const sensor_msgs::PointCloud2ConstPtr& cloud_msg){ color_id = 0; } } - + center_point.pose.orientation.w = 1.0; center_point.scale.x = 0.1; @@ -308,10 +358,9 @@ void cloud_cb (const sensor_msgs::PointCloud2ConstPtr& cloud_msg){ center_point.color.a = 1.0; center_point.lifetime = ros::Duration(); - center_point.header.frame_id = "zed2i_base_link"; + center_point.header.frame_id = "base_link"; steer.publish (center_point); - pcl::PointCloud clusters; for (int j = 0; j < sizeof(cluster_vector)/sizeof(cluster_vector[0]); j++){ clusters += cluster_vector[j]; @@ -319,8 +368,185 @@ void cloud_cb (const sensor_msgs::PointCloud2ConstPtr& cloud_msg){ sensor_msgs::PointCloud2 clustered_cloud; pcl::toROSMsg(clusters, clustered_cloud); - clustered_cloud.header.frame_id = "zed2i_base_link"; + clustered_cloud.header.frame_id = "base_link"; pub3.publish(clustered_cloud); + //} + +/* + if (create_feature_map == true){ + float angularResolution_x = (float) ( 1.0f * (M_PI/180.0f)); // 1.0 degree in radians + float angularResolution_y = (float) ( 1.0f * (M_PI/180.0f)); + float maxAngleWidth = (float) (360.0f * (M_PI/180.0f)); // 360.0 degree in radians + float maxAngleHeight = (float) (180.0f * (M_PI/180.0f)); // 180.0 degree in radians + + Eigen::Affine3f sensorPose = Eigen::Affine3f::Identity();//(Eigen::Affine3f)Eigen::Translation3f(0.0f, 0.0f, 0.0f); + pcl::RangeImage::CoordinateFrame coordinate_frame = pcl::RangeImage::CAMERA_FRAME; + bool live_update = false; + + float noiseLevel=0.00; + float minRange = 0.0f; + int borderSize = 1; + + pcl::PointCloud::Ptr point_cloud_ptr (new pcl::PointCloud); + pcl::PointCloud& point_cloud = *cloud; + + //pcl::RangeImage range_image; + pcl::RangeImage::Ptr range_image_ptr(new pcl::RangeImage); + //pcl::RangeImage& range_image = *range_image_ptr; + + //boost::shared_ptr range_image_ptr(new pcl::RangeImage); + pcl::RangeImage& range_image = *range_image_ptr; + + range_image.createFromPointCloud(*cloud, angularResolution_x, maxAngleWidth, maxAngleHeight, + sensorPose, coordinate_frame, noiseLevel, minRange, borderSize); + + int cols = range_image.width; + int rows = range_image.height; + + //Conversion factor + float factor = 1.0f/(50-0.5); + float offset = -0.5; + std::string encoding = "mono16"; + + cv::Mat _rangeImage = cv::Mat::zeros(rows, cols, cv_bridge::getCvType(encoding)); + + for (int i=0; igetPoint(i, j).range; + + float range = (!std::isinf(r))? + std::max(0.0f, std::min(1.0f, factor * (r + offset))): + 0.0; + + _rangeImage.at(j, i) = static_cast((range) * std::numeric_limits::max()); + } + } + + sensor_msgs::ImagePtr msg; + msg = cv_bridge::CvImage(std_msgs::Header(),encoding,range_image_ptr).toImageMsg(); + pcl_conversions::fromPCL(range_image_ptr->header, msg->header); + pub4.publish(msg); + + //pcl::visualization::PCLVisualizer viewer ("Viewer"); + //viewer.setBackgroundColor (1, 1, 1); + }/* + pcl::visualization::PointCloudColorHandlerCustom range_image_color_handler (range_image_ptr, 0, 0, 0); + viewer.addPointCloud (range_image_ptr, range_image_color_handler, "range image"); + viewer.setPointCloudRenderingProperties (pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 1, "range image"); + }/* + viewer.initCameraParameters (); + //setViewerPose(viewer,range_image.getTransformationToWorldSystem ()); + + pcl::visualization::RangeImageVisualizer range_image_widget ("Range image"); + range_image_widget.showRangeImage (range_image); + } + +/* + Eigen::Affine3f scene_sensor_pose (Eigen::Affine3f::Identity ()); + while (!viewer.wasStopped ()) + { + range_image_widget.spinOnce (); + viewer.spinOnce (); + pcl_sleep (0.01); + + if (live_update) + { + scene_sensor_pose = viewer.getViewerPose(); + range_image.createFromPointCloud (cloud, angularResolution_x, angularResolution_y, + pcl::deg2rad (360.0f), pcl::deg2rad (180.0f), + scene_sensor_pose, pcl::RangeImage::LASER_FRAME, noiseLevel, minRange, borderSize); + range_image_widget.showRangeImage (range_image); + } + } + }*/ + + if (line_fitting_on == true){ + int cluster_num = sizeof(cluster_vector)/sizeof(cluster_vector[0]); + + pcl::PointIndices::Ptr inliers (new pcl::PointIndices); + + if(cluster_num >= 4){ + geometry_msgs::Point point; + visualization_msgs::Marker middle_line; + uint32_t shape = visualization_msgs::Marker::LINE_LIST; + middle_line.header.stamp = ros::Time::now(); + middle_line.type = shape; + middle_line.action = visualization_msgs::Marker::ADD; + pcl::PointCloud cluster_lines; + + for(int i = 0; i::Ptr model(new pcl::SampleConsensusModelLine (cluster_vector_ptr[i])); + pcl::RandomSampleConsensus ransac (model); + pcl::PointCloud::Ptr final (new pcl::PointCloud); + std::vector inliers_; + ransac.setDistanceThreshold (.01); + ransac.computeModel(); + ransac.getInliers(inliers_); + + pcl::copyPointCloud (*cluster_vector_ptr[i], inliers_, *final); + cluster_lines += *final; + Eigen::VectorXf line_coefficients; + + //*ransac.segment (*inliers, *line_coefficients); + //pcl::ModelCoefficients::Ptr line_coefficients_ (new pcl::ModelCoefficients); + ransac.getModelCoefficients (line_coefficients); + double pt_line_x = line_coefficients[0]; // alternatively: const auto + double pt_line_y = line_coefficients[1]; + double pt_line_z = line_coefficients[2]; + double pt_direction_x = line_coefficients[3]; + double pt_direction_y = line_coefficients[4]; + double pt_direction_z = line_coefficients[5]; + geometry_msgs::Point point; + point.x = pt_line_x; + point.y = pt_line_y; + point.z = pt_line_z; + middle_line.points.push_back(point); + point.x = pt_line_x+pt_direction_x; + point.y = pt_line_y+pt_direction_y; + point.z = pt_line_z+pt_direction_z; + middle_line.points.push_back(point); + } + + middle_line.pose.orientation.w = 1.0; + + middle_line.scale.x = 0.02; + middle_line.scale.y = 0.02; + middle_line.scale.z = 0.02; + + middle_line.color.r = 1.0; + middle_line.color.g = 1.0; + middle_line.color.b = 1.0; + middle_line.color.a = 1.0; + + middle_line.lifetime = ros::Duration(); + middle_line.header.frame_id = "base_link"; + line_pub.publish (middle_line); + + //sensor_msgs::PointCloud2 line_cloud_1,line_cloud_2,line_cloud_3,line_cloud_4; + + /*pcl::toROSMsg(*final_1, line_cloud_1); + pcl::toROSMsg(*final_2, line_cloud_2); + pcl::toROSMsg(*final_3, line_cloud_3); + pcl::toROSMsg(*final_4, line_cloud_4); + + line_cloud_1.header.frame_id = "base_link"; + line_cloud_2.header.frame_id = "base_link"; + line_cloud_3.header.frame_id = "base_link"; + line_cloud_4.header.frame_id = "base_link"; + + //pub4_2.publish(line_cloud_2); + //pub4_3.publish(line_cloud_3); + //pub4_4.publish(line_cloud_4);*/ + sensor_msgs::PointCloud2 line_cloud; + pcl::toROSMsg(cluster_lines, line_cloud); + line_cloud.header.frame_id = "base_link"; + pub4_1.publish(line_cloud); + } + + + } // convert to ROS data type @@ -349,9 +575,17 @@ int main(int argc, char **argv){ pub = n.advertise("unprocessed_cloud", 1); pub2 = n.advertise("processed_cloud", 1); pub3 = n.advertise("clustered_cloud", 1); + pub4 = n.advertise("line_cloud", 1); marker_pub = n.advertise("visualization_marker", 10); marker_pub2 = n.advertise("visualization_marker2", 10); steer = n.advertise("centroid_marker", 1); + image_pub = n.advertise("pcl_image", 30); + line_pub = n.advertise("center_line", 10); + + pub4_1 = n.advertise("line_cloud_1", 1); + pub4_2 = n.advertise("line_cloud_2", 1); + pub4_3 = n.advertise("line_cloud_3", 1); + pub4_4 = n.advertise("line_cloud_4", 1); // create publisher for visualising marker visual = n.advertise ("marker", 1); diff --git a/src/range_image.cpp b/src/range_image.cpp new file mode 100644 index 0000000..06d17af --- /dev/null +++ b/src/range_image.cpp @@ -0,0 +1,165 @@ +#include + +#include +#include +#include +#include +#include +#include + +typedef pcl::PointXYZ PointType; + +// -------------------- +// -----Parameters----- +// -------------------- +float angular_resolution_x = 0.5f, + angular_resolution_y = angular_resolution_x; +pcl::RangeImage::CoordinateFrame coordinate_frame = pcl::RangeImage::CAMERA_FRAME; +bool live_update = false; + +// -------------- +// -----Help----- +// -------------- +void +printUsage (const char* progName) +{ + std::cout << "\n\nUsage: "<\n\n" + << "Options:\n" + << "-------------------------------------------\n" + << "-rx angular resolution in degrees (default "< angular resolution in degrees (default "< coordinate frame (default "<< (int)coordinate_frame<<")\n" + << "-l live update - update the range image according to the selected view in the 3D viewer.\n" + << "-h this help\n" + << "\n\n"; +} + +void +setViewerPose (pcl::visualization::PCLVisualizer& viewer, const Eigen::Affine3f& viewer_pose) +{ + Eigen::Vector3f pos_vector = viewer_pose * Eigen::Vector3f(0, 0, 0); + Eigen::Vector3f look_at_vector = viewer_pose.rotation () * Eigen::Vector3f(0, 0, 1) + pos_vector; + Eigen::Vector3f up_vector = viewer_pose.rotation () * Eigen::Vector3f(0, -1, 0); + viewer.setCameraPosition (pos_vector[0], pos_vector[1], pos_vector[2], + look_at_vector[0], look_at_vector[1], look_at_vector[2], + up_vector[0], up_vector[1], up_vector[2]); +} + +// -------------- +// -----Main----- +// -------------- +int +main (int argc, char** argv) +{ + // -------------------------------------- + // -----Parse Command Line Arguments----- + // -------------------------------------- + if (pcl::console::find_argument (argc, argv, "-h") >= 0) + { + printUsage (argv[0]); + return 0; + } + if (pcl::console::find_argument (argc, argv, "-l") >= 0) + { + live_update = true; + std::cout << "Live update is on.\n"; + } + if (pcl::console::parse (argc, argv, "-rx", angular_resolution_x) >= 0) + std::cout << "Setting angular resolution in x-direction to "<= 0) + std::cout << "Setting angular resolution in y-direction to "<= 0) + { + coordinate_frame = pcl::RangeImage::CoordinateFrame (tmp_coordinate_frame); + std::cout << "Using coordinate frame "<< (int)coordinate_frame<<".\n"; + } + angular_resolution_x = pcl::deg2rad (angular_resolution_x); + angular_resolution_y = pcl::deg2rad (angular_resolution_y); + + // ------------------------------------------------------------------ + // -----Read pcd file or create example point cloud if not given----- + // ------------------------------------------------------------------ + pcl::PointCloud::Ptr point_cloud_ptr (new pcl::PointCloud); + pcl::PointCloud& point_cloud = *point_cloud_ptr; + Eigen::Affine3f scene_sensor_pose (Eigen::Affine3f::Identity ()); + std::vector pcd_filename_indices = pcl::console::parse_file_extension_argument (argc, argv, "pcd"); + if (!pcd_filename_indices.empty ()) + { + std::string filename = argv[pcd_filename_indices[0]]; + if (pcl::io::loadPCDFile (filename, point_cloud) == -1) + { + std::cout << "Was not able to open file \""< Generating example point cloud.\n\n"; + for (float x=-0.5f; x<=0.5f; x+=0.01f) + { + for (float y=-0.5f; y<=0.5f; y+=0.01f) + { + PointType point; point.x = x; point.y = y; point.z = 2.0f - y; + point_cloud.points.push_back (point); + } + } + point_cloud.width = point_cloud.size (); point_cloud.height = 1; + } + + // ----------------------------------------------- + // -----Create RangeImage from the PointCloud----- + // ----------------------------------------------- + float noise_level = 0.0; + float min_range = 0.0f; + int border_size = 1; + pcl::RangeImage::Ptr range_image_ptr(new pcl::RangeImage); + pcl::RangeImage& range_image = *range_image_ptr; + range_image.createFromPointCloud (point_cloud, angular_resolution_x, angular_resolution_y, + pcl::deg2rad (360.0f), pcl::deg2rad (180.0f), + scene_sensor_pose, coordinate_frame, noise_level, min_range, border_size); + + // -------------------------------------------- + // -----Open 3D viewer and add point cloud----- + // -------------------------------------------- + pcl::visualization::PCLVisualizer viewer ("3D Viewer"); + viewer.setBackgroundColor (1, 1, 1); + pcl::visualization::PointCloudColorHandlerCustom range_image_color_handler (range_image_ptr, 0, 0, 0); + viewer.addPointCloud (range_image_ptr, range_image_color_handler, "range image"); + viewer.setPointCloudRenderingProperties (pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 1, "range image"); + //viewer.addCoordinateSystem (1.0f, "global"); + //PointCloudColorHandlerCustom point_cloud_color_handler (point_cloud_ptr, 150, 150, 150); + //viewer.addPointCloud (point_cloud_ptr, point_cloud_color_handler, "original point cloud"); + viewer.initCameraParameters (); + setViewerPose(viewer, range_image.getTransformationToWorldSystem ()); + + // -------------------------- + // -----Show range image----- + // -------------------------- + pcl::visualization::RangeImageVisualizer range_image_widget ("Range image"); + range_image_widget.showRangeImage (range_image); + + //-------------------- + // -----Main loop----- + //-------------------- + while (!viewer.wasStopped ()) + { + range_image_widget.spinOnce (); + viewer.spinOnce (); + pcl_sleep (0.01); + + if (live_update) + { + scene_sensor_pose = viewer.getViewerPose(); + range_image.createFromPointCloud (point_cloud, angular_resolution_x, angular_resolution_y, + pcl::deg2rad (360.0f), pcl::deg2rad (180.0f), + scene_sensor_pose, pcl::RangeImage::LASER_FRAME, noise_level, min_range, border_size); + range_image_widget.showRangeImage (range_image); + } + } +} \ No newline at end of file