From f198650640ec5fdae380f795aef8b68533b10ef8 Mon Sep 17 00:00:00 2001 From: yongwangzhiqiankai <422168787@qq.com> Date: Fri, 22 Apr 2022 22:13:33 +0800 Subject: [PATCH] =?UTF-8?q?=E5=BC=80=E6=BA=90=E4=BB=A3=E7=A0=81=EF=BC=8C?= =?UTF-8?q?=E9=AD=94=E6=94=B9=E7=9A=84=E6=94=AF=E6=8C=81=E6=95=B0=E6=8D=AE?= =?UTF-8?q?=E5=BA=93=E5=8A=A8=E6=80=81=E8=99=9A=E6=8B=9F=E5=A2=99=EF=BC=8C?= =?UTF-8?q?=E6=94=AF=E6=8C=81=E8=99=9A=E6=8B=9F=E5=A2=99=E5=8A=A8=E6=80=81?= =?UTF-8?q?=E5=88=B7=E6=96=B0=EF=BC=8C=E6=94=AF=E6=8C=81=E4=BB=A3=E7=A0=81?= =?UTF-8?q?=E4=B8=AD=E6=93=8D=E4=BD=9C=E8=99=9A=E6=8B=9F=E5=A2=99=E3=80=82?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .catkin_workspace | 1 + catkit_make_source.sh | 14 + ...1\350\231\232\346\213\237\345\242\231.png" | Bin 0 -> 87169 bytes readme.md | 234 +++++ src/costmap_prohibition_layer/.gitignore | 49 + src/costmap_prohibition_layer/.travis.yml | 107 +++ src/costmap_prohibition_layer/CHANGELOG.rst | 21 + src/costmap_prohibition_layer/CMakeLists.txt | 191 ++++ src/costmap_prohibition_layer/LICENSE | 29 + src/costmap_prohibition_layer/README.md | 167 ++++ .../cfg/CostmapProhibitionLayer.cfg | 16 + .../cfg/prohibition_areas.yaml | 13 + .../costmap_plugins.xml | 5 + .../costmap_prohibition_layer.h | 216 +++++ src/costmap_prohibition_layer/package.xml | 39 + .../src/costmap_prohibition_layer.cpp | 653 ++++++++++++++ src/disinfect_msg/.gitignore | 2 + src/disinfect_msg/CMakeLists.txt | 217 +++++ src/disinfect_msg/Packages | 0 src/disinfect_msg/msg/Dictionaries.msg | 7 + src/disinfect_msg/msg/Table_CostMapLayer.msg | 16 + src/disinfect_msg/msg/Table_Task.msg | 9 + src/disinfect_msg/msg/TaskPOSE.msg | 24 + src/disinfect_msg/msg/testInfo.msg | 19 + src/disinfect_msg/package.xml | 73 ++ src/disinfect_msg/redme.md | 0 src/disinfect_srvs/.gitignore | 1 + src/disinfect_srvs/CMakeLists.txt | 212 +++++ src/disinfect_srvs/package.xml | 77 ++ src/disinfect_srvs/redme.md | 0 .../srv/Table_costmaplayer_srvs.srv | 8 + src/disinfect_srvs/srv/testInfo_srvs.srv | 22 + src/slamproject/.gitignore | 6 + src/slamproject/CMakeLists.txt | 321 +++++++ src/slamproject/config/prohibition_areas.yaml | 13 + src/slamproject/db/TABLE_OR_ROOM_POSE.db | Bin 0 -> 12288 bytes src/slamproject/package.xml | 106 +++ src/slamproject/readme.md | 236 +++++ src/slamproject/rviz/visualOrientation.rviz | 390 ++++++++ .../currencyChassis_CreateSqlDatabaseMain.cpp | 77 ++ ...ncyChassis_KSDemoDlgTABLE_COSTMAPLAYER.cpp | 745 ++++++++++++++++ ...rencyChassis_KSDemoDlgTABLE_COSTMAPLAYER.h | 114 +++ ...hassis_KSDemoDlgTABLE_COSTMAPLAYERMain.cpp | 57 ++ .../currencyChassis_sqlDatabaseMain.cpp | 841 ++++++++++++++++++ src/slamproject/src/currencyChassis/readme.md | 71 ++ 45 files changed, 5419 insertions(+) create mode 100644 .catkin_workspace create mode 100755 catkit_make_source.sh create mode 100644 "qt\347\225\214\351\235\242\347\274\226\350\276\221\350\231\232\346\213\237\345\242\231.png" create mode 100644 readme.md create mode 100644 src/costmap_prohibition_layer/.gitignore create mode 100644 src/costmap_prohibition_layer/.travis.yml create mode 100644 src/costmap_prohibition_layer/CHANGELOG.rst create mode 100755 src/costmap_prohibition_layer/CMakeLists.txt create mode 100644 src/costmap_prohibition_layer/LICENSE create mode 100644 src/costmap_prohibition_layer/README.md create mode 100755 src/costmap_prohibition_layer/cfg/CostmapProhibitionLayer.cfg create mode 100755 src/costmap_prohibition_layer/cfg/prohibition_areas.yaml create mode 100755 src/costmap_prohibition_layer/costmap_plugins.xml create mode 100644 src/costmap_prohibition_layer/include/costmap_prohibition_layer/costmap_prohibition_layer.h create mode 100755 src/costmap_prohibition_layer/package.xml create mode 100644 src/costmap_prohibition_layer/src/costmap_prohibition_layer.cpp create mode 100644 src/disinfect_msg/.gitignore create mode 100755 src/disinfect_msg/CMakeLists.txt create mode 100644 src/disinfect_msg/Packages create mode 100755 src/disinfect_msg/msg/Dictionaries.msg create mode 100755 src/disinfect_msg/msg/Table_CostMapLayer.msg create mode 100755 src/disinfect_msg/msg/Table_Task.msg create mode 100755 src/disinfect_msg/msg/TaskPOSE.msg create mode 100755 src/disinfect_msg/msg/testInfo.msg create mode 100755 src/disinfect_msg/package.xml create mode 100755 src/disinfect_msg/redme.md create mode 100755 src/disinfect_srvs/.gitignore create mode 100755 src/disinfect_srvs/CMakeLists.txt create mode 100755 src/disinfect_srvs/package.xml create mode 100755 src/disinfect_srvs/redme.md create mode 100755 src/disinfect_srvs/srv/Table_costmaplayer_srvs.srv create mode 100755 src/disinfect_srvs/srv/testInfo_srvs.srv create mode 100644 src/slamproject/.gitignore create mode 100644 src/slamproject/CMakeLists.txt create mode 100755 src/slamproject/config/prohibition_areas.yaml create mode 100644 src/slamproject/db/TABLE_OR_ROOM_POSE.db create mode 100644 src/slamproject/package.xml create mode 100644 src/slamproject/readme.md create mode 100644 src/slamproject/rviz/visualOrientation.rviz create mode 100644 src/slamproject/src/currencyChassis/currencyChassis_CreateSqlDatabaseMain.cpp create mode 100644 src/slamproject/src/currencyChassis/currencyChassis_KSDemoDlgTABLE_COSTMAPLAYER.cpp create mode 100644 src/slamproject/src/currencyChassis/currencyChassis_KSDemoDlgTABLE_COSTMAPLAYER.h create mode 100644 src/slamproject/src/currencyChassis/currencyChassis_KSDemoDlgTABLE_COSTMAPLAYERMain.cpp create mode 100644 src/slamproject/src/currencyChassis/currencyChassis_sqlDatabaseMain.cpp create mode 100644 src/slamproject/src/currencyChassis/readme.md diff --git a/.catkin_workspace b/.catkin_workspace new file mode 100644 index 0000000..52fd97e --- /dev/null +++ b/.catkin_workspace @@ -0,0 +1 @@ +# This file currently only serves to mark the location of a catkin workspace for tool integration diff --git a/catkit_make_source.sh b/catkit_make_source.sh new file mode 100755 index 0000000..dfbf798 --- /dev/null +++ b/catkit_make_source.sh @@ -0,0 +1,14 @@ +#!/bin/bash +#sukai 2022-04-21 +# source catkit_make_source.sh +#catkin_make --pkg yocs_msgs +catkin_make --pkg disinfect_msg +catkin_make --pkg disinfect_srvs +catkin_make +if [[ $? != 0 ]]; then +echo 'catkin_make :error' +else +echo 'catkin_make :ok' +source devel/setup.bash +echo 'source devel/setup.bash :ok' +fi diff --git "a/qt\347\225\214\351\235\242\347\274\226\350\276\221\350\231\232\346\213\237\345\242\231.png" "b/qt\347\225\214\351\235\242\347\274\226\350\276\221\350\231\232\346\213\237\345\242\231.png" new file mode 100644 index 0000000000000000000000000000000000000000..84eb8b6a9d5ca9d82e059093a659ba2751844d3a GIT binary patch literal 87169 zcmbTc1yEc|)GbUxfFvXkAh-sb;O;WPoe2^kxDM{_!5xAHhXf67!QE|u;O>L#Fu4Ac z+6s!D(o@pssE8+2 z7re)af6p96WmKOd%b1o03FiJg_5eY4>gE9X{vC_DRBQXa)ta@JOQ7PK*e zf{kY@sg{FlGc=f$ZMz`uK>$@B35fzpMqEVIE&X80)l1=$ybm_hKoxKG?n3%ND15#+ zFT6H^=o6`Gltm&v|F67o&85ko%B88K;Y3WpoJrkJ3~FIm@7~2aj~>TRQ^$V&8G7R5 zu^8exdbhZtdzn6Z?E}<9W|ipy*C-bm%bY?70^*mV4G0SHvHrCNKyto}ycOfNsMwtE zDiRwToBB3ku59|-{;Vu^8aZrIVmT)#PJ4TMSAN}ptHcWQ8WL!fsHGpcq-SKzHQACE zh>Ctu4U2zz4aa#)(4QCjoMg-SwUYS1cH~ah;0Pb}Lr#DBq9cxT%%)By+s(eSt1FT7 zzZP%R+{B-W`1#G2Oj|N34kpkAG(|+j(Ng|n4lC6Js7cw`Wi`C^_72M9|26!~E}52D zQE>(vfETeTITR84k1eW~s4>(g>3Ij?+}1flSJ3B3WBz^BuhWGT$shC-lH*Rlam<^z z1pD_z=pEqt0ONF?6e+NWkR+n=q2O>%R7}yHz3k0{yRDSlzdfOJRTFLsF!j!Pe~2B^ zHXLiX+`t>)oRp#A)RFRa7Lr6)nSw=K?t^<=7)-QbN?EjR##A}Mjv1enO$=D=t0a)3yb?==?iHlSB5r5^0qirx^|5dW| zrA%1ejzc~_xDo6|j)x@GzoixN5it`EsB$8iH-VmQjOi+xQ)2QL2~Wp`lRY7*7dPUh_C@fnzgG zcS%z>cdh(O3dCUezWVhX1y&1fg4%ipUc2%DY_!>jgRnuZqZQGZt1ee>s(#QF^ zF*<$rMmMNp95=aYt_P)-WR{Fb?tkH@<0 ztB~G-VhkLq30kAv^K8WgN6QTtyW@YkRpSJ?C~gf8EWj+e0!3^9SMFD)=@!C)_(kFs zPLt2^$auRdd2u{XvKaO76bI&O=tkagTU~{aKK6b@K{L?8XZMW|c%A9~JSzkKxn2Mh zQ%EOkvCd&tLR=gQ+&yrlF;T$j@}JRKdDC)Xnyof0Q(0oUfx$at-4k@#q^poQ8x@Gh zK)73Fv{1f4^~b9@>q4X|-88(hiR7KOil=HmvpeJB3kf}czwd9rAUlD7t3-*)nlpC^ zH}(-A!6dj66bxMhsdrzmY(|psCZd1ZQ(-^#J+i7UblBNi#uHIdGedOm3FH*0ivs-`Ddt|&V=OZWRH z`7x$@dfYc}FZdC@RoF9DJNRX9C~warSV6xd{QbzJ+m{hZ-XJnE(emEyl>2#4$kqN^ zHm&r5dn*x_!-tTz7;%~d-!4u`E5?!P2}|XKmFv@%-DletGA0xk<9v!i;y9bEVNFia zUng9$6%u$6;5LAY*;pV8PR1xJxqlIZ4@64K__+dpvN~Qb)SyQq(miP~QzL1s!r{Br}mdS`_T?jMywRvg3ASq-a*38%J5g z^={~0k?mFMblbt>8OOyZ_ZUJkqV=;Gv&J*M?i44@PTFnd2SQyN(l0&s>BDIlj$Wfu zuRh1IjxPVCWT|7xxCjSxDqS=~U0;|?@Br-#2RMFt9n0N;qqnOQ*(N<2@j*Zm@iMul zlunpc zQ(fh%-lN2FQPx$}nq2eTn|6`eVaxyo-Y!Z8Wvs(wa~>gypMXfz)F31dW>m!FP#Er2 z6o(~11xsnK52DjBluEk8LPPt7n8BCYl85*4it+o(<3`96z&rmInBK{CnvEc*#S7a{ z8l9Hbl8$9VPWf%CB2G?KII%lR^1h}#wVfc=y(v^TiQ~26axu57;mhap$BdLVz=&Rm zVN)rQ(6U?jx(o8UOq;;R)O9}C1i{U53uMJNtIu5Gt!~y?_B1@F@LceV%;IiMB>4#j zI)-FkOOR0;`vZI`y{W^8$(?9?e`?DO&{~TsBzp|7P#RnD5AqOP0A}{UN0DLAK)%tY z`L`U#FzKh;f|6hOuoKMcxLUQo9Ck7^G z>ibDM{4)hysY=ls6@{}Udig`}bLVcOk`sI9NvSkE#PVaa{=3E&waoB5?3ewi;8#lO z?Nd`Pw3a>2vM#7H{4pJ%P{NUn`OeOApRKHJFjcV7m+;p_2Fve}3ZB+er`f*vsaVXd zV8?+p_`Ck~fnMz!){~Ooaf%rZN{~5!*F33RvjH(bV)ZFpMCTdx+q#f9{$@9aa*lKu z!>1Gq7WCjpoXC5alK?dMnLin+e=<30+C>pu zQT?Mk=wAF06-cwtidovnV*D|&jbO}zqAeIua$L2J8O=rC(}9d)u8o{d)I4-bCnFPP zN#9cSwWgf9HFT+?8>8iF&7Wa&0Vrj8Jd`eEAGpLYQ{@dOdw31(gXL`7xuGflaF7`M zMz1*5iSoRNC~&2d{CV`#*@3>py%U*^5wB|<^1+o=E5Ok)i(9@fW;C_4fF?&I*tu3Bd4$1YYrJ59Wo&*t{& zXg3#7j+_ptd3Lx={2|~~GbV=@8!|B?YWwq@_HD--th2s1n$7ni!4!CZU~PNj6(uRE zO=06fJ*Q0;SRpxSa4!h6qitYQ`V)mE-yr9lmm#?yIL zLlHE^yV_@M7o^W+eWq3GF%Dk>1f!M+JN@1N>5NPSGw%eWE2KsZkRO2F)uhVe1fd|EhP7!CqTZleuYq|;`aRC;K_6&!t``hs5qDkeKGQIOH{4Z3Wa5-S~TAm5ta;O^By2NbOf)geI~Z83)Z(4}OX zGG3hq(a2rVU8&SJW>H{xZQF#5VY2p|U}Bx=VJq_s<7a~Mk54e;?{p_{@qPX8O0{__ zQa9U}w`NR;dEMR#Oh_TZJ1#Q_KOI)dZ?;Y94G)U{Ot{wFiB4F)1ZGe#Ak=k<|B1fM zPMm{q4k%Kvt+&USr@u!K6R+ajPky_nqcdl#gCnC?2QwV%mJ#BQ)oB4R1+(#UECtj0BnF=|oa zx>3xKUJ%8Dgo>41xshazEJ&KAqkp=AtZx9|@pdu&)JH4iDQ&cozb>s-mG4m`)j^K5 zs}!7ba7Rnw?I~-(obwf>{g=F}YWc?oG#Zr^3k&WzU@A?ii(i(W<#5OhzQ&()#K_H6 zx!GUcsx)isKn|FeH#3h*$$jyqR6Zy>eW`-vRr%waqCde<3W+e_O)QmtxS}fge1#Jc z(|w|E587&m3x&k%?5DkpNICU(loU+K>H>QA6>%UyKYGZN&*hB3l$nNs8oMEJGvcw6 z=Y6K!kG{DEr~r5G;`=xa#beE()Y&uQ=2WFeyX7Zao2BxE=P!~X9*4qB_W4LM-wxrr z4Bv;^KjQWDV1ra=*<8w2y4OxP$7$`c()sMuyU={Vr&V3K%zlPff*<;rYbt^y^b{JC zO&`HpRsNOWD`6kKUte3MiJO@?;&e=H;*9^KXvXRje-155Yr!L21*S`l<`TM5^oOXL z3cm4?Z1fRAA_)Ljj?U;dL=3&Pw_gwD(!=-%__@&WBEq`tO^Z_IwS@)_pQ?AVU?+l~ zsQ;P7g{}eC0aMqnLxzTR?YkO7Of+(FDpCJ|NTb)k`&jUB=OhAfBf$U^zr}h4Jo%g z8pZ_Vi1**>HgkT+XwNY*0gQ}{O=7W433YWmnVFf-P*K4aLd4>Zbb|a5orv}PV*{FK z7$of$HOhIii3b=GM-Ckw9VCKotSSRI#Js$|c2ao3H2?HE&Kbc_n2+bmxP-jp`w|m_ z$)H{andHYqf)DO8zL5Us+tkH{p3%mVU?2-U#($^&IE=sP4{>M`#vUjmmpr}TSqK|C z`Y28<_1_?l$fF~yZd@o;)X4$DO-5L;BqD#H4q**a+F;!zFQ_$N7*6y-v_w^+d$hBW z0Q`diruNc3-Gmns9K(Y1a|733ut!X0zfiZx36%L4(G38_Q^8~`9gFit+TcWK$Z6Zq z9BCRLr;In-PY9M-+9){d@fFWNcf1u~ZXM@X}fp>CF z9JBs}^R?ipULsKcF1us$@E{^~iA^>-8}A?Ya)=2x-Z%lcZ%ueVyGZV@1Ill-xCF6L z4gYEA>qfW7G&A?1In8#1r)zZ+**_B&}*C0erEg9=DlqBVP>sw{|w=p_}rV z_Q~zS3|FU#;j>TnzHQ!(&oyT(Rmyw|1A2!~>?Z|Q5sD6! z5%EjZ2U*T@q#=Jjs^1zHzd5Z%X<4=W6aPDNN=gTG#*q<>?9Q$#0gS&h8@m8$Z}$@u zay(*~Zhmq_Y>>|Hy*V%5_gQo#*=>6$!to-AmM@`a3NNH9J0|*Xql;QrJq$|1GZNF~ zi}J=UXjHC|dHU8C_+cg+;g49cyi5-#^lB(gryrIEExf5yz#J?+YwDHu|2e*c=ca}1 zig2R4F%;dY7BgEao6LjJcDf(Am^5#NZa+a{XN8CeHfyyW}@Nb<}>ztfZ#CIkCC^9Gf}p!gfaozf4u-z|7l=Q;mE(Z0TpCWEBUU|w`b>E-;zU+8-HvusJW%3THx7$2>Y#jWx~(puV`c? z@e*tQybU#G0)araR&#Mn2GST6?r^Z6kPt`B2-6I2SY#x0vB6QJRINlU@zdW(j4i<- zCkJ_X3Htc>)HgJkxbiyS^Shl;;Irte-Yd!^{XasuMN2WAM93on(Za^wUbq1PL9pc3 zze_sGsUSZA9ZX~h3<*)mm5x2YkP$zks@2jR19uG%ziwLc5!m=!6iX)FfIwVQ66{Jq z>5$d1spLE<^zYPi>V$;$XIx|jQ>k5&{4Ly|;&lIxa&8UyZy^6!0F(a$E;KZ^D_96$ zSor8a-wW+$5z4bzYS z^)(S^|ItS%bDi_P8U`u9co;Sfd-DhrrqrJ#f-naj#Jqm@xxY!yPg(lWuTv(QNMG`~ znpS0B!=tuTl-aV3@ukdP=Mbm1{11g{k9}{`_Dl{xzg3);-fMDM>kLAmocNK5uC6ZO z-mTl!i2<`tV=npLt3O@r>I%q~h*-AcBb|W^?ARmDZ4EPpHDSiM3qhd_yz-VVeX#~; zm}K1u!nVd@>Tg2^2)yJu_}dU89{Ouy?&fO0O*^eR8ya5TWW%2DJU+d?^XbKd`agsi zi!wC`GQoJO{|4@*yBU#0U#J*_q)#B3KQmyTl@S{HJeAuzb;$sMVIzHgA-D``xdM;l zd2*a)zdyKgvlspuux<+I$;T%rb zegoT{yMTMCO?%;mm>c$5Zv>#moI203%(6CcwccDNy{dWw&7Dwj9>t0k*pz%+`AIxb z+B8-l4wW@1S@3>C4abU zH9sS1jz$XxWqa}w>#yq86Yv#$?_7FU+ASlxMU6P>(TU8M7w@FXv&3W*o2qBw<5oKOi3LZ~(!=doLwhwfvQFF2+`nrp~GxrP1bzWFcPm^-NO+OfU?NC_l7_@`zM6GOfS$&cdnNt_F9F*$nl0v<}Ih5uUw%Cj2NE`&Nla#ZOYAUT)rjuZ3`uD z%V=Ny=BKfN$yTbRwLG5?W7<2ixqZBnBXectAtV$&Tvw&V_;Nq?b{D= zZ-z7BWM@A`q3N92+Y>C7a=mYuf5zCJZ*b^tej&4d>`x51gm)oA6|vu1-`I#>cl_#g zbJ)0MjEojr;Ia}uy6d}9-=9B+lX9dU{R5;vcw{Cn&MxkH!vV=@BN6ApZ$ei6 z_Nm-~Lx&KH*E(RInYgppo*@dri|^kzM-C7$_b1-~FJ!$__>K@vz9OUU+u=kHIyBQd z+l~4>B4i?3Y6Tl|G*j0@N@_6qMk=1MXw_~d8~0#HH!@Elhxq_#2tWqSsPi>2F_YqV zJ2bt|`jOz4`$A%Z&d1Pgs^GJN0KC?AJ2!{k)8&Y23rfcS_LlpznSHlLI-he#px5Q} zr^oZK_F z>BZv@y}Z2K4r^wvZuZM}r%M;CL8%`wNTM~wp*FEPH8doBzH7s-E@RLx5l&c}24Dn5>6@b$n}-)LL9ZVl|U(vJfueqbC z#MTap^w`;#WAaxUNLq7AS1z*nFAI3_Y_7H&&_Pcha(-b0!a!xUtTIjeBQ@vpX|EYD z);F*l_ju(QPy`ggM+~^iB(7aOF_d`mR=l_goL5&@zuSC$DJ(UaP4(8PFL>Lcydz>) z9y)+O@a~2_0amR9uS~SW5dxY&Ax`hZBWZrG!b{N}a-IJ6UOnZL>Xhb%?2n=oYdhYI z8NACdy@^UGT6Q-7F%*y-+WAk*5Oo}zfC0f2oY0y5mE2)mZHKCm;Tdx zsY2yEI%4n46F0r)s11nsgGeJpIDT#ET97;Oe8u@kvZfXyTbM9jp(S=R*wE~AON`gX zYNZZc-P{^H)Mj;!eS~n~EHJBM`1Vm=-0crBOxc!7M8s|@Wm*eGmQ`<89F4QP;F}Gg zCEEN}-W=q9SR@NjZ>fUT)!XHXzPW3SFlvzfo!fp76H8EA?_LY-i={7gC@sdIrcsM4 zjbk0wj0-ohhRnMoRqxUNUYC z+272DNsq)%F;T5!dMPZR3VrqvKD-9v-)`N6k)5Yp^wI__HM(;X#4NYsJMNb${abLuI zf_k}t#qk^F_p%s)qlP8>%KQfR4jfzCMT?O-VA-oyMnPOm1OI+=Yo>r#Vl`KotYF`BieSx6k;9 zBs(yUZQO0D;!GF3^pFUf7uZEk|e7S?0pQx2RJBPvzO6gK3*Jmm=bY`U^hf)k<+J*`M zD<)H$(uP#gCrjPC2YkMnLZGRwu1NvNM0EMg$ak@|1ECl7R65_a{dZ1A%rF$fdIw^Y zCo4R^0@}&RlPvA2g*!MS1LNf;y1T<|2Z$z1@!jIf1YlQ(@Gm*}e;5*1h634UeoNZu zA34cz52@b1E9Kg3%#mOe%k|M8D(5rTTk&$QZp=u8@U6U|g>eny`m5zNNxestYQuB`L4}6+!Q{fnw`s>ge$56pv z?$$`awmZIZkeNK3WiXE(!_zw|9_pJ$>&8vk16tWKn%$Xub;KWRH<95*L(KO5Xo9o3 z&!T&g#l~JWLxAO|pX?#}G+T05nGo^|5!b%2)O}?WF3{SsDq~QNqqd2M#ON4nhG~0GDKW|SD#ev3*9L5j?YzY*C1#||HNj;! zppua7a}$Jv)c{{K=V1tR*&VKZn|C?>#siRM%xW`J{wIFZkrnZ&B26v;)_*C9|(r#CqNtQWs;r(8Pn>-WD!=E63FJ_$wsh+sL z7}%#@(cM%#eX)Fh@nX5f{`qC#FPm03VcstdX=vKsOP;&CfxZkA-H@fsxp#-Cf{)cRDf0*CoR3P&2M{eRL1W4GHk; zfcFR6l2-kA;F!DU-{Ht+x{LzHw8`Qmb3L(U#A|7-(DRfL!OJccqKq@zs$#n~C}Z6z z;lQ`@%u)@B!OfSZ_s3eHkZ2^tF2sX2DZtls{&zH|yBoo+W%TB@dATx67HQX9%*$cf zHEXmqU+WwBhs51ds^sw_5hCC{Gw`5Qx{Q7)rN#oc&HIMrn$_-w#c1CUK6`T_W}dEI zd#3m8mFLFWOncCxjumH;eb1cFF%Msq_N8#%(xRQCBh^Zd$}GMuw&N!DGicBGf#k!h z0SQ>u=6m&8f@msVhl{lf&i8Q-1J!-#j(iSu>;~eQa=sibI>8KR;i1wl5y0WhJUzJX zv7+FO9eU;gPl}ky4Tq(qt*nV914P5c=bRC9${I33p7njK`*X9>5{&?I#L3VP(F{H*gXRRRE!X0TiauK@7Ah<9+|TIv)xZAQc~xu<_r5yw%DOki&!ohTwF!b zp-=*u$0w$^rmpBojOT8TGdvCKhcDTr7r=krbdeoZCCopTDhsFzan_ z-q@|_?B*m*$K*rxGl6k|P8G@lS9)zA_ks~!;hXWO))gL_c4nDb@dqG<7wo+&puoSlY}+F4NJ0l^y2t^7a*dO#m~fKJ!H^>^&Q=9@hc6h7TJNuOYV?_fwzBIn<`a(eF_BEtG_>8 z8WJZ+Y-n^NBXd!HTty^%l)%D9}KDw~hq zr{~E7W}-tgN^}i>Y$nI?8hinX zyhN$TYJyX4UmS1t_gJW&$v(CRf~-N6g#!i9AKt}`m|BRfz4D8fF9(m_K*>z1XAd-{ z;$+0BC#o7v#H&aR3=58S9@)yZ3RO!_*Joko-i;ZGdqfUPMK64%P^v9-c=0Ag7K0|z zdF`L>_c)64$|De=|Ah5~C1PLaH~abs$xQdO>y5wKq(~sIQ7~KfW+FJyPE>5An{)`hK_5jdCg|sUzPx zn&scT3~klZOizwY7jllCl~#|=a@`*Dv4&~#f4$J-gWqYjvHmbYxjXpieyU0`+BN{G zDg8NFq+evCj9TU%u0jv;5C|JRt^2DWd>(bNnPH!vb8-MsIxrkbN8ofN~<#}$1Fpo%25oWUV;4?bZhhbzpyB)P4kQ0N^2>t3GD#36y7J)$qiXgvWs6fE~1 z`Y;eOPJhemQk~KHEK$mbqC&hAJ!p)R#y@I`y1mlShM9R(5Ze$zHxt zsW*#)N=sAsoKnAye+{fnB3+=eQI2QGT*bj!3|p_D_y5C<$2nV#;Va@~EGZfLCnc%7 zgiugkhNa#6#&7D#uGg|vDxxnh<0rzLU!HF#0ax;MnUP7bNCXZJ*ObtHDU^kt#+Lu?s^q`ng%FVHGMBfaEkpcjA@cn z4bBLO#A>c8$YQF<#PvO;1Li`ryJLO`UDIKS$geb*z%WTl{d;Z)rFO2$bH5sjnCNs_ zOV_&n$7-H~Jdx2Nw8(l3cHXZFvHnyz~)1vxciBWAP4|o$&Nm1=! z^3P2>JHwi>Ly#*ptY;5g4qO1~+74?;ql6V3q*tu>ZJq&jWOPn&JOHqDct=Ng_PF2k zj}#JH@^u3n&=Y~b{riVliAJSAIzF?pD=(s-r>Cc#|B$OIb`2#ghI@(+%6S7>yXR#! zHWf_`y2P?PC;@k+v{emL-3gXp`=Ou%Tl=RPckczFG&U>AwIg32%!s# z=k{+xLJsMQU0Q=a$BRG->GG?qb8Q^jsR!#yMi(O%^8RShkFQx^&9>-*OuDJ+D1|YU zylV_M3*J*U_-be7O&c*6&`uoNM!X#O7g?^bik4Y-t$cwG88h`Vu{}rM<(#NwKBxh^x3Fy zbfIGlb7eElI+lkK!&b6nyK5fh{YMJqm{ckaPc{R~txc}xPn_}FPbARbo`EmG1Za;p z@xVuUFRPn0j!LA;yJ{yvs&B#i_Clk2SuK#j&3B6zS}NdYw~xt#<8}bS@+~Qn^yS** z6fNcrXlivl?e{-RT1RajSYE1CS7dI6`X|}1t=V^tg*$0;uu%O^#B#c?5P%2E^#UZk zKM`gC%z78c=H#X?Uqs{O4jtlR^r~c3M1r9uKZsjr-qLXnAC{IJjaU}e{q`Ut#uJqL z$`x%Ur?5Ql9$ObT>`Ia$R>w`eTkpllbeenjn^2O|zFyz4R6K^pb0;|=F>Iyl7vRRx zWEON*WVk(9Zu{F>feP&P+uuuOm^^Y3>dHa!K;bAb36{27Kl3lIa@y7)tGe&$EWey^ zkj4r3xE?zSauBStBL!&H=B-+ri((B0ZFHn#tPBmVeBb&2h(3HolRLV5wi#gzw;ifT z_$hUjNqQiy*|RPa>mUIeG*ICEqaim)5Unx%LsFMEL7JIqc3OG)r<@p28d(e%`jMW> zKEu|SCEm6IrSkG#Y~~1_{1|9QfxDF!c~-gGTX|oKXfj&$f_$UC=L;?PLplukn$A6g zFNxdBuR|(Mt;j8|KbH@4cg?X^;*|Qhed!<_q^4FVbI6eN3z4L6WX{!QE0v z+ZwshHz~D0ZaUnuSQKq?*!!Sb>5l#895-f?xc{i%7~QFG&{SQIF@Inb z89NI<_pvI&OBFQ~xnz^D+Jv~=!%J=fPv8r0^gVx=Oj7_KOam#t%*Noy>IZvLwrOFz%utDM7Ih8kOJ;j7li z%n3CP8kzsdM$p~^To3k*85+jVac3G3o)&t;>TlnNpm`ATGm0ag6$q(;?qYxch)}XK zFL#qzgKKvN^ioO3Z1#%OpE$c&X3&{p=RbG^sG+jhtIS71wzxU3b=9R9M$GmeS4Z zE$g|F3np{|&1wpeZ)LFcLS41@Zt-N}k@w0=e10Edc`GkL7>w=UsvbiP&MvS80)NU$ zA&G9e@X6t62C=eFR&ME3;(5PbThimRtAbReYHjX?O3R24$V z?Q@L{I$Q1#ixn6aH2h<(G}g;4`>sp@%%JeMGRfOs0hhk+q#L)bow-Y~UyCX7=+&~7d&b{F ztN|d{scMmGm@F>xz=l(RwQ+Ede~)2@p^Tet(u{BCNu`04Hw-IWS0OIByI0)k+=T|f z{e94{f$Xmc8cS^d1|MH)aZ2+IUWwY!`4TfpU&_5G!_7TzKe`w#TeC59*+Ke9yX%8~ zA0ZkkGDigioU-W~i%E^pP4ZB#hc^?AH72ujc+EmC%%8L|tM#w+J%kR$ z*QSm?3hj2zsQKIIwJ7MPjWnNFNcg1PT}>&;lvS>(7m}7M?8uAQ3gEl?_IZlw{Qz|o zF?!}vPbVAQo%dllw6O*qlfkHt5O>AN1;d{Z@12aVVl{tU4EmavLnzpcMy|Hdz0=72 zb?nN48oiZE;5Qp=it5;Bbe*z%?0olINtv0^K1{i}#f;2*f2-+%a=BmPhb$L%=H)dx z{tb1SsU&u@F=vZza{D!amc7;z2Q!h}x~uZI>7^ySSkF_ZFVR3<&r53UGl)i*Mf#DL)UVn4`f3CHm1hGc?!mxv_e=8LCr?-y zjfZl%-N;wk$C*-?2rN4aL{*4#;rDiQ*Uy(SnZG>d5z1fHkb0BR1(JqFMLz{yHhoXi z-kKYnG7nA?5;LOtN6TM4|348^)GbZAtq2DCh)*Xxd&C=)>YiYJbf5H5tJUbvCKdbn z&|WiS($$1@tVrBlCZ)TPS3byg*|U%C)0AM*xsivhr^+IARn%}cUmqox(2awH?#{rK z{}9mdg{aA^O<$^dd|km5^0jW98XUkWfI-smF$FZ_TsLM~K(w@M>wLA}d17MdAl)Vb zh5NDmn#k(pF~3#|aecikZtZ9;&!qg?1vxxt?`s^+_qE1kw7G_{QJiL7 zpIHk;>;0IlMn>ifaD*F)9+>*`6TZXpXtpU}uuV-g-q_?B!-LO}IGo&BP6)RWiV?9N!; zju<0H^Age!;a)DL{y^giBO|K>%&-vEL^kcg^R);p-_zf#x{>7#Uuo&KdL0aV#Ft5V zvZBxw?PC|~dwM=hz0aO#Mzf*O^YbFu9PT9cR(5aswXJ`2LOJx2EeRz z?W3J$y!YE(x$9_+2*Xt`IM0LqYNf-wJZ6oEsuob0eA=C9^f;o=oNwX3#tTEwQs7f4 zuEcQ@{M|7|>TAzwp5K$Uo`?)U^ne0^o6}{I26Za0p-cgGy?d5oZmLKX62uy zN4n!xOgKPZ3VTr_p~Fa$m!bksYw+&UT1R#it=+bUZ3~5Sh>v2|R#PHK)bR0;h`Vuo z_B6g7@0_f4X*W8B{r>$c#2LFm{p#jseQix-EL+01KD`yk0r>k;gqp@1AYL}GbGfGW zpF|{9mfuJa{jWsy6ctr10%hHBz-m|R|0@v@N@u_-lyfJZNtW9{7W&|mWcRIQDHGGS!WUo)2#o;jo><7p?OSu#*)*4 z;F`?o&in1TdLAlEOwJyRnN;XEW814WbYQ4UtHnZOOmtj6u#pQoF^Ln=Jg_Hpth928 zB`l2BQxU&ie<00<l%>omtz_Fd|-{GQKMW)2LFzY_?)8V>Uy&cA?Rk0dX7T zErS~4@b!&i|GoGMT5Q5u#+!yM@JdLDNeA#JwXQwG=Q_H$+Ni~G?cSLcOnBWrNp!Gb zS<0+SgTs{oUgfr)o^D~LTEsWb)NqZ{agRwiHSVLq&|@ZEFKpVr!-bKftMFH(C$AJ< zYJD+_Mw@*{oda8x_2NrXf%Os8G@}|tB(xtN$Gm@pO8C=%%Ck7y#{t-A30Ba`r4wW- z5IS}n%kR-(j(oSy2@-s`^~!wF+!4wR^MyO_H#XODoi=`siojIl$|LCFIWRI~0$AbR zR6U4_$|dh0bGX&cJ$u@!J(#@Zjw9t1wzXO(WCqh^?k#-?RJ)Ed5nTUr72q{qijjr% z)+;eL+G4s$OoR83PS!5Df#qUt$I+4CqW}+H9g^2k`$x8Kg0J13x1N&tJ=_VbJ!2Lo zlTFXv{^za>#k*oU2lAiFc`u9A%N1Q)|9I@!e;(T~cloZkVbb&4_Ry$-RoiyIzyS>r zG|Kq+E{`NCWFBeu{X#a11TdvLtvq2%IppP)#z@tEB(hE1zJ1YD#&XTp$#nb3Rl0lF zmWel8r~e$WN(vb$0aQm7xi%5$3iJr)0(p0Zb$5p`{Uo7@qVWQ*X~{YliIZ)cVPr<# zf{yRiHiobwwcpYweSEXkMw+LUnAFjBY%DHj`f&4Iu-qN8aVfmnaN75=DDpi7B%=yGE1DUq(|a zPC`_Vq)W@*IppJY@Ys*&E^)mBw5^IlU5g-dBI6!Q)k~0K>cWW-4oS}ag-M?FOC`i?c zW=x@suMTwCpLO9};9W*iu@NJqH(e4owCu=*?zp&r6$;!FL7xHYDEfOykk zjrEApOiyJ|-?7|E8nIHM`%F}M!{^A)2T9-W+0Ik8VT2Sw?6 zg^WPVnrx(Bd^KsOOO;C$$7Ul`WgRN%G$Z~G-u>rBHi-g<;Go~kEpy+p&vc1IkB#FG zP*P8OXB6D2V9sarGlgR|3=cjsNv>rHd#u3{q{^<#(!OajuSN$2IlyG2xeY}@okG5w zPNTon&hmOpn;N*YOBwQP-v&r|f12BA>PB}+2&M+O974qtP!vfh8JB~5ZuB^0X~)(It}oX=GxL|YX<^rzN@lFBc5DP@ z0;T!~Hb|E1LJqZD96NQtP2V@c&BC77vfTR>FvN5g_?R}jn8{4s)D)^hhyh)skA^cQ zK}ex1H}4LMXo`cYD}_0pyzkVqyg1cu`PKN-BsfD#l4&CV?}<7NC0;q@3#M=D0oNCW z{LLpu?^lB##k#I*WVa+a8nxcrQ^qO$fiTJcuuP1k;L2!Ad1MqD7eDXmMw(Z}L<}cdKAUz03TS&k(J_=oJF}6c zS)^s39>esTAJvs-qu|{W)4kTgTufYS8>OVXi8Z3!28A0qye6d^HneL)5k;z& zecafR>|*-r6&b-P=A&GCV(}UpiP@F!#Sypi8s9ZRI)T4U=+M@NdGAy-R>w|x?HaY%kA>{-IMUzbZEBL@eEBO?!zmzVDz$p(@* z`b8Gb)y-~q6OF#Hv1}4==6U7lX32yGnp}^iGiROV7Ni9JnT0e=5K^I@2=q*8X8_cz0|FiU11c@{r~;*vP6tvvCTIN z84csj+qY*q@l?4gYHDhT!mCF|nMIqemXSCxD0IKyz?IJd`Z{GWk+L`}7hTP1ivsh2 zUTInZAEbrR(%(C53oH5Lr#&qbq29HDjDFRZ&innpy8t}-*w)^Qz#FpkllxG97?YWs zgBw#46N3s>TPbr@3rXkPCVG8FG462qd_KQL-9-hIEbved;F;&+9PBXn(iR(`dg^LKE72*tc_PV9ELA z)Uh;1{o|({6YE418F_2dwQ(gaFh+ceV!zUUtB zQF2{Gelrw6>Nr>1)-59Ov!N}k+I6PERC<%#;FVcsqG zi|gw4R`^29mdeQ*9&ofo-UQk*)$nxre^mxP+?1|KYTN~>zP)sb%ndkJ z%(O)M)y)6vtB8sVociKEd+PM!jx#^QJH9n|0Xwi9%QMDXMY8HRg?kOG2=^jK?>(TI zZD$;Kp-8*-AcnC4>zPRBccve3N`=RWevN(6P!ko4qqtG<2EV=&B<`4X&J-RG^z}L2 zW*H`5IC8X3!9=j-ZXO=WMVAgYf5BkCPEiuTZWLV5c8$smq(J$7IDnkN`fI?YY19&&zY$2gbqoHAstT)_E z1t9PYI-iWupl|Jm{($&{xl6 z)xm#uveX$Bim8gh7ia0YRXs3@v>#*p@y#=ls~4eU03epm#Q?=nza|&knB-fF-_hC% zF81q6xE7i^M&~8>Z;vWbSgOqoIVE=hi+sIHy!6ydr?9MGQUi@2^zvS*#$rYO@`7Fo zHrL&0+U7EoVdePFjzD7anQYe=TGXEtNbp$R>oJ zxpSwp(-=oEGS5A2Am9#>bjm4;7K{{a=iIWpEz7 zvZfO|W@ct)zh-7TW@ct)=9rn8nPPrp#+aFznVH#MpR@a&d-qmt)lSWiDUD_%wKQt= z(~o-KOpI;7+!kT;dL7LMs(+7`cUK+Ty|JTUyA$GPm3HWL$eLf!73wa_p25FeJ+A7g zy*&!w0;Kuh81S5^6pX9Kub?O_*2-b9*eZ+EkemWyY7DOL$L7wEyT@tN5*TQ(c9Yh# zVZpKSFHfW@lCdmQOId#So=Uy*aSo;PGOKQTJ^wK`Vl$(ZDRv~gzTk?@`2n3U*b8s; z!~ETK=Fd-^gDziwgRb41ItBUj6X4#_Cd)8!jtO)CVUbzE_8vvSsPKB%N?2kPojlZL zGkB~{PV02DLb-f4P4IhM1T9Z%h^ejM*@aFP*R5_}RWWW#;qJ#6AfS*Uf{2FaxYeD@ zMF$PhHRg-BO++$6Qx(p2oxDdVTdftaX{SVG2?fOM{ex$8#D7S?;8I%a?XHq_CvfT) z1Z7idpxi+zn-E27Qo26DUN5CCNBH{Uu}w2-UU=!~xhOmaBXa#VLWW%9gQjjeEQ2oP zV34UQ;`1a4%(CBDco$C?Kw9r|Am|%UO*_2awCb(4H&+wGrW*~8=lT^X^*X(=m^(m& zF}*gLp~===Z!?pX)18R50R)Q);kWnm`_|=|9hc>k=DbC0wEKtfhTaOo*$AA*D9XuLp|xPZiKdfKa;51MU3%u9}+%991-UsjdeEFk%Tc0C%XO0$1kw) zUc=R!6OQ@xB*@~J?e0Xh`$V&slX_Bd`bXU=w_z_TT*#!ts6xGmXbN&Pm*vo;r+ zL(!hjbj=R*wsuAzh7{LAf>cKYBkDlWf%b*21LJA$y$zLvjDX*|uCiLQhZQTd9GdgX zh+ixOt6uylI>>I!vbOqLH=4S<>?6JgG~Kgm3wXcZaIjDiM^}e4Q}uB(tf4Pn7xGC$ z{zYZ$5xJYJ6^@HK!A}elafK4r+L692rMC@O_;#MiY`xqWbc|xBXgdL&)dXua@W3N& zVK~-xdw5keftvEn;d`(yl0I|_vE)q_r!}al;3+n931r;cA_Mmdhdl22tcip1T8^(m zqM@q+7RdR9oVjdGqQM;PB!By%uX2ZQP|2b%-^8WN&zV6syBfbKmYT(XOZjjQbM>XCOYCOUWM>dCoJm>za+e zFD?KXKG)W=6v0kjipC>+gOC zQ~_=2?vgnvBH18e{huSMrf;l4_b=xfo%P&gJ&Q~jSiGS?SoKcm$c^*zk5{S?*mJ?c zgmk79#c90=J(mKwXddmY{dXib$X-W}mUn6~FY-OIHH49Q1E9*R2~yVi=I z`DWH}^D(NDHz4fS=+~--|J(HLo*AKrf<+JShRdc%=v;wr#bg|Kwij@WSub zxmcp<3uXHIuyr&1S#mQ~T|MrJWa$mq;kP=zg@8DCb6Y@{CK`AaLhyH02Lkj%Mv#`e zZvvu;7J=m-buK^2Q7yPIYg#)i%j-g9g(I&nOju7I77Fh9`<528uCiE@x#&GHmrc9- z2jthzpe%lpzfBt~&}EF@^*0SK8v$0^UbYNM1YUVSJ*Z6vB?;~T?$a*a^f&Z)<9}bs z)aC1VJ0R}zRQ(^`d}@j6*gs49Nufw$!N-;k$J3Yhk5pW+GFSJ6kQ{M0L)x4(BcsW2 z(L!F39q3{xZM27ukHeFT1U+WJ0(KKhS_bY^H>BlKHj1JNHNQ`c84NWSf~~OWubl8D z)qB@8n&a2zEAb1>u%Z0ePIbQA;1v=U?zivj5%;;a@7sXW(#J)5d*6lXGbqAq`280Gg}!Y~%aSV4C) zaA=pIxNm6s*Ji`d(dXs&%gJq$$hxA5Boh)f^WaO1 zKr52}mPzaGZFEwAyC?gyjK_!Ks@0%`kV9`!Nith5 zA{L~~k>&c_gjMXKBS<{0w#;&U@NNXaKy1W~_TvgG!9=VGN9{n0Ib4fJ(b6(1{u0U; zDK8CGlnW=WhBr4Nh7t?T?~J0g5?nyu{Y=whuQrNF5od7ebs5Em(-gHR$yt>M)z+Ml z8~qH6x%>6b}WC8uV_b)t`ep4kA^E6c3=t48Wr5@2BYo@1XVloSOM zhK_>=MIM3~*16C#`EwId_}mMk#yH4eNkOdPWVC2>&5R$ z>oA5&CpKWsNY1|9i!Vv=6-(Wf6J#3c@-ICJ^^ad6M`3PD2rGlng1V$|P}MCRX{8*B zy>G$|l08d>v~XSwCHj%SjXgOCXu0a1S45~++c$Uj$Zsp=cV#6L=^%w7!WNx^=6;@E z7o;w>k+XrHut>@l=)DgQFD8bELy{2hAdkMzcQ3X;Xk`RguP4JDLMYC#T!?GD22`#4 z9jXIMk2Q5SImWYb`>$(L;!NNakn;6QdVckl0-$;oiCbfR5ej6zi;d-8L9kF8O^!ND z`7^>wv(}jd7j7B0R$P!1Pc*NeZb-6jjk|gHh#kE#&W}JYvbo2uhrZWW?u8(uEk`7g zgCbm2>R_|`TxU!?5}x!f#*_3w&a5O3Do32k+{Dxh{8%`k-WeoMA+zGiOd42##1~G; z3CWY^(N~&`u!eakIV?Izn#3EOz#rF8u&47=bL!UIL=}Ifl!eC)^t*J4sy_LJUtn8A zra-YX1OU7wW!OhWR{^`&xiT_n{)|kW$jn&f7)PFbM0@vjqvTT>)17Rw^Z0$>nuPHi zXkuwBAR=Ldxwgm;1AuHN$aqMKun#&H5krOSXMORi`Xy8?O8 zI=dJquO2{;bTY0+dz5g^Y^Q++VrR<2C6$|WR$Zi>$YT4!GA}n^nf%zSI5qjCBSY!# zy>t_Vn!(e?r!Np?^!UO=cxaeRnpY!cVV(y$L_tLzwPbvXItzy<1aDHL1F^GIJ?4=n zIxrj0b(oxjI=cOHy4Y9)MxkkmqX1$P^a5D!6Y)rc+O&BnxLxu3b$`Jhm*P9)XKRIsr7nUI6ZPg@cTU@ z@vwS6iF(&j_83J7>RPin&)r4XbQ_r6MV3j7oGGn>=;=#lm6k71J?;WYn&EQ;YUiC8NvW7T< z01s$=BDH4NeZ78vk3x|X?2I5St`wEryH*P$uvJN^y*?RUYoEX@1IQaqK~u*x32$DK zm%7I0FK5w-sNr;H^t)WwCryQH9K5w4=HL+sMdQ zb^iu6XW(&DA0$re^k!{&hdXP|D ztdf+@pytBq^22DO9W?mPe-X}@P7tByig6GTTvg%vXh6nx(@U1ovlZzlDUM{*g@ov? zde8i^{^q|*2%nU$!$?=1!*_Cmu|C7KcXoa|+S4}+3~u2($m!+8E}5sRf!jS6CRt(7 z8k}1Q9?CNl=&t5oUYkG(W{bd3lXEzD6Q$2t8w;rd6!Yp#C9*zculMq`L8IC$kV}lh zJjmXfw0S{bqcut6t}`xo5zy}zeG$2-`0*wBf*IkK7~K&5T~KWQbyYeGmS$}G_}n6ib#}1uP=PqX zMt=OhPE;Y?i}}6!02B(@m$XC5KgF1C>%MT7$ot#yQo3T*!4`KJl*i6y%XH`d(%P|h z6KhoFV4`QBsZw7D>H@gt@94F^Ir#bqdx8&R)I~?qNdz+xMwi5>KqY~Cl$Tp4qdnS! z52)j;qQ12T*cNM8XE}9L^rZ|DWCNwRm%vPB9yfSEhF>0k!%Q?d%3z@~Ip+YG(;82t zf|n#k#v=W%Z2t=*-Ztbr_2y{rRlDt^NopP5VWc21XbNxe8p1EG0agTVQF{-#_$ehm zk3zzHH5f$2aeVhMKC=Y*)ya3uhV>YkmWQZGlPIvC3CJWJPcMW9I`ue_FvFB{>}iXo z=tczG3hf&plE!nqg^QCf+dvtqu$&C=fnwYwSr7j8PT6rIlNk!?@)a!`$jvq)cN{Y#Hjz&7uIe0q z+aC2OS};66j0K1J;D>-r3~y)3WurS^Zq0}A@S9eDe0lb&H5KzYL!r(Lnqh+g2gz9E z@hc`e=yrZ#upIB?UrU%XOaJ8;0=N-?#ExWtvI60aBLTgFVJcZE^20hR7Iz-Pxxm+& z2>MW2axg(Lqj)gx?cNMe@n1@es(8hS#i2L0{X!{9L{;DWBi8--j`+A(B z(xmb{?kOhSCe~;xeoPrsCFOQEak2cQ!5a#8`0ntRWVYf=Q4biop(S`Qtf ztfkY$(h^8XR&T>7P=B+Z2S!qT#m8RNov1 zTZ3$lAKo;$9AaYkYlttX^b`+7wPxEWuYBF?j4;}9$jeEDeuuxrJ-{;W|3&-D0b>f1 z7Ef}ao!gJQ6Kho=*}3L^l3ANY8`$y)8RJDU0ouwHAZW{V?)|g0uLVi;&L)g29+{lO zWYS;hcd8VR?0vL~#P@ItvTbE2u0tzXxy~Zk5LpxRgFdg(@*%}4P>r82EeU7$gMgUF z!+C{0%gLOIUrFj4iX|_!oob&QHXkD&H(<>i@llb zL$HA(qeI>-n~K#06{NoB;zCSbJ8rYw&fdQRf!HLf%!SpqUin@SisXw{_z;$L_B0Z^ zg1cDCB#{>bI`9UUd0cloewk|dn$lS}3Js^~-m7RmLf`MB$(&Ex(wrW1Zpb;HrL%_* zXM>rHR+W|jon!*z=Mo!Bvfrmlr}QY6W|h>O?wpdyK2h{E5r(=iEL3XW<)w7aJU(uI zcW-ccaj@Yg`sq~jWCb`&F6ibqHsTc=b6qNelD^^|*z zOYuWBojqh_Y>jRlz?50y=Q60Jv09=ud+C47A#}L`Fb7QXjDH#BAiH}U=hS7JBz8ZQGjN zYCPs6SmGHUdNcA!^&danrn2_p8$ouIUP8*RCjYo%D3Xt%;r-=VPE_5F{ZJPTB4BhifIx-QY_4 zYv0?Ymh{MMt5O}$_9SF;ct#2i=%Lt;pi4ESbrxVw>2!|U_weiVG724zukh;<#A$v%%6mdyFcp7`J)OA zzLvq_A@Vi*jzS}_`ojxVV>Xw4&rIV-bsr7Y+J+Yn?yp#Pzh7=1Q>rR+xg$1t;S@7H z=PX@zil)g~oJWZ4u49=B=eFutFskKiaCw%r7X0sYRGf4AiI#S zSribF!(Rv?hr_vuAj3P~9jb|@_z`Jss8&kYyXdSZ?^ru1H@k!5)|oY4`XWCnM&lg{ zsHPd-Ad|bar%fHhTLYbvR_scqj?PcnXYEjl1SVz7fGW~437o{>n;i>G=EnYHgq zqms^6hl0-@x18(sbQosmBJ=vJ(EzFz0|R*W0LX=a`QC~($moNMtsV|I8Fi!#b+`wH z&Ak5mz)VH{=D+)hQW2@cnFVSzq)uvUXIo)>7KudZQ7#p_AX>|_4fW$IR9N1+*#N1D*zD| zFgW~0*9{ip-EJ0=5CrB-UTTyY56(;O$71R?o=1_;*AovYz7+pObC$7+k|3unqyl)WnA2#Vvwa-$z4woWMwy z@SC8-gVbwAFdsQBn1B!fSSV1XV4c43<8dyCT!CZO{lt9%!?O2aOOtke29e^L?`P}1 z4z_G%W#yD*!_R~uRhoh7xUs8$xByicA6-l%GIaLFd34}jHPIeTq}=7FQ^5z*A?ro?vnJp@q>#GznF0aT`@$O$eo zFV4=zeM#T$fScjKX-~~o>bQb2CZz#HWZdxTaL6yilG}2rD0&1j6^j=Z$VBZ zzK*K_=4+q*t}q%Chj{D5moUf1$6GvZ$vK@4-ahdvbP#vU8#Ha#TZ3C#p2ZK5T!fxf z!u~V!C@K;tcFo8O2??6uvOA{9xO|u&NX=WU*4ox)4OBx5M2_@f3JF8b2jpnkI;ICX z9m_IeX{GLUflhfhD+o@~vA0A8a=Ls`JNA`urj*9tM;F6}6mu`Ky`5`5`#MPyp>nM` zBxHj}AbSFYpS4jcjCDf{{%|?8KTx8dluI0m6b}9J0Z&hLyF{VJ=;4Bs<5W;Xa9rC= z<9S}2o`s>XqbIAV=KV$Ma{Xj}s=N{o2StQyBppR2kn5f8spKJMmBLRwbku_8(!GF2 zp7z^V_eW@6zhYBfkz9y%Fr_kM!?kKq?y{Q&hl7*TZg(JrcDs9gUS8g1orK_%!PlT; zWM>~7A3ra=4deQ|;wLrQ*Ot07jZtMR1Y8?_nOvr$S{ zl$4S{@ynrto~?Zg)pKN`Ux~HIepE18kwLb7Mw?JBQ~ecRI56!Kk)SGyI~Cjf_jbvS zF(QoZ*Qq$XL(lpzHv|Nr{hM}<$Af8g><`MZ^4SI^=1l2g6Ylg4nU0~Nh@J6u40Sa- z|EAuiV;`c>wZpmiULNTc!lEI8iG-Y?e1o9`3+-O0pYU*)Ctmo2d792cSZYTJP$lGF zBl0DFu{21p-!0N1fz@i^vVltQiRw#;km3IkA_Hj`2`z4vOf*V>H8pOWyFHxn+y_Q6q$P{tWgA+n*;2O~7l=uY+faMkY%VuiKk43}R93q9LE z()rD~0k7A*{n)3QE>U>Hoakq+9GP6xB+qk)2lVG9hjQx^Lp@;(6p}cMw&H+-gP!h4 zxwlCmdkZ3+V$CUj2p>3Itf>P6h2-S=QqlgmQUN16FQ2yz2nevZe-d+B==qF(e|=Qy z@_qj|W?$#9D@LtanYQyR3WoiU9{QImik-4r%;#mmUwfK9{y*yJU&#zNGU8^)AD6`s z?h4xLEzzTPN*JJ;|CM0|=Ifx>ZoVo^Bzgmz$mNd>4i^2LG7WR%)r-@hgiR*#-}0uk zwQ)aQZXSMZ7c~?CY!`lgM76cGf7jP}RYs4A+al_c|4$RX3eHuxvl-@E72_ao6cA z*q|w6Y)lHIC6Pc*AoUq_hWaNLNNWx`koGHLQn+T-$Mi4~*fs_U62=y3LwxAh&l#>B zAH~a+3zVs6iEaLQ0`gaNX}DM+k#GnsCJxT$(H>;L70mO_e`$9x!JiBl>uuuZ=4H)I zXnZG9p(N;V6#sd=NA7&1!;3Om5@bbU++fiHW1y)&Rxysb{op!ef_E+qIi<{3-Jhv57K^oXV}e8 zJrR#0h60|>*vTI*QJhPOYjCbRte0S;C#&zJf<#~F)5x4o%-|SzrHygCE0l~?9lQEc z9hTSW*|s|VDJi?_wzc(v?BigSMuQ9NzIDRhzmX_3qxMn2#rR|Q6$I()tNY*yS0l?i z#Yx8`ne-QasV}1g+Yp<6k)7?E|IXoHiWle5#QNv?e&Xhc0@nx zsw(5uNJ_qM5p(kv;wWC`S;k4^iOWzK?;inv$o>D|CU$Zr#CBt)GE!cRwnu`x^Rcp% zvH7`O5LTvhgM9htKZPtZK|w*rt#Z0%5O4Ll-Z2_XHwkPdcGQQ!-k6i(A%v#X+q?BZ zkNk15e(8lV&6B^63NY{%2yfUwE;*9l)%3*BWO8uVQQ*LT$kxO5CD0!q*3yR$Ol^G~U zfoZ-o5=nY58DITbBk|S8|MOz-ar`uP_U561z}S9})fujn2ERa}J+RyF)%alDb$~Zf zn%o?#zm?%u{m|`)|?8C6LlW6WycgujSLM#0s4ZpNv*7IlE5Z@ex zGwfE%^Hxg%Aqy9Gct<0o8Yg$KN{!t4Qeb3nBq~r?447&@bcGiiF7ZXyyCcS>x~XR*^^E!2_wCbya085LmcV z?*;W*ky}XnoclE6`4@k~mu0n{M{hG-F{heiWo7$FH)zFY!I2wqaauMjZKE7+m}ASa zx@vfsl?|vOueIJL%t)CGttjN3SeBY~e6jeRXe|ui(g)nQr%Yb`Azo^YTEU+-{^b#-kU&3X zide1get`m5{8)rhy+$E_)+<>PUoi%b+71%pkR!4@fO#0spW>y$|Ct?VETG(RAT=@= zcVe@&b9l3b4IK3Pbf1R#8A5ZsrYtr*8*MZuo~liT%cAxd#s=o_oDmCGNYq0rcN@=SGKgK}VA z(y6C>ZlKw!(?!iTE@$Y@RvKci8&J=%)^frRon>fN7E?LA z`BG+tQ-Qv>;3=>bL9UDXny{;rZ9(rUI}4svgR(h$d&7mamKO#VF1|7vT z*{N$J4}s6cguYu``6XTpw%H7saGVg*PO}C2xNZ&RUN<0Xo0pc*dLOu&_&o zvos04K{K1fqP~yaf9QXp08e5R=}nn~Os@tK;89hffA%Ibn+QA}!9o5(0SG4cKI3Sq z0gj5Gs5mc7&UTFPhvZXM3Z!u4(Rl$aVXBGv$NnKxYH~^)TZdX+vl!!v>(W~Gp>Mox zO5LisQB+oS7@Zgj_{Wiyv3H{X_dJZi0`>wCP)sMfdUwzie4gG}g0autj0p51m&$dY z_H*F`$g+^V1QX-~mO?I#9^SN2aqVO3#sLK&(1-q`uNgp-Lt(Ca=N|&Vp>Vfk0BRV5 zD`H)!#vl5fB?pXA@UBHE0T{yk5smm4z70$evRg4nE;)t={QJT$eGHvsOr?`b>kx@L zLE+>nOfr$}<=V^|wCK;ZbliWG0x#G^v7V;%>>@|9DzxL=*I#E!Q*UFdWaOlTL3*&fM0!H6lm3+2Y_vSeKm{!TD5y zJUnPDwq}E%l^&~QI3L|#LUeT=jrFRC{>;_`G2XDX3~qDMAlH@I7O-KeX#x6SnCbca zo>zNP%m{@kOCJtymCA_&;>K((xA2~IApdHXep~3w^ZioKO64^KxliMWof(v|&SE~{ zb!6GY3%)qtsJOm`-~41Qr-zvWTicm>*yVZg!(>;3r=a9OFK+o!l9GJ1FcElrd*H1OeBG0A@~5+KwJ|9mAaHSU?T2Q9=07ZTyS#6wouXd4 zf6#}jE4E8-pmt~yrMK;viW|ydRPmP{x|YfwzZtu^5LtcjFQHeGaZw+TbnSXJx0(qe z?a2v5Fa#$zvt&=qt@w|f0Rl+6FKakc4qqvzJ2Nmmc!66x+x=TcOo%Auk+awS_naKu zgwL-?n7QB`uuH1~_VSRL_3a(5(Thw?>55E+^bB~oLr2V!uS_)__nNo)$t76t0X|E< z54c|uJY`DJzXD#l!BoOQ6aH-cJF@l*_xx3X!jlz6ji1bY67^t%O15UhgsGvnFH7Ki zK!S1e11pS=^b|W|&l(>NnI;`kpBJi@s!KO7YrX{P1WOKA4t4kH@>>z{ZYf*eacT?q z=d-uNw0Eu>CTqL)G9-qSQB+hEBY9TZ4$)@-iNd5}KHp7-pu%?vZZVZyT|?4^PMy z)M|)iJlkd9wq6 zRo!qG4F3j%oRS%Km2dLSyKK#V{L0I<$$tL+{R-ROxOHSp9g-NeQYG%%(B*oXKMey? z(fb=$J(2iP;v{a{2y+Wc;$B-B%~MKa_lOnhA&IZD#!<|l&$kqg!@m`#X5<&10wU0h zi6<}D;hRx%GAFA}<(adb7f(zBV=G9HU%?7lEn(bxlxpABv6O3>h!%4PA>|%)Xcv8? z4CC{OnJ-Ir-X6zG37k7$dTzq_L%!2j8`~!W+)eAd$NF%&7r!f8at7eZ@x5n0R?Hz_ zDP{5STn$+V3r18ob(ZiL8|vYi>0Wv!4PAsKmqVq%_)~>$dfzmWb}S;?k6S1^ z0{<=zL6Rgxp}W%W(d*>u{)xRJCJ#Q9aM3V_T4oJf88>xgqeeTHailXhHjZkEzR;ep z{N#b>3zxq3BxZ;$tdAz^56P8LB|j05EZ;W|F^hc%>wMI@JI+j!4-oF28w2~{xo19) zms{H)eZn6S%ziUnCuI?(pl@mWJ-<6>C!tk*L)=a^R018} zuIWqy+8t&iLtQuM)LO1w8@f`<`G$YFl`GI|^g9>&lQVOifBrXf7W17*p&4;KJ)wmG zQP+5rDTax^c!LRhhfuP)oFi$_n{K!S!z?HsFlZ(A+s)aM6I{d3FsUuBhfv?TYnp3q3DIzs z2&Pp2H{?~Q_cxS!qF|ns_jO0Xh0kl|h1|Fx@C|Yf)oklwT3J;TWydX7$*P38;K8=~ z-6!BjgW^Iq6;TTn=e92~F93L%QqOnm$4%IQa*Ie4^xF$1+VarNa zbQF51RB!O~D!R2~4j;+2ClCR7Fn2+CmJ4M+p&DVu}3-qho6)?=;%f0C1 z?<9TCSd~fxf}YXU0Q_EbxhAS2JR(x+ix-MCSQzGib@G0c^sO8iD-H$WV#}sJ+fnhm zz?`oq>t&Vd>EN3~`n;wbWo2uy-n-#8Ac669^-ORknyXwOGQgjgh*wXlxea%sD?QFf z$ju$bEdV@{YaL{H4C-WnRRi??ySz?g#Vr=Y(sdon38yP~bpvNZfn})iC@s-s@w)%Me zu*|hbYtHTMZ-eJ>0={4`Ztu3ryq+ut+Vl2EdRvF-mv=UR=Yb0k*JWu{+s-1lo{xdY zuM{<{Hu>Ut>hDeqrM+?VsP?Kz&oAg^2wgVFZt|Z{tbb ztV=E~a1;m1y)RA}oqF=<623f&y6D%70nvxGwb2lcB7_XKxyGk626O7bAlcDIK=uyB)FHs6ptcQH&trh?HSGZCi#-kSB_{yN#`N53k<|lht&|K6K=aEyhx4TORQX&Q8TyQew{G^MHyVTOj@CNcR*(1p3A!?Y%BSi7 zPVhj(4M3M#4@ls{0-_bjcPDArLw_>(#+cHHf;*xz$krj7l)q_deY|*K>8$J3SuA%! zO=lJo*qXWb?ie@x>0232gg!U3U%Tv33OisrZA&I84J1QvtVVtJ!CWOEioa6pAXKbq@Vx5y-8j80?B^UpiNb>RV~d8rf%e-J zrz-s3Sv!AO!XTE_C~Px&)ns0@TiDNW9tDi_+27EjJXy7D?1L+u{5}XGA8uL}vOT0u zz7ZHSvcrxl<(nSFIHqhpX9ob)tSOU~!x1u5I|_iNs{VozUEcn5>%|l5ZD0Qev=g(` z8L#A&@f*RnIGI@GF$3twmx=EF~&2TYOONnvEp2maW!$(YNz0O$7Nk8&&89KpVt%(oMLHauwYc$tM#vP8<=K2Zo)Pc=OzAt{ z{Yz$rrOp_}EA_D*o-)m7%}eZ)@k!y*~h{*G31x9bi`5$kDwg!e_u50Lt5NK$B>SWE zipuQ9h`_@d$MY4Hi>~)pw?^2Aro-5sY3uXVqz{-ThpRp)`17aC<;)sCQURNlc;O4D zlOY3m0$BiF#{^Eaw7NMa5Ovf3dx9`%$jgV|VEpb;9P@>cBA|N?OejEjc3#+i`&H_Z zR~DHYlhndORbAhtS^xz}ut-%5r#aDB346f-_F8sYiO-&5+OTmwc|Gi&+1r-bTc%-0q}X9FhL-`e-y!n^Z}+o-9fy;x ziZ~^K{@crsSD=NjFfLh~baq{sRB2BG8qI<$St>GVFKjclarHpM)@jbifW48Vk7bN+ zpxY-^C5`34Ew9pZg^Ws0S?r&Je3Xc!F%+N7KrOj^Yo=J2dq5!peuRZ>pmOrC8h?HQ zN)8H{7qH6CFo1|jM9gBUb3GpDDDg8k<;$VN@yy0fk}^TsrGP4jFmAYXMDFa;In-JL z-^xPsd}_`jKeyoF_$E?k;8(olo>o)J!@&7gQ^C03-DvA zSw;E{XDfAjKDmspl4_!avqkFjJloUv{@F?qLQqK)Qj$hVL=8Z$I$-i^y2^ju_rAky zh;W4W&r0JC$eF)Dba2Pf0Unc8Q_%Bfs9|v0vxS_@s?7|k#JW8;F+2S9!#-|tu#iO? zGsconXgGINb(`=$`82w$?k(ha0g3Uuq`!c22mmt_5Q+ow2ZIE2qmiv6{t?!-);t%h z-t@$na{e$qHHvlKI(yXUPBMAoM&g%};ap__FaWcnhBf|smx6nVGm@s~X7n;^`;s!G z>+w@YX(xXDhG2BY~299+kU43#Dj7Uoo35-*r%TKihCy=RTz2!anr!Lm_YH}##X4hG#ky-};? zM)&92nq;AAl-WuDW;9e(dU)rE`ikq1XwH}EPg7{#>d4_c@Ogpxp)wMR+B+^Co2o~G zZ>f8sKK#LG_7ZjW>yNDL>DNDcy?=`2Ozz=Qxx_XtQE2l#V7z3f{>iT<3)(Q=4Vu0) zHwqf%fCc~w1w0+ROCtlX6)V|q}!S~`W zfv1#V7jVQF*m3tKH+RO1nE#i5e0S;n$hjqxyI7Sm$}l4fAnY<5naV#0Ust#ZIPOi0 zq83{^8X&LisftQHi}v`?An|#ThF=_NZBVhSPF{&ATFQx}zawyrFJ-RY4M+?csk34Y z?2mdLLCv?>qt-5>3gk|OW>>TBvsBo0zLZ9*4Wv@WzjHJ2vEUDT%^GT>>9$sG`TV{- zk!E+s_nDaWbkK?g_oOQN$xLV@=8Wa;^~o9C`;}b8iv984iRuu{CQ%~ zX{S)`R>bSwq$#cC9Lr4?FPT|T1y?Q*%12PX&YX1DRpv6Z<%{p{fMR|4> zAl%cRU8G!~C^h7KBmZ~#M`~YBsi&0p&3svsWD)^9z-ht6x(!c%nZacD()=k!=#zk< z6`X#*CZuZzD>2w2$&wV6BdID{&!bSzqgdIr>M=;0Uc6ZGy$zEZMR&hAij0d3`gj*7 zM~8nTL2vPPW-T|Pc-T`rPQD_EGWq&CC7nYlUs6=k(qArEC@70^aPPe|+ zP8u)E!9n5-zm)V=M&a6i+%QIy&CJdORC#6pXlfxkxgy1}{So%J_XY(sUTYFQM<9Kh z74u=mv|B|e* z=(S}aHORz$LmSn+Zq-&Y9pjydWv<9e#Z+rJnWb5cJIps1<@bge>MrF$e~gv)I`yUZ zxhn-q2WuweCzgUt(9`E)=K+Cqb*ZU;-f9Z!GY`Xsit{{632LqDqg2#ZnJeAVGl94( zj3z_mZvziIrI`erlvbl5g8NfS)PLrri0Lv=5j@yNL-PR?*FVe5j9jk@i<$DosuJRi zx%RABGUM-Q6=;$*aJ-c+q!%?nmkyXC){~5SLK^o{fr@<0>c-W5B-iQ%&a}JOd_OHOFRXk zEKCsn(eBSmA(mDtGVkkqA9o^3&|KDNnWkykhp4V^)eRBMsT3f>W)h+9HZ>kEPWMLbGo7XBms^k0-h3BwV zr%VV-ZZ6cO3D5N;a2Yy+@ES>#!G1(MG;!x8n2RjU-n9OvDY`{?f?c)r+!|AEbm$~Y zC}XiD&bBSXxHwD|au=E3fV8Z!DpGtdhc|~;zG=ydyFo~ai3^C5=oQIy-BtIKm0XgJ zi2UTl-46{Kax8B8!Mn&*U(-DG{qLcv^_6j-$6E=9{%+L)1E?4;kx zvlk*2dg*z8+NfaE^PQXTNz}^E?D`a#qo>Jz!3c3v(ncLF+E*ah4mV zR)OXz3qo-1SYAYFb-A5WgH@u0+*)8I*^r3`l?awOXE2-({O9CHrN(+x5r89Q#K45o zxq7g3(54x_?0#PlvHA@p(bFh$Ec=+WZ|SsR6{x#*qRf2Pmoq5MXo*}+v-w)Nn>~Qz zR_yvwz2x=I;+G|fRZt}dsvON8v(6*JBhmkhw6_dy`BE zj+vR6nG%!C%osB>bIi=l6f-k3Gc(1^C^KH2bMOD0ccx~lrfRD6Nh-B=_Xh3m_59Y_ zni$K$i<6qw?skAHRX6skjGrsK&_pI&H>-Mo=CmKZ%q7!n>MP|lt~6+M1cKSuHn%$P zM}wo&D#&MZMZtS+kF}IkIUa~v)h*pQ&800pjuypux&>JxnShq)>j|z};jF^)b zo5NF;Z0dwtPV;R^d_vJavrFO*8ON6jpDjm+dkTM=regQJC*I(;gSGjo3*s|h-jw^^ zZ{(1&f-}SP{_%WGDG3Ub&Go@oId!}5DhjgaVSB9H+virRA z8JhS@w`}7OoMMiq)4G=<@XY%-xXT}D7T1He&tUnF*9ifT7|BgsZEA{_G+itrPWn&R5;?`X;P89Uct97 z?VqK6sS;7ON#18%MulEj``7AEY;_lg=u?RX2pYT^x7uCo-EA%*)OgSZ7za?cZ) z$5i2my>hRyUY(RM7AB$B9YobEkCe;jG@@^P%gK8H=PsJfvB*_kKZ}>y4egDnE#5o( z8~QNgGLxK!Hd$l!Mo9}YG9woEH!!YBb0Zk3xH&Ch4)K#hKys%!TQK-AA!dC=J?@K# znEL)?NS6IBf6yNVtvdV^<%WjFAC)f){0x-b$j&D0xL1H12W4zJ#fH;yrYCF4Y8
SOJv_1tr30y;P`#mgOI=ND>pN1ND=aZRSSOH&r%omB!wp!@hn4r!`= z3n9l7K4B>>Tr%gk&58;n(j5Og7r}CuP7;y|%qo*k#WxDy8(e^x@*kfiu?t9RQ;S6> z<8yXEnHtA(N&KzzZk)1!0}j#`qoI9ATFKc!{MAln$nas^;=7T1Jh#Pg8x5>s;!{Z? z{-TelqiYE1WQ4-Ym2Bxd!LcV;v9zgIm19+-{iz#e)+Mp+ge5LC73a4LHcR#TyYUc; zLE#AhAh`S|w}>+&X zNQj6HikdU7DUp&mGW_sly8tapZq#@uOooR`>M6*R-OCfaPp>Yt&k?y>)ti!X02grW z3(|BSRf9J5N!8$deX)DIo2jJY&Fvla<#>cbK8PB?0X=6H-_Z{&_7OEre~x#J0Gty~ zv=ms<-)+EXaYr(+A;h$iM));#e{4&DBmth5$3Mu&e?xUDgu9!QSP=u&Y|Qh}j_SR6TA zx+zTc`til`@vA9Nr7s7i5X^pL)6J;dYoCf>uGnO6!9G0FErx9Qr&?Ul%VEE0(Ovp@ z0!uebdpk72rU`4E(Dw+>m_4Wc=4jDAj56t3?Q70)#GT|YS9nKl@x{rwEMb<|_EWGQf=fJEK zB}akW{q?2q+S4U44P=3LQY?fF9NebT;EgL zIsRY|Gdw7|ivX6|f9Cr9z+C9E@aYWQ%47Y+u?H_RW*5lee3 z3d2vyEO%qOg($dArfMS9f61ed9_yN z7BIv0q0$=n}lAs!|C$eF?U}lg0UjHKq31NvE&) zV^}x0*LY%A3i6IN06sL7czui_33atyKY{hubhq4BPG)Iu`41~__oY3dG61sTzTsRv zxr9*iFh0_&nNJ39w9Jrm4ZN>Nq!z73d*SC@1zKGWLP-8K!F=*9feW=J9C--gb;d## zLWa#Pux1wxw?y5aLsNtu}&=RY{hT{L04Ngo|?=5<@jx5R)B zlUY-nTYos8`Qt{`1#<8_AO+lrPYB-QehByySY~kv1Vh??zNseDbq0x64ldM8&BAakRI-7!>Y*qWFROaw?zwcLRiY;kboAJm$cT9 zlRNwS1EADoE{{8^yu7?^9&Z0&77(kvuz*HMS!^}==*?G_5Z(lo`}(jQ_W37o!qz_Y zCny83(GeyAAZ;iVau8^~x~pJFlraP;PoX~}*J>^CCaHJ0f9zrvCZC@*9LM53RBs4c zpD8+Ar$$`a)|bMgX!x4)|QqxUGls{cbsPciuGR6V;0=*s*S(g6eQo<%1O z^p4dqB}lQFXOP;~fN*CrqxMc`6do_5nk-((PtI`WfmUW`bg}&_qRmaQRQF8xX;h?Q zu09xBrNwbQ%s5D$vjyas^<{S5_t<)oHS(%AiemI2KVdB;UB{g?dU~O-vdNKiG$dmj ziJ^7L#o~?U?$=~}?F4)7IAyheHREYJ%pHUl_howo$0}kCxxJ#dYBTwfr0e7Lz!trc zy@oK(Vz2_$v~e}TScP*fyTd3dybH$S1mybrt0U(`=9CGW-U(CzVR!py_wW7Pi7v#t zw2Q@JKvJZ-TMS8O%*-nHNliZ0Mx2B<#~vY9rYJqqOt+bA^O@xninFc9aHKTD0)q93 zZSn5Ph}gN>*vuU3&|Ghj;{8x2Z?d1 z3f-w5=WnyN4G{F5$%D%E0`+c!P_Re=1MF+W*6ku7k7D6M9FMH2SvXo;`e0il5e96d zm4k~?Yk8Bcw>K3kc2)2V&>?pi()nRlnsrwS77BL4X-3QJ)xvMe$NeNNo-Mi+q1pfA ztnk#Guo3^`xUw_VUY2tET^bK`7 zHJPG8uzGiYSO!=Q;+_AT<;eIZW$D-eJOA3lEtWL4U&^*9e7NwSKLNr^e3vR4fAgMc z#&!}1)*W_ZAW=I(REFR0+ND=lF6T|GIG$gfq)Mp0a(!T_WVZnc3MBW`T173Fw$r7Y zvo^%-B}oYMOt87{^&$XOpnXZ#7=LSQN~;6>Sl*{LpF`dy=Dmu|Xyx8@GjBGWKhZt~ zHjD6Rt-qk}rB2pC8t6KN78f63N+(~FgNj!!w>n>Q+@a*dy?QrI_00)le`1ac$*vgj z6iMRQ5^j=G(Ol>m4CWYF$eUw_r26c#7i&C>vNX2k#O%)K)%x9h*4ePnLl<#xB6h)AFter;^kXZbQR z=-T`rj9DljLR|M?-%FZP-4fA4<{ zWz%zE{0E}G_7#^ISv8K#Xi6zQwarRq-0AM}_K$7f&pq4>uw2bni2q~d{ojLw?(zvW z`rhb$Z!fpm=mwx1_f~!~K$~lxi7;5_5WVHZLWs}yZu9(?PybXzgMRh+`zs3?gwoSl z--6UTQJlxjsV->3ZVwCPY0mj>XWOMsg`zj&2P|(LYwA^RN=D^UlkgR3OD(PRO80=4 z_e`ZLjcs+pH0k71(&3Ut7lSVga;Z8Jn42i1EtyLYSf|5uW%|KQXTKOI0_B`Np;RjF zX5+`>Xd7lZ>xUb?NIjGKUtAK|PHbH3;s>nU0(BXI}b(RgA^=6P2}OmMZu5yFjh zJCmRe+!#5^X|Ai+SvD}5)Y)cbe-d1vc&{)OV{_!(ss{IsA>e;e`97^z8tToJ(L2uL z&|*p){{SD>%nM+8Fyo?`|Fu=}g+4Za3kAjIN0vD>mZok*>h-V7EZxb4UiMW_Yups@ z*Sdohqyh0C8{8D^*nh7^i@!CLDg2w&2)p;QuZ){R8)VpqDu;OzOCFv-o0Rz5KI=fRnopk zQ<5`W&e=(>zA&8>p~wS`EPZiQX@V?$v??mC?CCUe{36s?D*+H4I`}oU^x~r)0V^L& z2T&$$-eupXre4!L4mL(iGh#@R)>uxi;ZR#CtaFXYm0AASS(E1A+b3@z5Nw++xwjrRSKRI^=SmPBZ7{&++K4LAyIBUF z$njARamhF}jkQLUAbNPF8oPXlM|5r9PsTdh<-yzOxD%(U)8NK9hL=OgYYU!u@9D&o z>DwDy4uq13kSydj50iby`AmE01VpQ}1Nu2F2D($3fH_F!<>kSiIhbu1zszqE9@i?c z-9u}=Q8#0@!Ch6%9HM1&)}!css4n3ZgMd-sHej}-1z+q%Y{i{JeJ z(LggfUWg^bKad+peUSloq0l}ba`2S3OotZ?(kL&j*lh6E_d&Kg*3BW%(z`jCp`8{k z(4gdYy#(=@R(Y=W7lDLEsVW5h>Gp#yOeL)IpOUW?+>RDon>_tNoCJ3|tx-DbYAg-X zOqRij`dXQS5J%Of^L1cuUFxDejF#@%=b1!%7ZE$BcgYQ@&)*+^2c56fhyNTTWUV$d z#n_G!tSimVGM-LDO2qHTtZZ+t^%9~S(==0D#%7l+WH~8N^leLy>(c{LEMaZyQO;?% zX5WloQsPyU>)PfFya5E@(^e8Y>Nvl4Pni*6K?aMxj3_IJ7~dGEnrKGV&Zm=ZvxFjt z^o70{(!3{&&U&q3y~(gqe+G)QzLdyLB;em!&Lt_agYp>vIG7bP>p7f;cCR+ukraS) zI*>}||H{fN5*zVmamp{4xxeV|@C#y!Y#AN0??#!ChD+fEmX>`!c` z&G<|f9*|;f)}m7kGO(_(9#lQ-+>+rmYD>lXoQD4-VIe`eph4y4F5rNIF`sRA{s|}l zB)2<32%+G+_AYP@_@(utTOysMd=|TfZ~SYs>g}WVORK^yq0q`!Cj);By7A10^^Ww!EqrH@~!ZjN1weMw3U^pO33xMKPJ;kMU%`e4&i#*=tjxSBTiwjxkCkxMEsi*VLmk}J^I4t7+SyE zaWfJCMTe_J`jLEAVy_Cc*p@)QZq;aG?U*7n?oE9k6>q1y?>Q^w3FdQFJPMN(wG2#z za!c=HH6Uv&Uf1|ug0w{(9FhCvaxD{9mvgI!4bPYj+PzW1Yyz>(5u^8z@C0+eA1KsTHe0_q{O};`g$7d4 zaWVPd!mLtrI`l9s3MAM(KanN3OKHy89r8D@<%jX7F)9lD@NkSoj#{rFsp8S$iT=~i z1-Qjz_;ET_ce1RPMo0RYLY%*37=B-(@gXq zNs?~Y->%~7S2mhqb%2A@)pjMqKRyYmOCjac6vHVKvD;Fu<#4a-7nu(yUs2a>Ue#Zu z(w=m|lRB6@6rwL#RUPVQnZgGdA?x34(5Ukh5^Llxc6hj)HG9sxEoNHBs}lv-@IUc% z^F|}#_H{*-aXtncyOwvsbjz>WpcaHu>j96B1cH(t85HkqWCh0G`6hB;)d26Q;IAyi6 z@r<&pUQnjLb04H)TnVSHPxyFn^c~OJgm^j|g1%;Zzw1Qn$k?jHG-P*YrC(ArmJTm0 zf$_$S{s|`6A({9iB+*)Om7UZYoKxiHoIglYJ_I}crB>dh&u<1x)xRRo%YzeEQ04i%Vh zrpuC;y4sS~hCg@X%DCMd_R)^(656vGW@SsbPoMe-p?T~-Hb|9KBJxJq1PHnKObOKR zJ?t#(zihSrFt+??Js!?%9sZ`S$eQ;P04)8`6`3Xm*deZr%&ljg_|O)V7I1eNu*YnG zudsD-4>tZriAZzk4O@y>a;$#;zQGdJDl*b^Lg%X)ALnUun-Bqh>R#Zw97R~fxKsUr zN>xdY{LFx6On@YrME5i7&f*Dv48Rw5Jx^-Jen|T6BAe{h|NajPa2QjTHGjhW5akv2 zFR}8)=3?c%E|gXZ#~@{@U=Vu=GzEq4ubH4P(}De6wGG#cV0_dpyWcEvat=2f*|&oB za}f`8O5i;oVH0WelX;)XL4}aMR1X{9`EKDQo}{AV9PwYOvP8O3c)ojv2v!d(5GV!xL*d0N7 z8@#up&f6hFWwEr7(-cq9lsVxqK>-xMw_8KUrX3DWiBE3Ex{9X~3r9Cbp|coc>0go0 z3G7HVdLu8lq9gZ%Y~5=JCb&AO=qz?YE*X|Lchw(dDXWi)N2w^ zvfYyOpx9WQdUGCdz-v1{oXyF=UYvPuZ&iQ!{ImN$k4mTR43*^&Rhlgb+!VuhiGhIQ zu$#=MkfFh$)LI}-c0QdNT%*-^FeGjeJhMajDJ~8#7LLT{jV)^>79(CpSm$)Do&Eei zR-%b9s%dK2g0T{v*Q=u;*iO(?8jtIK1HVirSEf=cn+gb)NwPpw`y5S^B4pWYsuq2n z7bX6I*86j31V4*9RW+z$BqX809}x2Bum|y5WTgO(cxV*MtlO*wW^a*?TkPdTL#=cI^G1wj9G^4gTo8SStK6o6% zQu{uhFeNu&q)U}M>B2*fxIQHjO5E|^a3u6dZZ*EgnY&<4ws?IJ@8yMgvS$@Fsm`;t z_m1iS#;qR+J6mGUKlq6FIN~MY(J?hU7djMkXUcuxDO235nT*G-qZP&O;L2WdXIzJ> zqH#{^9e8&+B+Bq9DRvV-RdQ&~R=a&L;M@d@gUYTmXBlQgDk@& zZz=9V<&Mb2ldrX)j>O|Nqcp>P6ItFRjHy3TlJ-g_TKM`g9)>Uf{(`dd$W8rG~vmpQ@VIp)v4dC{Eaq2sQKVrxAqQ*|kDK4{+k26X=&S?N1^&SZybP1- z0183!IYvAklFVV&-fdF(M$2nrvwn3;ojKLV$)@w@?~ObLgwBRp291n#chT}Nit(W1 zkCK`XVO(`<{S|yV7UP{s(%uws4 zLg!e~qMRgaZW`1i09=;%msF|F8H#Bjgec-lmg)1 z)(8qW`WoL9>GDvf4Yq~|o?vkCh4IFmkL*5n=sp*r`y1lXoddY}i>_UtcOoqeZZtGx zSp~{|=?49d%5tt71Nb#oqAQNj`m-|v{qDv>@Z6Iv!{l+8Qv^WiF3}T11Q|wW>@~H6BCv`1AWWH&yVP~n_gWMpavjtz2Y?JVnIAR7lcT@}S1fZ;WSs4%+M8Tv` z=^_@4XPTh@+$W2G?(T`bSs-||H#hAW6;c$&hZJt^Sv=rZ2?bq3T#zMOEN|}4v9o=6 zpvpnvM7O z?q#0unZ3Uw>EU1!OhLmlvBiR|xw%})Ma9Zgbo~`-?pkDmip4ef!-!0Pk)8O+Voj$b zsnnK8dCBn1w2ZFS@QJj)h|^f)(h0Si&3sS9TNe0P4kl44`P_cX+ZOfaOP!4RzFEV> z8AEun-o^o!J*0-fG7mMu?dylyp2Cv5f)4(cUi+p1HMtoM?(}p4eiUPEYJ+L{&{Qg& zlGQ8z8?7#h*zj_e>ROHFk2^Uc6)X@K-Oh&qd-Q(Bdyc)^w+Itu&UY_1_7ktL`CPZb zZ~4Hts9mkj=lK*scP1E-%E0=KD%pke_YL;AA(A7=rFx@a z;1%=H?Y5T4nU`Z|^V|Mg|IMOSYbKY2B?eHneU3|3n{V=iz2L@^J^8e;$c}wcB?HYp zC{4zK`B2A`!}=t~^Rz;iQQ%L)XFBc|78*j0;-1!FhvcSt18-D7WMkuOJ&nYAQnP~A zib2-y8(l!E)SomJ2|e?j`!g7VH&h`Jk?+3N$KlVjU<=mGk;N8u$^s-YF~-+%b&*-} zm{Kx`aIv2M8jnXmOQNLa8-)42q}+E^%8}pzOGFPVJT8K2rg2XT*gF35>(1;XvgH<1_Pw^O~ig=Z>+EnnCNV zo{H86%?JhyADrSWxaoHnKm08HoX*=5Axx(n><)hLL<+_@kNdF6EwyWgw+ycu7IV8E zQfU>vi)2WsjV?DaPM#n9QjYqao!z0mkabz_Vt;$Cz!7;e@|Pdh;^9oho<3HqZBL(Y zGR}Q()$0v@*yUr$uX`T%r!w@iO+D5*7-4*l1(w<$U3B59iOcbpduVR=LpDkVfn8yS zjt+|c3)ZU9>8yxr3uD){sOPA6%4vtgV+K`v{+|9TBV}LeH?SkQ?7stHMmb8HFsg$w z@06n`xUxS?)-#b4Jm;*>$=Wa^T5hOV2S&d4^^>rihLXJz&V+k^U^ZuWjy^=13-|y_ z+co=0c|JLu`_%Gf(!koe7AYtMOdOP8$z5<$GUB&4Bi=4`m2c~JRCbCcwB4f~_9P2g ze?)U&L=RG*sb|(Dc{95y$L5&Y7&rxdiF~Zqcb!pEMySw8VrtaHj);Fzf8)-q#{|TC zd8t{$sg*ryjRgXq&6~YBAE7+u+42w*w$6<=ub7oHXA}435K9Sc3@=VxH~97<%=>_O z@ifs~_s(8)46J7lR}FRbVtKHKDxo+i9{nZ4{%(~^Lqi-fP@DQ{w@yGgWl-ft;UR&( zvnQq^(&qJOh%o#a7qn>iS;hMx45Z+E`w?t<;^oij)%#YyInu!|DcA><6Eo2yh38a? zVZqkPs$kE;2h&pE2lQf20#Y8@gSDkoxmM7})#mvEF6DS#Fa0+uDe??#iRtj7KMi z5;@Z^3siqrc#ht36O8aM33($ zPOJ4ndubW%5hI>Rub<_pYFJvbNFI0ja`Uo@=1W;H_m?cgjL#Tm`n&3J3_w%6`(N}; zw(Wh1;pp8FHnX5x+H^p)_k397hH97(Y0=!8Ee*Oipx!$Ro0MWIPpker864-EkLF+< z*kYJ3bz~;rCHhShUtfjnA|xpK zLOGzZnFe~{bE4(~O`@z~qs}o;rC@uxjO>f7i7+s&+>P4}Z9L>{WP=JD3gdw*xjHx_ z4bNc#iJW%5IAnRI(u$REd|+|!q>czJDH}a#%xSRG+gbpZUk74PCqrty%u&gwbon>? zPu}Zjx0pYM0XxNKNc@tnS;8m#^Av2EB7sAXT(eJ}l6{y3&ZoCowpma+843EDE${+C zAorzUZ3<+}jKvhO@!0Vn;Ss`N@bg0vEr;&{r4}h$b%hav_2-B74i==D^WI-Udz_hl zbd`Y{@62f0{+4tO>Mk|3>Y{+5SR7x(Y!>GcU#(SdyS zZ8VB00l#nXA8pr|Jiid4KKpw399zUs*!AxEU(T-TWX$F2W3|$H0l`>f07Zg6i zOJ%urhz{kVvth_%Y$3HBjayDPk_T_&L}5uSVX;JkkN%evt=TCq2?<;KiS`qX)CXD^ zn~lR<59*@SrjXxzPYP1x(NBLoFH}!T#I6j{lhPgtBUMUZw(^smxSJWoFy+2|$sf)% zQD`T@nKO%jJ?Nh;pbBPA;r=v*7kmO)@cP?s?^L?{%)B+%*W{{yk%~x#Pa&ps*k&h? zjBeqkGA`}2@vJIx@#nUY2{Kt{rYo+M>xF_Az$OP`oP`1{)X6Ez&lSy z_tUT9nlN?BVIR$mCrd|$RU>NyjM8lRehIka>fI4 z8+>1zBF#EU!s!|VahnslqZWmJ8(V7S?#pnK;6?I=xHIXQOpLH5r zLkY5_+F>Dob(NdHw2z-T5JBOW?eay=%oNPB#4x5Zu?5#h;%YSjKkJWR$~Aw}qBdZR z9B98(Jg3MsaeWl}dX>?8>kIq$z#`!1hNTUmcF)sxBb8vK0OUa~lXK4?+bYeUUsmwO zR1>#5yJlgC-(QCvhH{qjq;K9*#cf+1?ZEb2%dXRBzNN^ieb{UBJI0mxS5l?COm#;? zLTb~;d*=yRmqtiaB0=ih8WurveTsilu$uE$@EhJi{iV$^7^@M+`mBj-O1~Dv|3V!q zV`$>g?xshP{4sJ-u7>IpYp6PtO=_jfdHa6>xUdEUnj|#V=N?#wF>0sAJ!TW zrX8G|1t-gagObN6FW_Y9d;}QAp+h*1I6ALFi{cwOmN2cgY0U~wWw@(3Ab5FYn5%n=9&vo^wy-;zt zUV{aj2>JPefD&`U8J;!^wi6EvrLw&(%W+Z0Pj}-BUvewO+(7tHM@{njQkkdJjYgkC#?7U~= zuruZ<(1jxvrD&M&o(t%2BtExFnn@t4^;0Z{Cv~+I6Zl29m;QWx3W6+y#%Ao62#Oja zuT&B=wj{4e-R!+-yXo-;6K1&XZn+fe)`*&-u|X9+*trzPbL80rAN`%O2kIGgDw?9f z4j(Tf9Sxx8TWy8Gwcd_&oxzbs&ufoZ?W#v9l|ZcBQfhB(2f)}Z*lBK*Qzcg*?h-@d zb*1p%u&svjUl~r!nHm%8SOK+yex7Q1$K2r`Q5fGXPkz3`w5QGwB6H^=`VJRJji+%u z+Ukn=*Lo{>tuYw(9zRe+$$wlPcszfJd`qpf#pm%JW@?#&?Q;eybsZ=^$W&%L{8%y{ zwZfhPv)VxK??HAnKjI7(mmX2erzmidDJV_=4<#Wvrtrj=Hryz19XL7Ytu;arJ5TTV zLinydDfI7dt!C!r{9Kaw-bK2)sb@6eM8;1Fq08@?`M-&T=H|yEK`L9OS_Aeb)%E^C zdt;>yd|t07rpa{gC3D#)F^~gXtP6aQtke=HzX1~(de`E& zuOZ$OppE7Oh*bF3>HhE66Vj{$ty+|SoNc!=&p&Ve>m#=4r6p(DE@zzo%bSYP!(7NQ zr~hC9pjKV$rR)WxCP^k`{NJz>5GbKQlhm5_A5%5ZpGGYRVn9VkCe{Ve{h=+cCQSxI ziLJ~!+Z~J$5fd}96#asTh`5>!_@{Nm3T|#(AnNgTY4khW1jxcqfeH;ha@3#y~6o^IDvA<7c@!mW{bA&}|-UUx;#Mo1{a5N4BW3p>^hK_O4+#I!!BgE!_)+&qNpH1G-E>m&!__LVTN9}ooOUo=qMRw(>$E}I zBuEjFV)Ui|a{_#jvsVWQf%NL(Pz33Z3uKAMOY*Jrw5j}V;BKPa(E75i0_6nI3po9R z;W#ighQnLT!iHB9*Ij^O645nMv9w67wSdfPNoxhfEHoI`TXj409wVT4pdEWjt!ZDD zqie}h#SH#xpOUIs%*KGop}x9boT>+1lmq{qm`thlI$xtmtqoi^ur`h`9DRY;?npQ1 z$N774`a8<{r{oguz(YvwCP;bdOzGzM-v*IZWe>%H1P2AjYZBxF_cB13qO`iTJwv|ExAobqgKd?})HXCeqU++F61bdvP#= zgPTUHk=|HM1ai~64qL%w9GN4vcUD7;^-DFcJp@bekHk*GdLHy$nA^uFuZdE_Rr)Kx za4egxj5p7>65ZRwe!mFT?f$$4(A-hY`l8prT%i| zCo;7TM&q=%ILS#|%-w8{{eRIle+s5vI4<2ZEomdZuYGmImR}1RfxEn0bqRE(Uo&|2 z^`IyC|D|OTM(*fu_m`90OHO&!R3b$h$VfM-g|DWI%qjA;Sw?_pw8k>-~E@YQ%87#-+gGa3@!3~2G zq-ZP;Ir2UG4g>cFN2+`NbEY}gp1Hvo1~`VehslzLTS48sPMN#vo#3QA0gC7GS(`)d zEuW^y7(O1h5CIulMYd{4jC-|fo_n^FKd+zlUPk)c$y*Nk3br_j456)E3{c6kPfc+9 zBI0xSC8;6pSo2dcBu!$+Cu#A^^$hRJ+r+2!XvW`jq)$OPiC>9P=b(l9cjZ%44UAN? ze&=Mic9=0^3h)_ic6c9iUP+C6!AeWZ5YZ(vvH!rEj*%{q%DP2!We^8Dx_$HD!7wP; z9WE0On5aNm95+XGxTj%Mau$olR{OQG+l$60kSb74kT2Z`PrZv{3B_4#aYBMd^EcEp zW06lq6g6pT%&5q{mQ@i*v9HtT-hyX|OKUX7)VC$|{gHFoRur}C(KLKz)xgp+qEZLh z13yv-{VhKBbB}@YUmE1m9O2sypzr97Me``i_gD!3C0TwH%@GxUqYXaae!>HMS&;Pn z@4rOIBE3(L2$`tr-Eq17LRx7zK5DuIAH`hXK{#T z5qzQlI&UGJwhHda%oIH|rx?;rPBJC1&Pu`WgE|g0gu@nehJ0lZ-04h45Pe%?A+f`1 z1ezPSz&j6YpKEc&Dfr>GB2y^T$lmHDZG5v5Di~#M$f^%198}TPSc&OE$RO#q1A#&; zx=q)%qcdUALd(raKq!nprduiy6A(Li;7UYK30@ur9 zwUKADX!OOr6V+u%r^OX!S}A^ymfu_45xZU<)p`G5PM!_g-NpRyg8xEBLP|1Q#S)jm zYGD`~ivfapKZduwhgDQQ?eTm!JvG4Vl!JGn05-^vJ=V#ru9psf%ulD24@RsntuNzP zSpk~+RDkFOJah9{Que{1-{BRWzP`W1A;C<*ZhZs@mP0l?yN#Qv_tHJtDC<|JC-X22#vJqxU{MR;Th=(OtB;U(Y{up*_uuF2sB?hTPOM752j{-Tx*+sINS)I^ldWT~Qf9 zWx+jp>$?5NkQHKUcvxu_DnBNs*tmR@bpSK=9~MBQ31@gL%)Pbd79zM~4z~Th-Mv}) zg~EQG>=I*GFk@;YZhrOlOeYfk!{_GJGvr#ay>K6gDa3XSoy_Wy>;=I>+O(Z;b%B2y z^_?PN>$7L`%B@-gGr9eKf3J~o$H@Wls%trsK^Cz3rup&YJfO21;Uja>IT>`w-_G1* zYkzwL96Z=5Qw-&`^bt_Bx52dvYc(xeutYu4nn;4~)nlz3?zUO`dhbf3*@f9;LiP&QtPq>n-V~ktXYT4uYZl{!dyEfv~z**1_QW#BYQWdwtJ%Z5tsMVL~Ch9J%F3x za<)l&X$gzTP~y1Eur_sM-iE>QHDx!<)^Z(hf4Xlk5(f{cxK<7R94{`e-X{dpA9ucr zfVGj%)S~vYOx8Wdk3fsLQ45gbF9wg4Ibst|aV|^tE2Cx(uOYKBh*;&k*4c?v&c{~U zI;SctboP}zU8RPC=~5KuP+^ITw4US;yc@6C_l14q(+~S<;z+RvSNifQ;G)nrmE+cs z=h5kCWNB+(?%^rp*>LjLOLb%M86|BgYd&fQN;jToB6@`HK;^ue^o1rIZ|=qfcIL+H zZ#fKngTILu$EN$;qd%%rf|<|sX@ySZCp%)C@#XAx%hGs)KD>TK?O)Z#)o)hT%C=~7 zRw0ITpHBI`ABC1Hf%msgt2dBF7ttPGn|NdP#3%y&R}VO|nF{&Vea; zLaTK*q`HE=LIW4_29AmOUafVBGGzp&hzBkuejDWFprVR#kQuQQ@z^W6$DQjw65;h4 z1}#rz&QGaoc!%D)>e0Z0?q9}+Su@(zV9yL!xnq&uco8R3VC#bPwpkG*2ZWqo8v}i0 zs+T-(aB3oIowb>M?JT*jbA4a`ZJf}iuntD`2ws3#m48^opBZHx>D$-U5NK888zMKt z?t^cwwzyLOuw;+r*E4^+<$vQ%u2=dTPG3hzYwe`$q6mF;=GDt`F1%lgYpAq=NX&bh z!LKl@O?gk5RAxXMeZa2gy4(!m&$%n8qn97gk_rJ&Wp>1TKjhpe)QDE|qYZ1>%Hxlg1#_Z-FYHi`zuK_podyr23aH|I+x4oG>?8SRMAxN}`QWOxN z*69`zA%i@$>+2)V=;Vj$iQOZAalw--Fwd~JtdD$vjQX8sh4}EDK&%DZU>fg8S=$_x ztQXYw9Qgw+rK4hJZQJUoml=^DW~guoZnOcVCSN|qJaS7Rr59E9yHwm$@g9TY?moRX zPDgJp#$pZFt`*#l)l>U`1Z+jP;tM1yt?vs0Y{P(B(jVn87`Q!x2d)*|FP39>1R??0 zo9ZrId<92Kq`bdp!G^6cszvtm(#=fx+{7n-ph;Uw67H+608=n z-rs9Q1b?0FdK+VcIX*b@wP8Mgyg@u5lWy^II93%S3!mEuM?KAtA2MAA1}Gsm4{Ip3 z&pjovF?}wW+h~;Slp_B6jN`i0-5B2}e61t4Jh3>^@GGU9E>V>^jC8VHm0nEW>?;B0=Qq;s6jly7JX2OqA)8;L zCd9jsmLmK2WUo2hcoUp3t;SJ{0p;3V)&LvM_I0bxw0h8qEt9MJ}>m< za1|7qU{IL=hRfAt9;TqN?U9gI6VG#{x{$zLzdeA8;~1L9ZTL#R0H6=cyG|;~g-^ zB9r&<)TQ&I9u-!fOV2cRYeA!!qV61M%q#VT;coH(%IHF=lXI*&9M|M$FFxv0$JbFv zlIOkaV!AhqOoK|j!yvM$)fL`u6fRSC$_*TrLa~P@$^y_hHgEF@3mwtZxI_jyByqf2 z!E9@BB%VDZ2lPM0b({7FV)#IvTh}yt5{g zjt?+W-Qx29V^`H>=4gO7ysHkR zxRV91bkV3}6Cjr|Unhq~z*8KK;vX*py3#9}1Swcd>;21qxH_q)!A|S;%fy3S9#i8a zrFz)TDU2?X+mopXnVJnf0)~o29gDUbJMytX;4>$hBoctvHcx#8GCDfCHzQLJS}ZMn z0=;&DftGR_&(OHrB)f*|g{8q-#+=V$eZqLQij_uMOW~p+7Yr)Gxefp~pf(XMXqi^# zF->}t<`MP8gFsR)wsYyp3059)Gw(WBdUK>=h0;i%uBB_$@ydZT`rb<4VErgFhq-kkZ!juB6-0gRXKjoA4(@u}#ySP0UKky zRH32RmevW=gb{9*U6-|+Se=dufz#?T+8c^1oC|49KR7>^qbD!H6?5eNK<8gP)6q4= zJJ!?Z-(*ZjGgFQl^Z9O-`~l3MCwa-KALT8@FBycvyj2{wSg#WN?k;_m`nsZ97zG`M z^4NQbw@eeRYc(1-N^qg}`m}ohwUdy@NDt^SbX+X`-h4LfjQTa$YQbV2hp%8K%yZTS zv}R0tX=|JZ?9&&^TtE`?zT_fcLv&HzAGz`%tlIT6;~>@gK$k?x3Sj|i@z_FkQ$BO@ za&ndy$&oX$p}+7aMh76#&0FDIaARFxqRcT>KGYpw`sSD8>2VPE7A`-#C7HS9 zb=jTp_*u{VWZ?>=mY%y@k%<+-%4@b&9Ymv%Uo$2Px*sIU;x^J1i^1B-1}CU}*4)nK zy-3BtjqjlAF8A{kjo+Db=*L043)n^kg<8Jj?2_0Mm zwoBcaJir8_L54@-^1~s?HO2C&^R;NaI9}~nO&G_4D?NG}-?}!ME^aQv3^Y6||;?FRcSlmv1dTH^SrS{{csFV|FEa3suuu z;Z0JGF3v}76v8oB!zP98+5~sdiX%7>R62`?%Vf1BqTznzd2f%(6i#pRbT81JIQeZdSQ{`CknA9o)a?h;qI|+|HA} z!n>=20Y~Wcj|Gyo)x6Yu$M5~ER{xgqXO~3xF-LD4PRKF6x>cp?vYC|vw%7@*_fuY? zmmZ+GkUyfyB5yYClTmBhxafirU0Ft-lD$5L^W|1Z&U?==ka2lT>3OjOtj*d5rjlUV zO`73ClU%9hXUUlv(6UI|xW}Ga5!dPUgr$&IA4QmVmS}z6q_gxzGg-{{6<=Yj%5}C6VMMW8B=n10Z#yYS`g~f>U5?A%cX{Ra9vms0pyw`aD0TL40yM`c-4K|~7 zOG2z@0EiSt$`qAr6BEaSEr1@2768L%b8qT+#Or{^qL&MdF`Vj0tWzS>=Lek&} zz1^eLiFUxOH%#?jIALvLDOHNp1}V14Ofcs6FxGm&<(9*xro@(&(X5fK(G+3h^Z1fa zBZ=Dji^kQa=HS3W32D+LJd_GZ($C>g1eRj~HSTK)Iez7Jvv8lZ+Q163U2=AMXq1aP zsZpS{e~Y4Sk;3`?(16L2QrzupOoseIbP6_$$DwdCXl`e5_Pg%^U(9T*XWU*rFo|@EhRKK)c_|;U%8rN6*0X0rtMPhlV@tKAIEuU7E8qG`O#25Jh#Zc<_yP*1awFI)ClG z*w_pB0n%tX!+-4=KC4_Ju6m$w_{0Ij!;@a&e}5)8l-B%PP^hhX!~h^)B*;7&lk;mg<;N zLD&2^xd38o)B8`!&-4Os@PQgc=wrcc^riH%cHps_nlX*nE7atK{D$vP zS;r>ZcoP9)ALgh}>I)fkCRARgslO=^(ad)p(Yx*&IrDS~&gQ(?V)w_`8-*mr zp3JESb2$30&_Gdc-<`thd@$ZJd(T|9y%^xG@=EK6nxQiJ$=pEY&s&8msBABToz|~* z3gzNs@SLq;RQ!a626heveH<_mTffTJYaFcVQE+`Gb$*CyFONz zMejpkk^wUgbU1WHcQ-Pe3c6?LM(prk3#DMj=Kg-lGLa~G%rt1Lu$VGLJ(`DuEn3>s zS=M1OaoAiN3s+)%!Y(hK^MZ#0sI}U;=V_tFk*e6{GU2^MGw-%bvDrqSwp2}F-#LI9>p#E^X%0Sgt^P-&5eQt392DD}hf7dBm?OJNv;^4cHxISZ0 z0s0}zNMEH(v_4Mh#d*zb>^(a;J}1GMREjTwaqY#j<9e|s6uxZk=e_5_p=xy|v5F^b z9iG#fwEdpZXKS>6IK?eRBVMb0h%fN_hBkxaFhLc&ifE1o^oK}or6@y?pIjXEZYbqF zyAwS@UktMLvV|tmn4}~l-imW@|Er_II1~!WdJX*}5qU7+;zjT6($3CCADR}!y4(*^ zsI;=GDo?{@o~aZdl2n$oK=IgJP}`1(J!RnS6F|+xPy1n>qco-Cn{5F2hbf9hxhJq0 zB{hWR7Q+!Xi9yv}elx_1oydg)ivh5iC)$w~MV)W^`H@^aFO_N= zu%UIrmQW?JIU&p<^PI7%l$trKkr`TY@?<7){D6GCTE?rlH6<~OdfE7R%dUB)eAIp_ z<`9^PB!7Y6D-C6Pw)n19^XVOkO(SnuBo#}U{ZS=3O@8_5xEwzBAgMR};Fb*#*b+W5 zFbA)NFO-hW`_USzcd^tZXUk+>>bM7nZ^Jb48rFO{d7!+NH%a-L-ahy#qT~uJ`uz}q z(2Zv}uzSJ)jwf#m3u$U2)SL3>OuP1q$DS&A$?R>B-kB`{F8n(A`Ys9g9*-kvOj}*n zP!0_iOWxi?&iw%uCHg5&9#=`zJa$=D6c$p=ffG`Y#LLTT4?onvMkEriV~!I+bJi7u zR+@&$B8efDne2|C#Ddh=`<8MIiewZV8VdyPc{_+ew@O7EH`!1sgi;~!862d{6ejZb z^v<5sBz3)OvGL!EH3ot57={s#Z*JL*4(pVE7z&)xLXEtW-c}=f?VwUjdkrok(cAS| zL^WBHX=U8A=G?Y^d&dy8w7rNFmc#;r)Z_VdwMhT9bVFb}d^d){#gJufM!Iq)`Tx2)7&h6c6l(3~x{whV-huk94*)i$|)N%D9+Zi#owBI7^q`vvJ|#||eB zEG#mAjcnb~p7qel;z>Kf*z_E2ssf z27Ey`7dE})ePDd1mAqpvUQfYKsMA^(n8CWdL2*qSSGt@OvT|7 zyu=^yTA!ai5^!hzGhRZYH^38 zV@T!>a+j*rip$%apKwCT zO>F3Y+>`Dj(H}eOS8?EB!oZIT7yA3qzWmlgXOG331fJ#ldf zkkF04$AAHo&W_{n7t!Hs$&gA2kTd;job$+q{drrofeLnM38Sf#_Mf-5Rh$=%XTWlH zPH249bc7gS$RN#m3kyrk!=o{QB2ks$#HCl9$`5tkqNtI=j)j?c#q@k!VxZdBugK)F zA&@FqdCnhWI@0;QGgenuS;%BcvXA|dFW=*aMMQXp%Kdq}5+roQ@nBl&gn<;z#@=3k zXEfcEO8*7Tr<4?Cd@hGz$Y8O23#rS&J!1HLA_TB-a5-{$;(Pdk1`OOzhd&gHmHzq} z71Cd_K&!>AQ0uXCR(zuy|n(=oh-4@!QRi&}i72#MWA_L@iUk2d$#6g$kb3^$Pv$X-6) zJf{*qk<#r>%a9s6M*!dC_Qt*+5RK#b`w~X)2$K4|7GFEcc+JkvZs)d{WwVDZwj}`n_N57oUZw)%@syoK>;%AOfn=3uTuLz<5_Nz!ol!~$y zyvTnl!nR;eDInN*zS5-njA*tX=rJMp3WIfOmtG+o(7J8iaO&qo;h>}{dxUh5@i+Ir zF_Agvk114yZ6bGEWmu>gk(`NTvb@eEL#;jg*rlf~4StL|gNpFD-x|y{T5&`!tS4NZ zb=m8#Y2$t>`UI%s1~J(gW7&=pEr!1?X-9PpJJ7vi$+$p2QLZGWqVd9z2{-nZKC3qzg=W9r&nsY~-t3)f zAEe`IwrCsg1(n{d%yn!o&1((T=c#4j`^kU4r@ECdRKwTWX9(t`Uhd&v=T@@d5xH-< zS1I#ik0-bs`r1Ab>yfuV?%C-?C&UjR0F9)3Ob!zg(j(d3Ddlc8nctAvGQS+MjHJQ) z6bl=0c0T;2a{masl_Hr!R z{c^RvZv#xuBioULHjH!0d2_S=-ZlNe8SRML4?!!h2=X*JzQSn{05TqcFGhSd)LOom zpJj=czIgTO)!Uz{ut>2eeZJ_0=*UkRBTRtGj!4)O$!zs9Pe{i;p973K z7{N=hvkwLCVsc+Xo{fuZ8Fsp+Et^VkxW_lB24|c1rodc*&eyL+~g^wL7^W9~77o9)+ zb5jCvaeEo>G+38$?_gcwA>#0vvuA-M2ZvD?GNzb;`Wo&P5vpSd7)_xJ<51qWyc%_T zt&R4zi9C-(WJ`BKh5ZK`FQ_+>-IYCm<;Q4T^{bykt`kuAD^LDFdbX_yjiw~l0}&o~ zOT&(*`wjJXlO^9a;>9mAs{G|gg1!=a(Kc*S3!kmCMZK0VnOjdP!0HL(=5xCRULGgq zz$G;fg-#D8GL=N5LH|%PM6yz}9Jv78?K0&-C-S9t?&vxuH9zQUT{66Qsc;>UYn2Wd zUYrghqt#qjHX0TJ++G$&qcl=Ih-6>G=T;oG_sPsE81E-9!GARA_PB$tx5+ceN_1`U z7NZ(Y>a6G8kpmtZZ_CUJT#c&lDIIfUs#@6`1!9Nt9`oskgpslJ3K;B?NqaXX5mkG4 zmhCH;?TA{AcYP|`MoaoN88vh3xK#&|7SKuo-WUPC&Xej7a%JK?uZgJH*KHz&cx9WX z{SsrLQs7k`B504slnz7758IetJlJ0zaabvDe$rWx%0#HWXMF08Du^{_)9KEUGlW$i zwcDS;(gQy9huB~iP11lG%mX?i_G`uUd7Q&zb)Rae!;=sCqU`5XGQOEfM^R5A#=kwS z-1z1Ch|O#F(v z%C3Q&w~9@4fsoNDhW#|_6JTHno%70tw zz0y+#ZG)qBEgF~aiBylS!6&4#k^)`dPv=)QxoM1;jU?{jDF^7yT-LpxenR<>u?}Dk zW!By9C|A+>>1&DKDSpsKefLg6<)bb~3~$p*KXo+dYbwzx$`i(4`qcSO2fK2=g4cY| z=A_2_mqOlHped#JB~;fjqzM=hOrFil!yuE=Rmp{ zLk1AtuLV;`A|cmcE)lEM<~^$wO)k)VVZ9GhDnoiMMoHt|ix87=-Q8ls?#o<{JE3~;C##vXn z2evrIz}=)6+JHuhxI%GMn4=Os){6LG*()(+a5Sjai43>wZBb1T(rq+a>yk#>buWz`*AIe_m+Bwagm@qzeeM(&C zT~xcCjihMWw~lIrFMWg^)HRg6VH6htMvm3p7rM@!)gA}wC8I?yg|8MlDtKEqkpF&s z!I)SB4}&U!o?5X!U-|0j~|2C6YWn<&HPLawOlVgBD zwX@h!b6nbhX4uWCt-9Y*9k^ya-8=U}=gUC75-54ehA)Nxd)-F14V_AWvXS+A*R<<; z>Xo{(L3>U8J1^sx*0rj^ie;E4%vmTAF=A;+p>-SH>GhzF?lKRJD+aV8NG9_-JwpUu zZ#WTtlGjW|GkOYxQ`g%@^ayKgeH-h}ng|d!zXPg%Bi(vrJVhQ(^T@pH!zu786B05+ zz1=N2Ka~vLjCGPywLOBP3i?ZA_vy+Z=X8Ro>^|D-hG?i1YguQs(p7e-RK?6S`%6pb z3xRouT<+9U0e?9YdE)Wo&5W3si7biF`0o0Vf#I}ppZMHkp;8~_FJ}V6*0CyWUc8t4 zQxccwIKSx*g7nybh*va!`@a+xq2G%)%E08aCv4&tM3mefO(J6B$$^ly%wkT5q?A+0T$214rJGCo6g zaIk^se>#=mVA4PIfPxZj@X_}9vmmN6{7BKWMIcVrf;bs#YilWyDlvI~c%D=O78bVC zfJwGY18{*T#MA)V0ixmIrR8sipi(>^B&IMRC`i8EY6;>rF};MKxzq7taz4{Pr@_SP z2#l@~JpgBSKO4y4U{R)$SMyH2kB{jWkzbytBS_lC2#pVpBy3%YUABFmjll~HD~m%h z%1mfUZuHbarf3bmM!$6arQY-MUUK5S4wtR^6@aTc?ei5Otqvo#`9#^gWWTz-Ei4_y z^PWyIecL+RxQia8P}*#^ajR=)21Z8Y%RX#(n$hR-NRI|Es;vxK-4c`!Ki(uqw zqY&DYJz8EM5^{Lc>iI3{>4W3|UU=T?l&?)4VSD&Nf6t|#-++958zDRFN@t+%Q=MmJ zC}-Ea+y@sTUfepvtK>;i6nKuQ`|k+aBUzd+C)x-YKWY53GxCBu9xYJeaK}U`q&2bG z*|MG3)ps0 z$S170)?y;-1XdUd7#H0*>+H?JJXtoxtYH_s_1SGruKl?Ko5>6u=-uVn{OHBg*}4Z_ zlA63RZni;f~3dEO!-ZttgNB2QQlhZE0ucYqA{>pDD9GPI27d) z(58!cP@W`DcXis*IAypQe%x?~H~0e`Go%GXO9D+x*1X1%?=%ebj=dew(L-dm9;7?u zk~H3PFEzcfL&~Rjj~d^>U~t?hB~>Fxeh%&N{8TNY1Su>|1DM&g#K^7SUj-JmBX_FM%bH|ve7_(F=o+v+gE#@c+IlD zUU1Xr;9J9R>!V?xGfnIUI#OA(MZqj9iPx@m+8AOYac!>*pQ)B*nwzeI)?hj|4hZW8^X*qW40)Z z9M0jE%)J#yURGQzGzcPn%#MlZrHS;0DkK!}pGpS_7K`Rn_Uy0648>oFZQ;U8w<;8? zhuJB8awN1mE*|XjfoWJN<3v1@(233Y&=ZPDaha~a&QWhfw6bl{l|MhnIIEDQ-ls>S zUgz&=Ek*u8-E2lb>ZvJqukw=2$f~~JY>|=0R%Yvl2AI|Gz1UwxgYroC`bI2=Tk9BF zpga&6YW5!Ry+d?*Nk0a4qjG`nJ)JVypXJAuJo_3cD@}xs#||^wAfhgu>riM%)f@}` zd&IxFZ}7jkPh9E=CzhQL$}*(IF}7mzx(HmH6kDR<8oG|Jm6wL_Erb}qQSNAzT4d= zHGL7FMrO`RFlN?;6gEWf?$L$Ls4EoMY(+0Yh}?{dqKX0KbeCgQJUNieq&W3Zqc2&~ zWHn(edlO|{=2t$9d~mD7>PoFPuQL4f&LWepMsj3xEue`gu9yhPWwNf@!_Rz%wgKb1 zKju#GF_~umKXJz<`C)_hBXCV4~_b1gx}YgnORtT2IhVH|ea!LO3K z*Pk;>w@+7Caa?V}le?5`i*Mb-t+p;*c%8Of%r)4XBc-;w6cgoEV7CFf*)}JN7C3uA zuxYx<;=N_-=yLp)dawKtqu0AIvd2v030sK_XXs#lWq~hW#vb36SiQY`*!d4<#hn2|5nYEhss$N0Vc5)%)6U4LFfH?gbz z%d#U1sLRU4czH}14m<`mP1b#rwN`kO9UIo?ybyGsdQu18XlQCqaK9N49CvF~$!q>i z4!Hpxg^Xy<$3#2>hruu1%XuhQdf2u$rd*qT+Vk&4bA(H~+TI7*^3ne%A%Bij%J8>L zhvGUdNw-OVCe!CqLu9-bv*|(pl6M6n*SJWA9Y*0^a;mr zHV|aO+ZZTK<@D;J`(rdvPzG#D1j>VuQB%49{kwG-J88G?M$goS5=}#^3r%DA8<_+J zABSPvJsw=#`iPz%`}0X(U*ES#NHY%IF*H&lG|#_PmHVIM)<1KMmZat3No#aG$alty zdDj2{RNC*1vcxk&_uNa2{l1|0Fq6C@}T9SBR*iT-P)$VQVX&3m1-@@`r5} zI5)@5u93uG_mm3S`nd}=6g!t`!~MC*aw0kxI(pZg&Xb1+LB2C_nl{P8FyrOKWXyX7 z6hp87jc;Bcz)&Gk{^m#EJ7yGiYh=wD7>PQls-rN)VeILIR~>MBa}~7Jz}$SOke3B1 zgjH+BoHf)sw=*Qr!EkD$!{zNu;P-IGC&a|@TatWBSX0Fxm6gJcdt5;|JG3+GOuEOW z9&VAj#XxTm0TTxE&W>~L01V98admKndEZxd2bA;_ul8m4fw;H)T?y~f3)feC@{9@Z z>(|5s3w}TNJj(FWP-n%vGCf7LCbNx%^2$-UT8p{~<-B4vI{!%=yq67&+f9EsJ@beL zV2*rChC6^6D=~5n-3E2@CQ^XKr}Gasmo(TZmd$94$)UavO`$6*JMT-ui5nio-W?{_ z2UkD(sWN8sU9%7CKA_tV_PnUbSya#2{SNvd-)prN2(?OgM;^6f-lvSs`vcFZP-DWL zY?}d;f7n^p<&e-ilM+aOt#ey-{n69vr9Atxc=lFwGXFGu{?j}R%bfw4H99bKfE>*I z+qLMoANf9l0z)0_h8)my&rPjuF5DJj%YxGyUQ6Bkt8*K7*=j5V{8_A4l+pg~f)8=| zPgJYyuk~byOKq7Dsjs3!-b+sYp>FXeMhHSf(*?X< zv~CmRJ1;THZ;~e?%k*qub^3p9W3eL`AC@r?+;gN84Uw4g?R%OT$`~r=?1Y2Qy{@z? z^6ef{ILLU6&kMh#`$pp}I@5&EaR@iNTWl{z9bhdFW8OWnX$-t68RvfSZ03xI{@)4a zQ;c&W!v97vGGEB3Bkj#G&MimTEQ-?c{iM(v9cg;23?*i-rwv|J-tx7dMR(JhBWwb^+kNZNU+EuLIfR%k8@_2r|}BA08L zMB$#c{&{b~58BFlE7XK}EmpA*&Vj-Bf{)8@@;m4wxQP81u-q>aI9;2EPzE2l*>~ zFcP2z<{#@DT0+^{CixUVI!6Mmq0IeAz#BQCoA)2jsG$$}m-=h-HP6HiUv(!ny^I)A zs~*yb;wq%QNMmw!S+jb(W!C?ipq7?#Wp&;WuB?Z*LTYB0l$i;GUhzfouhoD14x3qm zb5(J4vi|o`G2}0V7l-1A>cLpe^+mE_ec&^{f2gWx&i)=qvM~@&9AN$AdLw`)* z_5kgX3s58I4juCz&Vg>uMj9Zwvg!lIJ5{?1oloD#nqU>r`)o}5mPMG~_oOfMl!4}c zs-H7!Kwy9WI@57CUL)FQ_^~&|PojN|dU8Uvz3b@1x@WS&l#x+nd>Rosq_g zLIP4H)c+^`_+GnU^S7@nI;}_ZX{Se<0bq-V8|3gq=&oKB4W)e+f!Z}^ccMx^FKJ3YE*XiV~IowVnA# zGdK@d6;K}Qoj_Nf$t56QNpj@d@-f)>{{i?4x5lLlODfy#vnTA^sG4>)DwDS%TQCj}Id;jW)o1^bBO!l`%av#>&)m5loZ}rz5`IefB z3)upfl*j((bdysWcSO~4FFj=c15f-*?uizmS)84XmE%K5a-ypB`z&k+-bHkJbif^I z!$}R!h50?_O->ZC)o*exO*`!)BN1r?t{*juxJFj6fPvb?a_N&5jzdA^~5D!nf0?l~F|TJOe8Z z1fLm0w1T;M;%=8W%Xl;Nk>v1yfqLv>Pbk{Ndpx8K>}?8Maym+oBE^l?Oz4i1hRq#A z*N#mj*kF4Ki zt=ipNtN#u1DF4(llV;D!EBs8Wl8pnk2tzaKpr#yxyqOA!J^bM0kxbXQs^$HJZg@GP9w zV;G7G;x~&%ZK)>Y%b;hv&c}jU3idy>t2D zZm!K6366VB0O^fZC}Zu`!WlNC7{uHX zL_cjh{|M^xaOJqfA;>h1u0zbaVp@PU(>N;O)oak>#{3@>V_ z+--`@%=3XuB8ikQ#Sq_^+MMU9EvZ3v5R2|??6np75P8}koJMSewO^$|qGObrU8v9q z-et3&sb!=!2V&c&L4|b$Hjm^p)r5%b!{pXbikF-E&8lpWwB{1$C^_ZpV3eKq{lh5_ zasT3!SPN5TqJ?GMQ!aO|@;#9`7JNxpEmIqnzs-p2j;-trlT*a;7~9T78ykdq z9Qd^?kY`nP0TqN$rdhwLw&<5D;uZ3DWbe~0!60z4ql!)_Mpe3s_#e6p?I1!T8%)S^ z2qE6|j$?Vru&$L44;bm2wg0eg>vI=0XTSNfj7%c-y0EdqfFu=PaPggtEqPj8G62^W zDXarS{XoIM;FxfGT&aCn*1G-x`iNf65>* z4~Aj-gpZ$)Kcj+}gbqqvu3hK|p^EGG0z`Vifbl==`FPH|n&6q9uCcg1GRDcc)#{~a zS`9X{#Tq%DQ^4b;zJFcE*?czI8ZkhN%S=FRfv0(PMfoMdS@}%q1llG4t9BHeR_8B3 zn_Tk~q87+gqm~){xVNExTGn|zXxRK3-A}9E40Mq6anT(;_4vy8SB*4FtD(drj;3m> z2VO1SOJ)_CZ#}5|)N;d=hy*P|55**=U%d>nFP{VVJXqZuo8bmH;E}z{`~w5?8zE{= z&`*UzxfJ&8_4SzT-!WWBP|(nPikgBM*8efOO3O0xkJj-Id-O9Kz0(xJl~LBvjCFJQ zr85nF4-?~wanMioZvp2e7Cz{Sy5m`NFc5++=#^Xq1f7yH<3b;{oaee=-l>+56hk(d zws*&JZouHb1IX|>?cNw0@36#!`Q5MawKpCfZSNh0Nl^^G2giRV4i0WH6B)5iHOn!Z z_*|%xclA-P#z;0tEzfDnOd|d#&gXZ9iYfQOa_V0MP@^~RA4Q9Qepew{2KJG7Z!TW% z@XdIRJ^**PW_E6q24ug-#EbLhe}A4`#usv!MNh)2zKxuQUi;3Wp|GDnKSD$>=BYOM z4Eo5($k~O3jjgTtLfdV<+Sea1ly~)E|B6+HjLoy5Ljx7koN!hRX;j-)2cG)la7!?<{_$Zi66R8>hOg~iQ_g_MS!^69uH^oX2g);2=q6jId zsHo%z(EcFgW-fwDknRJvDj|Dds-OR8v*f5MD-%(jbgs5` zcEs9`0`Eb^9n_k=RqOQ)@D!{i>5HdVSDmbhMEb9-@YbtGEwP%nNhz@-r#ivbjbG>b z5N152Ikp_LeiYCv;yOaAKRjpvtSc}^J(m!zjS0Ct-9RgbJrk%`AoIb7BL_G{Hv&+oDOEQzI!4}Oek#M3#N6HO77y= zc_gD4mEb}!rES*5Rc}jfqX}oq3_5Cj-k^u*S)EchH|??%UWYJ06@S^&1ml?VrSv@J zdPj9X@I()&L$4r%dy=14<`y-CTQe9pD z083qIb!R5!a=kU-MM@|7+n5N=>=*cs6W}TbbsZ&QD1GdW%XKa;wkt94 z2bjC=kIlC@Al2pn7?1PdT!=-GloQ9pj6Bjmq97`XpcgF;H2mN}6U&xt%J(D@$R=Lg z|5KBdKe342cre_uCR1gntc?!$+yx}?$#O8+2S-a|Q7JuY`sBl7gmQ%hw;!G>FQsgi zK_DstJ6Y*=sQ}m|OhHbbMg^YpBPvG-5&af$wS3V@;YkO+bf!+vq~4jb?&O2von>zA z0_YCcbr8UuR?Q(t{zQ8a7f$!yh7s9*8*j!3Z!c1MYjGZFx0;6HDB+Dfo4j_ufpRYy z|D&*nna4l#5hV>k$kp&NKF6dH-%Fvz0yMoi%BR&ez*ip?5wsap$>5@2tP1ZbgLR~u zvoZC4L&03t+N*#?FJm4BJs@H&5+KO#9Lx}a^I?XcHdoG@;;&P$=-`Ek!!#^iN234#!U7h z`q^DWQhMz0U_DcWRoUrY1|SD$96m~u=A!Dmvfx6emJWZ9iJ5M{%rcq*P-a`a-p%pFAZi#;K3{~ZoxK~+mRA8b=Xc-B!w$8erjDV!G@T7w_T`%sZt)G>dI)e&oe`|r8p;sFlSs_!fBlee5mt)Otr^(@l;*&W9-L}0SAm~a zQ7>Fx`-}yroRe~g;AFWt$iHGYSSe+}WhJqNV+c^!qSOU`^j)6+R2ag~pe=?5@Wbvu z_1bo`Zp_J-E{O!R@SObEkU0>q|sS|NLbX`;CknD45;aIj_wb$LMW4Y^pnd7+xk z-tBsIB!+!=9kXkHO+Vz+CHAs>v+MgU1)RE4-a^N=N3}We<>6@6MVA;J-9+pd`Z^~b z%Gq^5IEPDIZ`bEbXdpK;5N%x+km%d|mEn#K zq6z)yMf){qAB~0|H&UQl>vh7pF1@9_MqurVYk-LmN9&3WkY@bRm;-na%DT)B>2EkEDl zs3am8G(N;7fkRCQirHa&bXcL4ChTF&z`VM;@`pssWC;ZP4G->DhaJnyeDeB#bSBqH zNyLUbK7*(}5!;9z|HMR0Sy@>KTB4$%#ZImD%MXr?p}4!dH#avku}c35D{|d7bYh~3 zku5s>tu>*D1^q8%5geTRub?0Y6Xj>~j^eugFYuXFd9H`?i0dVH10Gb5qd7#3a8rDZ+?aGO+LcvmFTT*U#VL zjKNO!)Cz|xs?8Of$d97LdxoOu9U<6g>Of{QMN;-hdzxhVgI=^M1O7zX>!wJkAx~g5 zMUTf>yIWnVd==MoEC)(-P@;!VS5u@7B`cbKxb%&}RS%~r+!s%C=6yl(-o|U=37@ga z5z7}ttkTD7{iExp$FrT&0*f8=*r&@3)A5zrV*31pa|QJmU7b_GGGHCkmu?7Ff%WML z!3M0L%b}fyj49b?rsP4V(NLL6cJs`3HJ?&*OBfYZ?|&m5V7+4!c|HlU7noQqF$6r~ zhN<)GoOg|8N*^GOooAXw#eMNOGqXkwD$g?Kq#i9fk_n=9OlEInEPFB#h6hk4p_N$? zi0(D&i@K{54qN*f_tQlp(g5R6fqN6WOwDb<1F{<~8zXP>r4L8LjyX@xn^i=`*^ukE zrF_eBtL)^Eg-QwcNuq-cnx80tn-cdEt0w(QUYY@GCpDLK(e`xsSo zU}d`9RqisHqLT=_!;+Td36W`gczT}Eg1FGKr5RhKTs=G=ey&`*OM5N^y=ZHTx?|e} z#R4kWu`ABJgQjrFe+{>gO|YLplwRL>pJ{*3>GUVol>Co@@Q3v!aAMShk+gZ?J`Z^e0=6PVy-dUh|i0)93)H@fDJTV^b*ue&;$K@6U zys0|&0(GUzvHYRl2Ig>$4|;IMe0r2uh>SZU7)$%=@p~yEv9q9&N+#o2%-KRh0lA$w81O=F+q`1eU&-yOqA*z z3bMmk4%KY<(V0lQ4syb?m8G>W#$9KwB*{&8#7~|~ z2%9v^G2d;=E3FN@w+~xV*19u!-2ObiRp`G7RhQ(GCC=o?km?h`uy$jnb5MMr!x6)f zFoOPh=n-C2byunQhowM-Jj*#AtZ%u$bi`{T*B>-jCVKF*6R)%SC{j65JyVk2R19dx zxZwwZWXtCp7Vjy!l1VlWR(S~8Lt(q>s#^=#ufY&HG4!CJ6~v2lJ?qBPD4k*mhDLn({?{Nrua+fhU2!x z<%cbIibyzBLHcF=ZSqLfnP;~xt*ohwG3%xlWe>3^HZU*Nto>VWXBuL-Ddt5D;MDfx=3as!+y^5vCVzug^ktwT6=6p6~)|@wGDXh4h+8zfA^stJnd6x zEArRS)ZT8#jfS>L`=(cxd}4lPdEkN{Jv#VZ&X$VbY~xvX>9T~sLjA6rv^55UJ+zp=w_ckJS%(`;&^;}P(>8QPXA^yKMnimT2GJV z6xieeaec*Q>m)bG=QlR@lB-fuaN=M`0TejzEeVdTA_BCH@4v?@?6t=5hh7_a)-&;J zl2yYDv1U*EpIQ~nX;||oLX`q1a?W7ITX~X@QWcH#P9QYuf=f7pH+P}Xh|8lyB!XT%rPG-%tU!f_bBQ7-uN z%1OR`p$SIaQ54xD3wI)ZfrHMndtj!=Jw@xBf`24+zP$I{0ZV#K5@N0I8L;qDStjM5 z?~WKOt|;Jsbdz2sZk$z}!Or>Ryp(!pKUZB^RPbtCC6A+4Kj_4Y+)44L{6L_@9SKKr z^l@2!r;Dpvtj8X)GE?=|Q7H|EoILHfwKeB8F|gmId8b%^GF-8KG1yFf*j_vNJDz>8 zV$S?n%>(NB#bcl$5&fEL_1nI0nw8}6S{EcB96V#ujsH{JTSv9o>}$hqX`vJ=rMR`l zio07W8rbg%IWhAF&B|LX4o3^#N-M$SIm=f?h-c!k+-;YO;iFo?dl{lk}cLI0nyRrxqe99 zUhyv!`q~m#_0F9xct*VzUqu+dgPrJ4jz6idT4w#~O&}4TijdQ^sg%egm==S~38v4U zv9c?BBjD2_^>K4(Fe(}GF3O&15{Sv=NPVeOH&m&_lsccc(Wj_6vC|Kxbk%2l z-Q8>HIY=z=edP%`h*Rr~d|AB~Rg}b>j9AOs=FOfX9X`Vc=1C>SUvI%?v8)y#^7APm zmkuYmKSR8W(fz61550<4<#>Xzagj|w_P^WJ93;o4r~^lT>f8@Z)w(bv5M)xw44b%S zSsu_eqNE5xhB@MIzaZBoSBg3;@9PZ@H_$aqq)@D_k9P!%Fqj9b9Tw(uM@61ZSInKz zS-o3o_WI&$DgRUc84p8aUkoi^a;*~aZnX^;1#Wsr{N!D8k7Zcn`VHtCP+YP8a^6mH zV;@k5mZ@1U2P1OA=K~>_v6c!&^RfIxhtifi%zKib(q5`djDLG7=Vznaa#7`*K&lkH zr(-FgZuhc`_b$`P$regZS$LOFK-gq3l!bM!p=j`CU#bnCI6i6DH*v6h8`7uM@Og0X zG+&p=U#P*XlxkC8KZ&RV_mhBOk*6Bv2}3xVejjPqhJp-0gZrZk9k0%5ovzUIT|Nrf63umC%wX6r4~v5Hi6pZdku2Eu5D04Kc~Us^ zcQ?fR)exDyuW=f!;7%lNQn~y|WQlJ=mYxQ?Z%X(5B@o?*#A*O!< zd_f%lxoE@v8YS4<)pLT4=qEg{41>_2a3*cah_)r0jxyzdF3&j$jf&x{| z$%JTssz7%MSzyp}!7l1N#roN6;yX1ua1d$iP~{F+vL#%;5|TAqq=M!xC+;|F1o*Zl zMrS6My5#t3lIL}1t{j~jSyhCHE$WBmeUy#S6P@w(-R9`Abo1?f_j4K~VcQ<(#BQ3I zyZYl6`Spq1&I3(!j0Ju5J-{De)qRG_ahY==DS9-Mk!H#ie`na+#d*m$p0wN{C0}aH zKJ7gkj0~c%cPo{Zl6NLU5)YM_takA)foZ0)@GiEA{B4U0Q7Z>*vn8Y{kRqAr|! zC3T>u#H(^eq@?E#TZ#(llCVX+qb#Pr<9Vxx{Uc2d&5L-SRfdyCKI@hZ^y`Xuf-i;* z_zJa=vEJOFxb$GIr-+r$e4Nf=>SCj|Klpg{(y(j9FI>3lrRM}<>fiV_Eg(uY zdapJf3N2cwXvu5Y@q_qQ8g~cm?Cv6CU<`~JUvx9+vswLsj2I83^22xf%`8Ll6@&PX zAx1AAK=&%Qv19Yx`4Y{ZjZTQt^eJXX6ch*qVq#;9nw!68W@gqP2J>aY(RN8y6{NS9 zR%s>r>H+RXnCY5QwY|g7-2H7t7ZDl$Ck+SBA8ZZRaQrhYW@1dc6jg=1dFZ`&N6N#6 zJP+4LeIcQt1bLthCJbj?AgN=NbuLMJ<3NSf94A? ztE02?)ytRP#tgbxo4dP%;U*sGFa@Uv?iCZ5WdQ`kk26Wb{X-RqkOaSer-o`ank!*@ z15;uS>SB^_K0F!j zcoyKyV7_G8p6yj!{-^d0Xo%5t(959`5 zdtNC_QZUNO%C7e61sQ_a z-7|aDRc~;_#nc4Ud25z-cm1sjQL{e$6W@`5Hsu($FcG>k7ndvF3dM%qh#ut32Av7V zI-OiKbauR&?j<#=nuzz@Ivai=)#v7X=Frll_8yKT9Wi`$=*7geiq-cn>Kr0tQbLrz zPtl=wX3vA@Jft-{f`(F`AX`}|bmQvj>3Q|m_xt@)lD1PK(bE&$I=@X-S~z>#yuZKF zh<15n%&;SaXnnI_a2kNj=497>0=b=F_jnS!>R7x=ugPd1PC<&+63hmH)HXFe zQ0uqKn39H9A#1uF3;}$jyPQE{<5~$U7AR_VB-Q;ztequ16_~zPV-(>%dUvrRCq0;` z>dPOhFfk#1xt$oPi40sJrCf=qcs6s-H_qA3j;8Fr<|Wqm8oRvH zq!GA7s>qFJt#$~f(zrc~Ot}uJ!c%KxLtIxwoBl!T@x2P*OI7}*9o#DBGtKrZDX#2} zKfcLXa37sEd~@0$HjJQi6?=x8#4J!N=0hzSq2x>{km(WNM@zINamRICV|ECy2;;tR zxEzNQ`4t;8vVK$(`6&-NEM2$4q2^M_nMJ&Fq6Nt3gN+?vWA;hTZZF28=E~{$T=qRF z#dU#!$%5nL9N%y#2Y$6&`nDD7ewj~gn>bUtk;_$Vzfe!Ge`x$Ik_uw~3cK2^Y$|0; zypGc5xY1kjzKSm5bCh0H-jVM)q~J}8?ED=E7pJzlt9M{iGUR8o4sHXVTezuIYf`9} z_hchRX}L6oXQ4vW$&;i3Ij)|Os;I_ev@;hO*DRn<12`*dA=(Y;u&)%%u~H=*?#lKu z*?|H6)lITd_SB&c>2br(Ls}Q+-LkPvVtZ44j5Afne^|M2{}v8hSJUcLcVek6QaUf% zZ;L9_Yy=$PnR@<%bdc~9oAKDG2)8^5z*>>;%p|ZSZgC*?2zmqzwXq!lmk@7M?99@u zJfi&Sn%q17*P*$UOxXq3{85xI#W&P?xz~t9nry2mWmwuoO2FxxOP+o?w}MnOn{>1R zp(b%|a-GiaJ<`s-bu;WO&a<6uSOY>tZ;R!?u=XM?_1QcD8P9%`^UM3aPYBI53Zwld z?fNPapulj}n`c_6h**2{xK3Uzgw+YCc=< zUwV5RyZrVFh0Fi1px^0%=5LTB+$WYw{ive{%gdEpUgaR9L%aGTH@L?hT%Q{KUW3Jm z*FGb8)!dkGU2*N83K*mXRY*MVbTJvb7x)ROOX6xQd9?p&!C#S^WI1ule~m!F>Z5zr zh;?CATJM)}*yfP?GYUPDzCb7qYl$1Du62D_xG8uID%sE3#HkdFp3gs=n(@B3~eHOg!#GiQ)j z-iax_U?m==ef~B%fjg`PYnqP`?2()%_zsG!rgWfY%LQ!oDvt`Pp4BfkYBR`{_uF0! zB#&%GRAgvky+pyubcW)D&g%HMj>IyRg6Uyo@3>6p86g8>(zF}^jQNvX+!)+l~MHFH+0;sX--U+>z+-PS<-@2s0Q<9+l&oM16SjP z^9jblS-WxHvd=l`P=LsCGu~i=V%l-PmJpD!uI~z}1(C=-c7%4B55*ndP_~hTwB$Q# z>fnratea8?&Kli90Cf_fMbX@uTM8{q)?Q%#OLqa~C)@zcMmGd3J(uhbs)a+95XJb* zsBc-K4#)Wrp9Xv{eY%OsIxh~v>++ut+-5yhTOC#qO4i*#LDmHyb&|vyk0oOco9UE4 znghO9|Ct6Wq?DlOJTk}OjsKelQ;j)zlYpW0_A5|5>Sh~+t{0ey5wqO|nCd)zf3m4! z*|-tDdy8aj_5U6Uk2b9XSaf+xLw=3mmi^w5j}UMD?_%O#%t7>(953CtV^MLxOXkC67Jb>e?vserJ9BqO*y(?ZbgrW6E-ewxV)7%ReMN?W5eT+MuClZ)X0`R^tonA;1{w?9jLEO^m-{o!UjCzgTp5N7Q^7{817rdVxG68obbGdz+EIR zhs}55s_2I-Cqb zi@f&xk|~z(@(`P#%?M}-OtoV+bsKm@RdHcqDm7z8(1n7i4I8=HvUs}^eh zgKNIP|CfAViAQtD`p=fdZf72TKaCXMcx$DX_f=W1)CX?o>(=7G4tkA?&00z?M?DL{ zE7>wCoMnoDjG^3X7Pxb_JmDUF&L*Xfopo4j;!ZLxcTxH5gx~_934*XnZWq;Zat`fS zptrPT!6_6DokRGNkapOdohPKi3jeZ_g ziwBI;u{Y~E8RRr~*GF>gU4H~(oz_ciX-^G%A1gJ`wPJc_a(k2y7W#YlcNMdk%)CY8 z%brv0+bU8U0bM{+_&$hFyjl5Y|J`v~#8De)X{T6gpg61L#3;F84O?j`%P-$TQo>Z2 zqfS0^1rNuSC~7LAsw9{1YXeM-f0X?x9WpHVD^GW36NBT~2>?vYEh2IuB&!j#yf(jo z&}8T!a#I{yX#!bN&ST%zWXl8 zySRSB!~Q9*0?5l`a{7Myig(_{jS9{xjaX3TSzjObBMB$yAhAMN!jmcgcma`9tpU;9{jcoo3(2*)QrJ{}cgy21)qC0Duo zB#E1g%h=<$KS6N3NbmlGQv?^r_u;OTn?dODp31XFv-;A}?efosqI}C7xo{x`DKKcp+T?S>gPj{#SJ~&$pjw7*Yl)DZta~}*m zn80>aVB&$p29DwWbo0oE{wMx>5p0i(e>zWeSlfb9>TJGSGx07Rey7(ceG6w@;i`OA zc6<;EDjqb^RZ!+^XUeys;Zs)U2I1=mmi&Rd)$V90uyT;B6Zq*~%FW2g`19w_=V)lq zQOg&=MlK#6Lp!_hxHz?}&Oc7NcLVi(vH_wjTk~TEzrpCc0p@=|#D5KDFL!144`BDi zJ%3ngxQLBs{dS>f$yj$G|4+KY>gRu=bm3YyhrUavWGRM=_&?4BVEw-Ww(Y1sYYzV8 zzfrOKe+6zY>$vk-e%n!xtUWwpVHq!L47t)(MIBcJA(7k_wtR1;&YUhAmF!V)WJXAn z`UDtFeMXNl!zu87Grv?cmrnxSh?f*CDLe5}4sv!voQ81%uEtGAgQY`V_6M>M(sPn# z9>rQE&sKa(>Cl=h@h|YN_SIuqY%s{DH4=^L1Vxu|W;h9vN!;mtx8F#Ea>S&b7T!+DN5 zqoDv}y{d)P7*`xA7AAQCJK1EypVw<&{pC=9X!=Bn$`vMhp6mwHr6Z>x4AMHL6jD>v z;HD1xIgW7}(Iw0>fB!IrBFu#TCAf`SLVPwZYwPamxs*ujOZ|;7@FL%d5V43GAQ@mJ zv$nH*7XAJk23&7=#Dm*Bm;LTk>qP(ND?+<*v1aS5s<6*0+78}8%805$v>MR2U`CuQ z{kf7IsXlx8sV^;sIArPc>U3^5b6nj${TL|JU@3>2=D^2;GR(;aNO+|d$c`Gtf?}-TK@!J zQHxmy6N?9GkDDmVNO!b5QK8tb?QGv4)FHr)TLI?;vQ}e;<$@Ie<-!#NDDf`o}SvG zuI8}EV{Z$rp<#>|g>h{5JTp|xJ80pwx&)mn3f%wV4SONNTxIpivhpfa7#Tl^!wn5l zZvX4`-q1-r(2xAlt4kM23`(NIHD8N{_h#@#aRoo(Kj2&dbGCjg37C?{674nw&Ng3S z{!9-qxsCep0!h~7y2Siv`Z#m`PSZfp)KJu`Ge9z(0wT;xyhcAN{KC$2$Z=g)k*jqF zY~sL%&oo_&Ik<1tzgo6*Q6JGa_bK9DAOXIeW(Vl1o|xn;6?8h&RWTc;%lP^b{?@IE z3gpX?uXz=dH<4v{K=h+y@->Ei5;Asf84Ehg{q|C z9VymJs^qE`iQYE5o+RARC*hV;!m{2vr@lUPd$&68sCwgLv436ct<5xoK^gf{;PYP8 zefSICti#lzarX~2%yn7A1(1*6_>>1^OZsMA7sy8IsXaGq@5UIEJ{2VV*ll)hj(R5< zD{r>{wS$`+uj>pXsWtf4Al}k5s@(8>-a9AxOgN&QBkIBMM8_f~{xqZ49?6WF!WD9k zpgpqr!{F^+(FnQr3!~YM%p1_H0*Es5PyUWXrD-wLKLx*#N*5A&g@m&3g4|u@MOXmT zXjAPiTkj#+r=$uK*VQ@G;r|JJ3v1a@3FSgU%~116APb2rrV^%oYW;rX69K}Fx0%<3 z+vcndL3S>NQ4jCDI=?*X6yQaitGDC?hf%fqD8}`wyX;M^e@DaCNI6W~HBAnNAi()` zx+WAapJsUfz#*VXKcq#!wPDQ=%;=858THsVMv&iaE|NrwAKD0|vXC!eyMJAdmv3}Y z7{+@!%Xe^a(44OPvNt?c|MsSVoP1YbzKN7OYQ8jobY$n!0SSnZq<9#2*mtw}C0DjI zD6#GDP%H_KC`m_0767$_HdkeMMVenRN8_6Ug4oXoCDPNzS(i7A_|xw(5Wl;Q-Du~| zCsVUl4uK3)>h5Z-yH=nmk1MFn5G~yu9JE{nG@E=cICWbXc2ONyPcuZiBQXTKS-2D{ zy%a(PMPC7@KDxkAPc*xigkjwc8Y;)ajp;08xRq_khlOk&R~m(w6_kE%ywG)z>l!-q zPpKqfYVt>GEnbuPELfgyD;=FP7v}5g^ZBb@$DXV)8_m;gP(ZI)#sTE(x%pWMq0%_U zcd=C7CY1k!4DMOm{~m*T%Kq;eTqBnhvV~6rm^;NQYO(aw;$EtO(f*M}=p~lQyor^1 zA5-TSis@D<_-yXEEt?C~u@D)rB7kUM)(nT2w`wAe&?m7M$0BLqx6E*unn51|!2G+G{KYC(R3@MlWfwF847Jrvq9> zf^cS9zP-@Hm_<>6X4;8jxmt6Dux?{qO@GS)hK2bUfCsMy;QM ztFt9BdJE8m&5`V9UQu+^0>Irc10)ZiT-v~0K z2&e0c(U9DWPMFs#c2a(LR+F5vV`U{%+IzeNjqB45`kc=*$}~hMJELpU82(PzpMPDw=3xwM_gur934D+Po2ELln6+Qq#jyEqcP0@0B&prwgh4}Bz@zL zZ1H=XQ(FhOVDWQgel}{PJm1a0G2-;or}xPPTDYv=6*Py*bxh525eJs*2JxNgY<#B} zLg37esOij-tS3drM4*2nUNVNrF@0nN5%CEk>Z8Q z_m$;d?V3nG9b2nKIRUSdHw@1#2hZcK1>eS6Ati8{Ki9HCU%I9Aze_Ej`OlCw{ZBXo zXFg4XFg!(?ZhI_ZNbg=`aveL=n>YTFIc8%%lMj)+$SX5WrZEYW$xhj*S-4FjQ3*qfYpGWC5v zHF(4VBp=3{oHmb#`eAn6;30op&3Z9l+_krd#s786)_;J$?(9DzS@z!cQo-M4_3EX; z$@e*2+Jr%Je-#9+p?nj)*!D4lldt~HhrmI8bH^e517n^`5!O7Xm(T^0mik>PiTZ(G zL}!=wOnauS+ltW2AIr^jz7EE$ANZ)Ce|jexz^3)2Kj zCE(Cag+#10G}HAZR2wK+RVj`1ib3y%hazioIKy`}Ul#XOr>xbykx4y}H`)1;hmQMh7kVXJ??CEeGo>r`xnqg0^ofd1s_ZxX z#N7_z6hg6tCCU82fL?(9wtRH1K#6wPtk|m>=10LzjNg?;+%%G^5R_EIe-<>Y%;gdN zmk9TWgV&L_Y#)VjSwE95=7BFW)NK(tjX8jDc_2|4i01^HiFM{?3n%|cPq5tXjD^dgpkLv z-+S;~r_NOY9x*80l;GnV=?$v=%sD z<<^>BE9;6&LL&ROt;hivM=?sN*|_r;DnyBljV<~GHjOb{#+>oeb3Gh_7y0*>b{%(o z%SI**w0(P4h{gw32+F?~?gopyr0n$1&!@u62WgprG*kq!G9F{Te~D$ke7%N$!n*$- zZmrhIpkQK|(Xs3h=#gy<%A!!Y$=_4U|+lu{QI+N|v(4I4tQI_aNH@ ziPV3zWuSaPR?qa~b**}m4A)vI{NYl6H8hDUHCBtO1|CXZY+JsYBj7o@tM8*o9Q~8@ zm}&uUkc6Zxa4(WFl3TXM8h+h<;>hrCEsBf0Vxt=Xymjob7c2O>+UX6ZaI&0p{}{Ui zJNhJCaX?hS;qjAXm7CdZcRFSyTTU>*{sH8Oq!zED5Y4;zN#!Kq89BFRmooMPwD7jH zk`$;|n8zCglh8x6Y;6(L3mqIMKDy%AxroPn`R~GEVE6FYDx=QZe{9dc_>ZW#@*8sU zi-rCnqO}|t%rC1(qu2446Q>H)yc(Dym@-cMb4^ebnL6-dd2F5>T~BzzQ8ig(CJkL{ zi^a~_Nc+A!6wgtKiAsBp@7u5oPyYz&9NtV)azorL>XkHe+{h%&7Fv!_FjR z>6FP7+&QQDHDJlNXzMq&(4?n20F$+hH(xacN5$V^bYD#9#Q~)Ix0oKfhD7yWVqRf ztZl(#r73ioB)`ixnT%I%hfe?k`%G@T9^-}D?b*UwiD zY3K5NEpU!H8cyJ|d{9-?0+>;$x6AuClbe_pQp(f&r*@gTJ25Ul! zOYa59OvU9SC#f7tMevi0h}XWz2rM`4iuNXW0+yba@y2!x88@46i+yM+;*J^!SUDDB zaXS~iyEZ21(x|6+yP|8f&~?{0<;mU_EC@XLlZ$2D@eLC7B8FC>#>0ky1H*K98FN%_ z3VM@y4M3!uKreIt;FNp$y1n8%XH3$m0Z3#A8f>9x&ZJuymf-LXTY|y^X!pb_1_FU% z|>N={_9`K57tYpF>5P4!LQCf7!tBS6F zmpnJQspXC)JtLyz;kl}83ZgK=<8i>*N2+!_e`bKQe8(fxn#t4|rrWbWLAqx4F5!<9 z#@GsRMtd@0$z$1tF2}q0py0z7wah{DNxoPR_Qx_J!QmJyn|L#HCnlkr2oBjk0f8WBgm=wgU7RY?oxMT&$~MIUhm2OALm{g zJ78&ePi}MC6csn*${>wsAXu-exLWN~;#qR<-tneaGfYf@HxAQRMf8eTp#K2Zni)^J zx=Oq6@R{ABDT{vbQ8uhlYuM<2M(%3G#{5_0Zns1>+26a65oQwq4Pw_a^uH@>epXk` z+7&So^@>7D;D)?+QDW*yl=<#8VATX=EM-6LwmAI?$;iB+5?i>gL8|25ZhwBoDW6mj z+*Eko=*BU_)RzongCB~cm;EhL37sNZ>1{UpD5oS<=0}OQm$C1N--{qY6o-XCt91E4 zh}O9{%BEZwCicUL6Dyp`+8WMBRy_JXEleCX7S2rw>|Z-w*pP;$&9*n^QrvhtvIZ2h zD*?^hKNg~a!ZQ&DjwIq@o}S0|p)}YUj$f3_j+@Yq;MVsPCeGWg)O z7Fx)lm6*zUewxVk@aBO3XYquL?f1;qWTXXi9f_Hzk-8q)Jc9K{IO)i%n?;qZrFYB% z_1^E+$CPeLZ{Gjl?=`Kt4i@JuTb`jo)!`186`U8Im?CA(*ySPs#$K@HH^&?-kpDdx z4jhMq{Gw4W?v#HiM-6h^x;uD2@?8hDhV1fl)mhffuCJD4ukq`1;LYVW%Bx*L8|i+<-f zyrNd@W$9+=o>6bPi0w=jB{iL9MQH7o@?=U_luqKC!feiG;d6V+Ni#u{VZo&WlVcOAj9NWM8Rt2QQ{P z&d0W?7Z*sc)aPlrMeJWD$eEBPg`n-6WoRN_>O5|)@3P}e0f^k}xT zAru+S%;El!nK1p0xN6PXPL@EzC( zZb&KIT)%kl+HdQXFttFbShUc<#@O;$LbpcQuJ?QJ{!tqSDeERUV~|{l!&?*VnZ(!x z4Egb6Z;~K%C0hz0{2D?GO1m2)U=`+rEXmzF*gkKikAt%^|VUudmn)10DDl(h1 zVE2SfXTj*miZHmV`;kJVo%Q0P;pATHJjTPCLfD_#VNYUH6?!kg5$ywm49*Kirs2pM z0E|&miN_G#x}3gK(=Fch{l{_e6J~f;zx%2m6Crs|_oz-hHS8xf znpiiX)4d}U3&aK5c^PRRJ4aI_XY$=|PEg?B+R|s?Bz4%_ zw{ISg+ieqCHmJ@VAU83y3d}YI7zmtAxomY-uMl*9buDcoOwMmVMy#xFzkYhuT7`s% zb%eBk?n&2+t_z*C7f8E#Be&a-!r4UhVU8{R3=d?3citnxaYE8z#IAZU-bHzlyA1eT z{5amh?1iV`Ly>07C*^`juj%j7Q&xXC`eWA%9KW?#XAb7AiMf{{fU;^?9?zCqoS@X&<{LGCxi7%dxY#0{W&eTe z%UIu$FTP*R%;12~@aPeiB0xk)8NxV0-F^G)0oo`X{@fpaer3uUw>0N-ZJNK_h>zd2 zH+?A6`c9EV!~ANtNQ5uW6`hl30EOxuly$sEC!scrR>`Tp2#4lOul2_rx9%HHTesrH z>c-dioPCpJe*U)|{vohnu2bBlrhT&s@TX+^9J%nrwoRPZ&_b8qnx;dxo^s-@?;xGc z(K8%^v4b}D5K1A_kFPPkQ`Qyv+%Lv6Oy=Gf5=}|+&EtKTUCIpIxO%A^Fa>xMQLw1hFsra9o$D)WU!KtEE`i zxHqKDoimriWowj->jDQ+j0A-+H3oE9S^*nLXRig#Wz5*f$BV&bebC2YSyT@ad{6$?DNft=npK803vYj!> zu(l&Ez!z3pxMpBzdBH+4<0dxTBPGg!5SgeB=P%dYf7r}aIvhheVID?}jg3EmyyVS1`d95z`uBV@YjQ;d7166Tkd1VP2E8fTIaE; z_36LRyj1Ll-||aYG9w*b=*EUQgLbw22Tw{-(Wz1s_%GfMQ)pt1rfkc@gy-_FNjk%_ z3ZzJ{dwo_Y@iw9UMtuE~lMgd7+(GT3u8tRAFxdF%`pX{E$|N4#o-e>G@qa(u z^6SdLG=O>$6hX;fq{Q)!y`QsQdtmxm#9Ajr!3;?N!Y z$?@m5u%pzU_M-&`TP8>AbN{k`7isn4!RFU)5ucSq@GO#Ehm0aFBI-KRW2>|c=eq~0W_#G~NWY%wuIMOxKl3{SQN?OO~C6AzQGkDm^my(?b0WLx{ERws-O z07_DchP=+Db?W)~hv6>W2CmSj*Z3gyBfkBcSDnG>;>Z|+JteGaC1z!^Wy+%Uj0MJ> z%cNYe_fH`1zFDu7rn(%WGjE^34}QCbDQ60j61&_u;UDj-cRL(DBE$*(IhV5Hem=q4 zPI4bQ#EG#!H^&_RVRnkxn#(a*1go!$G+|_$BX!Q60jVU~Nm1#+6z)LKKcoyv`PR~V z(b&r{Ps~S}mUFzJ)f-@S`J#PCyX$5^){$#V*EThZ&21Bhv3R)`VzCr6>eg1Fm*uFG zokKKWKga*;()0?J%jz&H3t?CM3?68JM8^-^IBw7IP2})_i`V$r z?&J^$>>%rBB&cE4Ams4jx2SrxU^U)rBkGy2$Wom4BlnbtT}CK5*JE5H9tSpv^+)(s z-b_rVx6Dv=bkG&06b*POq|&4aMNjh8pLxWVoGx$OQ6wfTSr#r)#o^pkL5JFkbkU7{jQP#$zNfblb!%Hl=chYo}K68D!a3{%!Lww(JINh!*27|!;! z054=`bL6ubRJ^pglnY3Hpgmy@E2ysPlrPhe<7v2~5~oc5e(#AfG&~%;5XJrmmH1h5Fbe&pg$JwZT0Qtp|T^<>Z0CIyWVry;#BO(r!{6e z-MH$VgN`ac*R#L=Vg7n0i%II?cBBG>brx(|c{ex;{fO7)+Xt-qVRF7KLu?5ZUw^cS zU+6C?TPxv=G>ro}1O&h6kQ3J}d1IwR65|Qe-jv^KCHFX!-JQ4_JwE4SL09t*iK@5b zj_;thO#Y@_(dBD9!pW5B1neUtJ#O~6Eem{uK=p=Ihtu8fu){xufrXsZyUsmu8XF zRd|R8@IOa}>omHLq>laM|Yu| zE0n_XIsS0XfsFg2SoLj&iUrOd8r5Fq%T~}eX80MSQX3-PXXlj4#BdyG!;{6vQJ%Ke_LrmzlCUIp$V%-l zw_ISFDf;vlmsEAE^Zbs8C=nSQ9nSH9lQydoc)(v1%7b~lgL8%TGdBH$$ur;PW0ZK zjL41VYeY>>s`K&jmFmG)=)1RY$(L$@Ciaj#r(QL;&+dF#Wazhk?``G2nftyogzmTK-UJ4Bt^UB5Y;mpOmwVLL@ z$TZIP*we8yWNBuXvw~AE7oxbsq%u*u>ydZod@uZ>o9PoxjAqK{(rr|{C0hWxt7{*f zzJ@4?WPIa>LUlz%B+Ch11f9ML$XdJ9oOW{pE!IMam|BDsCy2B7KU*Ez>W5QtFr+>u zia&H{@9e;`lj}jf6F3vO<0*~u)4ZiNk^<@Zuu63f+W-=6RPb6olgymNpTVBXhAxBl zoS-3(Nv%zUiazw+qEr{ysc+E+*g4gng~1Bd1b?iBo|eB)xg$zy-_vR@p2`F|=o&Q# zVy5jGm|kV^%w&%^|4Q6i1*nob=BX8BnGK`@bt>S84hjGD1Iy)ma$a`xUYrYpi>jJi zVJQWzC>A_*m)?o%$HK(zjJ(!jVl)~5OdpTnBiP`PZIK&wfiyEgy4aU0V=V~67|To2 z|2Rf9UUJzTn^APHce7AN&drSus}{Sca}C>kBe4F&OfH3tfgu!1dLQ0CgE*84#vKzT zSXx>7c)c!EooN@j#?@98f@9yfRQGgJdXWWXzp%eGv{L1hqN7YKAxK$Nu@Q+1-fnnJ z!+x?cL^i++mqTheeNAcz3W|1z7aLg?cX^Cu@u2D{Jy_%SgzP` zhFr6D*Ax_ZSlzeKd~k)Ck3SQ3N)7d3swv&JQr*SKG}~V3OTByhw&+ZjhAnC0+;`bJ zd3hG*xAIyGmwq|q7I*4srC<~vzokR{yR)#Rn08xnB6;$BSG@+|0qV(e$|davhus?& zKE#`MB+F zxlvqvBshi6eU*8fJ-#zL-1B(v6B+O##TsxR>pL6$vPbiezy0 zZh>MIkI5M;CW*O(NU6Rh2fN$v|3s*tu6QyuW6I*?PA43<;KvDom?u)I_1^*FwVs+4 zaWSDHh__NVrg5a=FS#*)vh?h^n#Q~8gpJ-=V}{_ibpUV8S@zSCXx+~1ytuP*WAdMY zGA?PTL=9mVyt$|aVtm5WdojD$I?PPLytSX>vITlr!b|89heI?$h*9f;y(?`bi}Oxp z>U`U_G^83GGkFO3l|QjfB(Q=qEC^grPxgtpzr$axP;LcRw>g znDBw8O>hadR8NvNH!beTjkpF!qx_PUfKhvS+1Y*ciX@newq^30>diZXP9cukvjPs# zf9`fE%wlgv049y~>#F^;Ya82t9JM%u+zDKCP>%G!#(JU1*1GMZf79G<=N8Bp5&25_ zR}r?1%2Jnhx-sOtH&+J(lFPxW#WfG;uzaYxO=!d4OwYf_xE^1iaDGjT5i0q~I#IsX zK(3ZjuzD}0*ke&GhY}RSGL?aK@=5V0PoNA$u?)AUUk1eVlf(Y@dP$=JVJ;7WvRY-g zD?MCz>(n@>Z82ts*~T_!;i+&j2I9CFT$qNXWxOb#;*sd5JvK^lV zH|}};$bthU&Y;AHhGha2rSJx zSz)C{gbr~Tzz>MvX$lm-QfLzuAvH~)n1}W2meDRH>TH_L{LzW z2)v3J{GM|p1gg|go7MsX0z_Q)K8uU`xAZDcxQWowN%(@o z!{rKNS;q@?tl&c%x6~F0`x~yWx!ymNghw4v&V}SnD<_VfmBkzh5HG0l(YeIeFO*|F zL&cK#Vs5D2j*VpE;FoZ-ud%W5Ep7qcr-rAKLF9!vEn>| zIA;tJm}+&dyRGxjs7>iOk_tXt|3+?@nA8k(I3c1obq_Ze5n<7%-ca~`>Nb2bqJ)fD zLXUp~V|Y*YOaF$5aD5QvsPgZiPZ4sg+<(i5|5s2O{#6~OW!Pt+2Ob|@dvJ4vbbK+u z^Ew?B`V6PWY|{e7rjhTWqV0O4LiyWQGH&EU5qVPy``G`Xc$7nV6F565tBL zkvEpO`*j47k{eCt1rHr_5z#V?pW~zLi&m + + + + + + + +3. 分别在global_costmap 和local_costmap 的文件中 plugins 下添加 + global_costmap_params.yaml 中: + plugins: + - {name: costmap_prohibition_layer, type: "costmap_prohibition_layer_namespace::CostmapProhibitionLayer"} + local_costmap_params.yaml 中: + plugins: + - {name: costmap_prohibition_layer, type: "costmap_prohibition_layer_namespace::CostmapProhibitionLayer"} + +#### 测试启动使用介绍: + + 0. roscore + + 1.创建数据库 [数据库只需要创建一次就可以了] + rosrun slamproject currencyChassis_CreateSqlDatabaseMain_node + + 2.数据库调用 [启动导航前优先启动] + rosrun slamproject currencyChassis_sqlDatabaseMain_node + + 3.虚拟墙qt界面编辑 [qt界面增加虚拟墙数据只支持 line,具体使用看图片] + rosrun slamproject currencyChassis_KSDemoDlgTABLE_COSTMAPLAYERMain_node + + 4.刷新虚拟墙 【当数据库更改虚拟墙数据后需要发送topic重新加载虚拟墙】 + 4.1 引入头文件 + #include + 4.2创建 Publisher + ros::Publisher costmapProhibitionControl_pub = node.advertise("/costmapProhibitionControl", 10); + 4.3发送数据 + std_msgs::String data; + data.data="refreshCostMapPlayer"; + costmapProhibitionControl_pub.publish(data); + + + +#### 代码中使用介绍: + + + 1.查询虚拟墙数据 + 1.1 引入头文件 + #include + + 1.2 数据库操作 + ros::ServiceClient SqlQueryClient = nh.serviceClient("/QSqlQuery"); + + + 1.3【默认条件查询 MerchantNumber=EMPTY MerchantName=EMPTY RobotNumber=EMPTY MapName=EMPTY Robotfloor=EMPTY, + 需要改条件的话自己去数据库节点src/currencyChassis/currencyChassis_sqlDatabaseMain.cpp改源码,类中搜索 queryAllFromTable_CostMapPlayer 】 + disinfect_srvs::testInfo_srvs table_CostMapLayerService; + table_CostMapLayerService.request.request_type="queryAllFromTable_CostMapPlayer"; + SqlQueryClient.call(table_CostMapLayerService); + + for (int i = 0; i + 5.2创建 Publisher + ros::Publisher costmapProhibitionControl_pub = node.advertise("/costmapProhibitionControl", 10); + 5.3发送数据 + std_msgs::String data; + data.data="refreshCostMapPlayer"; + costmapProhibitionControl_pub.publish(data); + + + + +#### 项目实战通过 turtlebot3 仿真运行 + 1.首先确定数据库是否存在,不存在就创建 + 1.1 roscore + 1.2 创建数据库 [数据库只需要创建一次就可以了] + rosrun slamproject currencyChassis_CreateSqlDatabaseMain_node + 2.启动数据库 [启动导航前优先启动] + rosrun slamproject currencyChassis_sqlDatabaseMain_node + + 3.启动turtlebot3 + roslaunch turtlebot3_gazebo turtlebot3_house.launch + roslaunch turtlebot3_navigation turtlebot3_navigation.launch map_file:=/home/iimt/map.yaml + 4.启动虚拟墙编辑器,取2点,录入数据 [qt界面增加虚拟墙数据只支持 line,具体使用看图片] + rosrun slamproject currencyChassis_KSDemoDlgTABLE_COSTMAPLAYERMain_node + 5.启动rqt_publisher , 选择topic名字 /costmapProhibitionControl 发送 "refreshCostMapPlayer" 重新加载数据 + rosrun rqt_publisher rqt_publisher + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/src/costmap_prohibition_layer/.gitignore b/src/costmap_prohibition_layer/.gitignore new file mode 100644 index 0000000..13faf0f --- /dev/null +++ b/src/costmap_prohibition_layer/.gitignore @@ -0,0 +1,49 @@ +build/ +bin/ +lib/ +msg_gen/ +srv_gen/ +msg/*Action.msg +msg/*ActionFeedback.msg +msg/*ActionGoal.msg +msg/*ActionResult.msg +msg/*Feedback.msg +msg/*Goal.msg +msg/*Result.msg +msg/_*.py + +# Generated by dynamic reconfigure +*.cfgc +/cfg/cpp/ +/cfg/*.py + +# Ignore generated docs +*.dox +*.wikidoc + +# eclipse stuff +.project +.cproject + +# qcreator stuff +CMakeLists.txt.user + +srv/_*.py +*.pcd +*.pyc +qtcreator-* +*.user + +/planning/cfg +/planning/docs +/planning/src + +*~ + +# Emacs +.#* + +# Catkin custom files +CATKIN_IGNORE +/.idea/ +/cmake-build-debug/ diff --git a/src/costmap_prohibition_layer/.travis.yml b/src/costmap_prohibition_layer/.travis.yml new file mode 100644 index 0000000..19562b8 --- /dev/null +++ b/src/costmap_prohibition_layer/.travis.yml @@ -0,0 +1,107 @@ +# Generic .travis.yml file for running continuous integration on Travis-CI with +# any ROS package. +# +# This installs ROS on a clean Travis-CI virtual machine, creates a ROS +# workspace, resolves all listed dependencies, and sets environment variables +# (setup.bash). Then, it compiles the entire ROS workspace (ensuring there are +# no compilation errors), and runs all the tests. If any of the compilation/test +# phases fail, the build is marked as a failure. +# +# We handle two types of package dependencies: +# - packages (ros and otherwise) available through apt-get. These are installed +# using rosdep, based on the information in the ROS package.xml. +# - dependencies that must be checked out from source. These are handled by +# 'wstool', and should be listed in a file named dependencies.rosinstall. +# +# There are two variables you may want to change: +# - ROS_DISTRO (default is indigo). Note that packages must be available for +# ubuntu 14.04 trusty. +# - ROSINSTALL_FILE (default is dependencies.rosinstall inside the repo +# root). This should list all necessary repositories in wstool format (see +# the ros wiki). If the file does not exists then nothing happens. +# +# See the README.md for more information. +# +# Author: Felix Duvallet + +# NOTE: The build lifecycle on Travis.ci is something like this: +# before_install +# install +# before_script +# script +# after_success or after_failure +# after_script +# OPTIONAL before_deploy +# OPTIONAL deploy +# OPTIONAL after_deploy + +################################################################################ + +# Use ubuntu trusty (14.04) with sudo privileges. +dist: trusty +sudo: required +language: + - generic +cache: + - apt + +# Configuration variables. All variables are global now, but this can be used to +# trigger a build matrix for different ROS distributions if desired. +env: + global: + - ROS_CI_DESKTOP="`lsb_release -cs`" # e.g. [precise|trusty|...] + - CI_SOURCE_PATH=$(pwd) + - ROSINSTALL_FILE=$CI_SOURCE_PATH/dependencies.rosinstall + - CATKIN_OPTIONS=$CI_SOURCE_PATH/catkin.options + - ROS_PARALLEL_JOBS='-j8 -l6' + matrix: + - ROS_DISTRO=jade + + +################################################################################ + +# Install system dependencies, namely a very barebones ROS setup. +before_install: + - sudo sh -c "echo \"deb http://packages.ros.org/ros/ubuntu $ROS_CI_DESKTOP main\" > /etc/apt/sources.list.d/ros-latest.list" + - wget http://packages.ros.org/ros.key -O - | sudo apt-key add - + - sudo apt-get update -qq + - sudo apt-get install -y python-catkin-pkg python-rosdep python-wstool ros-$ROS_DISTRO-catkin + - source /opt/ros/$ROS_DISTRO/setup.bash + # Prepare rosdep to install dependencies. + - sudo rosdep init + - rosdep update + +# Create a catkin workspace with the package under integration. +install: + - mkdir -p ~/catkin_ws/src + - cd ~/catkin_ws/src + - catkin_init_workspace + # Create the devel/setup.bash (run catkin_make with an empty workspace) and + # source it to set the path variables. + - cd ~/catkin_ws + - catkin_make + - source devel/setup.bash + # Add the package under integration to the workspace using a symlink. + - cd ~/catkin_ws/src + - ln -s $CI_SOURCE_PATH . + +# Install all dependencies, using wstool and rosdep. +# wstool looks for a ROSINSTALL_FILE defined in the environment variables. +before_script: + # source dependencies: install using wstool. + - cd ~/catkin_ws/src + - wstool init + - if [[ -f $ROSINSTALL_FILE ]] ; then wstool merge $ROSINSTALL_FILE ; fi + - wstool up + # package depdencies: install using rosdep. + - cd ~/catkin_ws + - rosdep install -y --from-paths src --ignore-src --rosdistro $ROS_DISTRO + +# Compile and test. If the CATKIN_OPTIONS file exists, use it as an argument to +# catkin_make. +script: + - cd ~/catkin_ws + - catkin_make $( [ -f $CATKIN_OPTIONS ] && cat $CATKIN_OPTIONS ) + # Testing: Use both run_tests (to see the output) and test (to error out). + - catkin_make run_tests # This always returns 0, but looks pretty. + - catkin_make test # This will return non-zero if a test fails. diff --git a/src/costmap_prohibition_layer/CHANGELOG.rst b/src/costmap_prohibition_layer/CHANGELOG.rst new file mode 100644 index 0000000..87dd510 --- /dev/null +++ b/src/costmap_prohibition_layer/CHANGELOG.rst @@ -0,0 +1,21 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package costmap_prohibition_layer +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +0.0.5 (2017-01-25) +------------------ +* Support a rolling window map + Enable support for rolling window maps + +0.0.4 (2016-10-30) +------------------ +* Enable recognizing Integer values in single points +* restored deleted line + +0.0.3 (2016-10-28) +------------------ +* Install scripts added + +0.0.2 (2016-10-27) +------------------ +* Initial package version diff --git a/src/costmap_prohibition_layer/CMakeLists.txt b/src/costmap_prohibition_layer/CMakeLists.txt new file mode 100755 index 0000000..44159ab --- /dev/null +++ b/src/costmap_prohibition_layer/CMakeLists.txt @@ -0,0 +1,191 @@ +cmake_minimum_required(VERSION 2.8.3) +project(costmap_prohibition_layer) + +## Find catkin macros and libraries +## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz) +## is used, also find other catkin packages +find_package(catkin REQUIRED COMPONENTS + costmap_2d + dynamic_reconfigure + roscpp + disinfect_msg + disinfect_srvs + std_msgs +) + +## System dependencies are found with CMake's conventions +# find_package(Boost REQUIRED COMPONENTS system) + + +## Uncomment this if the package has a setup.py. This macro ensures +## modules and global scripts declared therein get installed +## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html +# catkin_python_setup() + +## Enable C++11 support +include(CheckCXXCompilerFlag) +CHECK_CXX_COMPILER_FLAG("-std=c++11" COMPILER_SUPPORTS_CXX11) +CHECK_CXX_COMPILER_FLAG("-std=c++0x" COMPILER_SUPPORTS_CXX0X) +if(COMPILER_SUPPORTS_CXX11) + set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++11") +elseif(COMPILER_SUPPORTS_CXX0X) + set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++0x") +else() + message(STATUS "The compiler ${CMAKE_CXX_COMPILER} has no C++11 support. Please use a different C++ compiler.") +endif() + +################################################ +## Declare ROS messages, services and actions ## +################################################ + +## To declare and build messages, services or actions from within this +## package, follow these steps: +## * Let MSG_DEP_SET be the set of packages whose message types you use in +## your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...). +## * In the file package.xml: +## * add a build_depend tag for "message_generation" +## * add a build_depend and a run_depend tag for each package in MSG_DEP_SET +## * If MSG_DEP_SET isn't empty the following dependency has been pulled in +## but can be declared for certainty nonetheless: +## * add a run_depend tag for "message_runtime" +## * In this file (CMakeLists.txt): +## * add "message_generation" and every package in MSG_DEP_SET to +## find_package(catkin REQUIRED COMPONENTS ...) +## * add "message_runtime" and every package in MSG_DEP_SET to +## catkin_package(CATKIN_DEPENDS ...) +## * uncomment the add_*_files sections below as needed +## and list every .msg/.srv/.action file to be processed +## * uncomment the generate_messages entry below +## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...) + +## Generate messages in the 'msg' folder +# add_message_files( +# FILES +# Message1.msg +# Message2.msg +# ) + +## Generate services in the 'srv' folder +# add_service_files( +# FILES +# Service1.srv +# Service2.srv +# ) + +## Generate actions in the 'action' folder +# add_action_files( +# FILES +# Action1.action +# Action2.action +# ) + +## Generate added messages and services with any dependencies listed here +# generate_messages( +# DEPENDENCIES +# std_msgs # Or other packages containing msgs +# ) + +################################################ +## Declare ROS dynamic reconfigure parameters ## +################################################ + +## To declare and build dynamic reconfigure parameters within this +## package, follow these steps: +## * In the file package.xml: +## * add a build_depend and a run_depend tag for "dynamic_reconfigure" +## * In this file (CMakeLists.txt): +## * add "dynamic_reconfigure" to +## find_package(catkin REQUIRED COMPONENTS ...) +## * uncomment the "generate_dynamic_reconfigure_options" section below +## and list every .cfg file to be processed + +## Generate dynamic reconfigure parameters in the 'cfg' folder +generate_dynamic_reconfigure_options( + cfg/CostmapProhibitionLayer.cfg +) + +################################### +## catkin specific configuration ## +################################### +## The catkin_package macro generates cmake config files for your package +## Declare things to be passed to dependent projects +## INCLUDE_DIRS: uncomment this if you package contains header files +## LIBRARIES: libraries you create in this project that dependent projects also need +## CATKIN_DEPENDS: catkin_packages dependent projects also need +## DEPENDS: system dependencies of this project that dependent projects also need +catkin_package( + INCLUDE_DIRS include + LIBRARIES costmap_prohibition_layer + CATKIN_DEPENDS costmap_2d dynamic_reconfigure + DEPENDS +) + +########### +## Build ## +########### + +## Specify additional locations of header files +## Your package locations should be listed before other locations +# include_directories(include) +include_directories(${catkin_INCLUDE_DIRS} include) + +## Declare a C++ library + +add_library(costmap_prohibition_layer src/costmap_prohibition_layer.cpp) +target_link_libraries(costmap_prohibition_layer ${catkin_LIBRARIES}) + +# Dynamic reconfigure: make sure configure headers are built before any node using them +add_dependencies(costmap_prohibition_layer ${PROJECT_NAME}_gencfg) + +############ +## Install ## +############# + +# all install targets should use catkin DESTINATION variables +# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html + +## Mark executable scripts (Python etc.) for installation +## in contrast to setup.py, you can choose the destination +# install(PROGRAMS +# scripts/my_python_script +# DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +# ) + + +## Mark executables and/or libraries for installation +install(TARGETS costmap_prohibition_layer + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} +) + +## Mark cpp header files for installation +install(DIRECTORY include/${PROJECT_NAME}/ + DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} + #FILES_MATCHING PATTERN "*.h" + PATTERN ".svn" EXCLUDE +) + +## Mark other files for installation (e.g. launch and bag files, etc.) +install(FILES + costmap_plugins.xml + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +) + +install(DIRECTORY + cfg + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} + PATTERN ".svn" EXCLUDE +) + +############# +## Testing ## +############# + +## Add gtest based cpp test target and link libraries +# catkin_add_gtest(${PROJECT_NAME}-test test/test_simple_layers.cpp) +# if(TARGET ${PROJECT_NAME}-test) +# target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME}) +# endif() + +## Add folders to be run by python nosetests +# catkin_add_nosetests(test) + diff --git a/src/costmap_prohibition_layer/LICENSE b/src/costmap_prohibition_layer/LICENSE new file mode 100644 index 0000000..861fccb --- /dev/null +++ b/src/costmap_prohibition_layer/LICENSE @@ -0,0 +1,29 @@ +BSD 3-Clause License + +Copyright (c) 2016, TU Dortmund - Lehrstuhl RST +All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are met: + +* Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + +* Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + +* Neither the name of the copyright holder nor the names of its + contributors may be used to endorse or promote products derived from + this software without specific prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE +FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. diff --git a/src/costmap_prohibition_layer/README.md b/src/costmap_prohibition_layer/README.md new file mode 100644 index 0000000..0f3f761 --- /dev/null +++ b/src/costmap_prohibition_layer/README.md @@ -0,0 +1,167 @@ +虚拟墙 + + + navigation里如何写自己的全局路径规划插件教程 +http://wiki.ros.org/navigation/Tutorials/Writing%20A%20Global%20Path%20Planner%20As%20Plugin%20in%20ROS +https://blog.csdn.net/heyijia0327/article/details/42241831 +https://blog.csdn.net/qq_41995710/article/details/88750354 + +# costmap_prohibition_layer +ROS-Package that implements a costmap layer to add prohibited areas to the costmap-2D by a user configuration. + +Build status of the *kinetic-devel* branch: +- Travis (Ubuntu Trusty): [![Build Status](https://travis-ci.org/rst-tu-dortmund/costmap_prohibition_layer.svg?branch=kinetic-devel)](https://travis-ci.org/rst-tu-dortmund/costmap_prohibition_layer) + +禁止层,虚拟墙 +https://blog.csdn.net/qq_41995710/article/details/88750354 +在Costmap_2d里面插入Prohibition_layer(禁止区域层) + +他们都喊我sao G 2019-03-25 16:37:10 2036 收藏 19 +版权 +在Costmap_2d里面插入Prohibition_layer(禁止区域层) +简介 +costmap_2d在navigaition里面是一个很重要的板块,通常默认的是三层地图(静态/障碍/膨胀层)叠加在一起,构成整个完整的代价地图,但是我们也可以插入一些自定义的图层,然后实现自己定制化的功能,基础的教程大家可以参考costmap_2d中插入自定义层。本文的主要目的是来告诉大家如何在代价地图中插入Prohibition_layer(禁止层),然后在已经建好的地图中设立禁止通行区域,关于prohibition_layer具体的作用大家可以参照roswiki上的解释。 + +具体实现步骤 +1 代码下载与编译 +  之前我们学习插入simple_layer的时候是在自己的工作空间(catkin_ws)中建立一个pakage,然后再去自己创建.cpp文件和.h头文件,再去改cmakelist,添加.xml文件,在这个教程中我们不需要这么麻烦,我们可以直接在github上把prohibition_layer的包下载下来(源码下载地址戳这里).,解压后放在自己的工作空间中的 src 文件夹里面,然后在终端输入: + +$ cd catkin_ws("catkin_ws"替换成你的工作空间名称) +$ catkin_make +1 +2 +编译完成以后在终端中输入 +编译完成以后,可以查看ROS系统里是否已经有了这个layer 插件。在终端中输入: + + +rospack plugins --attrib=plugin costmap_2d +1 +当你发现终端中输出: +这就表明prohibition_layer已经是一个可供使用的地图插件了. + +2 在代价地图中插入prohibition_layer +  完成步骤1后说明prohibition_layer已经可以供costmap使用了,现在我们要做的就是把prohibition_layer插入到costmap中去. +  我们在自己的代价地图参数配置文件夹中找到 global_costmap_params.yaml 和 local_costmap_params.yaml ,打开这两个文档,分别在两个文档的末尾做修改,修改后应该是下面的内容: + + plugins: + - {name: static_map, type: "costmap_2d::StaticLayer"} + - {name: obstacles, type: "costmap_2d::VoxelLayer"} + - {name: costmap_prohibition_layer, type: "costmap_prohibition_layer_namespace::CostmapProhibitionLayer"} + - {name: inflation_layer, type: "costmap_2d::InflationLayer"} + +1 +2 +3 +========================================================================================== + 下面我们来把创建的simple_layer,放入全局global_costmap中。要想使得ROS接受你的插件,要在参数中用plugins指明,也就是主要修改move_base中涉及到costmap的yaml文件,下面给出我的修改: + +1.costmap_common_params.yaml + +obstacle_range: 2.5 +raytrace_range: 3.0 +robot_radius: 0.49 +inflation_radius: 0.1 +max_obstacle_height: 0.6 +min_obstacle_height: 0.0 +obstacles: + observation_sources: scan + scan: {data_type: LaserScan, topic: /scan, marking: true, clearing: true, expected_update_rate: 0} +一定要注意,这里添加了一个obstales,说明障碍物层的数据来源scan,"obstacles:"的作用是强调命名空间。 + +2.global_costmap_params.yaml + +global_costmap: + global_frame: /map + robot_base_frame: /base_footprint + update_frequency: 1.0 + publish_frequency: 0 + static_map: true + rolling_window: false + resolution: 0.01 + transform_tolerance: 1.0 + map_type: costmap + plugins: + - {name: static_map, type: "costmap_2d::StaticLayer"} + - {name: obstacles, type: "costmap_2d::VoxelLayer"} + - {name: simplelayer, type: "simple_layer_namespace::SimpleLayer"} + - {name: inflation_layer, type: "costmap_2d::InflationLayer"} +3.local_costmap_params.yaml + +local_costmap: + global_frame: /map + robot_base_frame: /base_footprint + update_frequency: 3.0 + publish_frequency: 1.0 + static_map: false + rolling_window: true + width: 6.0 + height: 6.0 + resolution: 0.01 + transform_tolerance: 1.0 + map_type: costmap + +———————————————— + +原文链接:https://blog.csdn.net/heyijia0327/article/details/42241831 + +=========================================================================================== +5 +6 +3 修改launch文件 +  完成插入地图后我们还需要修改自己的launch文件,我是在自己的move_base.launch 中插入的,这个大家根据自己的需求,你用的carlike就修改carlike的launch文件.打开自己的launch文件中插入如下内容: + + + +1 +2 +其中的"turtlebot3_navigation"需要根据自己的情况修改,你打开自己的launch文件对照上下文就知道怎么更改了. + +4 设置禁止区域坐标参数 +  完成以上步骤所有的配置工作就剩下最后一步了,设置禁止区域坐标参数. +  首先需要在参数配置文件夹(就是和 global_costmap_params.yaml 以及 local_costmap_params.yaml 相同位置的文件夹)中创建新的文档,命名为 "prohibition_areas.yaml". +  然后在prohibition_areas.yaml文档中输入: + +prohibition_areas: +#定义一个禁止点 + - [17.09, -6.388] +# 定义一个禁止通行的线 + - [[8.33, 2.11], + [8.26, 5.11]] +# 定义一个禁止通行的区域 + - [[-11.15, -15.614], + [-12.35, -13.89], + [-10.05, -12.218]] + +1 +2 +3 +4 +5 +6 +7 +8 +9 +10 +11 +注意事项: +1 一定要严格按照上述格式来设置坐标,我之前遇到的格式错误导致不能识别禁止区域坐标情形有 +  (1):坐标前的短横线没对齐 +  (2):定义禁止区域或者禁止线,两坐标之间缺少了逗号 +2 你可以同时定义多个禁止点/多个禁止线/多个禁止区域,或者混合定义多个点/线/区域. +3 禁止区域的坐标如何设置就需要你根据自己建的图来测量,这里就不赘述了. + +5 结语 +完成以上所有内容,你再次打开自己的导航就能够在rviz中看到自己的设置的禁止区域了,这里贴出我之前做的结果: +这是我在实验室里面建立的地图,图中的红色三角形是我设立的禁止区域,矩形框是我画的四条禁止线,小车现在在矩形框内,当我把导航目标设置在矩形框外的时候,结果显示的是无法规划路线的. +———————————————— +版权声明:本文为CSDN博主「他们都喊我sao G」的原创文章,遵循CC 4.0 BY-SA版权协议,转载请附上原文出处链接及本声明。 +原文链接:https://blog.csdn.net/qq_41995710/article/details/88750354 +https://blog.csdn.net/qq_41995710/article/details/88750354 + + navigation里如何写自己的全局路径规划插件教程 +http://wiki.ros.org/navigation/Tutorials/Writing%20A%20Global%20Path%20Planner%20As%20Plugin%20in%20ROS +https://blog.csdn.net/heyijia0327/article/details/42241831 +https://blog.csdn.net/qq_41995710/article/details/88750354 +http://wiki.ros.org/costmap_prohibition_layer +move_base 分层代价地图的作用(翻译) +https://guyuehome.com/28201 diff --git a/src/costmap_prohibition_layer/cfg/CostmapProhibitionLayer.cfg b/src/costmap_prohibition_layer/cfg/CostmapProhibitionLayer.cfg new file mode 100755 index 0000000..11b028c --- /dev/null +++ b/src/costmap_prohibition_layer/cfg/CostmapProhibitionLayer.cfg @@ -0,0 +1,16 @@ +#!/usr/bin/env python + +from dynamic_reconfigure.parameter_generator_catkin import * + +gen = ParameterGenerator() + +# For integers and doubles: +# Name Type Reconfiguration level +# Description +# Default Min Max + + +gen.add("enabled", bool_t, 0, "Whether to apply this plugin or not", True) +gen.add("fill_polygons", bool_t, 0, "Whether to fill polygon cells or not", True) + +exit(gen.generate("costmap_prohibition_layer_namespace", "costmap_prohibition_layer_namespace", "CostmapProhibitionLayer")) diff --git a/src/costmap_prohibition_layer/cfg/prohibition_areas.yaml b/src/costmap_prohibition_layer/cfg/prohibition_areas.yaml new file mode 100755 index 0000000..ad9c1d8 --- /dev/null +++ b/src/costmap_prohibition_layer/cfg/prohibition_areas.yaml @@ -0,0 +1,13 @@ +prohibition_areas: +#定义一个禁止点 + - [-3.8, 4.13] +# 定义一个禁止通行的线 + - [[-5.0, 4.28], + [-5.97, 3.32]] + - [[-3.15, 4.4], + [-4.18, 3.13]] + + + + + diff --git a/src/costmap_prohibition_layer/costmap_plugins.xml b/src/costmap_prohibition_layer/costmap_plugins.xml new file mode 100755 index 0000000..c1f3fa9 --- /dev/null +++ b/src/costmap_prohibition_layer/costmap_plugins.xml @@ -0,0 +1,5 @@ + + + ROS-Package that implements a costmap layer to add prohibited areas to the costmap-2D by a user configuration. + + diff --git a/src/costmap_prohibition_layer/include/costmap_prohibition_layer/costmap_prohibition_layer.h b/src/costmap_prohibition_layer/include/costmap_prohibition_layer/costmap_prohibition_layer.h new file mode 100644 index 0000000..f69e55f --- /dev/null +++ b/src/costmap_prohibition_layer/include/costmap_prohibition_layer/costmap_prohibition_layer.h @@ -0,0 +1,216 @@ +/********************************************************************* + * + * Software License Agreement (BSD License) + * + * Copyright (c) 2016, + * TU Dortmund - Institute of Control Theory and Systems Engineering. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the institute nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Author: Stephan Kurzawe + *********************************************************************/ +#ifndef COSTMAP_PROHIBITION_LAYER_H_ +#define COSTMAP_PROHIBITION_LAYER_H_ + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +namespace costmap_prohibition_layer_namespace +{ + +// point with integer coordinates +struct PointInt +{ + int x; + int y; +}; + +class CostmapProhibitionLayer : public costmap_2d::Layer +{ +public: + + /** + * default constructor + */ + CostmapProhibitionLayer(); + + /** + * destructor + */ + virtual ~CostmapProhibitionLayer(); + /** + * function which get called at initializing the costmap + * define the reconfige callback, get the reoslution + * and read the prohibitions from the ros-parameter server + */ + virtual void onInitialize(); + + /** + * This is called by the LayeredCostmap to poll this plugin + * as to how much of the costmap it needs to update. + * Each layer can increase the size of this bounds. + */ + virtual void updateBounds(double robot_x, double robot_y, double robot_yaw, + double *min_x, double *min_y, double *max_x, double *max_y); + + /** + * function which get called at every cost updating procdure + * of the overlayed costmap. The before readed costs will get + * filled + */ + virtual void updateCosts(costmap_2d::Costmap2D& master_grid, int min_i, int min_j, + int max_i, int max_j); + +private: + + /** + * overlayed reconfigure callback function + */ + void reconfigureCB(CostmapProhibitionLayerConfig& config, uint32_t level); + + /** + * Compute bounds in world coordinates for the current set of points and polygons. + * The result is stored in class members _min_x, _min_y, _max_x and _max_y. + */ + void computeMapBounds(); + + /** + * Set cost in a Costmap2D for a polygon (polygon may be located outside bounds) + * + * @param master_grid reference to the Costmap2D object + * @param polygon polygon defined by a vector of points (in world coordinates) + * @param cost the cost value to be set (0,255) + * @param min_i minimum bound on the horizontal map index/coordinate + * @param min_j minimum bound on the vertical map index/coordinate + * @param max_i maximum bound on the horizontal map index/coordinate + * @param max_j maximum bound on the vertical map index/coordinate + * @param fill_polygon if true, tue cost for the interior of the polygon will be set as well + */ + void setPolygonCost(costmap_2d::Costmap2D &master_grid, const std::vector& polygon, + unsigned char cost, int min_i, int min_j, int max_i, int max_j, bool fill_polygon); + + /** + * Convert polygon (in map coordinates) to a set of cells in the map + * + * @remarks This method is mainly based on Costmap2D::convexFillCells() but accounts + * for a self-implemented polygonOutlineCells() method and allows negative map coordinates + * + * @param polygon polygon defined by a vector of map coordinates + * @param[out] polygon_cells new cells in map coordinates are pushed back on this container + * @param fill if true, the interior of the polygon will be considered as well + */ + void rasterizePolygon(const std::vector& polygon, std::vector& polygon_cells, bool fill); + + /** + * Extract the boundary of a polygon in terms of map cells + * + * @remarks This method is based on Costmap2D::polygonOutlineCells() but accounts + * for a self-implemented raytrace algorithm and allows negative map coordinates + * + * @param polygon polygon defined by a vector of map coordinates + * @param[out] polygon_cells new cells in map coordinates are pushed back on this container + */ + void polygonOutlineCells(const std::vector& polygon, std::vector& polygon_cells); + + /** + * Rasterize line between two map coordinates into a set of cells + * + * @remarks Since Costmap2D::raytraceLine() is based on the size_x and since we want to rasterize + * polygons that might also be located outside map bounds we provide a modified raytrace + * implementation (also Bresenham) based on the integer version presented here: + * http://playtechs.blogspot.de/2007/03/raytracing-on-grid.html + * + * @param x0 line start x-coordinate (map frame) + * @param y0 line start y-coordinate (map frame) + * @param x1 line end x-coordinate (map frame) + * @param y1 line end y-coordinate (map frame) + * @param[out] cells new cells in map coordinates are pushed back on this container + */ + void raytrace(int x0, int y0, int x1, int y1, std::vector& cells); + + + /** + * read the prohibition areas in YAML-Format from the + * ROS parameter server in the namespace of this + * plugin + * e.g. /move_base/global_costmap/prohibition_layer/param + * + * @param nhandle pointer to the ros-Node handle + * @param param name of the parameter where the + * prohibition areas saved in YAML format + * + * @return bool true if the parsing was successful + * false if it wasn't + */ + bool parseProhibitionListFromYaml(ros::NodeHandle* nhandle, const std::string& param); + + /** + * get a geometry_msgs::Point from a YAML-Array + * The z-coordinate get always written to zero! + * + * @param val YAML-array with to point-coordinates (x and y) + * @param point variable where the determined point get saved + * + * @return bool true if the determining was successful + * false if it wasn't + */ + bool getPoint(XmlRpc::XmlRpcValue& val, geometry_msgs::Point& point); + + dynamic_reconfigure::Server* _dsrv; //!< dynamic_reconfigure server for the costmap + std::mutex _data_mutex; //!< mutex for the accessing _prohibition_points and _prohibition_polygons + double _costmap_resolution; //!< resolution of the overlayed costmap to create the thinnest line out of two points + bool _fill_polygons; //!< if true, all cells that are located in the interior of polygons are marked as obstacle as well + std::vector _prohibition_points; //!< vector to save the lonely points in source coordinates + std::vector> _prohibition_polygons; //!< vector to save the polygons (including lines) in source coordinates + double _min_x, _min_y, _max_x, _max_y; //!< cached map bounds + //数据库操作 + ros::ServiceClient SqlQueryClient ; + //虚拟墙操作 + ros::Subscriber costmapProhibitionControl_sub; + //2. todo sukai load prohibition positions out of the sql server + bool parseProhibitionListFromSql(); + //虚拟墙操作 data:start stop refresh + void callBack_costmapProhibitionControl(std_msgs::String msg); + + double mark_x_, mark_y_; +}; +} +#endif diff --git a/src/costmap_prohibition_layer/package.xml b/src/costmap_prohibition_layer/package.xml new file mode 100755 index 0000000..7fc1872 --- /dev/null +++ b/src/costmap_prohibition_layer/package.xml @@ -0,0 +1,39 @@ + + + costmap_prohibition_layer + 0.0.5 + ROS-Package that implements a costmap layer to add prohibited areas to the costmap-2D by a user configuration. + + Stephan Kurzawe + + BSD + + + + + Stephan Kurzawe + + + + catkin + costmap_2d + dynamic_reconfigure + roscpp + costmap_2d + dynamic_reconfigure + roscpp + + std_msgs + std_msgs + + disinfect_msg + disinfect_msg + + disinfect_srvs + disinfect_srvs + + + + + + diff --git a/src/costmap_prohibition_layer/src/costmap_prohibition_layer.cpp b/src/costmap_prohibition_layer/src/costmap_prohibition_layer.cpp new file mode 100644 index 0000000..9ad3437 --- /dev/null +++ b/src/costmap_prohibition_layer/src/costmap_prohibition_layer.cpp @@ -0,0 +1,653 @@ +/********************************************************************* + * + * Software License Agreement (BSD License) + * + * Copyright (c) 2016, + * TU Dortmund - Institute of Control Theory and Systems Engineering. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the institute nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Author: Stephan Kurzawe + * sukai 注释 2022-03-26 + *********************************************************************/ + +#include +#include + +PLUGINLIB_EXPORT_CLASS(costmap_prohibition_layer_namespace::CostmapProhibitionLayer, costmap_2d::Layer) + +using costmap_2d::LETHAL_OBSTACLE; + +namespace costmap_prohibition_layer_namespace +{ + +CostmapProhibitionLayer::CostmapProhibitionLayer() : _dsrv(NULL) +{ +} + +CostmapProhibitionLayer::~CostmapProhibitionLayer() +{ + if (_dsrv!=NULL) + delete _dsrv; +} + +void CostmapProhibitionLayer::onInitialize() +{ + ros::NodeHandle nh("~/" + name_); + current_ = true; + + _dsrv = new dynamic_reconfigure::Server(nh); + dynamic_reconfigure::Server::CallbackType cb = + boost::bind(&CostmapProhibitionLayer::reconfigureCB, this, _1, _2); + _dsrv->setCallback(cb); + + // get a pointer to the layered costmap and save resolution + costmap_2d::Costmap2D *costmap = layered_costmap_->getCostmap(); + _costmap_resolution = costmap->getResolution(); + + //todo sukai 这里加载虚拟墙数据库 + //数据库操作 + SqlQueryClient = nh.serviceClient("/QSqlQuery"); + //更改字典数据 + //SqlQueryClient.waitForExistence(); + //虚拟墙操作 data:refreshCostMapPlayer + costmapProhibitionControl_sub = nh.subscribe("/costmapProhibitionControl", 10, &CostmapProhibitionLayer::callBack_costmapProhibitionControl, this); + + + // set initial bounds + _min_x = _min_y = _max_x = _max_y = 0; + + // reading the prohibition areas out of the namespace of this plugin! + // e.g.: "move_base/global_costmap/prohibition_layer/prohibition_areas" + + + std::string params = "prohibition_areas"; + //todo 苏凯 加载虚拟墙数据 + if (!parseProhibitionListFromSql()) + ROS_ERROR_STREAM("sukai Reading prohibition areas from sql TABLE_COSTMAPLAYER'" << "' failed!"); + + //todo 作废 用上面的 (原) + // if (!parseProhibitionListFromYaml(&nh, params)) + // ROS_ERROR_STREAM("Reading prohibition areas from '" << nh.getNamespace() << "/" << params << "' failed!"); + + + //======================================================================== + _fill_polygons = true; + nh.param("fill_polygons", _fill_polygons, _fill_polygons); + + //todo (原) compute map bounds for the current set of prohibition areas. 更新costmap区域,updateBounds的参数 + computeMapBounds(); + + ROS_INFO("CostmapProhibitionLayer initialized."); +} + +void CostmapProhibitionLayer::reconfigureCB(CostmapProhibitionLayerConfig &config, uint32_t level) +{ + enabled_ = config.enabled; + _fill_polygons = config.fill_polygons; +} + +//更新costmap区域,updateBounds的参数 robot_x,robot_y,robot_yaw 是机器人的当前位姿,不需要我们人为的去设定,ROS会自动传递这几个参数 +// https://blog.csdn.net/heyijia0327/article/details/42241831 +void CostmapProhibitionLayer::updateBounds(double robot_x, double robot_y, double robot_yaw, + double *min_x, double *min_y, double *max_x, double *max_y) +{ + if (!enabled_) + return; + + std::lock_guard l(_data_mutex); + + if (_prohibition_points.empty() && _prohibition_polygons.empty()){ + // std::cout<<"=====sukai===================_prohibition_points.empty() && _prohibition_polygons.empty()======================="< l(_data_mutex); + + // set costs of polygons + for (int i = 0; i < _prohibition_polygons.size(); ++i) + { + setPolygonCost(master_grid, _prohibition_polygons[i], LETHAL_OBSTACLE, min_i, min_j, max_i, max_j, _fill_polygons); + } + + // set cost of points + for (int i = 0; i < _prohibition_points.size(); ++i) + { + unsigned int mx; + unsigned int my; + if (master_grid.worldToMap(_prohibition_points[i].x, _prohibition_points[i].y, mx, my)) + { + master_grid.setCost(mx, my, LETHAL_OBSTACLE); + } + } +} + +void CostmapProhibitionLayer::computeMapBounds() +{ + std::lock_guard l(_data_mutex); + + // reset bounds + _min_x = _min_y = _max_x = _max_y = 0; + + // iterate polygons + for (int i = 0; i < _prohibition_polygons.size(); ++i) + { + for (int j=0; j < _prohibition_polygons.at(i).size(); ++j) + { + double px = _prohibition_polygons.at(i).at(j).x; + double py = _prohibition_polygons.at(i).at(j).y; + _min_x = std::min(px, _min_x); + _min_y = std::min(py, _min_y); + _max_x = std::max(px, _max_x); + _max_y = std::max(py, _max_y); + } + } + + // iterate points + for (int i = 0; i < _prohibition_points.size(); ++i) + { + double px = _prohibition_points.at(i).x; + double py = _prohibition_points.at(i).y; + _min_x = std::min(px, _min_x); + _min_y = std::min(py, _min_y); + _max_x = std::max(px, _max_x); + _max_y = std::max(py, _max_y); + } +} + + +void CostmapProhibitionLayer::setPolygonCost(costmap_2d::Costmap2D &master_grid, const std::vector& polygon, unsigned char cost, + int min_i, int min_j, int max_i, int max_j, bool fill_polygon) +{ + std::vector map_polygon; + for (unsigned int i = 0; i < polygon.size(); ++i) + { + PointInt loc; + master_grid.worldToMapNoBounds(polygon[i].x, polygon[i].y, loc.x, loc.y); + map_polygon.push_back(loc); + } + + std::vector polygon_cells; + + // get the cells that fill the polygon + rasterizePolygon(map_polygon, polygon_cells, fill_polygon); + + // set the cost of those cells + for (unsigned int i = 0; i < polygon_cells.size(); ++i) + { + int mx = polygon_cells[i].x; + int my = polygon_cells[i].y; + // check if point is outside bounds + if (mx < min_i || mx >= max_i) + continue; + if (my < min_j || my >= max_j) + continue; + master_grid.setCost(mx, my, cost); + } +} + + +void CostmapProhibitionLayer::polygonOutlineCells(const std::vector& polygon, std::vector& polygon_cells) + { + for (unsigned int i = 0; i < polygon.size() - 1; ++i) + { + raytrace(polygon[i].x, polygon[i].y, polygon[i + 1].x, polygon[i + 1].y, polygon_cells); + } + if (!polygon.empty()) + { + unsigned int last_index = polygon.size() - 1; + // we also need to close the polygon by going from the last point to the first + raytrace(polygon[last_index].x, polygon[last_index].y, polygon[0].x, polygon[0].y, polygon_cells); + } + } + +void CostmapProhibitionLayer::raytrace(int x0, int y0, int x1, int y1, std::vector& cells) +{ + int dx = abs(x1 - x0); + int dy = abs(y1 - y0); + PointInt pt; + pt.x = x0; + pt.y = y0; + int n = 1 + dx + dy; + int x_inc = (x1 > x0) ? 1 : -1; + int y_inc = (y1 > y0) ? 1 : -1; + int error = dx - dy; + dx *= 2; + dy *= 2; + + for (; n > 0; --n) + { + cells.push_back(pt); + + if (error > 0) + { + pt.x += x_inc; + error -= dy; + } + else + { + pt.y += y_inc; + error += dx; + } + } +} + + +void CostmapProhibitionLayer::rasterizePolygon(const std::vector& polygon, std::vector& polygon_cells, bool fill) +{ + // this implementation is a slighly modified version of Costmap2D::convexFillCells(...) + + //we need a minimum polygon of a traingle + if(polygon.size() < 3) + return; + + //first get the cells that make up the outline of the polygon + polygonOutlineCells(polygon, polygon_cells); + + if (!fill) + return; + + //quick bubble sort to sort points by x + PointInt swap; + unsigned int i = 0; + while(i < polygon_cells.size() - 1) + { + if(polygon_cells[i].x > polygon_cells[i + 1].x) + { + swap = polygon_cells[i]; + polygon_cells[i] = polygon_cells[i + 1]; + polygon_cells[i + 1] = swap; + + if(i > 0) + --i; + } + else + ++i; + } + + i = 0; + PointInt min_pt; + PointInt max_pt; + int min_x = polygon_cells[0].x; + int max_x = polygon_cells[(int)polygon_cells.size() -1].x; + + //walk through each column and mark cells inside the polygon + for(int x = min_x; x <= max_x; ++x) + { + if(i >= (int)polygon_cells.size() - 1) + break; + + if(polygon_cells[i].y < polygon_cells[i + 1].y) + { + min_pt = polygon_cells[i]; + max_pt = polygon_cells[i + 1]; + } + else + { + min_pt = polygon_cells[i + 1]; + max_pt = polygon_cells[i]; + } + + i += 2; + while(i < polygon_cells.size() && polygon_cells[i].x == x) + { + if(polygon_cells[i].y < min_pt.y) + min_pt = polygon_cells[i]; + else if(polygon_cells[i].y > max_pt.y) + max_pt = polygon_cells[i]; + ++i; + } + + PointInt pt; + //loop though cells in the column + for(int y = min_pt.y; y < max_pt.y; ++y) + { + pt.x = x; + pt.y = y; + polygon_cells.push_back(pt); + } + } + } + + +//2. todo sukai load prohibition positions out of the sql server 加载 +bool CostmapProhibitionLayer::parseProhibitionListFromSql() + { + bool ret_val = true; + + //数据库设计 costmapProhibitionLayer + //FigureType:point point_A_x point_A_y + //FigureType:line point_A_x point_A_y point_B_x point_B_y + //FigureType:polygons point_A_x point_A_y point_B_x point_B_y point_C_x point_C_y point_D_x point_D_y + //设计数据库【x,y】,【x,y】 + //查询虚拟墙数据 + disinfect_srvs::testInfo_srvs table_CostMapLayerService; + table_CostMapLayerService.request.request_type="queryAllFromTable_CostMapPlayer"; + SqlQueryClient.call(table_CostMapLayerService); + + if(table_CostMapLayerService.response.result_Table_CostMapLayers.size()<=0){ + //std::cout<<"0. ============================table_CostMapLayerService.response.result_Table_CostMapLayers.size()================================: "< vector_to_add; + if(table_CostMapLayerService.response.result_Table_CostMapLayers[i].FigureType=="point"){//点 + + geometry_msgs::Point point; + point.x =atof(table_CostMapLayerService.response.result_Table_CostMapLayers[i].POINT_A_X.c_str()); + point.y =atof(table_CostMapLayerService.response.result_Table_CostMapLayers[i].POINT_A_Y.c_str()); + point.z = 0.0; + _prohibition_points.push_back(point); + //std::cout<<"1.FigureType==point 1.point.x: "< l(_data_mutex); + std::unordered_map map_out; + + XmlRpc::XmlRpcValue param_yaml; + + bool ret_val = true; + + if (nhandle->getParam(param, param_yaml)) + { + if (param_yaml.getType() == XmlRpc::XmlRpcValue::TypeArray) // list of goals + { + for (int i = 0; i < param_yaml.size(); ++i) + { + if (param_yaml[i].getType() == XmlRpc::XmlRpcValue::TypeArray) + { + std::vector vector_to_add; + + /* ************************************** + * differ between points and polygons + * lines get to a polygon with the resolution + * of the costmap + **************************************** */ + + // add a point + if (param_yaml[i].size() == 1) + { + geometry_msgs::Point point; + ret_val = getPoint(param_yaml[i][0], point); + _prohibition_points.push_back(point); + } + // add a line + else if (param_yaml[i].size() == 2) + { + if (param_yaml[i][0].getType() == XmlRpc::XmlRpcValue::TypeDouble || + param_yaml[i][0].getType() == XmlRpc::XmlRpcValue::TypeInt) + { + // add a lonely point + geometry_msgs::Point point; + ret_val = getPoint(param_yaml[i], point); + _prohibition_points.push_back(point); + } + else + { + // add a line! + geometry_msgs::Point point_A; + ret_val = getPoint(param_yaml[i][0], point_A); + vector_to_add.push_back(point_A); + + geometry_msgs::Point point_B; + ret_val = getPoint(param_yaml[i][1], point_B); + vector_to_add.push_back(point_B); + + // calculate the normal vector for AB + geometry_msgs::Point point_N; + point_N.x = point_B.y - point_A.y; + point_N.y = point_A.x - point_B.x; + + // get the absolute value of N to normalize and get + // it to the length of the costmap resolution + double abs_N = sqrt(pow(point_N.x, 2) + pow(point_N.y, 2)); + point_N.x = point_N.x / abs_N * _costmap_resolution; + point_N.y = point_N.y / abs_N * _costmap_resolution; + + // calculate the new points to get a polygon which can be filled + geometry_msgs::Point point; + point.x = point_A.x + point_N.x; + point.y = point_A.y + point_N.y; + vector_to_add.push_back(point); + + point.x = point_B.x + point_N.x; + point.y = point_B.y + point_N.y; + vector_to_add.push_back(point); + + _prohibition_polygons.push_back(vector_to_add); + } + } + // add a point or add a polygon + else if (param_yaml[i].size() >= 3) + { + // add a polygon with any number of points + for (int j = 0; j < param_yaml[i].size(); ++j) + { + geometry_msgs::Point point; + ret_val = getPoint(param_yaml[i][j], point); + vector_to_add.push_back(point); + } + _prohibition_polygons.push_back(vector_to_add); + } + } + else + { + ROS_ERROR_STREAM("Prohibition Layer:" << param << " with index " << i << " is not correct."); + ret_val = false; + } + } + } + else + { + ROS_ERROR_STREAM("Prohibition Layer: " << param << "struct is not correct."); + ret_val = false; + } + } + else + { + ROS_ERROR_STREAM("Prohibition Layer: Cannot read " << param << " from parameter server"); + ret_val = false; + } + return ret_val; +} + +// get a point out of the XML Type into a geometry_msgs::Point +bool CostmapProhibitionLayer::getPoint(XmlRpc::XmlRpcValue &val, geometry_msgs::Point &point) +{ + try + { + // check if there a two values for the coordinate + if (val.getType() == XmlRpc::XmlRpcValue::TypeArray && val.size() == 2) + { + auto convDouble = [](XmlRpc::XmlRpcValue &val) -> double + { + if (val.getType() == XmlRpc::XmlRpcValue::TypeInt) // XmlRpc cannot cast int to double + return int(val); + return val; // if not double, an exception is thrown; + }; + + point.x = convDouble(val[0]); + point.y = convDouble(val[1]); + point.z = 0.0; + return true; + } + else + { + ROS_ERROR_STREAM("Prohibition_Layer: A point has to consist two values!"); + return false; + } + } + catch (const XmlRpc::XmlRpcException &ex) + { + ROS_ERROR_STREAM("Prohibition Layer: Cannot add current point: " << ex.getMessage()); + return false; + } +} + +//虚拟墙操作 data:start stop refresh +void CostmapProhibitionLayer::callBack_costmapProhibitionControl(std_msgs::String msg){ + + + + + + try { + std::cout<<"1. 虚拟墙操作 refresh"< + + disinfect_msg + 0.0.7 + The disinfect_msg package + + + + + iimt + + + + + + TODO + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + catkin + roscpp + rosmsg + rospy + std_msgs + roscpp + rosmsg + rospy + std_msgs + roscpp + rosmsg + rospy + message_generation + message_runtime + std_msgs + + + + + + + + diff --git a/src/disinfect_msg/redme.md b/src/disinfect_msg/redme.md new file mode 100755 index 0000000..e69de29 diff --git a/src/disinfect_srvs/.gitignore b/src/disinfect_srvs/.gitignore new file mode 100755 index 0000000..85e7c1d --- /dev/null +++ b/src/disinfect_srvs/.gitignore @@ -0,0 +1 @@ +/.idea/ diff --git a/src/disinfect_srvs/CMakeLists.txt b/src/disinfect_srvs/CMakeLists.txt new file mode 100755 index 0000000..ad830ed --- /dev/null +++ b/src/disinfect_srvs/CMakeLists.txt @@ -0,0 +1,212 @@ +cmake_minimum_required(VERSION 3.0.2) +project(disinfect_srvs) + +## Compile as C++11, supported in ROS Kinetic and newer +# add_compile_options(-std=c++11) + +## Find catkin macros and libraries +## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz) +## is used, also find other catkin packages +find_package(catkin REQUIRED COMPONENTS + roscpp + rosmsg + rospy + message_generation + disinfect_msg +) + +## System dependencies are found with CMake's conventions +# find_package(Boost REQUIRED COMPONENTS system) + + +## Uncomment this if the package has a setup.py. This macro ensures +## modules and global scripts declared therein get installed +## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html +# catkin_python_setup() + +################################################ +## Declare ROS messages, services and actions ## +################################################ + +## To declare and build messages, services or actions from within this +## package, follow these steps: +## * Let MSG_DEP_SET be the set of packages whose message types you use in +## your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...). +## * In the file package.xml: +## * add a build_depend tag for "message_generation" +## * add a build_depend and a exec_depend tag for each package in MSG_DEP_SET +## * If MSG_DEP_SET isn't empty the following dependency has been pulled in +## but can be declared for certainty nonetheless: +## * add a exec_depend tag for "message_runtime" +## * In this file (CMakeLists.txt): +## * add "message_generation" and every package in MSG_DEP_SET to +## find_package(catkin REQUIRED COMPONENTS ...) +## * add "message_runtime" and every package in MSG_DEP_SET to +## catkin_package(CATKIN_DEPENDS ...) +## * uncomment the add_*_files sections below as needed +## and list every .msg/.srv/.action file to be processed +## * uncomment the generate_messages entry below +## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...) + +## Generate messages in the 'msg' folder +# add_message_files( +# FILES +# Message1.msg +# Message2.msg +# ) + +## Generate services in the 'srv' folder + add_service_files( + FILES + testInfo_srvs.srv + Table_costmaplayer_srvs.srv + # Service1.srv + #Service2.srv + ) + +## Generate actions in the 'action' folder +# add_action_files( +# FILES +# Action1.action +# Action2.action +# ) + +## Generate added messages and services with any dependencies listed here + generate_messages( + DEPENDENCIES + std_msgs # Or other packages containing msgs + disinfect_msg + ) + +################################################ +## Declare ROS dynamic reconfigure parameters ## +################################################ + +## To declare and build dynamic reconfigure parameters within this +## package, follow these steps: +## * In the file package.xml: +## * add a build_depend and a exec_depend tag for "dynamic_reconfigure" +## * In this file (CMakeLists.txt): +## * add "dynamic_reconfigure" to +## find_package(catkin REQUIRED COMPONENTS ...) +## * uncomment the "generate_dynamic_reconfigure_options" section below +## and list every .cfg file to be processed + +## Generate dynamic reconfigure parameters in the 'cfg' folder +# generate_dynamic_reconfigure_options( +# cfg/DynReconf1.cfg +# cfg/DynReconf2.cfg +# ) + +################################### +## catkin specific configuration ## +################################### +## The catkin_package macro generates cmake config files for your package +## Declare things to be passed to dependent projects +## INCLUDE_DIRS: uncomment this if your package contains header files +## LIBRARIES: libraries you create in this project that dependent projects also need +## CATKIN_DEPENDS: catkin_packages dependent projects also need +## DEPENDS: system dependencies of this project that dependent projects also need +catkin_package( +# INCLUDE_DIRS include +# LIBRARIES qRcode_srvs +# CATKIN_DEPENDS roscpp rosmsg rospy +# DEPENDS system_lib + CATKIN_DEPENDS roscpp rosmsg rospy message_runtime +) + +########### +## Build ## +########### + +## Specify additional locations of header files +## Your package locations should be listed before other locations +include_directories( +# include + ${catkin_INCLUDE_DIRS} +) + +## Declare a C++ library +# add_library(${PROJECT_NAME} +# src/${PROJECT_NAME}/qRcode_srvs.cpp +# ) + +## Add cmake target dependencies of the library +## as an example, code may need to be generated before libraries +## either from message generation or dynamic reconfigure +# add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) + +## Declare a C++ executable +## With catkin_make all packages are built within a single CMake context +## The recommended prefix ensures that target names across packages don't collide +# add_executable(${PROJECT_NAME}_node src/qRcode_srvs_node.cpp) + +## Rename C++ executable without prefix +## The above recommended prefix causes long target names, the following renames the +## target back to the shorter version for ease of user use +## e.g. "rosrun someones_pkg node" instead of "rosrun someones_pkg someones_pkg_node" +# set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX "") + +## Add cmake target dependencies of the executable +## same as for the library above +# add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) + +## Specify libraries to link a library or executable target against +# target_link_libraries(${PROJECT_NAME}_node +# ${catkin_LIBRARIES} +# ) + +############# +## Install ## +############# + +# all install targets should use catkin DESTINATION variables +# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html + +## Mark executable scripts (Python etc.) for installation +## in contrast to setup.py, you can choose the destination +# catkin_install_python(PROGRAMS +# scripts/my_python_script +# DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +# ) + +## Mark executables for installation +## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_executables.html +# install(TARGETS ${PROJECT_NAME}_node +# RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +# ) + +## Mark libraries for installation +## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_libraries.html +# install(TARGETS ${PROJECT_NAME} +# ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} +# LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} +# RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION} +# ) + +## Mark cpp header files for installation +# install(DIRECTORY include/${PROJECT_NAME}/ +# DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} +# FILES_MATCHING PATTERN "*.h" +# PATTERN ".svn" EXCLUDE +# ) + +## Mark other files for installation (e.g. launch and bag files, etc.) +# install(FILES +# # myfile1 +# # myfile2 +# DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +# ) + +############# +## Testing ## +############# + +## Add gtest based cpp test target and link libraries +# catkin_add_gtest(${PROJECT_NAME}-test test/test_qRcode_srvs.cpp) +# if(TARGET ${PROJECT_NAME}-test) +# target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME}) +# endif() + +## Add folders to be run by python nosetests +# catkin_add_nosetests(test) diff --git a/src/disinfect_srvs/package.xml b/src/disinfect_srvs/package.xml new file mode 100755 index 0000000..dd8f14b --- /dev/null +++ b/src/disinfect_srvs/package.xml @@ -0,0 +1,77 @@ + + + disinfect_srvs + 0.0.1 + The disinfect_srvs package + + + + + iimt + + + + + + TODO + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + catkin + roscpp + rosmsg + rospy + roscpp + rosmsg + rospy + roscpp + rosmsg + rospy + + disinfect_msg + disinfect_msg + disinfect_msg + + message_generation + message_runtime + + + + + + + + + + diff --git a/src/disinfect_srvs/redme.md b/src/disinfect_srvs/redme.md new file mode 100755 index 0000000..e69de29 diff --git a/src/disinfect_srvs/srv/Table_costmaplayer_srvs.srv b/src/disinfect_srvs/srv/Table_costmaplayer_srvs.srv new file mode 100755 index 0000000..74bcc51 --- /dev/null +++ b/src/disinfect_srvs/srv/Table_costmaplayer_srvs.srv @@ -0,0 +1,8 @@ +string request_type +disinfect_msg/Table_CostMapLayer request_Table_CostMapLayer +--- +string result +int32 result_flg +int32 result_count +int32 result_maximunId +disinfect_msg/Table_CostMapLayer[] result_Table_CostMapLayerS diff --git a/src/disinfect_srvs/srv/testInfo_srvs.srv b/src/disinfect_srvs/srv/testInfo_srvs.srv new file mode 100755 index 0000000..56537b5 --- /dev/null +++ b/src/disinfect_srvs/srv/testInfo_srvs.srv @@ -0,0 +1,22 @@ +string request_type +int32 request_numRoom +int32 request_status +int32 request_ioNum +int32 request_quantum +string request_area +string request_markerName +disinfect_msg/testInfo request_testInfo +disinfect_msg/Dictionaries request_Dictionarie +disinfect_msg/TaskPOSE request_TaskPOSE +disinfect_msg/Table_Task request_Table_Task +disinfect_msg/Table_CostMapLayer request_Table_CostMapLayer +--- +string result +int32 result_flg +int32 result_count +int32 result_maximunId +disinfect_msg/testInfo[] result_testInfos +disinfect_msg/Dictionaries[] result_Dictionaries +disinfect_msg/TaskPOSE[] result_TaskPOSES +disinfect_msg/Table_Task[] result_Table_Tasks +disinfect_msg/Table_CostMapLayer[] result_Table_CostMapLayers diff --git a/src/slamproject/.gitignore b/src/slamproject/.gitignore new file mode 100644 index 0000000..7c82a58 --- /dev/null +++ b/src/slamproject/.gitignore @@ -0,0 +1,6 @@ +/.idea/ +/cmake-build-debug/ +/images2/ + +/debian/ +/obj-x86_64-linux-gnu/ diff --git a/src/slamproject/CMakeLists.txt b/src/slamproject/CMakeLists.txt new file mode 100644 index 0000000..33f84a4 --- /dev/null +++ b/src/slamproject/CMakeLists.txt @@ -0,0 +1,321 @@ +cmake_minimum_required(VERSION 3.0.2) +project(slamproject) + +add_compile_options(-std=c++11 ) +add_compile_options(-std=c++14 ) + +set(CMAKE_CXX_STANDARD 14) +SET(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++0x -O3 -mtune=native ") + + + + + +####################################################################################################### + + + + +message(PROJECT_SOURCE_DIR "${PROJECT_SOURCE_DIR}") +find_package(catkin REQUIRED COMPONENTS + roscpp + rosmsg + rospy + std_msgs + sensor_msgs + cv_bridge + image_transport + tf + + disinfect_msg + disinfect_srvs + geometry_msgs + +) + +find_package(OpenCV REQUIRED ) + + +set(CMAKE_INCLUDE_CURRENT_DIR ON) +set(CMAKE_AUTOMOC ON) + +find_package(Qt5 COMPONENTS Core Gui Widgets PrintSupport Network SerialPort Sql WebSockets WebChannel REQUIRED) + + + + + + +################################################ +## Declare ROS messages, services and actions ## +################################################ + +## To declare and build messages, services or actions from within this +## package, follow these steps: +## * Let MSG_DEP_SET be the set of packages whose message types you use in +## your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...). +## * In the file package.xml: +## * add a build_depend tag for "message_generation" +## * add a build_depend and a exec_depend tag for each package in MSG_DEP_SET +## * If MSG_DEP_SET isn't empty the following dependency has been pulled in +## but can be declared for certainty nonetheless: +## * add a exec_depend tag for "message_runtime" +## * In this file (CMakeLists.txt): +## * add "message_generation" and every package in MSG_DEP_SET to +## find_package(catkin REQUIRED COMPONENTS ...) +## * add "message_runtime" and every package in MSG_DEP_SET to +## catkin_package(CATKIN_DEPENDS ...) +## * uncomment the add_*_files sections below as needed +## and list every .msg/.srv/.action file to be processed +## * uncomment the generate_messages entry below +## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...) + +## Generate messages in the 'msg' folder +# add_message_files( +# FILES +# Message1.msg +# Message2.msg +# ) + +## Generate services in the 'srv' folder +# add_service_files( +# FILES +# Service1.srv +# Service2.srv +# ) + +## Generate actions in the 'action' folder +# add_action_files( +# FILES +# Action1.action +# Action2.action +# ) + +## Generate added messages and services with any dependencies listed here +# generate_messages( +# DEPENDENCIES +# std_msgs # Or other packages containing msgs +# ) + +################################################ +## Declare ROS dynamic reconfigure parameters ## +################################################ + +## To declare and build dynamic reconfigure parameters within this +## package, follow these steps: +## * In the file package.xml: +## * add a build_depend and a exec_depend tag for "dynamic_reconfigure" +## * In this file (CMakeLists.txt): +## * add "dynamic_reconfigure" to +## find_package(catkin REQUIRED COMPONENTS ...) +## * uncomment the "generate_dynamic_reconfigure_options" section below +## and list every .cfg file to be processed + +## Generate dynamic reconfigure parameters in the 'cfg' folder +# generate_dynamic_reconfigure_options( +# cfg/DynReconf1.cfg +# cfg/DynReconf2.cfg +# ) + +################################### +## catkin specific configuration ## +################################### +## The catkin_package macro generates cmake config files for your package +## Declare things to be passed to dependent projects +## INCLUDE_DIRS: uncomment this if your package contains header files +## LIBRARIES: libraries you create in this project that dependent projects also need +## CATKIN_DEPENDS: catkin_packages dependent projects also need +## DEPENDS: system dependencies of this project that dependent projects also need +catkin_package( +# INCLUDE_DIRS include +# LIBRARIES visualOrientation +# CATKIN_DEPENDS roscpp rosmsg rospy +# DEPENDS system_lib + #CATKIN_DEPENDS geometry_msgs roscpp rosmsg rospy tf + CATKIN_DEPENDS geometry_msgs roscpp rosmsg rospy tf +) + +########### +## Build ## +########### + +## Specify additional locations of header files +## Your package locations should be listed before other locations + + + + +include_directories( + include + ${catkin_INCLUDE_DIRS} + ${OpenCV_INCLUDE_DIRS} + ${Qt5Core_INCLUDE_DIRS} + ${Qt5Gui_INCLUDE_DIRS} + ${Qt5Widgets_INCLUDE_DIRS} + ${Qt5Network_INCLUDE_DIRS} + ${Qt5SerialPort_INCLUDE_DIRS} + ${Qt5Sql_INCLUDE_DIRS} + ${Qt5WebSockets_INCLUDE_DIRS} + ${Qt5WebChannel_INCLUDE_DIRS} + + +) +# /usr/lib/x86_64-linux-gnu/libpthread.a + +#message(STATUS ${Qt5WebChannel_INCLUDE_DIRS}) + +# ${Qt5websockets_INCLUDE_DIRS} +include_directories(/usr/include/eigen3) + + +########################################################################## + +add_executable(currencyChassis_KSDemoDlgTABLE_COSTMAPLAYERMain_node src/currencyChassis/currencyChassis_KSDemoDlgTABLE_COSTMAPLAYERMain.cpp src/currencyChassis/currencyChassis_KSDemoDlgTABLE_COSTMAPLAYER.cpp) + +add_executable(currencyChassis_CreateSqlDatabaseMain_node src/currencyChassis/currencyChassis_CreateSqlDatabaseMain.cpp) +add_executable(currencyChassis_sqlDatabaseMain_node src/currencyChassis/currencyChassis_sqlDatabaseMain.cpp) + + + + + + + +##################################################################### + +## Rename C++ executable without prefix +## The above recommended prefix causes long target names, the following renames the +## target back to the shorter version for ease of user use +## e.g. "rosrun someones_pkg node" instead of "rosrun someones_pkg someones_pkg_node" +# set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX "") + +## Add cmake target dependencies of the executable +## same as for the library above +# add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) +# qt加载的库 +SET(QT_LIBRARIES ${Qt5Core_LIBRARIES} ${Qt5Gui_LIBRARIES} ${Qt5Widgets_LIBRARIES} ${Qt5OpenGL_LIBRARIES} + ${Qt5Network_LIBRARIES} ${Qt5Xml_LIBRARIES} ${Qt5Qml_LIBRARIES} ${Qt5SerialPort_LIBRARIES} ${Qt5Sql_LIBRARIES} ${Qt5WebSockets_LIBRARIES} ${Qt5WebChannel_LIBRARIES} ) + +message(STATUS " Qt5: ${QT_LIBRARIES}") +## Specify libraries to link a library or executable target against + +########################################################################## +###############currencyChassis#############龙源############################ + + + +target_link_libraries( + currencyChassis_KSDemoDlgTABLE_COSTMAPLAYERMain_node + #${OpenCV_LIBS} + ${util} + ${tinyxml} + ${catkin_LIBRARIES} + ${QT_LIBRARIES} +) + + + + + +target_link_libraries( + currencyChassis_CreateSqlDatabaseMain_node + #${OpenCV_LIBS} + ${util} + ${tinyxml} + ${catkin_LIBRARIES} + ${QT_LIBRARIES} +) +target_link_libraries( + currencyChassis_sqlDatabaseMain_node + #${OpenCV_LIBS} + ${util} + ${tinyxml} + ${catkin_LIBRARIES} + ${QT_LIBRARIES} +) + + + + + +########################################################################## + + + +############# +## Install ## +############# + +# all install targets should use catkin DESTINATION variables +# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html + +## Mark executable scripts (Python etc.) for installation +## in contrast to setup.py, you can choose the destination +# catkin_install_python(PROGRAMS +# scripts/my_python_script +# DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +# ) + +## Mark executables for installation +## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_executables.html +# install(TARGETS ${PROJECT_NAME}_node +# RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +# ) + +## Mark libraries for installation +## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_libraries.html +# install(TARGETS ${PROJECT_NAME} +# ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} +# LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} +# RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION} +# ) + +## Mark cpp header files for installation +# install(DIRECTORY include/${PROJECT_NAME}/ +# DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} +# FILES_MATCHING PATTERN "*.h" +# PATTERN ".svn" EXCLUDE +# ) + +## Mark other files for installation (e.g. launch and bag files, etc.) +# install(FILES +# # myfile1 +# # myfile2 +# DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +# ) + +############# +## Testing ## +############# + +## Add gtest based cpp test target and link libraries +# catkin_add_gtest(${PROJECT_NAME}-test test/test_visualOrientation.cpp) +# if(TARGET ${PROJECT_NAME}-test) +# target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME}) +# endif() +# +## Add folders to be run by python nosetests +# catkin_add_nosetests(test) + + +#c++ 打包 | 把所有node节点名称加入 install +install(TARGETS + currencyChassis_KSDemoDlgTABLE_COSTMAPLAYERMain_node + currencyChassis_CreateSqlDatabaseMain_node + currencyChassis_sqlDatabaseMain_node + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} + +) + +#静态资源打包 +install(DIRECTORY launch +DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +PATTERN ".svn" EXCLUDE) +install(DIRECTORY filepath param script/source images db config + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +) + +#catkin_install_python(PROGRAMS src/ laser2pc.py +# DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} diff --git a/src/slamproject/config/prohibition_areas.yaml b/src/slamproject/config/prohibition_areas.yaml new file mode 100755 index 0000000..ad9c1d8 --- /dev/null +++ b/src/slamproject/config/prohibition_areas.yaml @@ -0,0 +1,13 @@ +prohibition_areas: +#定义一个禁止点 + - [-3.8, 4.13] +# 定义一个禁止通行的线 + - [[-5.0, 4.28], + [-5.97, 3.32]] + - [[-3.15, 4.4], + [-4.18, 3.13]] + + + + + diff --git a/src/slamproject/db/TABLE_OR_ROOM_POSE.db b/src/slamproject/db/TABLE_OR_ROOM_POSE.db new file mode 100644 index 0000000000000000000000000000000000000000..88268367f670eb084b461cbb8f70f94919ba1338 GIT binary patch literal 12288 zcmeI#U2oD*7zgmvvH+TNbupwDhOFLc;u=n0D7(_q)o20}S?45PbY(kp&46Mpaoid| zjkkUpKZ#y=;VCbYg2`^Yarr+9W=HvBW|Z>l2Eo_?3)pG4d~CfmpIx0`Oj90Cx400bZa0SG_<0uX=z1pXs| z&+mkiLaFd2OvCerca(n?q3>^fcahv9J1t8JE?U52Cda5C((WWH&&_-9`??#H=3?QpzG znN2SSal8oV#QZq|CwRNaTlT$N-&~tFgZ$iGo4afC13u3M9`Fsbg~zT~R8FWsqR~0K z{`g_Q-`|69lJdvmeXvOz(9N~%y}q3Nqa^t&5# + + slamproject + 0.0.0 + The slamproject package + + + + + iimt + + + + + + TODO + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + catkin + roscpp + rosmsg + rospy + std_msgs + roscpp + rosmsg + rospy + std_msgs + roscpp + rosmsg + rospy + std_msgs + cv_bridge + cv_bridge + cv_bridge + + + + + image_transport + image_transport + image_transport + + + disinfect_msg + disinfect_msg + disinfect_msg + + disinfect_srvs + disinfect_srvs + disinfect_srvs + + + + + + + + + + + geometry_msgs + geometry_msgs + geometry_msgs + + tf + tf + tf + + + + + + + diff --git a/src/slamproject/readme.md b/src/slamproject/readme.md new file mode 100644 index 0000000..74d6d5e --- /dev/null +++ b/src/slamproject/readme.md @@ -0,0 +1,236 @@ +送餐机器人:双轮差速导诊车 +slamproject +系统ubunt16.04 +依赖:opencv3.4.9 +开发工具 clion +项目路径:/home/iimt/workspace/workspace_ros_guidance +静态资源说明: + filepath: + 相机内参: + filepath/camera_calibration.yaml + 棋盘格图片与小车pose关联的文件 + filepath/extrinsic_param_car_in_eye.xml + 相机相对于小车的坐标 + filepath/calibration_ex_params_car_in_eye.xml + 不同二维码在基坐标下的坐标 + filepath/target_qrcode_position_with_base_*.yml + 餐桌在基坐标下的坐标(作废,用数据库) + filepath/target_foodcar_position_with_base_*.yml + 配置餐桌(作废,用数据库): + visualOrientation/param/params.yaml tables:按示例格式填写,遵守 名字tablea:->table*的顺序填 值不限制格式,tablea不要填对应的餐桌,a号默认是0位置; + 配置送餐车到达目标点后的等待时间: + visualOrientation/param/params.yaml waitGoalTime:单位毫秒 + images: + 棋盘格图片 + 注意:images文件夹中不允许有其它无关的文件,注意保存的图片文件名字格式; + 路点数据,数据库文件: + /home/iimt/workspace/workspace_ros_guidance/src/visualOrien/visualOrientation/db/TABLE_OR_ROOM_POSE.db + 地图更改位置: + src/controlMaster/luanch/amcl.launch + +------------------------------------------------------------------------- +qt:serialport安装 + sudo apt-get install ros-kinetic-qt-create + sudo apt-get install ros-kinetic-qt-build + sudo apt install libqt5serialport5-dev +二维码识别: + 二维码安装包: + sudo apt-get install ros-kinetic-ar-track-alvar + 创建二维码: + 新建一个目录,cd进目录中: + rosrun ar_track_alvar createMarker -s 5 1 + rosrun ar_track_alvar createMarker -s 5 2 + rosrun ar_track_alvar createMarker -s 5 3 + 启动二维码识: + roslaunch robot_vision usb_cam_with_calibration.launch 【需要在launch中加载内参标定文件,注意文件路径及文件名字】 + roslaunch robot_vision ar_track_camera.launch 【改二维码尺寸】 + rostopic echo /ar_pose_marker + rostopic echo /visualization_marker + +视觉定位纠偏执行步骤: + 1.内参标定 + 标定包安装:sudo apt-get install ros-kinetic-camera-calibration + roslaunch robot_vision usb_cam.launch + rosrun camera_calibration cameracalibrator.py --size 6x9 --square 20 image:=/usb_cam/image_raw + 【标定文件在cd /tmp 中解压改名:camera_calibration.yaml cp到/home/iimt/workspace/workspace_ros_guidance/src/robot_vision目录下】 + 2.外参数据采集 src/saveImgeAndCarPose.cpp + roslaunch robot_vision usb_cam.launch + roslaunch visualOrientation saveImgeAndCarPose.launch + + 3.外参标定 src/CarInEyeCalibration.cpp + rosrun visualOrientation carInEyeCalibration_node + 注意:images文件夹中不允许有其它无关的文件,注意保存的图片文件名字格式; + 注意: + 需要收到小车当前pose及二维码pose + + 4.标定:二维码位置,餐桌位置,初始化小车姿态:收到小车pose得到二维码在基坐标的pose及得到小车在基座标的pose:【先启动小车】 + roslaunch robot_vision usb_cam_with_calibration.launch 【注意加载内参文件】 + roslaunch robot_vision ar_track_camera.launch 【注意改二维码尺寸】 + roslaunch visualOrientation sendOdomClient_sql.launch + 注意: + 第一次运行需要创建数据库: + rosrun visualOrientation KSDemoDlgCreate_node + 需要收到小车当前pose及二维码pose + 目标位置手工输入编辑: + rosrun visualOrientation KSDemoDlg_node + 5.送餐演示demo + roslaunch robot_vision usb_cam_with_calibration.launch 【注意加载内参文件】 + roslaunch robot_vision ar_track_camera.launch 【注意改二维码尺寸】 + roslaunch visualOrientation sendFoodCarDemo.launch (自动更新小车姿态) +6.自动识别二维码调整小车位置信息位置 (方差大于1阀值时才会触发调整小车姿态) + roslaunch robot_vision usb_cam_with_calibration.launch 【注意加载内参文件】 + roslaunch robot_vision ar_track_camera.launch 【注意改二维码尺寸】 + roslaunch visualOrientation automaticComputerInitialPose.launch + +7. 启动导诊车ui + roslaunch visualOrientation sendGuidanceCar.launch + +日志: + 日志路径: + ~/data/log/ + + +----------------car--------------------------------- +1.通过获取tf坐标转换获取小车坐标并实时发布出去 src/ListenerCarBaseLinkPose.cpp + rosrun visualOrientation listenerCarBaselinkPose_node +2.发送小车pose得到二维码在基坐标的pose及得到小车在基座标的pose + rosrun visualOrientation sendOdomClient_node + +-------------------------校准角校准-------------线速度校准----------------- +1.校准角速度 +rosrun zxcar_nav calibrate_angular.py +执行完成之后,根据提示执行如下命令: +rosrun rqt_reconfigure rqt_reconfigure +点击start_test 转360度 +先记下手机指南针第一次的度数,比如:静止时第一次手机指南针度数50度,如果点击start_test后,小车转动后停下的度数超过50,那么就是转够了一圈有多,如果小车转动后停下的度数小于50,那么就是没有转够一圈。分以下两种情况: +情况1:小车停下后度数假如是60度,那么小车实际上是转了370度。 +此时角速度比例系数 anguler_scale= 370/360 = 1.028 +情况2:小车停下后度数假如是40度,那么小车实际上是转了350度。 +此时角速度比例系数 anguler_scale= 350/360 = 0.972 + +2.校准线速度 +rosrun zxcar_nav calibrate_linear.py +执行完成之后,根据提示执行如下命令: +rosrun rqt_reconfigure rqt_reconfigure + +点击start_test,进行第一次的走一米测试,测量小车走的距离。 +假如小车走了1.1米,那么线速度的比例系数 linear_scale = 1.1/1=1.1 +假如小车走了0.9米,那么线速度的比例系数 linear_scale = 0.9/1= 0.9 +bringup.launch + + +修改代码: + anguler/home/iimt/workspace/workspace_ros_foodCar/src/motorControl/src/motorControl.cpp + odomMsg.twist.twist.linear.x = AvergeVel*linear_scale; + odomMsg.twist.twist.angular.z = deltaThVel*anguler_scale; +----------------test--------------------------------- + +获取基坐标下小车的坐标demo:src/getOdomClient_test.cpp +启动: + rosrun visualOrientation getOdomClient_test_node + 发送serviceClient小车坐标: + request: + 1.serviceClient + 2.消息名字 serviceName = "target_odom_service"; + 3.消息类型:qRcode_srvs::qRcode + response:得到小车在基坐标下的位置 + +模拟发送小车位置的数据demo:src/sendOdomClient_test.cpp +启动: + rosrun visualOrientation sendOdomClient_test_node + server: + 1.serviceClient + 2.消息名字serviceName = "target_qrcode_service" + 3.消息类型:qRcode_srvs::qRcode + response:ok + + topic: + 1.publisher + 2.消息名字 topicName_odom = "/car_odom"; + 3.消息类型: qRcode_msg::qRcode_msg + + +------------------------------------------------------------------------- +usb_cam 启动报错:v412-ctl not found + sudo apt-get install v4l-utils +控制台 + sudo apt-get install terminator + 打开多终端同步输入 + win + G + 关闭多终端同步输入 + win + shift + G +更新命令 + sudo apt-get update + sudo apt-get upgrade + sudo apt-get dist-upgrade + sudo apt-get -f install +标定板: + 角点顺序,红橙黄绿青蓝紫的顺序 + 红色为x坐标 + y的方向是相机摆的方向 +rosrun rqt_service_caller rqt_service_caller +turtlebot-3仿真 + 启动: + roslaunch turtlebot3_gazebo turtlebot3_empty_world.launch + roslaunch turtlebot3_gazebo turtlebot3_world.launch + roslaunch turtlebot3_gazebo turtlebot3_house.launch + 控制: + roslaunch turtlebot3_teleop turtlebot3_teleop_key.launch + Turtlebot开始根据激光雷达的信号开始自主规划避障: + export TURTLEBOT3_MODEL=waffle + roslaunch turtlebot3_gazebo turtlebot3_simulation.launch + 打开rviz + export TURTLEBOT3_MODEL=waffle + roslaunch turtlebot3_gazebo turtlebot3_gazebo_rviz.launch + rostopic type /odom + rosmsg show nav_msgs/Odometry + + 开启实时建图功能,算法选择gmapping, 还有多种slam算法, 如cartographer,hector_slam + roslaunch turtlebot3_slam turtlebot3_slam.launch slam_methods:=gmapping + 尽可能保证地图闭合,然后保存地图为文件 + rosrun map_server map_saver -f ~/map + + 打开自动导航功能 + roslaunch turtlebot3_navigation turtlebot3_navigation.launch map_file:=/home/iimt/map.yaml + 初始化小车pose + rostopic echo /initialpose +二、配置文件 +        move_base使用前需要配置一些参数:运行成本、机器人半径、到达目标位置的距离,机器人移动的速度,这些参数都在rbx1_nav包的以下几个配置文件中: +        • base_local_planner_params.yaml +        • costmap_common_params.yaml +        • global_costmap_params.yaml +        • local_costmap_params.yaml + + +小乌龟: + 启动: + rosrun turtlesim turtlesim_node + rosrun turtlesim turtlesim turtle_teleop_key + rostopic list + rostopic pub /turtle1/cmd_vel + rostopic pub /turtle1/pose + rosservice type /spawn + rossrv show turtlesim/Spawn + +rviz + 启动: + rosrun rviz rviz + 选择add,加tf + 选择Fixed Frame,选择发布的tf话题 + 保存启动文件: + File->saveConfigAs 选择一个目录存放,改好名字 + + + + + + + + + + + + + + + diff --git a/src/slamproject/rviz/visualOrientation.rviz b/src/slamproject/rviz/visualOrientation.rviz new file mode 100644 index 0000000..8a525fd --- /dev/null +++ b/src/slamproject/rviz/visualOrientation.rviz @@ -0,0 +1,390 @@ +Panels: + - Class: rviz/Displays + Help Height: 78 + Name: Displays + Property Tree Widget: + Expanded: + - /TF1/Frames1 + - /TF1/Tree1 + - /Global Map1/Costmap1 + - /Global Map1/Planner1 + - /Local Map1 + - /Local Map1/Polygon1 + - /Local Map1/Costmap1 + - /Local Map1/Planner1 + Splitter Ratio: 0.5 + Tree Height: 814 + - Class: rviz/Selection + Name: Selection + - Class: rviz/Tool Properties + Expanded: + - /2D Pose Estimate1 + - /2D Nav Goal1 + Name: Tool Properties + Splitter Ratio: 0.588679016 + - Class: rviz/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.5 + - Class: rviz/Time + Experimental: false + Name: Time + SyncMode: 0 + SyncSource: LaserScan +Toolbars: + toolButtonStyle: 2 +Visualization Manager: + Class: "" + Displays: + - Alpha: 0.5 + Cell Size: 1 + Class: rviz/Grid + Color: 160; 160; 164 + Enabled: true + Line Style: + Line Width: 0.0299999993 + Value: Lines + Name: Grid + Normal Cell Count: 0 + Offset: + X: 0 + Y: 0 + Z: 0 + Plane: XY + Plane Cell Count: 20 + Reference Frame: + Value: true + - Alpha: 1 + Class: rviz/RobotModel + Collision Enabled: false + Enabled: true + Links: + All Links Enabled: true + Expand Joint Details: false + Expand Link Details: false + Expand Tree: false + Link Tree Style: Links in Alphabetic Order + base_footprint: + Alpha: 1 + Show Axes: false + Show Trail: false + base_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + base_scan: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + camera_depth_frame: + Alpha: 1 + Show Axes: false + Show Trail: false + camera_depth_optical_frame: + Alpha: 1 + Show Axes: false + Show Trail: false + camera_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + camera_rgb_frame: + Alpha: 1 + Show Axes: false + Show Trail: false + camera_rgb_optical_frame: + Alpha: 1 + Show Axes: false + Show Trail: false + caster_back_left_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + caster_back_right_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + imu_link: + Alpha: 1 + Show Axes: false + Show Trail: false + wheel_left_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + wheel_right_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + Name: RobotModel + Robot Description: robot_description + TF Prefix: "" + Update Interval: 0 + Value: true + Visual Enabled: true + - Class: rviz/TF + Enabled: false + Frame Timeout: 15 + Frames: + All Enabled: false + Marker Scale: 1 + Name: TF + Show Arrows: true + Show Axes: true + Show Names: false + Tree: + {} + Update Interval: 0 + Value: false + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz/LaserScan + Color: 0; 255; 0 + Color Transformer: FlatColor + Decay Time: 0 + Enabled: true + Invert Rainbow: false + Max Color: 255; 255; 255 + Max Intensity: 13069 + Min Color: 0; 0; 0 + Min Intensity: 28 + Name: LaserScan + Position Transformer: XYZ + Queue Size: 10 + Selectable: true + Size (Pixels): 3 + Size (m): 0.0300000012 + Style: Flat Squares + Topic: /scan + Unreliable: false + Use Fixed Frame: true + Use rainbow: true + Value: true + - Class: rviz/Image + Enabled: false + Image Topic: /raspicam_node/image + Max Value: 1 + Median window: 5 + Min Value: 0 + Name: Image + Normalize Range: true + Queue Size: 2 + Transport Hint: compressed + Unreliable: false + Value: false + - Alpha: 0.699999988 + Class: rviz/Map + Color Scheme: map + Draw Behind: false + Enabled: true + Name: Map + Topic: /map + Unreliable: false + Use Timestamp: false + Value: true + - Alpha: 1 + Buffer Length: 1 + Class: rviz/Path + Color: 0; 0; 0 + Enabled: true + Head Diameter: 0.300000012 + Head Length: 0.200000003 + Length: 0.300000012 + Line Style: Lines + Line Width: 0.0299999993 + Name: Planner Plan + Offset: + X: 0 + Y: 0 + Z: 0 + Pose Color: 255; 85; 255 + Pose Style: None + Radius: 0.0299999993 + Shaft Diameter: 0.100000001 + Shaft Length: 0.100000001 + Topic: /move_base/NavfnROS/plan + Unreliable: false + Value: true + - Class: rviz/Group + Displays: + - Alpha: 0.699999988 + Class: rviz/Map + Color Scheme: costmap + Draw Behind: true + Enabled: true + Name: Costmap + Topic: /move_base/global_costmap/costmap + Unreliable: false + Use Timestamp: false + Value: true + - Alpha: 1 + Buffer Length: 1 + Class: rviz/Path + Color: 255; 0; 0 + Enabled: true + Head Diameter: 0.300000012 + Head Length: 0.200000003 + Length: 0.300000012 + Line Style: Lines + Line Width: 0.0299999993 + Name: Planner + Offset: + X: 0 + Y: 0 + Z: 0 + Pose Color: 255; 85; 255 + Pose Style: None + Radius: 0.0299999993 + Shaft Diameter: 0.100000001 + Shaft Length: 0.100000001 + Topic: /move_base/DWAPlannerROS/global_plan + Unreliable: false + Value: true + Enabled: true + Name: Global Map + - Class: rviz/Group + Displays: + - Alpha: 1 + Class: rviz/Polygon + Color: 0; 0; 0 + Enabled: true + Name: Polygon + Topic: /move_base/local_costmap/footprint + Unreliable: false + Value: true + - Alpha: 0.699999988 + Class: rviz/Map + Color Scheme: costmap + Draw Behind: false + Enabled: true + Name: Costmap + Topic: /move_base/local_costmap/costmap + Unreliable: false + Use Timestamp: false + Value: true + - Alpha: 1 + Buffer Length: 1 + Class: rviz/Path + Color: 255; 255; 0 + Enabled: true + Head Diameter: 0.300000012 + Head Length: 0.200000003 + Length: 0.300000012 + Line Style: Lines + Line Width: 0.0299999993 + Name: Planner + Offset: + X: 0 + Y: 0 + Z: 0 + Pose Color: 255; 85; 255 + Pose Style: None + Radius: 0.0299999993 + Shaft Diameter: 0.100000001 + Shaft Length: 0.100000001 + Topic: /move_base/DWAPlannerROS/local_plan + Unreliable: false + Value: true + Enabled: true + Name: Local Map + - Alpha: 1 + Arrow Length: 0.0500000007 + Axes Length: 0.300000012 + Axes Radius: 0.00999999978 + Class: rviz/PoseArray + Color: 0; 192; 0 + Enabled: true + Head Length: 0.0700000003 + Head Radius: 0.0299999993 + Name: Amcl Particles + Shaft Length: 0.230000004 + Shaft Radius: 0.00999999978 + Shape: Arrow (Flat) + Topic: /particlecloud + Unreliable: false + Value: true + - Alpha: 1 + Axes Length: 1 + Axes Radius: 0.100000001 + Class: rviz/Pose + Color: 255; 25; 0 + Enabled: true + Head Length: 0.300000012 + Head Radius: 0.100000001 + Name: Goal + Shaft Length: 0.5 + Shaft Radius: 0.0500000007 + Shape: Arrow + Topic: /move_base_simple/goal + Unreliable: false + Value: true + Enabled: true + Global Options: + Background Color: 48; 48; 48 + Default Light: true + Fixed Frame: map + Frame Rate: 30 + Name: root + Tools: + - Class: rviz/MoveCamera + - Class: rviz/Interact + Hide Inactive Objects: true + - Class: rviz/Select + - Class: rviz/SetInitialPose + Topic: /initialpose + - Class: rviz/SetGoal + Topic: /move_base_simple/goal + - Class: rviz/Measure + Value: true + Views: + Current: + Angle: -1.57079637 + Class: rviz/TopDownOrtho + Enable Stereo Rendering: + Stereo Eye Separation: 0.0599999987 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Invert Z Axis: false + Name: Current View + Near Clip Distance: 0.00999999978 + Scale: 100 + Target Frame: + Value: TopDownOrtho (rviz) + X: 0 + Y: 0 + Saved: ~ +Window Geometry: + Displays: + collapsed: false + Height: 1027 + Hide Left Dock: false + Hide Right Dock: true + Image: + collapsed: false + QMainWindow State: 000000ff00000000fd00000004000000000000016a000003bdfc0200000007fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000006100fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c0061007900730100000028000003bd000000d700fffffffb0000000a0049006d0061006700650000000317000000cc0000001600fffffffb0000000a0049006d0061006700650000000330000000ce0000000000000000000000010000010f000003a0fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a005600690065007700730000000043000003a0000000ad00fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004a00000003efc0100000002fb0000000800540069006d00650000000000000004a00000030000fffffffb0000000800540069006d006501000000000000045000000000000000000000038f000003bd00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Selection: + collapsed: false + Time: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: true + Width: 1279 + X: 336 + Y: 67 diff --git a/src/slamproject/src/currencyChassis/currencyChassis_CreateSqlDatabaseMain.cpp b/src/slamproject/src/currencyChassis/currencyChassis_CreateSqlDatabaseMain.cpp new file mode 100644 index 0000000..a895faf --- /dev/null +++ b/src/slamproject/src/currencyChassis/currencyChassis_CreateSqlDatabaseMain.cpp @@ -0,0 +1,77 @@ +// +// Created by iimt on 21-3-20. +// + +/** + * 苏凯 + * 22-04-21 + * 创建数据库sqllite + * rosrun slamproject currencyChassis_CreateSqlDatabaseMain_node + */ + +#include +#include +#include + +#include +#include +#include +#include +#include +#include + +using namespace std; +std::string MerchantNumber;//商户编号 +std::string MerchantName;//商户名称 +std::string dbPath = "~/workspace/xuniqiang/src/slamproject/db/TABLE_OR_ROOM_POSE.db"; +//主机名 +string hostname="iimt"; + + +int main(int argc, char *argv[]) { + + + //节点名 + string nodeName = "currencyChassisskSDemoDlgCreateMainNode"; + //初始化节点 + ros::init(argc,argv,nodeName); + + + std::string home = getenv("HOME");// + dbPath =home+"/workspace/xuniqiang/src/slamproject/db/TABLE_OR_ROOM_POSE.db"; + + //创建节点 + ros::NodeHandle node; + + QApplication a(argc, argv); + + QSqlDatabase db = QSqlDatabase::addDatabase("QSQLITE"); + cout<<"dbPath: "< point:点 至少1个点数据, line:线 至少2个点数据, polygons:多边形 至少3个点数据 + + if(!sql_query.exec("create table TABLE_COSTMAPLAYER(Id int primary key,FigureType text,FigureName text, MerchantNumber text, MerchantName text,RobotNumber text,MapName text,Robotfloor text,Point_A_X text, Point_A_Y text, Point_B_X text, Point_B_Y text, Point_C_X text, Point_C_Y text, Point_D_X text, Point_D_Y text)")) + { + qDebug() << "Error: Fail to create TABLE_COSTMAPLAYER"; + } + else + { + qDebug() << "TABLE_TASK TABLE_COSTMAPLAYER!"; + } + + +} + diff --git a/src/slamproject/src/currencyChassis/currencyChassis_KSDemoDlgTABLE_COSTMAPLAYER.cpp b/src/slamproject/src/currencyChassis/currencyChassis_KSDemoDlgTABLE_COSTMAPLAYER.cpp new file mode 100644 index 0000000..883bbad --- /dev/null +++ b/src/slamproject/src/currencyChassis/currencyChassis_KSDemoDlgTABLE_COSTMAPLAYER.cpp @@ -0,0 +1,745 @@ +// +// Created by iimt on 21-3-20. +// + +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include "currencyChassis_KSDemoDlgTABLE_COSTMAPLAYER.h" + + +/************************************************************************** +* 函数名称:SlamtecKSDemoDlgCostMap +* 函数功能:目标点管理对话框构造函数 +* 输入参数:无 +* 输出参数:无 +* 返回数值:void +* 创建人员: +* 创建时间:2021-03-20 +* 修改人员: +* 修改时间: +**************************************************************************/ +SlamtecKSDemoDlgCostMap::SlamtecKSDemoDlgCostMap(QString databaseName, QString dataTableName, QWidget *parent):QDialog(parent, Qt::WindowCloseButtonHint | Qt::WindowMinMaxButtonsHint | Qt::WindowStaysOnTopHint), + m_Group(this), m_PrimaryKeyLabel(this), m_PrimaryKeyLineEdit(this), m_QueryButton(this), m_NewButton(this), m_UpdateButton(this), m_DeleteButton(this), m_TabView(NULL),m_model(NULL), + m_OKButton(this),m_CancelButton(this), m_DBName(databaseName), m_DBTableName(dataTableName), m_operator(-1) +{ + //打开数据库 + m_db = QSqlDatabase::addDatabase("QSQLITE"); +// QString datName=QApplication::applicationDirPath() + "/CONFIG/" + databaseName; +// qDebug()<<"datName: "<("/QSqlQuery"); + try { + //更改字典数据 + SqlQueryClient.waitForExistence(); + //查询字典数据 + disinfect_srvs::testInfo_srvs dictionariesservice; + dictionariesservice.request.request_type="queryAllFromTABLE_DICTIONARES";//查询字典数据 + SqlQueryClient.call(dictionariesservice); + for (int i = 0; i < dictionariesservice.response.result_Dictionaries.size(); ++i) { + // 构建map,key = 文件名, value = pose + dictionariesMap[dictionariesservice.response.result_Dictionaries.at(i).Key] = dictionariesservice.response.result_Dictionaries.at(i).Value; + qDebug()<setTable(m_DBTableName); + m_model->setEditStrategy(QSqlTableModel::OnManualSubmit); //手动提交后才修改 + m_model->select(); + m_TabView = new QTableView(this); + m_TabView->setEditTriggers(QAbstractItemView::NoEditTriggers); //设置内容不可编辑 + /*************关联槽函数*********************/ + connect(&m_NewButton, SIGNAL(clicked()), this, SLOT(onNewButtonClicked())); + connect(&m_QueryButton, SIGNAL(clicked()), this, SLOT(onQueryButtonClicked())); + connect(&m_backButton, SIGNAL(clicked()), this, SLOT(onBackButtonClicked())); //todo 1 sukai 2021-08-19 + + connect(&m_UpdateButton, SIGNAL(clicked()), this, SLOT(onUpdateButtonClicked())); + connect(&m_DeleteButton, SIGNAL(clicked()), this, SLOT(onDeleteButtonClicked())); + connect(&m_RefreshButton, SIGNAL(clicked()), this, SLOT(onRefreshButtonClicked())); + connect(&m_PrimaryKeyLineEdit, SIGNAL(textChanged(const QString &)), this, SLOT(onPrimaryKeyLineEditEmpty(const QString &))); + connect(m_TabView, SIGNAL(clicked(const QModelIndex &)), this, SLOT(onCurrentTableViewClicked(const QModelIndex &))); + connect(&m_OKButton, SIGNAL(clicked()), this, SLOT(onOKButtonClicked())); + connect(&m_CancelButton, SIGNAL(clicked()), this, SLOT(onCancelButtonClicked())); + /*************模型关联视图*******************/ + m_TabView->setModel(m_model); + /*************选中行为为整行选中*************/ + m_TabView->setSelectionBehavior(QAbstractItemView::SelectRows); + /*************对话框窗体初始化***************/ + UiInit(); + /*************对话框窗体初始化***************/ + setFixedSize(1100, 500); + setWindowTitle(QStringLiteral("执行任务管理")); +} +/************************************************************************** +* 函数名称:UiInit +* 函数功能:目标点管理对话框界面初始化 +* 输入参数:无 +* 输出参数:无 +* 返回数值:void +* 创建人员: +* 创建时间:2021-03-20 +* 修改人员: +* 修改时间: +**************************************************************************/ +void SlamtecKSDemoDlgCostMap::UiInit() +{ + int id=0; + SqlQueryClient.waitForExistence(); + disinfect_srvs::testInfo_srvs serviceMaximunId; + serviceMaximunId.request.request_type="queryMaximunIdFromTABLE_TASK";//读取数据库最大的一个id号 + SqlQueryClient.call(serviceMaximunId); + id=serviceMaximunId.response.result_maximunId; + + m_PrimaryKeyLabel.setText(m_model->headerData(0, Qt::Horizontal).toString()); + m_NewButton.setText(QStringLiteral("增加")); + m_QueryButton.setText(QStringLiteral("查询")); + m_backButton.setText(QStringLiteral("返回"));//todo 2 sukai 2021-08-19 + + m_UpdateButton.setText(QStringLiteral("修改")); + m_DeleteButton.setText(QStringLiteral("删除")); + m_RefreshButton.setText(QStringLiteral("查询所有")); + m_UpdateButton.setEnabled(true); + m_OKButton.setText(QStringLiteral("确定")); + m_CancelButton.setText(QStringLiteral("取消")); + /**************灵活增加界面右侧数据显示形式******************/ + for(int i=0; icolumnCount(); i++) + { + m_infoLabelList.append(new QLabel(this)); + QString m_modelName= m_model->headerData(i, Qt::Horizontal).toString(); + + // m_infoEditList.append(new QLineEdit(this)); + + + if(m_modelName=="Id"){ + + //读取数据库最大的一个id号 + int id=0; + SqlQueryClient.waitForExistence(); + disinfect_srvs::testInfo_srvs serviceMaximunId; + serviceMaximunId.request.request_type="queryMaximunIdFromTABLE_CostMapPlayer";//读取数据库最大的一个id号 + SqlQueryClient.call(serviceMaximunId); + id=serviceMaximunId.response.result_maximunId; + QLineEdit *pEdit = new QLineEdit(this); + pEdit->setText(QString::number(id)); + m_infoEditList.append(pEdit); + }else if(m_modelName=="FigureType"){ + //图形类型 point:点 至少1个点数据, line:线 至少2个点数据, polygons:多边形 至少3个点数据 + QComboBox *qbox = new QComboBox(this); + qbox->addItem("请选择图形类型"); + qbox->addItem("point"); + qbox->addItem("line"); + qbox->addItem("polygons"); + m_infoEditList.append(qbox);//new QComboBox(this) + } else if(m_modelName=="MerchantNumber"){ + string merchantNumber = dictionariesMap["merchantNumber"]; + QLineEdit *pEdit = new QLineEdit(this); + if(merchantNumber.size()>0){ + pEdit->setText(QString::fromStdString(merchantNumber)); + qDebug()<<"QString::fromStdString(merchantNumber: "<setText(""); + qDebug()<<" 空 QString::fromStdString(merchantNumber: "<0){ + pEdit->setText(QString::fromStdString(merchantName)); + }else{ + pEdit->setText(""); + } + m_infoEditList.append(pEdit); + }else if(m_modelName=="RobotNumber"){ + string robotNumber = dictionariesMap["robotNumber"]; + QLineEdit *pEdit = new QLineEdit(this); + if(robotNumber.size()>0){ + pEdit->setText(QString::fromStdString(robotNumber)); + }else{ + pEdit->setText(""); + } + m_infoEditList.append(pEdit); + }else if(m_modelName=="MapName"){ + string mapName = dictionariesMap["mapName"]; + QLineEdit *pEdit = new QLineEdit(this); + if(mapName.size()>0){ + pEdit->setText(QString::fromStdString(mapName)); + }else{ + pEdit->setText(""); + } + m_infoEditList.append(pEdit); + }else if(m_modelName=="Robotfloor"){ + string robotfloor = dictionariesMap["robotfloor"]; + QLineEdit *pEdit = new QLineEdit(this); + if(robotfloor.size()>0){ + pEdit->setText(QString::fromStdString(robotfloor)); + }else{ + pEdit->setText(""); + } + m_infoEditList.append(pEdit); + } else{ + m_infoEditList.append(new QLineEdit(this)); + } + + m_infoLabelList[i]->setText(m_modelName); + m_infoEditList[i]->setEnabled(false); + + } + m_OKButton.setEnabled(false); + m_CancelButton.setEnabled(false); + /**************灵活增加界面右侧数据显示形式 END******************/ + QHBoxLayout *TotalHBoxLayout = new QHBoxLayout(); + QVBoxLayout *TotalVBoxLayout = new QVBoxLayout(); + QVBoxLayout *UserGroupVBoxLayout = new QVBoxLayout(); + QHBoxLayout *UserEditHBoxLayout = new QHBoxLayout(); + QHBoxLayout *UserButtonHBoxLayout = new QHBoxLayout(); + QFormLayout *UserPrimaryKeyFormLayout = new QFormLayout(); + QFormLayout *UserSelectFormLayout = new QFormLayout(); + QHBoxLayout *UserSelectHBoxLayout = new QHBoxLayout(); + QVBoxLayout *UserSelectVBoxLayout = new QVBoxLayout(); + /*****************界面右侧group布局******************/ + for (int i=0; iaddRow( m_infoLabelList[i], m_infoEditList[i]); + } + UserSelectHBoxLayout->addWidget(&m_OKButton); + UserSelectHBoxLayout->addWidget(&m_CancelButton); + UserSelectVBoxLayout->addLayout(UserSelectFormLayout); + UserSelectVBoxLayout->addLayout(UserSelectHBoxLayout); + UserSelectVBoxLayout->addStretch(); + /*****************界面右侧group布局 END******************/ + + UserPrimaryKeyFormLayout->addRow(&m_PrimaryKeyLabel, &m_PrimaryKeyLineEdit); + UserEditHBoxLayout->addLayout(UserPrimaryKeyFormLayout); + UserEditHBoxLayout->addWidget(&m_QueryButton); + UserEditHBoxLayout->addWidget(&m_backButton);//todo 3 sukai 2021-08-19 + + UserEditHBoxLayout->addStretch(); + + UserButtonHBoxLayout->addWidget(&m_NewButton); + UserButtonHBoxLayout->addWidget(&m_UpdateButton); + UserButtonHBoxLayout->addWidget(&m_DeleteButton); + UserButtonHBoxLayout->addWidget(&m_RefreshButton); + UserGroupVBoxLayout->addLayout(UserEditHBoxLayout); + UserGroupVBoxLayout->addLayout(UserButtonHBoxLayout); + m_Group.setLayout(UserGroupVBoxLayout); + TotalVBoxLayout->addWidget(&m_Group); + TotalVBoxLayout->addWidget(m_TabView); + TotalHBoxLayout->addLayout(TotalVBoxLayout, 3); + TotalHBoxLayout->addLayout(UserSelectVBoxLayout, 1); + setLayout(TotalHBoxLayout); +} + + +//todo 4 sukai 2021-8-19 返回ui +void SlamtecKSDemoDlgCostMap::onBackButtonClicked() +{ + // system("rosnode kill SlamtecKSDemoDlgCostMapMainNode"); + // sleep(1); + execlp("rosrun", "rosrun", "ui","ui", NULL); + qDebug()<<"======ui====="; +} + +/************************************************************************** +* 函数名称:onNewUserButtonClick +* 函数功能:目标点管理对话框界新增目标点pose按钮槽函数 +* 输入参数:无 +* 输出参数:无 +* 返回数值:void +* 创建人员: +* 创建时间:2021-03-20 +* 修改人员: +* 修改时间: +**************************************************************************/ +void SlamtecKSDemoDlgCostMap::onNewButtonClicked() +{ + for (int i=0; isetEnabled(true); + } + m_operator = INSERT; + m_OKButton.setEnabled(true); + m_CancelButton.setEnabled(true); +} +/************************************************************************** +* 函数名称:onQueryUserButtonClick +* 函数功能:目标点管理对话框界查询目标点pose按钮槽函数 +* 输入参数:无 +* 输出参数:无 +* 返回数值:void +* 创建人员:廖明胜 +* 创建时间:2021-03-20 +* 修改人员: +* 修改时间: +**************************************************************************/ +void SlamtecKSDemoDlgCostMap::onQueryButtonClicked() +{ + QString toFind = m_PrimaryKeyLineEdit.text(); + QString ID = m_model->headerData(0, Qt::Horizontal).toString(); + m_model->setFilter(ID + "=\'" + toFind + "\'"); + m_model->select(); +} +/************************************************************************** +* 函数名称:onUpdateButtonClicked +* 函数功能:目标点管理对话框界修改目标点pose按钮槽函数 +* 输入参数:无 +* 输出参数:无 +* 返回数值:void +* 创建人员: +* 创建时间:2021-03-20 +* 修改人员: +* 修改时间: +**************************************************************************/ +void SlamtecKSDemoDlgCostMap::onUpdateButtonClicked() +{ + int toUpdate = m_TabView->currentIndex().row(); + QSqlRecord recode = m_model->record(toUpdate); +// for (int i=0; isetEnabled(true); +// m_infoEditList[i]->setText(recode.value(i).toString()); +// } + update_infoEditListSetText(recode,true); + m_operator = UPDATE; + m_OKButton.setEnabled(true); + m_CancelButton.setEnabled(true); + +} + +/************************************************************************** +* 函数名称:onDeleteButtonClicked +* 函数功能:目标点管理对话框界删除目标点pose按钮槽函数 +* 输入参数:无 +* 输出参数:无 +* 返回数值:void +* 创建人员: +* 创建时间:2021-03-20 +* 修改人员: +* 修改时间: +**************************************************************************/ +void SlamtecKSDemoDlgCostMap::onDeleteButtonClicked() +{ + int toDelRow = m_TabView->currentIndex().row(); + if (QMessageBox::Ok == QMessageBox::warning(this, QStringLiteral("提示"), QStringLiteral("确定要删除") + m_model->data(m_model->index(toDelRow, 0)).toString() + QStringLiteral("吗?"), QMessageBox::Ok|QMessageBox::No)) + { + m_model->removeRow(toDelRow); + m_model->submitAll(); + } + + m_model->select(); +} +/************************************************************************** +* 函数名称:onDeleteButtonClicked +* 函数功能:目标点管理对话框界刷新目标点pose按钮槽函数 +* 输入参数:无 +* 输出参数:无 +* 返回数值:void +* 创建人员: +* 创建时间:2021-03-20 +* 修改人员: +* 修改时间: +**************************************************************************/ +void SlamtecKSDemoDlgCostMap::onRefreshButtonClicked(){ + m_model->setTable(m_DBTableName); //重新关联数据库表,这样才能查询整个表 + m_model->select(); +} +/************************************************************************** +* 函数名称:onUserNameEditEmpty +* 函数功能:当m_UserNameEdit编辑框为空时,显示所有目标点pose +* 输入参数:无 +* 输出参数:无 +* 返回数值:void +* 创建人员: +* 创建时间:2021-03-20 +* 修改人员: +* 修改时间: +**************************************************************************/ +void SlamtecKSDemoDlgCostMap::onPrimaryKeyLineEditEmpty(const QString & text) +{ + if (text.isEmpty()) + { + m_model->setTable(m_DBTableName); //重新关联数据库表,这样才能查询整个表 + m_model->select(); + } +} +/************************************************************************** + * 函数名称:onCurrentTableViewActived + * 函数功能:m_TableView视图选取当前行槽函数,内容映射到右侧目标点pose编辑中 + * 输入参数:无 + * 输出参数:无 + * 返回数值:void + * 创建人员: + * 创建时间:2021-03-20 + * 修改人员: + * 修改时间: + **************************************************************************/ +void SlamtecKSDemoDlgCostMap::onCurrentTableViewClicked(const QModelIndex & index) +{ + if (!m_OKButton.isEnabled() || (INSERT == m_operator)) //只有可编辑并且操作为修改操作时才映射内容 + { + return; + } + int currentRow = index.row(); + QSqlRecord recode = m_model->record(currentRow); +// for (int i=0; isetEnabled(true); +// m_infoEditList[i]->setText(recode.value(i).toString()); +// } + update_infoEditListSetText(recode,true); +} +/************************************************************************** + * 函数名称:onOKButtonClicked + * 函数功能:OKButton点击槽函数,确定修改数据库 + * 输入参数:无 + * 输出参数:无 + * 返回数值:void + * 创建人员: + * 创建时间:2021-03-20 + * 修改人员: + * 修改时间: + **************************************************************************/ +void SlamtecKSDemoDlgCostMap::onOKButtonClicked() +{ +//sukai + QList infoTextList; +//todo sukai + m_infoEditListSetText(infoTextList); +//sukai + if (infoTextList.count()text().isEmpty()) +// if (m_infoEditList[i]->text().isEmpty()) +// { +// QMessageBox::warning(this, QStringLiteral("提示"), QStringLiteral("请将内容填写完整"), QMessageBox::Ok); +// return; +// } +// } + switch (m_operator) + { + case INSERT: + { + if (QMessageBox::Ok == QMessageBox::warning(this, QStringLiteral("提示"), QStringLiteral("请确定是否增加"), QMessageBox::Ok|QMessageBox::No)) + { + int col = m_model->columnCount(); + int row = m_model->rowCount(); + m_model->insertRow(row); + for (int i=0; isetData(m_model->index(row, i),infoTextList[i]); + } + m_model->submitAll(); //提交修改 + } + } + break; + case UPDATE: + { + if (QMessageBox::Ok == QMessageBox::warning(this, QStringLiteral("提示"), QStringLiteral("请确定是否修改"), QMessageBox::Ok|QMessageBox::No)) + { + int col = m_model->columnCount(); + int CurrentRow = m_TabView->currentIndex().row(); + for (int i=0; isetData(m_model->index(CurrentRow, i),infoTextList[i]); + } + m_model->submitAll(); //提交修改 + } + } + break; + default: + break; + } +// for (int i=0; isetText(""); +// m_infoEditList[i]->setEnabled(false); +// } + //sukai + init_infoEditListSetText(); + m_model->select(); + m_OKButton.setEnabled(false); + m_CancelButton.setEnabled(false); +} +/************************************************************************** +* 函数名称:onCancelButtonClicked +* 函数功能:OKButton点击槽函数,不操作 +* 输入参数:无 +* 输出参数:无 +* 返回数值:void +* 创建人员: +* 创建时间:2021-03-20 +* 修改人员: +* 修改时间: +**************************************************************************/ +void SlamtecKSDemoDlgCostMap::onCancelButtonClicked() +{ +// for (int i=0; isetText(""); +// m_infoEditList[i]->setEnabled(false); +// } + //sukai + init_infoEditListSetText(); + m_OKButton.setEnabled(false); + m_CancelButton.setEnabled(false); +} +/************************************************************************** +* 函数名称:~KsUserManageDlg +* 函数功能:目标点管理对话框析构函数 +* 输入参数:无 +* 输出参数:无 +* 返回数值:void +* 创建人员: +* 创建时间:2021-03-20 +* 修改人员: +* 修改时间: +**************************************************************************/ +SlamtecKSDemoDlgCostMap::~SlamtecKSDemoDlgCostMap() +{ + qDebug() << "SlamtecKSDemoDlgCostMap::~SlamtecKSDemoDlgCostMap()"; + m_db.close(); +} + +/************************************************************************** +* 函数名称:m_infoEditListSetText +* 函数功能:取数据库数据填充右边栏数据 +* 输入参数:无 +* 输出参数:无 +* 返回数值:void +* 创建人员: +* 创建时间:2021-05-25 +* 修改人员: +* 修改时间: +**************************************************************************/ + +//todo sukai +void SlamtecKSDemoDlgCostMap::update_infoEditListSetText(QSqlRecord &recode,bool flg) +{ + + for (int i=0; icurrentText(): "<currentText(); + const QString &string1 = recode.value(i).toString(); + pEdit->setCurrentText(string1); + + } + break; + + default: + QLineEdit *pEdit = (QLineEdit *) m_infoEditList[i]; + pEdit->setText(recode.value(i).toString()); + + + } + m_infoEditList[i]->setEnabled(flg); + } + +} +/************************************************************************** +* 函数名称:m_infoEditListSetText +* 函数功能:取右边栏数据 +* 输入参数:无 +* 输出参数:无 +* 返回数值:void +* 创建人员: +* 创建时间:2021-05-25 +* 修改人员: +* 修改时间: +**************************************************************************/ +//todo sukai +void SlamtecKSDemoDlgCostMap::m_infoEditListSetText(QList &infoTextList) +{ + + + for (int i=0; icurrentIndex(); + //sukai EMPTY提示用户 + if(i==0){ + infoTextList.append("EMPTY"); + }else{ + infoTextList.append(pEdit->currentText()); + } + } + break; + + default: + QLineEdit *pEdit = (QLineEdit *) m_infoEditList[i]; + qDebug() << "pEdit->text: "<text(); + infoTextList.append(pEdit->text()); + } + + m_infoEditList[i]->setEnabled(false); + } + +} +/************************************************************************** +* 函数名称:init_infoEditListSetText +* 函数功能:初始化右边栏数据 +* 输入参数:无 +* 输出参数:无 +* 返回数值:void +* 创建人员: +* 创建时间:2021-05-25 +* 修改人员: +* 修改时间: +**************************************************************************/ +//todo sukai +void SlamtecKSDemoDlgCostMap::init_infoEditListSetText() +{ + + + for (int i=0; i0){ + pEdit->setText(QString::number(id)); + }else{ + pEdit->setText(""); + } + } + + break; + case 1://QComboBox + { + QComboBox *pEdit = (QComboBox *) m_infoEditList[i]; + pEdit->setCurrentIndex(0); + } + + break; + case 2: + { + string merchantNumber = dictionariesMap["merchantNumber"]; + QLineEdit *pEdit = (QLineEdit *) m_infoEditList[i]; + + if(merchantNumber.size()>0){ + pEdit->setText(QString::fromStdString(merchantNumber)); + }else{ + pEdit->setText(""); + } + } + + break; + case 3: + { + + QLineEdit *pEdit = (QLineEdit *) m_infoEditList[i]; + string merchantName = dictionariesMap["merchantName"]; + + if(merchantName.size()>0){ + pEdit->setText(QString::fromStdString(merchantName)); + }else{ + pEdit->setText(""); + } + } + + break; + case 4: + { + QLineEdit *pEdit = (QLineEdit *) m_infoEditList[i]; + string robotNumber = dictionariesMap["robotNumber"]; + + if(robotNumber.size()>0){ + pEdit->setText(QString::fromStdString(robotNumber)); + }else{ + pEdit->setText(""); + } + } + + break; + case 5: + { + QLineEdit *pEdit = (QLineEdit *) m_infoEditList[i]; + string mapName = dictionariesMap["mapName"]; + if(mapName.size()>0){ + pEdit->setText(QString::fromStdString(mapName)); + }else{ + pEdit->setText(""); + } + + } + + break; + case 6: + { + QLineEdit *pEdit = (QLineEdit *) m_infoEditList[i]; + string robotfloor = dictionariesMap["robotfloor"]; + if(robotfloor.size()>0){ + pEdit->setText(QString::fromStdString(robotfloor)); + }else{ + pEdit->setText(""); + } + + } + + break; + default: + QLineEdit *pEdit = (QLineEdit *) m_infoEditList[i]; + pEdit->setText(""); + + } + m_infoEditList[i]->setEnabled(false); + } + +} +//todo sukai +void SlamtecKSDemoDlgCostMap::onUpdate() { + ros::spinOnce(); + //处理消息 + if(ros::isShuttingDown()){ + QApplication::quit(); + } + + +} \ No newline at end of file diff --git a/src/slamproject/src/currencyChassis/currencyChassis_KSDemoDlgTABLE_COSTMAPLAYER.h b/src/slamproject/src/currencyChassis/currencyChassis_KSDemoDlgTABLE_COSTMAPLAYER.h new file mode 100644 index 0000000..3e65714 --- /dev/null +++ b/src/slamproject/src/currencyChassis/currencyChassis_KSDemoDlgTABLE_COSTMAPLAYER.h @@ -0,0 +1,114 @@ +// +// Created by iimt on 21-3-20. +// + +#ifndef VISUALORIENTATION_currencyChassis_SAMTECKSDEMODLGTABLE_TASKPOSE_H +#define VISUALORIENTATION_currencyChassis_SAMTECKSDEMODLGTABLE_TASKPOSE_H + + + +#include +#include +#include +#include +#include +#include +#include +#include +#include +//************sukai****************** +#include +#include +#include +#include +#include +#include +#include +/* + * sukai + * 21-3-20 + * 测试 sqllite + */ +using namespace std; +class SlamtecKSDemoDlgCostMap : public QDialog +{ +Q_OBJECT + + enum {UPDATE, INSERT}; + int m_operator; +//主机名 + std::string hostname="iimt"; +public: + QTimer* updateTimer; + ros::NodeHandle node; + //数据库操作 + ros::ServiceClient SqlQueryClient; + //字典数据 + map dictionariesMap; + void onUpdate(); + + explicit SlamtecKSDemoDlgCostMap(QString databaseName, QString dataTableName, QWidget *parent = 0 ); + ~SlamtecKSDemoDlgCostMap(); + +private: + + void UiInit(); + //取数据库数据填充右边栏数据 + void update_infoEditListSetText(QSqlRecord &recode,bool flg); + + //取右边栏数据 + void m_infoEditListSetText(QList &infoTextList); + //初始化右边栏数据 + void init_infoEditListSetText(); +protected slots: + void onNewButtonClicked(); + void onQueryButtonClicked(); + void onBackButtonClicked();//todo sukai 2021-08-19 + + void onUpdateButtonClicked(); + void onDeleteButtonClicked(); + void onRefreshButtonClicked(); + void onPrimaryKeyLineEditEmpty(const QString & text); + void onCurrentTableViewClicked(const QModelIndex & index); + void onOKButtonClicked(); + void onCancelButtonClicked(); + +private: + QSqlDatabase m_db; + QString m_DBName; + QString m_DBTableName; + +private: + QTableView* m_TabView; + QSqlTableModel* m_model; + +private: + // QList m_infoEditList; + QList m_infoEditList; + QList m_infoLabelList; + QPushButton m_OKButton; + QPushButton m_CancelButton; + +private: + + /*所有用户信息容器组*/ + QGroupBox m_Group; + + QLabel m_PrimaryKeyLabel; + QLineEdit m_PrimaryKeyLineEdit; + QPushButton m_QueryButton; + QPushButton m_backButton;//todo sukai 2021-08-19 + + QPushButton m_NewButton; + QPushButton m_UpdateButton; + QPushButton m_DeleteButton; + QPushButton m_RefreshButton; + /*所选择用户信息容器组*/ + QGroupBox m_SelectGroup; + +}; + + + + +#endif //VISUALORIENTATION_currencyChassis_SAMTECKSDEMODLGTABLE_TASKPOSE_H diff --git a/src/slamproject/src/currencyChassis/currencyChassis_KSDemoDlgTABLE_COSTMAPLAYERMain.cpp b/src/slamproject/src/currencyChassis/currencyChassis_KSDemoDlgTABLE_COSTMAPLAYERMain.cpp new file mode 100644 index 0000000..470b614 --- /dev/null +++ b/src/slamproject/src/currencyChassis/currencyChassis_KSDemoDlgTABLE_COSTMAPLAYERMain.cpp @@ -0,0 +1,57 @@ +// +// Created by iimt on 21-3-20. +// + +/** + * sukai + * 虚拟墙编辑 + * 22-01-15 + * 第一次执行前需要 首先执行 rosrun slamservice currencyChassis_CreateSqlDatabaseMain_node 创建数据库 + * + * rosrun slamservice currencyChassis_KSDemoDlgTABLE_COSTMAPLAYERMain_node + * point:点 至少1个点数据, line:线 至少2个点数据, polygons:多边形 至少3个点数据 + */ + +//#include "KsTestDemo.h" +#include +#include + +#include "currencyChassis_KSDemoDlgTABLE_COSTMAPLAYER.h" +#include +#include +using namespace std; + +//std::string dbPath = ros::package::getPath("visualorientation")+"/db/TABLE_OR_ROOM_POSE.db"; +std::string dbPath ="~/workspace/xuniqiang/src/slamproject/db/TABLE_OR_ROOM_POSE.db"; +//主机名 +string hostname="iimt"; +int main(int argc, char *argv[]) +{ + + //节点名 + string nodeName = "currencyChassis_KSDemoDlgTABLE_COSTMAPLAYERMain_node"; + //初始化节点 + ros::init(argc,argv,nodeName); + + //获取主机名称 + + char hname[128]; + gethostname(hname, sizeof(hname)); + cout<<"hname:"< +#include +#include + +#include +#include +#include +#include +#include +#include "disinfect_srvs/testInfo_srvs.h" +#include "disinfect_msg/testInfo.h" +#include +#include +#include +#include +#include +#include +#include +#include +#include + + + + +using namespace std; +std::string dbPath = "/workspace/xuniqiang/src/slamproject/db/TABLE_OR_ROOM_POSE.db";// + +int time_int=50; + +struct SqlSendMessage +{ + + disinfect_srvs::testInfo_srvsRequest request; + disinfect_srvs::testInfo_srvsResponse response; +}; + + + +//指令队列 +queue instructionQueue; +mutex *m = new mutex; +//操作sql日志 +void logWriteSql(string type,int id,string status){ + try{ + + + }catch (std::exception e){ + // ROS_ERROR(e.what()); + + } + +} +//操作sql日志 +void logWriteSqlString(string data){ + try{ + + + }catch (std::exception e){ + // ROS_ERROR(e.what()); + + } + +} + + + +// ============start============虚拟墙=======:TABLE_COSTMAPLAYER=========FigureType-> point:点 至少1个点数据, line:线 至少2个点数据, polygons:多边形 至少3个点数据========================================== + + +void query_disinfect_msg_Table_CostMapPlayer(disinfect_msg::Table_CostMapLayer &t,QSqlQuery &query){ + + t.Id=query.value("Id").toInt();//执行路点任务id号 + t.FigureType = query.value("FigureType").toString().toStdString();//图形类型 point:点 至少1个点数据, line:线 至少2个点数据, polygons:多边形 至少3个点数据 + t.FigureName = query.value("FigureName").toString().toStdString();//虚拟墙线或点名字 + t.MerchantName = query.value("MerchantName").toString().toStdString();// 商户名称 + t.MerchantNumber = query.value("MerchantNumber").toString().toStdString();// 商户编号 客户编号 比如龙源或者某个餐饮店比如海底捞1号店【每家店铺可能包含10台机器人,它们在同一个场景运行所以它们的客户编号都是一致的(方便多机协作)】 + t.MapName = query.value("MapName").toString().toStdString();//地图名字 + t.Robotfloor = query.value("Robotfloor").toString().toStdString();//地图楼层 + t.RobotNumber = query.value("RobotNumber").toString().toStdString();//自研底盘机器人编号: longyuan_wt_00001;思岚机器人编号 SLAMWARE-812370; WT5LS103194: 云迹 机器人编号 ; + t.POINT_A_X = query.value("POINT_A_X").toString().toStdString();//第一个点位A + t.POINT_A_Y = query.value("POINT_A_Y").toString().toStdString();//第一个点位A + t.POINT_B_X = query.value("POINT_B_X").toString().toStdString();//第二个点位B + t.POINT_B_Y = query.value("POINT_B_Y").toString().toStdString();//第二个点位B + t.POINT_C_X = query.value("POINT_C_X").toString().toStdString();//第三个点位C + t.POINT_C_Y = query.value("POINT_C_Y").toString().toStdString();//第三个点位C + t.POINT_D_X = query.value("POINT_D_X").toString().toStdString();//第四个点位D + t.POINT_D_Y = query.value("POINT_D_Y").toString().toStdString();//第四个点位D + +} +//删除数据ByFigureName +bool deleteTaskPOSEFromTABLE_CostMapPlayerByFigureName(disinfect_srvs::testInfo_srvsRequest &request){ + bool fig= false; + try{ + QString connectionName = "currencyChassisdeleteTaskPOSEFromTABLE_CostMapPlayerByFigureName"; + + QSqlQuery query(connectionName); + +//============================5.1 更新数据库 ============================ + +//更新数据 DELETE FROM COMPANY WHERE ID = 7 + QString deleteSql ="DELETE FROM TABLE_COSTMAPLAYER WHERE FigureName='"+QString::fromStdString(request.request_Table_CostMapLayer.FigureName)+"'"; + //qDebug()<<"deleteSql: "< 2754433){//刚建数据库的id数据有问题 + id=0; + }else{ + id=id+1; + } + response.result_maximunId=id; + + }catch (exception e){ + //qDebug()<<"数据库操作异常请检查文件是否存在!" ,"send"; + } + +} +//保存虚拟墙数据 +bool saveTASKFromTABLE_CostMapPlayer(disinfect_srvs::testInfo_srvsRequest &request){ + bool fig= false; + try{ + //查询字典数据 + // selectAllFromTABLE_DICTIONARES(); + //qDebug()<<"===========================保存数据 ==========================="; + QString connectionName = "currencyChassissaveTASKFromCostMapPlayer"; + + QSqlQuery query(connectionName); + int id=0; //自增长id + if(request.request_Table_CostMapLayer.Id<=0){ + //sukai 查询数据,id自增 + query.prepare("SELECT * FROM TABLE_COSTMAPLAYER order by Id desc limit 1"); + query.exec(); + QSqlRecord recode1 = query.record(); //recode保存查询到一些内容信息,如表头、列数等等 + int column1 = recode1.count(); //获取读取结果的列数 + QString s11 = recode1.fieldName(0); //获取第0列的列名 + + while (query.next()) { + id = query.value("Id").toInt(); + } + + if(id<0 || id> 2754433){//刚建数据库的id数据有问题 + id=0; + }else{ + id=id+1; + } + }else{ + id =request.request_Table_CostMapLayer.Id; + } + + //============================ 保存数据库 ============================ + // //虚拟墙点位储存 图形类型 FigureType-> point:点 至少1个点数据, line:线 至少2个点数据, polygons:多边形 至少3个点数据 + QString installSql ="INSERT INTO TABLE_COSTMAPLAYER (Id, FigureType,FigureName,MerchantName, MerchantNumber,MapName,Robotfloor,RobotNumber,POINT_A_X,POINT_A_Y,POINT_B_X,POINT_B_Y,POINT_C_X,POINT_C_Y,POINT_D_X,POINT_D_Y) VALUES (:Id,:FigureType,:FigureName, :MerchantName, :MerchantNumber,:MapName,:Robotfloor,:RobotNumber,:POINT_A_X,:POINT_A_Y,:POINT_B_X,:POINT_B_Y,:POINT_C_X,:POINT_C_Y,:POINT_D_X,:POINT_D_Y)"; + + //qDebug()<<"installSql: "< point:点 至少1个点数据, line:线 至少2个点数据, polygons:多边形 至少3个点数据 + QString updateSql ="UPDATE TABLE_COSTMAPLAYER SET "; + if(QString::fromStdString(request.request_Table_CostMapLayer.FigureType)!="EMPTY"){ + updateSql = updateSql +"FigureType= '"+ QString::fromStdString(request.request_Table_CostMapLayer.FigureType)+"', "; + } + +// updateSql = updateSql +" MerchantNumber='EMPTY'"; +// updateSql = updateSql +"', MerchantName='EMPTY'"; +// updateSql = updateSql +"', RobotNumber='EMPTY'"; +// updateSql = updateSql +"', MapName='EMPTY'"; +// updateSql = updateSql +"', Robotfloor='EMPTY'"; + if(QString::fromStdString(request.request_Table_CostMapLayer.POINT_A_X)!="EMPTY"){ + updateSql = updateSql +"', POINT_A_X= '"+QString::fromStdString(request.request_Table_CostMapLayer.POINT_A_X); + } + + if(QString::fromStdString(request.request_Table_CostMapLayer.POINT_A_Y)!="EMPTY"){ + updateSql = updateSql +"', POINT_A_Y= '"+QString::fromStdString(request.request_Table_CostMapLayer.POINT_A_Y); + + } + if(QString::fromStdString(request.request_Table_CostMapLayer.POINT_B_X)!="EMPTY"){ + updateSql = updateSql +"', POINT_B_X= '"+QString::fromStdString(request.request_Table_CostMapLayer.POINT_B_X); + + } + if(QString::fromStdString(request.request_Table_CostMapLayer.POINT_B_Y)!="EMPTY"){ + updateSql = updateSql +"', POINT_B_Y= '"+QString::fromStdString(request.request_Table_CostMapLayer.POINT_B_Y); + + } + if(QString::fromStdString(request.request_Table_CostMapLayer.POINT_C_X)!="EMPTY"){ + updateSql = updateSql +"', POINT_C_X= '"+QString::fromStdString(request.request_Table_CostMapLayer.POINT_C_X); + + } + if(QString::fromStdString(request.request_Table_CostMapLayer.POINT_C_Y)!="EMPTY"){ + updateSql = updateSql +"', POINT_C_Y= '"+QString::fromStdString(request.request_Table_CostMapLayer.POINT_C_Y); + + } + if(QString::fromStdString(request.request_Table_CostMapLayer.POINT_D_X)!="EMPTY"){ + updateSql = updateSql +"', POINT_D_X= '"+QString::fromStdString(request.request_Table_CostMapLayer.POINT_D_X); + + } + if(QString::fromStdString(request.request_Table_CostMapLayer.POINT_D_Y)!="EMPTY"){ + updateSql = updateSql +"', POINT_D_Y= '"+QString::fromStdString(request.request_Table_CostMapLayer.POINT_D_Y); + + } + updateSql = updateSql +"' WHERE FigureName='"+QString::fromStdString(request.request_Table_CostMapLayer.FigureName)+"'"; + qDebug()<<"updateSql: "< point:点 至少1个点数据, line:线 至少2个点数据, polygons:多边形 至少3个点数据 + QString updateSql ="UPDATE TABLE_COSTMAPLAYER SET "; + if(QString::fromStdString(request.request_Table_CostMapLayer.FigureType)!="EMPTY"){ + updateSql = updateSql +"FigureType= '"+ QString::fromStdString(request.request_Table_CostMapLayer.FigureType)+"', "; + } + if(QString::fromStdString(request.request_Table_CostMapLayer.FigureName)!="EMPTY"){ + updateSql = updateSql +"FigureName= '"+ QString::fromStdString(request.request_Table_CostMapLayer.FigureName)+"', "; + } + + +// updateSql = updateSql +" MerchantNumber= '"+QString::fromStdString(request.request_Table_CostMapLayer.MerchantNumber); +// updateSql = updateSql +"', MerchantName= '"+QString::fromStdString(request.request_Table_CostMapLayer.MerchantName); +// updateSql = updateSql +"', RobotNumber= '"+QString::fromStdString(request.request_Table_CostMapLayer.RobotNumber); +// updateSql = updateSql +"', MapName= '"+QString::fromStdString(request.request_Table_CostMapLayer.MapName); +// updateSql = updateSql +"', Robotfloor= '"+QString::fromStdString(request.request_Table_CostMapLayer.Robotfloor); + + + if(QString::fromStdString(request.request_Table_CostMapLayer.POINT_A_X)!="EMPTY"){ + updateSql = updateSql +"', POINT_A_X= '"+QString::fromStdString(request.request_Table_CostMapLayer.POINT_A_X); + } + + if(QString::fromStdString(request.request_Table_CostMapLayer.POINT_A_Y)!="EMPTY"){ + updateSql = updateSql +"', POINT_A_Y= '"+QString::fromStdString(request.request_Table_CostMapLayer.POINT_A_Y); + + } + if(QString::fromStdString(request.request_Table_CostMapLayer.POINT_B_X)!="EMPTY"){ + updateSql = updateSql +"', POINT_B_X= '"+QString::fromStdString(request.request_Table_CostMapLayer.POINT_B_X); + + } + if(QString::fromStdString(request.request_Table_CostMapLayer.POINT_B_Y)!="EMPTY"){ + updateSql = updateSql +"', POINT_B_Y= '"+QString::fromStdString(request.request_Table_CostMapLayer.POINT_B_Y); + + } + if(QString::fromStdString(request.request_Table_CostMapLayer.POINT_C_X)!="EMPTY"){ + updateSql = updateSql +"', POINT_C_X= '"+QString::fromStdString(request.request_Table_CostMapLayer.POINT_C_X); + + } + if(QString::fromStdString(request.request_Table_CostMapLayer.POINT_C_Y)!="EMPTY"){ + updateSql = updateSql +"', POINT_C_Y= '"+QString::fromStdString(request.request_Table_CostMapLayer.POINT_C_Y); + + } + if(QString::fromStdString(request.request_Table_CostMapLayer.POINT_D_X)!="EMPTY"){ + updateSql = updateSql +"', POINT_D_X= '"+QString::fromStdString(request.request_Table_CostMapLayer.POINT_D_X); + + } + if(QString::fromStdString(request.request_Table_CostMapLayer.POINT_D_Y)!="EMPTY"){ + updateSql = updateSql +"', POINT_D_Y= '"+QString::fromStdString(request.request_Table_CostMapLayer.POINT_D_Y); + + } + updateSql = updateSql +"' WHERE Id="+QString::number(request.request_Table_CostMapLayer.Id); + qDebug()<<"updateSql: "<try_lock(); + //互锁 当获取锁时,如果其他线程持有该锁,无可用锁资源,直接返回false,这时候线程不用阻塞等待,可以先去做其他事情; + if(!tryLock) + return; + + bool fig= false; + + //2.取出一条指令中的夹抓状态与定时器时间 + SqlSendMessage sqlSendMessage = instructionQueue.front(); + +//============================================================================================== + + if(sqlSendMessage.request.request_type=="saveTASKFromTABLE_CostMapPlayer"){//保存虚拟墙数据 + //*********************************************************************************************************** + // ============start============虚拟墙=======:TABLE_COSTMAPLAYER=========FigureType-> point:点 至少1个点数据, line:线 至少2个点数据, polygons:多边形 至少3个点数据========================================== + fig= saveTASKFromTABLE_CostMapPlayer(sqlSendMessage.request); + //刷新虚拟墙 data:refreshCostMapPlayer + std_msgs::String data; + data.data="refreshCostMapPlayer"; + costmapProhibitionControl_pub.publish(data); + }else if( sqlSendMessage.request.request_type=="deleteTaskPOSEFromTABLE_CostMapPlayer"){//删除数据byId + fig= deleteTaskPOSEFromTABLE_CostMapPlayer(sqlSendMessage.request); + //刷新虚拟墙 data:refreshCostMapPlayer + std_msgs::String data; + data.data="refreshCostMapPlayer"; + costmapProhibitionControl_pub.publish(data); + + }else if( sqlSendMessage.request.request_type=="deleteTaskPOSEFromTABLE_CostMapPlayerByFigureName"){//删除数据ByFigureName + fig= deleteTaskPOSEFromTABLE_CostMapPlayerByFigureName(sqlSendMessage.request); + //刷新虚拟墙 data:refreshCostMapPlayer + std_msgs::String data; + data.data="refreshCostMapPlayer"; + costmapProhibitionControl_pub.publish(data); + }else if(sqlSendMessage.request.request_type=="updateAllByIdFromTable_CostMapPlayer"){//更新TABLE_COSTMAPLAYER所有数据数据数据byID + fig= updateAllByIdFromTable_CostMapPlayer(sqlSendMessage.request); + //刷新虚拟墙 data:refreshCostMapPlayer + std_msgs::String data; + data.data="refreshCostMapPlayer"; + costmapProhibitionControl_pub.publish(data); + + }else if(sqlSendMessage.request.request_type=="updateAllByFigureNameFromTable_CostMapPlayer"){//更新TABLE_COSTMAPLAYER所有数据数据数据byFigureName + fig= updateAllByFigureNameFromTable_CostMapPlayer(sqlSendMessage.request); + //刷新虚拟墙 data:refreshCostMapPlayer + std_msgs::String data; + data.data="refreshCostMapPlayer"; + costmapProhibitionControl_pub.publish(data); + + }else{ + //其它数据默认 true + fig=true; + } + + //5.删除队列中的这条指令,sql 操作成功就删除否则在执行一次,直到执行成功 + if(fig){ + instructionQueue.pop(); + // std::cout<<"6.sukai 队列 yes executeSql====sinstructionQueue.pop()" <unlock(); + e.what(); + std::cout<<"QTcpServer 数据发送给所有客户端: " <unlock(); +} + +//数据库操作 disinfect_srvs/testInfo_srvs.h disinfect_srvs::testInfo_srvs::Request,disinfect_srvs::testInfo_srvs::Response +bool callback_QSqlQuery(disinfect_srvs::testInfo_srvs::Request &request , disinfect_srvs::testInfo_srvs::Response &response,QTimer* executeTimer) { + + try { + + int count=0; + + if( QString::fromStdString(request.request_type).contains("query")){ + m->lock(); + + if(request.request_type=="queryMaximunIdFromTABLE_CostMapPlayer"){//读取ABLE_CostMapPlayer数据库最大的一个id号 + queryMaximunIdFromTABLE_CostMapPlayer(response); + //cout<<"queryMaximunIdFromTABLE_CostMapPlayer 查询 by Id"<unlock(); + // executeTimer->start(); + }else if (!QString::fromStdString(request.request_type).contains("query")){ + //除查询外所有的数据库操作都加入队列执行 + SqlSendMessage sqlSendMessage; + sqlSendMessage.request=request; + sqlSendMessage.response=response; + // cout<<"1.加入队列request.request_type: "<unlock(); + + } + + response.result="ok"; + return true; +} + +//定时任务从队列中执行sql +void executeSql( ros::Publisher &costmapProhibitionControl_pub){ + //从队列中执行sql + executeSqlfun(costmapProhibitionControl_pub); + +} + +// ============end==================数据库操作all=================================================== +//ros::spin +void update(){ + ros::spinOnce(); + //处理消息 + if(ros::isShuttingDown()){ + QApplication::quit(); + } + +} + + +//检查数据库文件(所有类型)是否存在 +// 1:存在 0:不存在 +int IsFileExist(const char* path) +{ + return !access(path, F_OK); +} + + +//3秒后检查数据库是否存在,不存在则建立 +void startTimerfun(QTimer *startTimer){ + // string dbpath1="/home/"+hostname+"/slam/TABLE_OR_ROOM_POSE.db"; +// std::string home = getenv("HOME");// +// dbPath=home+"/workspace/xuniqiang/src/slamproject/db/TABLE_OR_ROOM_POSE.db"; +// +// startTimer->stop(); +// QSqlDatabase db = QSqlDatabase::addDatabase("QSQLITE"); +// //cout<<"dbPath: "<("/costmapProhibitionControl", 10); + + + //======end================================ 注册码验证 ============================================================== + + QApplication app(argc, argv); + + QSqlDatabase db = QSqlDatabase::addDatabase("QSQLITE"); + //cout<<"dbPath: "<setInterval(100); + QObject::connect(updateTimer, &QTimer::timeout, &update); + updateTimer->start(); + + //轮询检查队列中是否存在需要执行的sql操作 + QTimer* executeTimer = new QTimer(); + executeTimer->setInterval(time_int); + QObject::connect(executeTimer, &QTimer::timeout, boost::bind(&executeSql,costmapProhibitionControl_pub)); + executeTimer->start(); + + + //3秒后检查数据库是否存在,不存在则建立 + QTimer* startTimer = new QTimer(); + startTimer->setInterval(3000); + // QObject::connect(updateTimer, &QTimer::timeout, &startTimer); + QObject::connect(startTimer, &QTimer::timeout, boost::bind(&startTimerfun, startTimer)); + + //数据库操作 disinfect_srvs::testInfo_srvsRequest &request , disinfect_srvs::testInfo_srvsResponse &response + const ros::ServiceServer &SqlQueryServer = node.advertiseService("/QSqlQuery", boost::bind(&callback_QSqlQuery,_1,_2,executeTimer)); + + + + return app.exec(); +} + diff --git a/src/slamproject/src/currencyChassis/readme.md b/src/slamproject/src/currencyChassis/readme.md new file mode 100644 index 0000000..c6eb1ab --- /dev/null +++ b/src/slamproject/src/currencyChassis/readme.md @@ -0,0 +1,71 @@ +龙源通用底盘 + 链接机器人热点: + 名称: longyuan_wt_00001 密码:longyuansa + TCP连接方式:TCP连接 10.168.1.10:31001 + 配置网络 :10.168.1.1 密码: longyuansa +编译: + 直接运行这两个命令: + catkin_make --pkg disinfect_msg + catkin_make --pkg disinfect_srvs + catkin_make + source devel/setup.sh + +启动功能介绍: + 1.创建数据库 + rosrun slamservice currencyChassis_CreateSqlDatabaseMain_node + + 2. 获取base_link相对于map的坐标,实时发布小车坐标 + + rosrun slamservice currencyChassis_listenerCarBaselinkPose_node + + 3.数据库调用 + rosrun slamservice currencyChassis_sqlDatabaseMain_node + + 4.路点标记 + rosrun slamservice currencyChassis_savePoseByOdom_node + + 5.设置初始点校正机器人位置 结合 cartographer_ros 算法 + rosrun slamservice currencyChassis_initial_pose_set_node + + 6.导航逻辑 + rosrun slamservice currencyChassis_carStartServiceMain_node + + 7.发送 movebase + rosrun slamservice currencyChassis_car_action_node + + 8.发送 位置标定 + rosrun slamservice currencyChassis_savePoseByOdom_node + + + 9.网络接口服务器 + rosrun slamservice currencyChassis_netWork_server_node + + + 10. 测试网络接口 + rosrun slamservice currencyChassis_netWork_send_test_node + + 总启动: + roslaunch slamservice currencyChassis_sendfoodCar.launch + + + +=================================================================== + +1.路点值编辑 +rosrun slamservice currencyChassis_KSDemoDlg_node +2.执行任务编辑 +rosrun slamservice currencyChassis_KSDemoDlgTABLE_TASKPOSEMain_node +3.定时任务表编辑 +rosrun slamservice currencyChassis_KSDemoDlgTaskMain_node +4.设置,字典编辑 +rosrun slamservice currencyChassis_KSDemoDlgTABLE_DICTIONARESMain_node +=================================================================== +仿真: + roslaunch turtlebot3_gazebo turtlebot3_house.launch + roslaunch turtlebot3_navigation turtlebot3_navigation.launch map_file:=/home/iimt/map.yaml + + roslaunch slamservice currencyChassis_sendfoodCar.launch + roslaunch rosbridge_server rosbridge_websocket.launch + +==================================================================== +