From 61160010b294bbfc5c2d33603a8722d109e4847e Mon Sep 17 00:00:00 2001 From: SakodaShintaro Date: Tue, 30 Apr 2024 10:04:48 +0900 Subject: [PATCH 01/27] fix(ekf_localizer): updated ekf gate_dist params (#6871) * Updated ekf gate_dist Signed-off-by: Shintaro Sakoda * Updated README.md Signed-off-by: Shintaro Sakoda * Fixed schema.json Signed-off-by: Shintaro Sakoda * Updated ekf_diagnostics.png Signed-off-by: Shintaro Sakoda * style(pre-commit): autofix --------- Signed-off-by: Shintaro Sakoda Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- localization/ekf_localizer/README.md | 20 ++++++++++++++++++ .../config/ekf_localizer.param.yaml | 4 ++-- .../ekf_localizer/media/ekf_diagnostics.png | Bin 103904 -> 104312 bytes .../sub/pose_measurement.sub_schema.json | 2 +- .../sub/twist_measurement.sub_schema.json | 2 +- 5 files changed, 24 insertions(+), 4 deletions(-) diff --git a/localization/ekf_localizer/README.md b/localization/ekf_localizer/README.md index 1b09420f5047d..b91282015732e 100644 --- a/localization/ekf_localizer/README.md +++ b/localization/ekf_localizer/README.md @@ -130,6 +130,26 @@ Increasing the number will improve the smoothness of the estimation, but may hav - `proc_stddev_yaw_c` : This parameter describes the correlation between the yaw and yaw rate. A large value means the change in yaw does not correlate to the estimated yaw rate. If this is set to 0, it means the change in estimated yaw is equal to yaw rate. Usually, this should be set to 0. - `proc_stddev_yaw_bias_c` : This parameter is the standard deviation for the rate of change in yaw bias. In most cases, yaw bias is constant, so it can be very small, but must be non-zero. +### 3. Tune gate parameters + +EKF performs gating using Mahalanobis distance before updating by observation. The gate size is determined by the `pose_gate_dist` parameter and the `twist_gate_dist`. If the Mahalanobis distance is larger than this value, the observation is ignored. + +This gating process is based on a statistical test using the chi-square distribution. As modeled, we assume that the Mahalanobis distance follows a chi-square distribution with 3 degrees of freedom for pose and 2 degrees of freedom for twist. + +Currently, the accuracy of covariance estimation itself is not very good, so it is recommended to set the significance level to a very small value to reduce rejection due to false positives. + +| Significance level | Threshold for 2 dof | Threshold for 3 dof | +| ------------------ | ------------------- | ------------------- | +| $10 ^ {-2}$ | 9.21 | 11.3 | +| $10 ^ {-3}$ | 13.8 | 16.3 | +| $10 ^ {-4}$ | 18.4 | 21.1 | +| $10 ^ {-5}$ | 23.0 | 25.9 | +| $10 ^ {-6}$ | 27.6 | 30.7 | +| $10 ^ {-7}$ | 32.2 | 35.4 | +| $10 ^ {-8}$ | 36.8 | 40.1 | +| $10 ^ {-9}$ | 41.4 | 44.8 | +| $10 ^ {-10}$ | 46.1 | 49.5 | + ## Kalman Filter Model ### kinematics model in update function diff --git a/localization/ekf_localizer/config/ekf_localizer.param.yaml b/localization/ekf_localizer/config/ekf_localizer.param.yaml index 4cc71e0904ca8..19bfd2d498b68 100644 --- a/localization/ekf_localizer/config/ekf_localizer.param.yaml +++ b/localization/ekf_localizer/config/ekf_localizer.param.yaml @@ -13,13 +13,13 @@ pose_additional_delay: 0.0 pose_measure_uncertainty_time: 0.01 pose_smoothing_steps: 5 - pose_gate_dist: 10000.0 + pose_gate_dist: 49.5 # corresponds to significance level = 10^-10 twist_measurement: # for twist measurement twist_additional_delay: 0.0 twist_smoothing_steps: 2 - twist_gate_dist: 10000.0 + twist_gate_dist: 46.1 # corresponds to significance level = 10^-10 process_noise: # for process model diff --git a/localization/ekf_localizer/media/ekf_diagnostics.png b/localization/ekf_localizer/media/ekf_diagnostics.png index 2580d6d973290235f1d131251b815db319c07af8..16de42ac2d85a3d175aee06f3cd381d1ed5cb452 100644 GIT binary patch literal 104312 zcmdRV^LOM=yKOYdWMbR4&6(H}Ol;dm_XHE$HYP^Lwr$(Caq~Uryz9L8u5f zpHi2g;CVXaZ(tYiDD^;AG@zVq)uLZs&Xf*&+DZiOoVq-C4xZ z#K76Y&X!ok!p7wDAs84dGb{UEQ!O+5etIw~`+iaZF$>FniXSuEUT`1>*FjONQtl)! z7#J~_l<0RA_w>^>H)o8#mCmb+b-;|5zc6t?04{H^WD=>4MJ~DpCi+j&M_5`~>h@4} zF;T^0(&?6IzG*&5BmpQ0@E^l%ZdngeP+yTHg;i#s(&L=iSJzV3+EUEiGM8}VM4`kK z(Z!lzdNy>xKfmow75V+ir4EfH!=OhOQ;f$i*1vLVY>qS_(7c|a9ne!scREnlwZ7wY zVtNglQI75O1IU?QPw^5iYb3d2`Ya|!>e&uFRo#0q0k0m!6>F5bwvncl(Rk{;_#|Q- zH;_l_+UQeRqX=N1v(!Op+7gLZJEsxp(vZmGZ?F7MkaTSB14K640r?`ODJ{-KYIaXP ztTJBxn|ftjrAicHD?ZY@gVjZ3!{Khu9Iz?pi1nXGF7FFJFnYFzFo z=$C*;6))b&wjb+_h*5fJ8YD~_iANK2E?hNw(dZ%!&|Dh7SXQ>j zM5VghyO6h=XUlGu1p%_KuhQ6)NHQA9Rk}p)XgX#lj0Lo`F7supOHHSxJ=x24w!4J zF(D8&iB{*slJDD9x9R|mM%LWALr zj08leZfwPBB8ENu)k|%# z49oFM4~@c%EFESZ-=G?eSXM6SF1gP-76%JjdaG~6GQQRdbXDc?O7a^WFHf?cB@!uj zajBnx;h#KaTcUTRC?s#0Xfc~xyfUm29+i4VZzNY|oE2YiGs$zlF+pohH7t3*`N}X> zZH-jSQse(l8}qMP>~FoB0aUDUgTszqXhmI5d0e_Q=+}FqYUYyom=X@X0vZ>&S~MJUW&MzYExL47AQEgkZjMp(90j7h28*3fT~+a?-g$N2_?H4dPQP^Kj>z(H+q)? z*%s!h8HI5byW7KSx*_up(;`L`CpQQhe*aLpct%)Z zGy_N}aj{)D;l__1M5XolX$hlvGRil7?5MrBk;A>cLRoC*z$WKEuB4IwsyX0gkxC81 z5fef4Uz2zh7|ZoFKi}JJi&zltrH}{`Ai+c)+ogQZ@!d9#kg6FgDX0CWgiebJ2>24*qKL*EthYn78!sbT@lLI-7N-zS4PJYiHcv_C>hD$mnu9XhJpEY4Y`MT+M63q{B& zzqOikC%s_Ynk;i(^Lma(M^tng(={H<3IoTpmx5GYioagM^=z4<#q}&U0*zNXzE5ZP zPLC={OjNtb`0O_2`sDbo2Jocvlno$c`O*-#Bt=SE%v$N6r9S+o09Z?@e#Z3ti zTIA9!6MLsh!zU%RsJV$7=o`VL8H1Kj6qDH>=CV^sAa?p&o9wKlO-fqP!@BEG>OSYK zX8PVNo5+|<51EFE9HwRRWZj`GnqK3kE(d#ENetP*eg3M%i!_*2_tpzChQZ-+E4NnX zmG>0fr<>39F%dZ)dxLS+CAX-UVJ)%>ZXp2^bv-%>^6_+ zb>6W)3}@GmjDAJ|0-zhEP+4Ov*;r(yD{3yfB9pZjwft z5v+{67IgCCTjXfHTh-E+eC!zIqWd}1*i+njc6h1qW7kp^91f0|@->pBUM-R0){03h zW`v|p_+3N1pN&%5E&a>VpDXxrEE6x~Z}z4md{PQ->ClX)LVwj*uWK*4a|V5$TxDBW z%*c)P*ltQFBi*BV{x`<7{E@)*KYam|`=pga+c%6cR$j*DHbgAhArCWgyR86F7pK~* zD8TI)Rj8@y5f6DxQ=(lkFN{z~D)Wl#YwEA#C^=*u+YRwv7eLc(XkBRF_t&g65-B8= zddX*BlIs9DH2ALRy(D%NsieEMyx!pNuebm@2SgMH{5U2nui!$B-4FwbJ{K}|?1IU( z6LKAGM^kO(D-PmRE#(wOs*> z@1d(nPeU5p-rgXZ(zE-gNkh|3B_;883E;5 z!A?i%Ypo&NMjn>G?%F{@Ituz@Rpa~`CB!)ZK`3-@-=h%TVj7Dkq5`t3(c^cByvn-W zlZ)n`)NE-KQd&4GZQy%(*P9nR677XX+{e-s6dVstxCc3M)^gVc(&aUa6(34BMV@EV z*od~KD>~03>{-;gep}wJPx#_5hrMnKG1VC!CWTy;5g&f0IncxjIxF|FfNL$>$0gQ@C_J&}GAe;5^diRhnQPnO zjjcqe1{OV%Z^;}01)h=Py%woTMcfeq&T-z-_+9qC_`XmKFoGnwNqTj9T;jv$wNwa% z(z)0v?&D_$gbkmBa*ZlYwh_mpuNC3E`kf!u_s-=wi4-12oh?f3)`t)8uu6`jc?%VnSN znE8l8js9{6?wO~0m@#z!RwF!#xLzF*l$euue zCJwhBejK)VFJ;tjjTGwUzIPsl%~T!qt)mqa%adJp)E`#5zTTOd znTI)db5x3v!>#0_-&SfP9Yx3@oFveyBzF6f)5w@Tc1{d_!yPPw_z2sib=iv` zlZMhuNs@5BPYX+?uvP2}Q5U@A@^|t)dhnr6tVF!}TQ1cieH29e2ilqK;^N?=}9f3=2^h z7ENV;oAB#OUksy-6I)f|`JZl3k+126^x7ZHsmI8EgSGfGuu)ZA$>Q!0=oZ+Wu~W9s zhPqKPn9jv!VJ{YdPM?Gr_q*A4pX8a<81H?ZroH@EQW*W|Mo>xxZ|m%6kWq^p$m_w@ z^+Mo#EJ?bdSeukKcdUY0nd!*=ne_(FKmuM1vvR(y6unpb!5fN`db>3t8f7Kr`+fZ= zNYJibF)@y8dHO!if?lU7*uh6@+9xn3&_^%VxkA^p@pDx&3AU|@6cJf190e~}Gfysi z(wGykkrTjWhk-Dcz)eqYK_@5<1*9CCsHI*ZbEfdFBrsq^z}!r7-3vs;Dt?g~q%N?I z+o4BuruE}tRHr`H1g?=NTX~QT)&imf}H7_LkggS8{8iq zP2$}+u1ru+sYDBTbZ>9RM;=8j9lp{Mg<0lL*GpfD37)@QK04DOlWUj`gwe6&1kuAr zEPU%mO<%RtyIL=~enOxS`MM;s-WuPpbz4QLZ_te)L*|%VA75#HJrF!`C}K5{bun!7 zvZ|D*BabHR&iJPkWW4`cw^Nnw<{vX;_mY$hxo2e=cbS;_Njg;HVhl%vvP-7mgU8ey zd?>YIY~8Soie`=#wx*X`;ufRWL9re?I?rUAXxBU!V@N`1$gR!o^| z$ccx)Lk4wGW4Z~!(y6E}M+qgyV7ubS!)6T25N1hVUkM(R!=Bgb<;zrUc_tq3N1a(b zU6ll%oGRhW)}()?kHJ%)v(G}N`B@VJzmbw6DZfM~40F%)v7!PkZzrfiXFNkjhzaw`6QS?Iu(~>^Y5?jxxEC4w6%9uQt^pd- zZC*M$A>j8C@h`z?OZ2wjF-ks@&{9dpO9Jg_v!Sr)TyfuJRTW^rMkR&{91MvGq+N_L zxU`eTr7fMeMg}4uJzMpo=&ilv-P$UNcl%fyvbIPGcS&Dw$M4{5pd@UnI%bFP)1GJ? z;^XON9A=irgl1KFooS)J7qz~XQionM74b4*{3l(LL+uvBSt$U3K8tKv;gAzylbA8v z5i%2G7JJGg%(0~w^Qax%+d1V)4Q6ZUKpqpfSAoy51$xw>@7d-27xgoTP(U4;yDRwx z?voLskZ^+vvzpP`v6!5cRlL=9Sy>%)%sjIB!EA|}cufRi;&QV42;-h8+b_+OD@Mi% z4jKzolZ02`Ux||9tEq@Dbh38;Rd#Qd9P90*wJ?<899oa2?Z(Y_&be2cOFc|>T(6(w zM0pN%1ks4dcJEKbow#SCeNdqYp9(-Eu+IqJ*#%Oo=bsVvuCHQ-8ZI80x(qXux!{UxS5L-ghQ{!jp}8;Ap#}$N zGgnkdCRcc|^fN`>7-Utdwhj+?o{O0(azR-zz|ozPV`s017ME%IRzN{ZEt;8;xKu+K znM5flh>D9sF%{FbZ8`}xM%uTrM2d)lA|R#OswiuXn~T#%k?Z`025pN18rew2P9uwv zG_sAgwXhOwj{b$MaXWv?+7L|KUUgoShRnWzrf*Lv056z5k<5a;x@xT|Sqv!$R)PivD z#*@%8KwC66M~e!hmXxOK}4bzq!P3BzT0>bH@sKdt@!RU2-@cIuBeTPV$ZWEz-Z9~Ax zYReZHR^>dkCywoIZtttMzzxh+l?_?w!Wf9*#_Iq3%+7coxWCx@`}!%w<{DbBQeiNe zV_79t9D$5EZnSdEF!=9cC?L)?HlD}pv~F$ZP?HBQXP)Bb#E z^j_sV=vRSDnD>$_!uf8eU7F-Oc6&Jf1D&KJN=z)=j=qG__Vd|4Z{ai%(x8#tNjOM~qaCvZeck&}DC44qWqV@3@|=G||lJua|+ zB-R_D@nxunV$yU*dcX4FZL8Soki^F&i1d2 zPy?zS!qjO&!GRxIY_(rC<4{rL;88l(4@`%5MiD|cG^d;j){j*iAJt+nlioOh;Wr=o z!mJLqPlyrg6y_y`gA|5t&i6}xl}E4XpG)9kUf;o{q}F~0N`%nE!$SP#Z1FCkwp33c z^|qs(Q8+#PZ(=o~SPGI`n6kE`rzIXNmjy(sIVKbAw|g`<5M_N)dmNNbZ}pQ6jbXKn zuxNNZJqAOUtK8(M()OCow&a^wb3k$*Sz|VOL_~rlFwES1Th%BZ-z7bo<&OW8xQtVX z=T|MQn2kh0F-p`Y@$?%#QxP7;bsOCSl67U&hzXV*lHh(#Ra|}bqnI3_6*tPi)l6dK zi3~)InHA6*R?ac4#`;Sq5GWtN1h+p_YbO+azX#c89F@ojk~gF5utUPc>EIJ63hQ0u z&wu4R5iQ5g{^x395TK3q{!_{bJ{G!`IHhJp`;NMUNpCzKIW(WB1-p}Y*?FxSOIlu-++!SD#2QQ_q|o5@gKhW<`XUm16_^iLHYOBJR> zjVv(SNX;R?3B5eA3`>>rx%h(<^nTGq4v>w>VT1jbjeBd+BYURZYmZoGJ5p&Zs#*89 zv)~gJO0W6cN@lAWLqU(>-s7z`i?v;gMib+0@(!$4U|8Ji;Litcpm7zw5$W##`jn+Q z7}ZLNgr;{YI$-h`dOhY1bTJ>2C?#A*`5cYq{yEx+ zfr!g$_@=UT03L(>T)v_TxW`l`fstJ=a~L zACgks4XNEo4A+M*36DwKXxGVG;J9isDNLm(it9u+jtCzw{(;Y|jTeks*Y~;BXKu`UM z+Yzy}P-jC#&n5jGZ6>m-}vQUm^dAeY<;w) z&@2om%8Gi~3M&xgW^A8WFueWi5Pv&Iju8ou4F7?>uG+y<3^@?glIy;cNoY=qnV8Eq z76h)+W3EDkPC7XZzY%rhQoB7uDqxC_swto)SyScz7CJhJbZ{RNedbi4xM(lt$4l;y zJkq&T<^E|b}r$pHEXIrBHs6yFITeMy~EW4e}U>| zJF$eKLW4WMyCV1#boFPWuB@Yc(ju^c2HUHk+B4kVwnB`l3E6^~ID#dWD;>eKU;e*A zaM+7^cyhP=r_c8^t#)tBPI^{9CUoYWO#AdLpDm)H^b7Vk6X5MO5wS17xphno7lBS@ zC}({x=xr(& zr6`CiCL~Fe{0!>|)f$;y&w`7~Xk0@=I+WY7+J5HjKXfukzq$%4g<)L(|h03U3 z5dW73k!az>^e-uiNEw6oU(%F^_}hQW9k!<$3ehwS5WU*31WU)rQhFO&xuXWx-K#RO zJ6VAn~Q6Fa)94ARgpJ|?&BU>Kpl1Z^DuuAlz zVdYl)bb)2*Genn<7-B;SE&Lkh=FpIVWf|+ac_$j@!FM3~rz*C!K*sG!lZ7!a6NVHz zHBg7sJUwTb+I`hdHXOXctgT`k7^Hr+;h1J}F?mELZ6}pi)a6Pl!|A2^5YAQC!~v_> ze1*Y;UD0AReR3#Q{`Yv4rdnSVCRdZm(KT&*W11EB1iA&NQ@8m(V^G)J2^?2}8U5-k zmz4<{rfu#ik<`hdF=K(RYeOHWt)$69eOrFksuX0$Ma^lqRCCvGaTo*%*pKO3HH(sspkY+FB$3@Z>Q+H(&G)tu|QK`Ay#+ECW(qUqKA7oUO$8&fV- zm1*yX`$v$;sbFSs&lnnmB9)#rE=1Evo+Ll0xuf&YiXr7%2kTqP@7p%(wS?}10M~$} zl@0pw6hsPnN7bOtAp6(QT;mHyh8*A5H8p#EbBs~pe)GRdD)@~D{Zz47cX?|;Hz96J zazPWGKdE-@fqQF%O7yt_DO5 z@S?k3RWoE3Sc?s>eCr-}PWRkh$j|Hc|x&dz!Y$*i2{dZ_F3)?PW-=V8Ohadtr4uoD7{DGz25y4<1-y#^z+ zXOH*Io;De@f*Pog`m0>e>ymjq`T*l}1rb&bsaQMyZ3*^aW~yT^ajeA;R-_bRQ2)tn(WNj)Qve_&e90V@%2FXFHZ1d)!oo zFYEXpJaTUw=K{FHlK(4>?6!J_=XY}TG>S6IFAz{KV2bvUZ8wYK4STsDsV)$q(ZaNO zT{e+s7r(a~TwnWUj4PwYXsErB=$vJcZ?KU>Z37{bpmua8%DThHwRJbercvYgB@FQH zD+WVSBZ^WMRK#LD>pgF?Hhyp8#gpL(a!i!~19yedGL_fgNvYL3A;r>I>_B4Ead9tB zK^kzqFnu^*J6-qkBWFM=_pBq^IPYQy-b40J=#3BW!6ma=!pq2)Er2%} zDx#uF_apJT2>Hf@Ox4)zEXixVOm-;6vzs~^-ii~PT|UaG_&Usz%c>0Y-w82UQmwb+ z8j@$-&&+tvWBFE7HeH7^4eko`f2Sq0i?Sv6o@3C*m}JEttm87!MVc{8(0B#S#S?#g zbJK~rI9?|zaEoI_JvTy&TattLrW%V?gg?POe*$|x9>$uKGe-efc8VRqr!6na#CY>X zZEYs6c>Q^db)U3Z586!)4n9dQBV7Jof_{sZ)~DkaHXoOX<~A}{rlqq=zu{a;*7t+I z*RUqU?)`e&YRV+$HjlN`PJ{;Mn8egyk^UTjs`|IAmIz3H<4G|xAH$F@8Xd)dXY*R_ z(hkV5B~o`Vn(Jcc;r;Nj&?(M-Tp2U0d6I6QW-z(U998^6+f_~t#N{|C`^WQ_Ct>u- z4}YdnF@=789jX4GrUmA;d-2;lA|qi5%>0iv7ZvoqEMXUsw-Ft_wkZFD=^6sW(v(*k zb$a{>U^ltaCs9+bQuXtbg>uYq&iOC@V9vjD$+YU9EovU6uFq^uY$)a%=4VSf@?T^A zU+dxjFGH2*KQx*g_cneZ{j+-ts^yw>FzfTqFHEXs>Q@rSpL?6jpG#<21?GOy_CV+! z^iNWkm_VmiW7zj?PJFHC@0aVf6+_P4mn8M>X}`SP zD7MZE&lj1!VNtaJQwH9{lDL`eQ26kHrW&7%V!c%kFEJ6DsXYaTdmPnkzkv(UKb!`# zinexERidRhQ~Q~+riV$SB531d>D- zW-%2WiV;lmTp4lk$`AImfL?9_a3;%kLpVOx>RuNb-MHe7$c&x=y;V`3H+#+DUo!yi zlsUm*L+BXY$ z`(W>C4Xa8r*i46rTm#@~aFJaBl74&Er^wI_PB&1FK$`@b?%`fl|1V4$2_;SzKblC z-oyip#5H$pse{E=@Y*u%WMU+~c9aD7bI=?)e|*I`F!NKVI+4I$yYhIq`}HlcvpYWA zf$V4zR>>N?30u{q*ZYp$VaWBzx5qfZId;&3Y`)!%%Jq5LFvvH$cALRc@Q$ZNxl{j! zWO8OGWrnfUrxwp^DqJ@}EO0x=VzGyR%9g3XoD5gor?dc?@fm%jVd)7ZyPTXnIfQ-6^I1@HV zou?k=4(Y^Nd)nVz1cFVkL?S4JYN~o0&6xOo)1jgS21D%Wq~OeKD7-G27celI_*AVe z*PWM-A%9St^FL%y|D7?tOdwFSb?mrgY))3Qi#p{kzjRccHd#pEjeiGewEjJm8 zb)on9U@6OY(to0rKYXAbafz@GsTp6W4#x?4qedJ5r(L{uOy+D8G!|aJR0xDF&g-xB^tOj>RQ z_7TQWc!8EowjBN(o@5hp`wp@}n3NTv~> zSEYtyq93vFW1d46j}KEL4x;|J)&eDD>L2UJ|0D~9jW(~A)35!J0UL{0R9&;cPN4|5 zz?AOA-V)vakm0pJGB8ferAA5%>@pYb@!hEa=J^H3T)OV0Eb!eY1}cHRC~XQYD%)qR z*%p(hvnf}M6pb#r#-9xX)#>I$sPG`koLLmAVow~-eZ z$!2Gny(bUhOAkHP-8iBSK|tH-wIUGHyexSz=P?)cr1&`WV=uc_1mZ2I-%kzDD}Y~k zW|${TfK_lK63R)iBV`_53+Y+&B>{ zVyv91`3tLj<=DH-PVVw$15lSh_t7=*OUz?-$=~nFmB9F-tA$;=kTjmrcKh}o5*bHC zc62Q3@aqR(OUDP~Ig@&Rd9L2l&sPyr8r2fk2*EYUW^;8i(jl)2Nh{*N&N$b&UDan~ z$MNOz8AZG|Z(Z~v0pWdzs|Oa>*e>#NCz9bEL?m4R_doo7hh)5khIM~YOrZu;p;bmj z-Y!Wa>uj@TSD8X^ZYuVESTWdXwX?$_@LvyUl_)@j^59Ce$YPS#~z|fPO z2>)$KEWpScSz-9fb(EfRgInP54U2d+(6g46%QUg=_nYKYWBnZ0KVhWoSj~5G)1EZ* z*{{cvJ^u6dqfbbkW`0E0>zI$50wq;>KcT9gOSLY==?{vO>YfcYcrlMzpfI734eO*5tI{jW-2yf~S=0(cCv_UT~b?-)?PXHvM)XsGP{Z49m%=H5v+8 z3?-KESr=gVXt|n451GTzZZ?n zD=Nd=vs6m?N+x|R>R*Dcr0hdIyfINKm?cLfjW+XR-S$@$)d@$@1}$HLWg=zo*X%7V zJ17~``<&Ziht{cF#=0!eOu-Gty~~0RQ#W5q$D1=Y4z<=?>L}JZae?F@hjqefQ9nk+ zC|jvG1Fu2OFnym`5^!PJTSu0N6+WQ<%+E52#gp#OkaC|q3hWVmq0V@Z&%&7XWg z6xBOn+egNoikl%(bM9?xN`#J@njl#9OeVDp=DcdGJ})`t_oFAB0xIG z@(-*%XdClqvL%6_$x(4jS-o4!E)BoY!ldkME zq&pa)DjVj5aBfMhL1&qNzVXtp=c%PzE6q^;Ow}^MFBaEx?<=M!az<;}yuIR3n+7aK zS6@kwL+ZVow^washItnkxs1jT$CLtnTi7yLln}?WKiKvL4{Un&am25l*PaXp_Euq% z;vq*5H~d1syxN1*FX8E=KuoTtvn)kc8KpPu8M+a)%DMW45Utk9<(UBq=E9XUFLpc% zVE>LRXWw!i;RYzhf$i{GX-Z~B0c}mB_?E^~McQp3AT?+v*`6kiZ z0IBQRN=kFes|b2BjFEoHzj_2XKAKo4I*jz*8oBhT*-I3Ee}?bgaE1g@>dplX0g84z z|Gi2hXWNV|7}{`jMQWc)N*pJQbwn5~EUCj?=i}ng_Sz~pQ<;SH)3Q=z^R-{n!^q~D zVK0>qK-$44hM%^Pm|Hk{gN#i{B8WL9%nT)ycM%yXBf2{*?IA$9^N`vn@;iFWb36;-3LD!}Y~U~@y8GHXUm+kv&UL`)dXOCLNWGBWYdaLjlX zyr@xLHWt%Be2P8KJpd!I+knt;7FpzyjrAy=?qJ86FxCziDum?5(-R6REGsQ&_USqN zu&HtW!7Gy=qKCYf@5VbhOfn0>0!Ob+uSGf-{1d^(7TMQ|N(@LAa{&@+)1!o+uv*$8 z90{JZOVn5Mmv-~hh#als+gVIueJrY<+l`y^Y=B@*r-9cwbG=6Cp+W=aQxUN9`1om$ z;2Wn-Bv;Bf+}3zQsYG|;=i94KaQImtq<g*}E3RZ5njtyemi#Ve7ceU`=-Ky4 z7v#zs&%td(WW9f@#&=x&`+7wgNwhjp?H^~3QRd(=hTU&Bv6msFPy0f6BA>p0I<8P` zIAfoYIZ%dhgku8#7%6fD-M#WUxOH>D1GI-==z-5C!X63QiMsk}_OpS1DEN(v$LXAT zh8Ml}?*M4C$Dm9uNajZ3dhOz9^H%R($qaczn#{ zc4EMZf80t&aI5Xl0kVvPt`@e0VYddOHg8X@D@k;il~2ck#qN7tIu9sSkU}J(W&PHuc)+%hqRkKqhPH5_woY#*e!X09w^d@H+jTu_l`=0%`bTgQUR~2 zc^>I@(JrdMk;aYPc|1eTz0p@oF+OPfeFMa-UZu&7Jb4#hNYb(ZVLK$JIdXMA%^`~L z7SGh4)@SDwczx}crSZ07N;&KB-{u%xJKG`+Y80bZp9P*7diC;8|9u0wA4pZYu`+Q? zzcbr{xH!LX4)?c=+kDk4wnxUxR)kXF8T>K{`OY&`m|my33Xy)F`|=8Mxi) zzGDOU2sLNcS-5ODf@5C-%LH_+0!^Cmm^XE3^djA0xbBN^YTm3P7oL5`;{y9Ezl%(| zU_qFtCMqT#(z;W-nZP4bNVW{7JgPLluNG6;-=}YCkz?2GzV*b7P{9#MG@~IiR%DKE zvoSJ@{cH_}*^f=2J}D$Aro$0>cT<{@Qs<528PL|J6>h5WH6IrpFC3WM_a7<~s>x!B z@SaL9N@lZyJUXYKK{JAo+F7k@tv!4LhlD{i-t=laoZaKl#Ps=kfv`NHL^B^=m}Rzw z#Kv<3HgIJTuH}uQ147oSRvFi$RsL%59Xc9{v;0jUhzjLXW&j&HO%{xLlV^U!EKnze zQ#6s;G65UdzY5oMAxR7TNp*E;fa=05CLmXtd1kTJ%whsjqfP5i)xIvyuHAdKED{UW z3>oyFCj75bu)Gw@9b-X|Fs$~Qe9jlM2}!ua;Y93hEgn0#e*ilk z(|`^R>=-F#3zTTDEQG4Xqe$*y?#PpePJXt=i0u4^tbH1sYs}MuQ_NV%nTho6EeG3f^93p-2W7wPs^@NH$I#@;Y!D`y1_hdsN}eX@f}8G9?!A7nQMjm|O74XyFOd$j%c*$8T~-!C5^ zx6G?w7+ORC)2z&OuOHMTBv7bO`P6>7)H>);ilL;$xrR;arH0>w_jG$17ctO9q0pg@ zzF`Wd66Xf2%l!CCK{7<+)kY*Ao$c!+EPA;%agl_CKVHiLGRsKe@Oo#*V@cv+T9qHs z%xR2@H9o zXw^xk2k1+CsLccTC2YTW@rYs%rHnP6mox`ZSLtwuD-6KzmV_fmzFsrjV3p}-aio-u zROCt3K%38EKQitRwkGmUnM&VZ9H{?_P0nNY(Yo)O^T0Rw+7=y$2TICo>z_F@#-_90CUb{WR5yKSro zM|ytE0hdo4Z;2ep2gY)A@CHXpc~7k)7)q8kaIvvpI}UEgyO#qS?mgU3_& z(eBQFf+`U7pT8BdMGyZ^csp)Nt19eifWukR9^@n()P6O;jX4FRtd+z;gjTW+O` z>WSZ@v{JVg67;dumkRI>SRD41IFIG99f5d;rNc$Wd_we^-3n>+>;&#)ci~!|@Z;e9 z!`pTeW(NT+hl^*fg!nfCV(;yd=RD$F`y6F!4yR1zYa2nE{H)`bg zYzm58vpslUXfL>IZI1y~49_op?0r3N{eaEPs!i=F8XRb|WpCr#82$YbZX~BMx52{9 ztqgDGz><5hduK%&Qa+c=C%Aqj@^-%6`!u&U8!Ssw>cS`^Ux4a@ID@0zi~kZ(fjCB& z?D9I{K!zq03G5oHSW5hu6bc{VWXgI?E%FH?}j~$7K6Cz}2=jHLxBn1m+8#L!xCZr}~f_*4ExcczO^? z53Y%(wb(-}ExIoa^FwtM(K52hy z!WLq;1QRNIIKrc6at-RcaN5)T+}peziZ>H$1Os1Xgcwegcc0N#e`5!Pogcq|BspHK zVOIoY2g|jXt+|xIID5D~X^Rb6J5r!@q$AKd19NI<_kv^xR9i{o%3ja2u`R0UMqnrm*qg4gf zAH9%^NrHLsDW^HvUlYW_NE1+_Cv-8nu_*<_ExcKZh>(D-H%5~CQF`9)Rdo>jIRSJ6 zS0+3ai#tJq&?twXm@6E$6mUO1Dy@94nf*?1wv_I{h8hA_ZCni*r%=g7wlvJA530uBB1w~Q`Eywzu@ge$f27eYoUV79+pwn zXLXU`-pA0&&EY%Ho8ceFeOZS+>Q4xHJch(zbpXuPn+2mJIU20%L?K@E`=womuyBf{-KXpR_i>Nl#FSwX z2#x9`q2S53)IYXmThSme;yzfty1H5l98~Ebr2)T#Em#Q~l5bd!9$5qhR3uQUf3e#9 zl#`2mtn{%6aFK$&)pL)Smvp^;NPC=mUOC0SSy)Ao(&(nC^ywFHMtfw~uCtIDOt^_h z)iz5f?Slvd3Xzq+SkM0Iq$gG)mL}}X7pfmG%`{z%&z6Z@GR{4F2tI<`-4C=QqpbbA z*d~(7Iu`vD%ziUKpey1;mChzHQzoVGEu=Vsh$_cakrLMYKDNyDb;g!EC%$kD6cwA0 z0mVi3doWdT))+7C2D7Pp{2x@yAy^=<<%>az=M)mKZ6|6UipQ_GfcL6hxkTycRTflE zla!NNaHpqCub+!fjk}{!m6w=U9CP>`dtik`!ihWZ&Yz7XGwYaq`MZ~Uw2TAZZ45YHn8N1Bcy_`^*|S)=;ZIY z{Tr0KuCGKaha04}jZrA&xdQ&VMr6c4Bv#s*)tv-hUS!U{f6w?~pM(BTH5c#9QTa?pSUP+$6E9h%>~_Z7>95Q@jBEnAkyOK;QPU z1R)iil$cux?ELuV5=g)4a&MKGR0)F|fU51(!rD^zC%?aMcswpD^OwJJ()lD-xe&V2 zWKwZ^Y+pVy&M?KATQOlL?RNDwza0+n;*h^mcSpx)he_ zm=k|kSPPT1p&uV2QM}i_ENR3hqKPAQ!QFWDx{>s)TWX4UuVryTy4a1>cOgS*HQZn# zK8HqkM~_DbM+2EQV!xPeu+6$T?-T79r4;r+#@#8P za^r0md~c0WN^2=0yI<;)YaiWYNyIRAFB8qAP`R)9ourwno0PJ(&dogRDP3&x7b-73 z=E)kB^2-7;T5$0T@^gVszL}9atZFcvIUU1?7Bw-wX40wzEd>`m%KACRx-K>Jqg7J* zDY?YuuefZ{QT*Cb8ZP)SotHHau4^|=lVM?VBcZt9Z8)dAxdiI*E4Ea z=d>y7`lzfT%QbtM%btB->(F?q#ijZyJNRjM@LvT9DgYRa(g%4oePjvb?^Alr?PKbP z>04iC35Q%RaI?&TYnxU^=~O?gpNiPSy*S?et*X>9XD!YMRVBL)yM5e}W1Wn?G0WtY zP3$u{3h-JwGg1LTC)eU#C#*xP)M6H_p18;W$dTR_*CiDpN`xZW102$0dnb(ZgsfI3 zay-P3MnwTauw{vDpJgJ0gWcA47Ic*y3>vLgZ}Qp}_;pyvln!I|cS>e*5+u!=ecvy_ zO32%9+>s<)?nOfEl0{PdfF7lSHyf!WxnaTaK>Tq-gJZO)nTgwxP=KzAhntXPk zy&u$z;lp8)(6LlvnLV)6E+RAH--SitRS?1Lt?Y+t$SuCS^BV!-f~TXP#UxI>|R^+-zZqmm>AO zz160{#M#Fk!4!}7E@`&B@Kv~(YgVeagLKCckCuqg;mOAE(*-T!E)eiP z(SqddMIMk$vi7l@KU)Iz)BS4na!d4nn;m-cF1qtssXAQb|m+`4cu_JW}-^igD6ZoxY!bQYANhmUBnI z6!-oI@#yspd8O~%_+~0cW|;`D@#)&jsr`oJpnDf|D%ffv2vnU+1y0KRFT3ou``dZr zTfEx7tM|jb=CY(=y`~~e%Y|T7 zKT&Zv$9(lCjeT}8Q{Jqxb-DYH3E>?dE-G0Gc)w1KpZ$Gk#_7=axB{}kU56IXoTF8$ zvDH&hM`}%Hzp6P~sa}wPcsirCCf<=LDh!3J#8>H44If{ZG#(s#`p~B?s1g^9D#Dp}_)l zR`n=k1%4bhPbG}5=CDny|Kwxhm_2Eq*$+tCPyWe4slI?&ScRTcDi)1PC_3J_mJqcW zoCD9zH8a8IbGrn?WcO?CZxY_k$HC-}ki5=6p$&eb+`#01Sg- zTxkWq-8jDF_5y=N%V+0;-j`|(Nq@LXQI=i4#&9o#sg%=$ouwi)uQ!6u&Mp|6PzKnw zk?zvyl;<5ekSV_jcu<6CF2G$3py6%hsNPTh4Fqi`XiwAjyxVGN5yafOybHxiVQDTi z=M31S-5T8Wul7QR@1P;Bk#wAixXu1>T=6d7Wr9aGflX}MJSAp~3W+ls()Jd|h>D^r~Ei-nOP_YP{o0Lq_2tth)J>k2~Yw9EMB)^Z}3-xLj z+=PLxqpWW9l!x;g$ShqVasImdo+LwB&20Po=Z4Wko8BeiV5p*$383)S%^fkYAU&aM zB^uXUZKN8h1uMD0%1gv1|EMi0dDu}j`WBv;|HN2L4Pla$KA0q(5-hPy?cQQuJnpCxf1?!kB8g@iCEB$VM!0cY5n9adhNsEeyPovn)9@23xO?8`B zIXNUZ_*endG2KL=!;vC>nYdah{*{R!#RN+^4VFtrMkUo#;icK|iqMiyoguKh7sV8| z`&4JSjCV{3h{;~UiA~9%Vka4R{) z>7bIV9nYO!*TV)gG9Z8cKL6N04<`=S7Q zfVn*DO@*EnqTAkRrQ2<$%ba|bQkySB5DW=dE%u_WY7#PJ!)W03aq=IX1eBf_{SK24 zKlHO&@;K*ZXI9AtkO&;`O_MeMMJ0+Anc*uKKBn&e3y zy7XC+Tew~bdBdC8b4)erHa#|am{I5@zX^D-RYsO?iDOK>rq%}u6=lx)Eg%|Aerk6( z#DjPG^jiwIIIhnxI?TRbRy9BH$)taBZ|DijJyU$Xz`)xDl*MvyQcU472E%j`(1#t)Y^l?(FRSExzj?`0@(Y3l?)d6Uq$ z^*8_N?hnra*t?{|x9UFexJ*31l`iv*Q5K&R=A_gK#yxpS6hyVV>ANkx4ahqAnB%Kn z*sN9<&dsQsUp^@ZyuC{h#a%STQgl>u*V&l!#&a2a#@OXRz0*IueBxuVvv7**JWU8i z)&RbifvOT_&uJO3 z{_`_9(l<0UR<9QLk!&*xM^r+};n5;bWS*qqnPRw{$R=`p=`kI93pEctUe;8OD}VMg z8^~dUe_VK^(_wnPe||$q!%im&?=SrGPso?(Xwquc9eMr3vbwr#!?{l0l!3JxO?KPv z6@mY3@rmU)_gp9iFvOE)VPtGVW{RB1#2-9=05BS1d_gQID1N5&fPXgpBaZ+uH28|G zIQUOs+b1;VV}ngIgDnHrkv*9$V&&scy<1XA{z}k$l-8V)x3|}5@9*Q;5L7T?gt>jCp zn@4A-NhUb9R0 zbnA+7#iQ2+-R{Yqd>wGod`~%$JP!qAAIXbFILkPNjEgfJ!7I!8d;(I!bZ;|v7e*~m zx2sUTr%fcdwvFt7f0Qi-_}>OO_M&s;ll3EG81&;{35%WbxLfXTOQDsdt;37WG@4lF zf>}X`%omt!#?UUEAF^4Hp*2tEC>&_G7ra24>E6< zk3LFbha7_}`4g9yS@eb*G?mrd$MhRMw*=h!o_xX^9%+KGG;aIzm7Gv+>`}&Z@kSNi z55i(=Gl>n2{Jl?wmD^Voc~5q$0y|LCj=kpd@sTw9RAdcPoRYz?7}5b!TKB63!#=tq z`67w@K9T_zY3h9A6;y&Lq}78W%jYQ5@B^cW+foXqu$As1tmer?*C^I|5qw{bca%6S zqw_Trvhh%rX@r%8#=jDknG-V2OANwvg#)DnkdW}GB$!rmxW4!~c~b%mTkKkzk)I)K zdw=0l*u1O8_>O{<^sWaT{PDY0lnI_Ts8p%$-U}cKzS5{K++?U$xs#4TgTJ{-O@I=U z7q<6-aCxYw+NDr!E>)BtPq7ngg0z@0RYY2>+1fy=zLzKJk^uYM5)5c<^9q1&tVupuPT67_`= z?Uxey8C~b@Sb5}gcb~FCMft_xglNtTi%C8;PgEIbvUq;(u!^Jzkyg93PPYyE&79pKFaC2ODRoIGmy~*rUJ!p! zD(7NQ<5@ODIb;}xep<2HD5_c3G*fK4TB@I8eOL9`@traXuq>y><@Dd8E>xphR4O$dp&wu-tYjdb&^nw+-4&hRXgnoT-5?@k!~`gaLfh)iUU zF_Z94Ux#467bg^wOi*`VRIr_zLX{l2uPO;_0oKhOZ)!aEz7g+G(*W_YVre$&+I&)~W!dq4;i>zQi)&RCe%0<(=lyE#h!adp>g2?bi}1jpArZPT7f<@7rNc6{)8SC?zv$9fwR=L%TmrhW>H zeY`1A>JG=U$%%v&SZ~skYIeoWBy3psOy#E&CY9ZIdhU)<$BGoTdPdtoOqATLt~P(By3v9p{_s10nqLIe_n!_G zxXb;3%XssKOs@?146%2J_w(Dd{q3%(#>4&vFq=W~dGd{N{x9%g^b%rI`|*Ak|J=IT}35u)5| z2v}Ej4z4k*R7#lpyKcjET5Z&@I{EDGV+(Wo2&Gu~>AU;%LdbdRGhMb+1_$A^zPhfu ze4me%SB@f2`xIG+DSor!nRVNHhlzc+U+DFE4aaY_+fDKt?nmouyHk;-`J|#|agsd- zj@wA+cmar@02Q)Mvr-TCxYbvefbSC6Ci@>0D(pOJklA_gMY{tIiH;?`++?*uGoF1i z576w{m$$-ZXpK?B!a>X?L3V39gSXT7Bl0!SQP4k0YBULv6E86rmQ!?-Ca$2P@o9*Pu^DE^PUEhExPT_Cr ztJ!bd^o6*{p&c1LZS4e%g|Vs>Fw*Y@tOyDc%ftf_qj?A!evn_ye#gNNPQDf{L^u%s z%3|@)?4_vsHR`c(f)(j-Y5H;~Z4b3@7>mFn!Sy^Cd-O16=iul#?0qBna^D%0#yr`5 zi6AbVYO1a90&41gh25&NwZfEAeH%KJkZ?xM_2gwcj3+J>4yDv}b9w7kCZfZc0YX-m z!t8%Ln$RmO}Pn#1-W``bYsuG>`y|J~7ah;%Nsa{`8p zTM=wP(7ENJy~fwl0%_FY;gH_Hc1=GE^|HjVW74E;E_T;eZ9!ZcDlde67G%ny?qSuo zw60NXz4VWCLnN?+kdj^(|FIC1^8y0VO8&%G92Q1wXilBqcw=o_&1Uc``<`jdxm+>- z%LNb<>@>;NzSTnyL!yPz%f0J09S2A8t0Ud_rds{d68*Q^Kl;Y|W3_yaV<|cdtm!?r z7+1U3-5MRCkelcz%lTZ#rZ63M4kxv#&+t)|E`Q$w;GZP-?UsRm4)YQ*p$pd+U+6#r zD5b0V$Oa{=mT{fnn{UvUw=hts68ocmh2<&z7|o#qmECCxkHaUp>@dYI70y*+$@h_K z>En*ird7HOA?zn3SY|0M{7NrQ5nse4vPDDM*FBZCSRQoxeM&5wd6fof4dT8L;(gb3 z;$qC}oU1AdHFyu%$^nY`rnq-Sfi&X91w1Z%ul>52OS=ih_CchGs@7vhp*kAWk@g3L zs1i}O?(uf$jEIPgs147``nQAXjuXX%P~314)Kb1a_*`bzI!Fk)NH-VAIu@hn!j2Ge z$kL;sL|OR&RYk9+s10GMPze)>!4DI|JbTT|(KM$4sk%Kz#-wA07<9RfG6J$&S0XG) z!*LN{?SI@&Vz!PnLf{%C@2vHuQV9P6jxW|(t^d1x3V^&tuS-Re3ZZ(}ED1(zM8@4m zPOdELZf8GlU%2~L%@DOas8LL8x*f(6srg0iMhf!{e@4%Bde@CMrI4!1=SCYA2e#=4z;AAST_G{JEC{_k<98da3#59f|d_H+VS zC0I%UKNiM>0uCg=%3|g0L}e=`UY*wq%LevZAb0gYYS3;K90ge^*JAwyaaj$S?DSmG zc6QSd))licD^#R{`QI-MF?Njd?ikO2bOGRr5JrSH$65{SG z6L>Q<$zPIAuhBP1nk9fN`Dx9mS!@|74jWX*XcKfLP_8Z|_WhL$nuSDHM*&RGOGhr%=P|@g95m*a@QU z;8D1Wk?E*yU z-J;glcy8fDlHcov9EU6@n>aU^BWUX6xia}yNI+{bL=1mpw8Mxcrug1``UB45*>OJT z9W`)5Yl!F3IbYBL#$gX6=w3ky_ZNySw|4I{i`oQIgEWE3Nj{N^HhXy5iVNUrB$b!b z9S#Yg4xy_;yS|a$U1}YM%~J)AfAJPv6Isb(?1Y&cvD9x%8H3gu?At`M!IcC`W$n%* z5Wg||$lTy>KRkA9SBWR(G7EU>pNo8a9Lu)-%QS<4FhLfW*}rU0f9A5SPkNL-*_pcD z8y-tNDHr`;eW-tPpw_Mb-yA6Vx!{d{z0XeYUQ?*UVE9eVA;kx)A(F}wl04Hf=#h!x zdd&TR)urep@q}s#Pu<8561_bqN3%t!o12nvJle)#B`%4W2>;24aOEy(%dFijvw|8Y zlub(d76M?!oyp&T0m(ynEvSc60!d-b+p}ekeBL%Cck06|efgQ77O3piYdDKx`~5 zonS0+z+~jE%PR{O6Fm4ok%cw!KlxEcoMB;b8M;{;a_hl%%pS4^uL3*e4&dPaVW7R5 zIx0=i?h^{~j(!6)WzyMY?dPaf!J-*y?qDh5i zPllr14Z~Z-S45)@#E()9hYZ!aw|jbb)5PuP?PYL+*+`SQeAN5WG9I z0Q7p(0QgYp_RXLq83|aEHCzpxH{NvGN>z(37WjyP1T~)L&k?8s0gd8|*)H6A&$BaL z4QI4HWH>RBA)IqeK5jSibNyXge&Qs>pH2-3QwkUJyi8x6#3ltW1&lEaoj%QQTOSW^ zZ*en%Rp}eNS<@SR?|-~f#JtW##TUU;cskQPL&GgIIsT}ZC2)}^m^hlZx${n2)}l4A z>GD?YG(Ha1Uyc)qXv(Oj#qf6^) zf~D;0IaTs#I#U4la51r4Z#n4{RY07@C*=0Zq1nh6)pjm$D|PyV^b>yL$w?gDW7&6) z!!w!L-Jn~o;jJZrPXAj$qT0ZU>&7;&e(qdmhSiE%WD$rKKU+}0K$%f*M@D!ne^Dqy zTJd97QkiyV=KZPZtr-bV3ndtXdvKI^J;~GL!q;#Z{WL!mpM3q~0$^=5D7Q`;aEn?7 zd*Y9(q3^z!!;VTrnAl2QZX7R72ivR%P0Y(~ZHys}!cEPr%uvyQ>}yR_4a^T+yn)!# zQ(eh*082Gm1_C6g!U!jND!yyUxRPHicGqUmt@0IC#&!gm2v`mJr)aHT9=!Y-UDg!Z z{2wQ3UULv2UlUMGMdGcG0L7%B?0Dk3drPaE-+FZk<)Zv^9Ap2Tb@0j>U-RPI=#}5nW{~`Y9Psg-QI&vHa zz<(9jasDZ;=d%J0yH>||8-ne3Z;qHbBl6$}n7z{;c_MJc^46f2Psg$kuVB}1mcDHq zr}lO+xUjt60y$gf{+Z6qswMqLft{E~1za6P`%%auG>X~+_E&yTj<^2Ljj`e~cgnOt zQ2O+V5#{EPrN0_7a5|?Q0Q2b|HV7Zy{2_aLeTFYK6#r2ZCol)492wr!`c1+H8^SH_AlBBR%prN4GwH@7n;J(M4JHEwL6Opk$od40WCZO=I$wvLB z^4rU%rTNv6t5xa;q@`E`@v-Y>Vvi>8+@-3IGnDXPlm>*Qkp*S#(qthlcy z0N!M&%8-JeGK=KhmZjyTLgf%tW3WUutq-X-9-N>iDJQcGUMlJo zX~ih#@-~Wnxtq#~20m&+D$%{;4B0{sgh`Bt{2L|x^-!iHA6YZ8z6oMX^3s2nv7N4m ztNTB{p7mqvA#K)1+7A(`No0_C7nBqtEyBAxFvLc*ahdFIL`p@ZbC!y#(scKcDR&x;opnBFbys@J~{Ncn8Rc%4n5}%x55d90$V`o;y*yiW~vA=2b6Uqsqth|c@ zGz4j7KWN-9n4cd$Qa2hb1X1;AzOZS#ud}U}FnjaoFI@x#dd3e%an*tQJl;%`IIT}D z+KF53a`?>Im2vsEFilGMYc}PnZ|K_y61msopZj6*P;sVUF!{^D&13G{E?Nt4{oeWC zrG>s_e6qw;3Y>`6KoO{8)z=tJKicjb)~`}VjTF3lU*2AKIx^;=Y@T~}q-080(#!-m zBr0mSAxK-1k6S<~pA0s%0;Bo=F|zIq*W6sU?b<7ah(&E`q82XWw_rutlb*P7b~$_5p{jt z3NG<3Y@1MHGHbI2cGQ2i9xtw!`DokQAe8>r-13iWjwc?H9!&qXUEy}91C?L5fBvT6 zA-_4g^bK=V+aL&Qkt&m4ze&>9jY&XYb;<2@s%wkz_kUJ79g7_KKP_C4Sfom{jFKgB zSwkj+emPXPh3@KIBP>2(4_=h`ELkc#`5szkTKFVVwEW|xe-P7q0f@wxYl))Tc1kh= zo_}i27sk>n>@E4QAMPvehZvkQzLq$J{_}U?%TVZwvB2I|KiR8&Sj?^w?qG^m1F0d>%V1$Tj7j08EpUmO7(y(T&}T!%MQb31|C>TzUYVg zi8pVT|Ki!d+IzYm54g*uH^)bKpargN25RgMID-58(tiF<2$-mlw=J|0;lyqyuUhwA zzVQ84ap~SLdcWqe7$>vt#EuDZa+Yp~iQl?D;cwhAC?HFk@va}aHSwCY^(KE&a;+fNQh*k zhtVZJjV;{aa%E*C_;#NL(BeB{TAvJ{{BlLsYlmIWN*_3=*%`LW(wC}WS(&kCdL&vd@-Mx0@mZT{U;(wYEE zi?*=EK%hab25fMdTwH}bqw%YKUV2CS#CX=VT_Ikq(D@QrPl$Z$R~fX?zODYh)7pnZ z;L(7=CV7|HCgl=%3m`iV1ivn(S<>FqwF{ZoOZVun@36i@i2fNx|U{5r^kHq#W3#i5) z=uPxuW5k;tjx4%twGL)jWxdmSYZaj3{_6cI$+l?ern=&dl!1Z%&DBJjW@bqV2BE>w zhPh5rXSs?%$9u^L83EjrXem>g9Hw$S5&@P?{X5}lV3*aWN>pjI>Me$WY(i5qOuuxe zM_x5YP4k!4Z%*jcl?2FQK}r*T7jds~Tw;kD^BB3V4fVzDy1Ng(+M=C>xL(iOhM`cb zntt0YIH(VSbwJKsiPz5jO!N!07`?}H&|(AbO1Vpg(6P#)8u|4r*S z0HgGY|0KlUw81%%OP(<)x_FA*`CU5*H=)LB_E_o>%i@?yc!}V;8%NO-w|t+#AvISc zqYUbs8;Oor_yXa7>pUbEUgI5K+da}HhSNb~i-@G)6XVm#XEwP48o7H%! zQw~BKL?|S5l2yOMXq7p6*_OJAi14PFsDvqmNR-jn&nlD6T&QlrTiu6RJvvW>rP<=c4Zm{%i? zEWH;Uko@(#IX6<#;kC?RGlI88;$rfuVYE~Ri<(^)_Q%4g*sy6-aFb6=QY9QFBH6*z z_u(RRnr{J=j?UPeuhB=UOJC2z`xY5DVQ7e&l}dihW=!@|*{?=wVV9si=wmwcsJq!qhfXu^x9Ac#qm{JUOExW^<>OYo#V2 z2@{bJuXP-ohgT>a7*nKq6Ry&8^p=^^zfj>z+4PB`S4T-P*q>(LTkADdq0N9kx4@2aJ6*r3jfv zHZiAcK3&Vb^wj5upb-p-5#8~ zxSQ~;yWeycs40#Rjc2`Tev!$^PZ5tki?8hobhmG&|8B}_wVb){T2%i@p1nwf47v;5 z@!H?r=K$F2kk2zuiG_9?q)Je)64iY6%igPR<%~bQNjk8WL=o*5>0JO=*&V!C;LZbt>+j zo2l7FYwkJ`3ln)s72cr|^X(q$L2S&=l_cxd(VTC#!t(^tQ3P!ekS}yKR%eSVu)ih)a z(pk6fyy$qe)M5+BxlH6(g^&_y3{i4x+q@Tgu5!%gTUIiU zKz`&-ETuOISOhnHH)&rH*Kt}4*4I@fp)}KK) zbdIgt%{YNww)-ADo)1s4RJ0aDjlsY@K+E# zVjx?6I)`^C68~@dI6hZhyt>B$G8&$kj+C=Sqj!k24RU*O-XO&6@rtF*&%tlS8kB|? zTL?;NPJpAQEY30zZ-&t%>p}mCZfsYDFDD>T1!|H(tgrWBeDylM!gyQ^$*fvu{hT_N zwacQn;Mvn=e!PI~loF+i^-O4S#pP$OX=66EH=q}3l&i=eaHvrcwV*H}I8l|*ggnw{ zZTLu)xHITOF#7ud79yxGTBn_SoIqcu`S*81ph%g{N*=DcX^z*hlj%9b-dDp|%0VH2 z+}5qzzRPO1vbX*SvuPdATW1mVYi9vC;*$L z{=Ppd^fl@m;)S#B$-51|lqO?WQoGl1cA(0{r-dLAp(&V=Wb&5d&2xR`AGLQ1%qN&!95+fBNIp|M=sA#_Ii@ zx||sROrYu@&zR;!@kFQ_??z#Fyb~L^XV%+B0M&;>E}LARosV=~3==r??FTbv$Rgi} zar=p(_5-uOo@OYtAc%Bt=2|*isG((t$;}h&UwUdNOO}>(h0(^99GF4zbnXD#__wI$ z%ZDUQ6};hnSAoH<1H&@kOVG>=b(P|G^bqHF(!*`}G{g^BO4hi*o`BQ%LJCL}wBhza zrrn&gIC3eIsDhV%;&JzH*N#u8P3bm2DPLURZXZ0l(xucge$d{h%`pBXG6}=tppRm9 zg2M~R?Sc=40KW`x(#mptgvp0pS(s_m5xmqR{BJ`}dyjwp+PmKR)=4^xifC#+?` zm_a*k-IdGVt39p;nqTUGQP~%k5r$oU=Q^NeDUSxy= zyX>bQTc(JE!ww@69{p7D;-RA0-a%~IE9c__Zdb;6sWIG8j$#4!m!Ce6Y;VQ8J5-ud z7s&P3Y)gwNa(eT-8j1>goQtHlANo;1fCfWn+~8L^aU8!p&-H$H!lyh~)qvd-xBPN_ zjda(f8fAOtPq(f!f-+Dabu;yhx>oxd0fEAMwiJ6o+$ z1|SH54*hr~JMJ5cU0)yS$?^~buKYILn6p{5iRt7Cq5_M5csQExadC{sq^&apf?R8* zGp{LVE^Rkz5*|gjsVyVN-iZ1ye{GR`4Ge);x=1Ndo1g*+){s+XITyD!``_GZK_Wm? ziT8A;5NAq3&HN2Cflz7Q8i11g*W$KCT)T+qpJAw;t&egm$`z@bml>YFPQ&Q>EZ~#& zR_;j)ZE_*Zr5MRZv!8+dkNZAhn%RALSag!thDNF|BlMqx8}32sicW@a>#MdNm#~sQ z0;Xbr9<_g2AH?mU-=C2o1QkI=e}W3CC@4hd20MwskmYb3)74GQz!D+PT&#O{3fO>w z((frj%)Rr;d)ZxHoTV(MIJz9Br=WdogC5Kbp=GJ&s)0a8(DYic?^rtb9+iRQSa;c? zTJuSb0IKu4EbZzc~S zB_n^|i12|t2R1ksRwj`+`|b0?9}w&ms#?o_vkAzY*x+}nW#SsXzW!Wb)bK60a%N6VP4Ln|dqQ=>+DIA{O!b>!*}@hZd)byC5TvA6 zV7nSD$uGVmU3X2!`R`U2yFj7V5if@ObD^4(axz%b#VgI7=99C_frm= zK1u<6NXla#H{4rEoNwMk4i?I<$LU^2rx#stgm0q$kj{zj&AfzJki%p5XS;d1#tDtj z=Otz~>n{|CPBfyAXMnbLqsL#G~r@%DEi{51=YfW(}n z@ibK0ZP)) zn|AE4o5Yz-r#d6XZ-iMj+UEu>%VtF?$46Vrf%k!L12p~oNzf4iF%*X#!zDl+^KvzX zoN6E-B@plG+$Rh#-Zdg%CZc=)?I?S8YM>TO+qY?B&yIXJo#kzR-IVsyT0BB1TgY0J zB5S5>#R@NvC4X>1U21cPDPm-LP*55uB-*YFLeuyeUCOYbe4|;IXfG2~g5Xr0D^*;O zP%F@@{~Dckq4pyQb5YhH2}jVWUQM}pW_Ba*JITr8*4l0&*9{OCn$vaYv~0^*zFbN& zA_D%sr=)s6$ajNnY9_)zoudqr60SAQ3o+%Xg9Al=~&THyzQq8LI zO$#j3ZDm?@E-_}-NL_h5siD%Mb$-P>Q_CaGC|6N|p*}fV!@|-_;ycV>hQwwJ8}!BN z;s&M{D^nFaA}|DIApXk*FesOIN%f-%Ev+4s-fzZ+ml|8*2;;Mam{KgwS27k(LfzLW zJ=Mu}6SBzeeAs!}*MEq)^82Ll@jIqF!TG~U z<<`VzILdsW!8*R<1{As<6n$@rYfq?aBpAqSb(t++_^Qc9d1)k0*u8L;=#n}J{7I9& zActE!1fbl_1I}V0{f~58z+9TULi|x!i15g!GXV~gPvD{lt%zSU2xkC1_j?s2--CGn6CH4&p7**!u3s!VT1{ZC>`5|Z1^op}z7wuru3``}S#TUwPx$E+@M>%MVI z019Rj;6XjYb3nK>`P03v#hI0K{b$3;H=AEYTj=xHyB%477Q_DHG4ViR?(7(_YiY%V z?C}uSSc55$-Qi5=NcMa^6F1$@GEedG@%lIzC)zq7d~7r5=LWn(f-=U)&`{gR5ckQk z8^Jlbc;x8NS9}j!HZNLQTEe6Y3jd1!ub2Cc7c~0%`q~VbetiY4_<|w>LG6H0CQ^J% zj5~UaH-@~pVJjbe&7_dnR}^UcGA1JV3T4`w>gbrSph{HtRoqY}+IcC~IOD_$!tJ1& zF3oI&R8#Dm$Cs}17{p#fIF5K+O{lX{ZTi~hnD1}jMWsl?SZQ;xtscp;H79 zt|g{&fxz&La7a&Oy0(Mm7zf*}nGlkuWcN>Qr`;4TGyEfv#UaBbyZ7T8wSRsKFT)3L zV27|LV{>Y`9};x?oauG%J69iPD?0Y9_d{DDVv^g&?$f3F{j{Pp0Camj zt`rCMpZ&veTUYSC-ID``=|UgMHLJQQp2VL(m))w5&=jV`tlt@%Q9?;C``d>*!8mb~ z*>)5-rf0p2?G`_#6p=DAkcd~jezRQ%yjEi)v-BZR3;w>^%IZMJFu`b-WT&@D4RKwW z7fNnKOV=6`#{vB*)RS0zwAh5#cJ4H_;+F074*GOqaDZlId*}6>Bq#i?j7$`IK-ez4 zD)~gkj|_dTZJ>c(zwG#RJifZYpNC=?PkuR^w~RSwvSk@p1TFOtYe-&yv=)%kGuts| zKOgBT<_Nip@n!I0FJhH?g6tLq0Rc^2!!xt&@UIky>Umj!ePcGH4Xjfq zdb&GHsx?0_Zmed@+(Y8SWn>--i&V2HVP(Ig)Xi!y6uFg})?wUnzIZnMfg8{~t5urk z?`z_M*BE+ud4R*r%;Z7Lqed?%o{`GU!||eS)~h)P$5A+OI4>LbWP1OT`-HX51>SU> zpQV{*e1?=njNCej`+LL9S)fAP*3 zyCBNEfBYSci1K*-8IwFXKfWQ^8XrPkX{ibVuu$39Cy6p9KDop2hd(PA(b2IQ zb-d35H5{^;x+~PAMl^u*^9WF8WIf_lP-71a%KORyAF<)DPmElyl$4O;>#pHUtCA2C zz>4f_2m4`($8q7AU4;ofmRn~lRbc$vtcp>8QocW_IblQ`7SxpB{H2c1d&HHHlF8T% zR|6}8!|s3Yr`i)TCNewP!|aKUMoz5Yhb!^+{*tX4%osMl!`v04`ch;Sm7qix_SGDR?tyMZ_ul?EI=h?2veuUn8lka~j2Vc1{;IcwH<*`Y{JVI=th6zMlwe62TMH@9JMk~i>;CYUNRR zI%BP&3tlZGo=2{e?wiOk%*b`x3PHeAv-N>Efj1zZ?{{#b8-3GL9q}UM@0l$>T8k6C zVF33!o_J={S$*YIM#v80i)wyUOc_&#?tzNl?Ci zW?&#bjD2DBPX-j4qd1aT0FU9_SNZupA&=+etUeH{eAY-N(Nl9lTmh= z5xT^Bv^NV+N_0r{Aj>x|d~kTkzoWvmcifU#r~U_=5RuM_(QP8#CS0yw zk#Ib4cZC42RRpS?=Xi@BjE8DxEe}!)oC|2(N#u5F(Cyg}4@wy&CRZ{DjQmGNi$qZs5R{gA zQ@_s<-ijYK3E9TaKbYi;AYe^`5H`~w)O)uf6HI=XpnDoILZE(LEA5^Gf=nPmf6RnH z;$3)QRYUVcj;PGRK;^47BO5e3Y7Mk0%HTxLT$8U`JaL>&6xrtyU?f{T?l6Gx`zu6y z)q#p|Pe$W_2I{)F+{65D(7JzHKnf%2Z|_)TVFFW=65L=rCM8e$p_5iu5k!gWE|WU1 zX-!&Q!XysI#W~YsC)kKJo~`1slhWoXC%RopiU^U{%%6aBg@TRN0uE5`_cQPVa$KX+3) zd8MI?=yrMH>+2>ryc>SP zX13AAQ7fXch}QzC9b4U7BM2BOQH8EhwwcRM05ADLWz7veuQGUQ*@&ZZA-XUWC=MD8 zB$OZ<`V&P?ToFAuWq_wZXD*grO-fWN)60>C_Z%44o+pZiMpX-F^qg^6^XxnLsQ<%cY;?=i<@$co_k z))u&B9~A`!OHV&@@gqZE_h(HNk!;mwfeuPx<@X6BtK+q>QsrHde`nmQ5 zm<`Znq_Z}Y`pyqbhDY5F&+pZBKxp0Bvpp|iE6wLfC0&GJyahOi9i6`-QoPm6&UeiV zf#y{lZbe~=G6ayKAi^t-?&Jz+P=DQO0c+pR$65SAyXpjhR?`S|xDYcx zB<2;LRYjUmAm~;*L0h)XA+&+^hN@O@Y9tQpc1?ROoe<0enYLkbmu&TAz0{RnG>^rp&>@s(5ohelWJ za-&d}(Ivu9J@*wq#`7CbAvREu6Uj@qV z!)IQDeCcG5`yVkmqH=b&cPk9~p7*P`RgV!%fyR2PcJ~I<6r07OcX~LHceGPO2@7YU zDE;1UMJ{}IM$0R@+OcuV-dSZ9!7gLt&IH$$ljpTFXbemmF22Yv2cjyoKG{8zqdaoe zNqFIcY$5HanIcagId0)A_ZRA@u1uF8aM?dzcqTx7^d&k{aLE1z-faR1~ z?ziEXS(G$Ln7KYz@ycb(t0d zoQl2c$HeS}x=d9zW8qd>|H>i>%-sK-!r+>uj64epn6#|*IXBEHme0@imBO9DzeH=$ zEp}*9raG#wQ@!$@lq*+Q93BkBl~LfepQFG=j`B1`8S$u^1B2y@Ym$baIk_&8x1pc~zKO>Sg7cNok6#;W!Z%vb?K)rN#9+fa(^!uU(w*iK zR)h27WW{o>szdB=mhLceO=^BeQz%cV^6#fd5CX=6ngU37CA*`sILoT%$D}1br-{kD z8ND$ER~+^C#rL0yw)lS$?UszTvJ5sKeQp=oJ?%Z$+Bm zJ|3oOqdv1KUCj*qyuK}aMf*{G^ zND7qK7gF#!+r}uxhL&HTk_!xc$aiwtMYIx|(tzVxV;u@`nH^%vXhdG}Z(fgjdx{IY zCBC=HHE5E~iBWOZ#%NK4h7A3uA#Y+r2uDY;`UA?Fw}sX_!oB2no^jV&2XC^y(AmWP zP3%IQ>YEhqqWHFcn&TMR)`zz-N@6vbuj`N5K+EWrz?mu$J37;$hzp*&k@pXOhJ4ou zC{ti#W2g5(di>G+zJr}^$oyu4jEnnLaQIIp>aa8=y4)vmBGb~+FzG`7S;ygjw~kQ* z3lcWQ^a%s!<8J+Uvce+)ERQuVOaNdV6w7|8;;S(Slg7d(B*Ll zw*1kI?3dm0W8VQ(>7&nk3Mi+VacuPc?K$=FZT;EEnYHnP8BK+gT!003>*GLwr12Ar z#gzr)T(0Rl!%SklD?o-aX2U!@Kn3#|XR^ zbFq(AC$~LbN-jM^=C0FU?oI8^TC~D#f&hhXt*{1Jgz=36f|$E!gd#-^K#<)FE0|5 zswTq%-kX&WAovfnt1mG*>gslpe!;PH!l1aA5V&&hC=s+ z37sEZ?=q$NpVZ+}UP1xc&R#D{>rUfORbQsYDQ880@wTHc` zi?z!6d!sHZe@MUddN>Dn-?n_}`g^D=R?-k|9_csK!SZGjOt5s?^>I{pfxh~qg&Pc+ z+Qks*oKIt^dpLqN>+F~;on`K8-(am?ll(!1rij` zL073JvzN8-@!x41_FL8X{5bc+;(yJduGTq1^PDa&uC~qf{P^C1SiP0iOQ6O!W012F za$c!4ze$_v>@j^z*8+p0AunD^o1)IiL~zZDz44J@LZ9={XDn8dal0uGmZu|cMk`AJ}_(5F1DE*6h0q4ca?>9JK=nVS!^$5gD7N2UiRICn^ zEMVtkwfp#j*=_6s52eN(!>c?weWxk2s_ypH{VLr<95u$7_&(~MaQDh)sv6FTUnSed z$Vc0FFv=*f?;mR5+%T_rbUb6ZS>oj88Q=9V#CDmn6#F2eQ~u}p1npi34q@RJrXT;Yei*ov?py9o#MK+YyI#ktw*(yAn3tL`D8mx)0flur@Xw` z)u7xIa1%TS(pKbrnZ6p?B+ac-vphdMlxl(#bu^8q625VrOV{hBa2u}h4f+>?3*UU{-=Mb8S0fUV#+J+8&utm&MMXqt{RBWJ=M z4a)nO;qa7p^Xx8ep0#S@fFkOX?snb;&8)ZhpJYIoQn!{RJNLKQ`n8mSH zk%gj>HnvBh;r5hQa*sv87MH~G?A4-7w`om=S)Dn$w${(bE;hP7wi}>s-A%OLhs(#z z$n+8~RMiF9wP6j*GFFZ~YsIcYme4uSMJPVsE?L5t{euXMyo>j%A1pp;9;2bEPzZ{K zCnd@_IU@hw*>ds7Ib zNA>-`HH4jRUgxe9*1^*;UEl4rM@!l6y>R0()=A1N;8gXH357(5kIUN{$_WKVk6qNq?2MWiY zU5E5rFw67JlijjHA~Y&{VHrqHiBqru|Aeg%j%$u9KaRlVbl`ko=Vh4SJfjfANB*p? zGvP}d*Z|KzK%v3GOhvM|zD~{Ib^byj%K?{eZ=pGA0)kSck&D8LidIKIFum|?zEk+^ zs+~G+9FL_fAZTdK_pmknW%b?8F&Vx4;@^J(9QnJ-*BEe3sH&4=bCXk47)p+Jo*0M> zPK=a$^7Pb^ARg&Xu4s04b?XMQyDh2E4?O&ek|XW8Nv|Ex0e}&9$<2XwX5@Q9OALQD zTU3_)UOt(a@-0fUTa)3T6y>GY;|p&nvk)LGm#}ki@i%16_W*GwRL{EfH(v6eM zDZ2}IB~f7}S^8_1y9vfw1}jEe<#S0FzxE9GP~{1CUjp2&j~r2XNBg$_>(R`v$?#u_&!Y%CflAUEt{ zdwMv4*S~r1=ee}3u<|Rp_j;Lm0R`ye%sUn>3iODnll`qD-X244?<53={;8JtH~LHP zFf>IU?MM%^XKi($&+)bx4WGp*hW`rR^u&QP4^2T|M2f<^KFT#C+Cy-)-HOJe+1>6$ z@2Af`PW8N%ifeQg7`~nUnHj*)DyGd-Yd+Oj zk9;tRtY{WF=d#@k65aON88t3GDG;)wm8O-VqNBv%VX}?Oc>qe1Taq6&))~pe!vj&a z4aebree8RgEHD-_rOj?SrwwMsBWol{i+tDiD!kXzZhyq6MeffXLP8=dajREfS9oZX zEN ze=w3WSBx?^;jn3?Sty7sodyiE23LcDW?4n-@Z}4dbUBQ#joD=3B}rZ?qTRn!+Ca`w zl_3Naa zd}z9JdSKp`Wk-4ieFtKSA#a?FkV$}{)XQcqs4`ONUY9F`+Z169k72<^C%jaX{GpV< zfWWgVAB4VM^~88WKpxdTCbi^B7=~)M0K^;<*zAygF~Cds_NJfqvJum*UN-t+)n(ka zh|L7L0RX@52)S|;)#9}R5pr1Bp-oQMe;j4}UmP_U$cY{efdl;g9^vZ9GNSTmpy0v#`YIB}S*w!Uo9|HP#DQ}OWB9hK4dqnsS;HX0~A z3crVxM+!{!lS+FH;`CNc>3i67GODvTz;h%fwwVC=-9`pd0rcPDYV1F7^{B%a)JBg- zjP)P4(oU5yE`!l0P;T&?)>G^cznkdpTLWYD zI6>QjLVWT^5&aKZ>Gu!*O5?f_fxB2Bv}1?$M}a9*1p$+kjO_{51{(~%YfY0A!Vj=D zf+(~)nl@J+{wuIwc6|~2Ih9R>gkz8P@@SfDOLpozj0jkUIZHb z4;IVVja4rT#E209zFxo^H2W{-YMJ9LD61YD*>cH@Lw@JUfY59|Zct<`L)L6yX*_B% zwDR87ZwtZKeiVWG9b=iJ&}J9_gr@N5a;xL<8}*=?6d7%?`TqJLuWJ0@y`hpb(JY!Q zeQ5JaBd)v;JiG!UsTI>8{ta6JTQv$Zr9Bn^4I5S z`EaTkSyO@46s6fMv*_f-4i;WVAe6u9`QJNF4mM(BSO|}H7@UI-nP2G@XozO3&n*8Y zOs+5H62K_dUJbLikrl()65vQz0fB%laWFW$H5ZHLn;woiAadUkh#!QcyTArwvN>Ph z7M2DPLRycrk|KIoDbbz+(FBP*#c(s3 z9x3o*{UR$}s_Qx1adoU`u(w}tm~Kp*q@><_PR7TV`;fN)BqzpT(Vfb$Fvf=AH;L!u zZpI<3C0Gl(khi>Z=ZaMFDC4q3F}FxX{An#KM8xm^9HDQKQr@eg9cg7W#mAJ#9(^Uh zZ-luR1MCyJ*AJs+A?4>=)jS|V28L_2dX9tnKCMI8Mz4;$2>K0kPOK{(u18wIyuDOS z;ps?=l%9U=EBM*&Mo`;em$?`wa$^!Ys%E;`<9b+*x%&$Ek#pKc?*3i6dp4+4UbGtE zax{B%`sZdWsFY>9n)8Senb@N(x5A6KiFJ>Egqg5)tW+~=p>aze#IuzjnYP9Q)@bpn z#6JRUBHQ~kfWsjmzt?gRs1Nz%@p^*!Qen(F&L!x481ZPRc2;*KtO2aZo0gD$YKf8e z_ts^b1Bz8e^p13C+=?mZvD=22M&FK>R68xArOX4zu?6+ZGW-vT++EywUck?~eaxs6 zMRZ_!7-L<|rDAVY=wnAHp^)2wBO}w9jPLQjZ*3J`{gIy8<^|2Uk^snN&0tW}Zr~=< z6$+{*1OoZeO>p9#J#6QKMhgmQXZD`n8NTs)O4wd_Bwgl4DbwEl)G0nC2|79zz9@6X zBD;3SA7Y`|U?J+$Ty+`Mb3m@h4B8$c;zxJ`c`hUj7(!ZD$W?dfd^OF6l$3CDH12&U z?@aS!!OymEYb!y~*9v>mPqLWo4)FDPc&44R?Hdap-MS%AphW|$W>4C`2)^(J3?TLO zV67otp?yv*h7Yw&Wx!A|Hq0)&Z{~W_pq_KkwtCW$-?O#KU=;Fgt-z)ILL|XLTs=E} z6u-5{!TzS)LiybcsEkje(*}t1w?^pG=JPNG4GI$HSw^l#KLMUsL8hR1KZH_7Am3sT zf=`}Z8y&$ebU@Dnv>Z-%Xw26eFlJ!bPU=*{Tz~ma*LE{-N%b4_=KUE{=fl~tz#UA5 zcRP;Y6KriQ;^DsfE%fhfJ|G)h&cQR?5q(W@cJJ0#1#c}8!26*eD2Rt0$y0vU-W_Lt z4?x8`*E06fDxo&74G-OsumDP_94tX2Pa`?znY#}$s8B&)oxd`bK0Ru(2ZcL#XyJx$ z?P3Ygm)(O+S^?kJ&ii-EL=6h36|Qm%+6y}K6Pa4DS#;$sjL5ijSDa&a`4u&)LdBd) zROh*xRBMXMVhb|gCYbSQ`bR_RT>=mg6Tv%N&BM=dFegH67)<9^16+af&wBOP@7z$Q zbm!}EU`xC^2ZDp<-{_E2&r6xLm>;734|K=3EO8K+Nmha&+tU{?xg^_Z9w({x91IAi zn?>y`tse<)#YV0$41+^`*3R`LsAHz^jsGG*@gumfaz>MK7|c)L&_)He!!>%%Sl@K_1!U}({ZI5{>(V~z!=s~p z<{baI-Os4sg?fCZ(PFZ)ldu>f-(jU;M`QelJ!UJqgIcz4BGf?Uc78mevTiXGe$@Q; zivNlF#J;ij-)-pjlyN+fn!t2#WBOvn@011)2TrI#nbDV@*B$oAZOHIzY@)V`6Nx@B z_Xh+uI;0;UplYPLw{XDSnemIHqcr$lg?Yt+3E@vyW}zD>;6+Yayaehi@P=r2&8|yn zcnmpzGiB#iMi2c%nd!X0h@)!m;Uczn@16CM@N<#nd?@L$>gI2+!%yEwYEDf~g1!yn zAg0rWtJ=fy$Z81=ju@Lz4*pR6+uT2slmmP4qOnndnL&aXem?#04MO9)m& zQC=ab64v!4*&Xx*C;8jqm=i+rX22sdyt^{<>qo+~BQ0R&iA7Eoy=0bK)r^`lpnijmTZfDrAT&I=!ZG;j`AeF8Nt z0)f$Y(vIR92rv?SnGomnck00_F|XjtFXNOoHDAM7`3tCU?pw}rx>MtO_4wdMPq_Dr zmxdV$p*z2tvojoQ(L+gP3W}A|eA>@j<+Zp;2)S!}`*hm3_xoGT0@Tl@*+BoNJMP#K<0gYnEGtL=ct1Md=2q9eHy(c%uqXjtbcYIRu509uVGskBHUh& zH;|z&YyrSrF<+Yf*+Eifis{{XisuNUz>?F;iBD5d)Pdh<3I96_RI&Jj>vxCF3RP^4 z-DgNL)+P&{z$1@&72YnkDz*;>;D>>Y({xoYim73Mexenf7}7EJ;H8|Yil zN#u8IGXKxdKGJtx>vo&A;kfGenBA$$LhE1sJni|;`+aGA4}RvzyP&*P2#?+9bGGjk zWEj&UXxc|VYz@>H0W0P%wNJl<&X_ChnZKkasH6#8{noJ1-*xp1l|+p8L-VvYnb;|s z^15zo?K~+LYp_5B-6VcmEza_$ibmT4^u4s^K8-~GrP4Ghu^7~~ezt)X%FmRqBwX(# zr3W8uzvgF!(L1Y8Q>m2_cJrob&OWZLu=s#cC=kXX`tsOjJbHw7LjbLsrR)dAs39L) zgGXy2dOZOp)hr>XxSD_xv2a9*W-|e}G%fO$*ZNq06GM1^ua?wgbi(`WR3H&S@vvni zS|@0<$7}+gB!UzG%2;%>MmAkLneb>ClE3_!* z-#2I|eXkL=v$~h8INOr!n=KYVXuB;bg-dqGtdR?xsWc-1Aa~XO}_6HGbUX`MaA{GrPT-+;Nbpv8(;YnW8v&86E(E5S)SPs zTfkhy_z|U?<_jIY2vr9AWba4e#O&5k7EKyFnHHlz29X>|$5f>$teg`-8g6*!0%$JYr2c|sfR>+Hl zBP|6Dk~q(QAWh0Z%4%u6MkF}_7}2tV|)C)8(&=M>_Znr zo!)#;r+2Xw@BCo>idvnnI$L)1tB>dOwUn=_rcX89^y^x-B5FB^FB;6ug#6wQU`X5u z)9Gw0TZg|1AGB%Ox`}8v-`cH)XNFWICuF$5{`xPIt-MS-t&p&8JgNc?HTl=*-)4|} zd&9(<8Ky8270%8feRL=_tdUQXyni%YCR|qdJT@1YTO*G+w-BglK?iK(}@u zL3FLzBG8;z)4j=a%sAnUu+gcGwH@Z<1iHIlnDO>X$-t~QKK~|AvsW7D_1%*`MZp!I z!0@nt1*F20!KZR{2RY1qX%uR^|HkuT%e!tQSr6aQI!?$?#V7U zpg{F~@5$6Ehr{4#%AY9gblx2rVsz!;;#*cD$@wAy5TpUNw3OW!yP+PZ5@Nxj#&&Wi zyQ^sxO0-$CQavRYpQHJ6R6Nj zKE2c2?9EqfiG}SD1kKK?0plnbe&y3)#a#3S@CN5q23>B7%+) zD1xzzP1LI+!9iX-s6wlnv*S5E7NwUUJ0cidDS?jSofGI{@Cf_&SE2e!#RJ{2Fl5Lz zUvq)AF4=`-Ai!YFObuIo7SFlwI9q$H+1WKAY9U-kA)ymd;0^X!p}0FSnz}-VWmbXm zy@McaI77(e084AOX3J3#Y5>&0wAh})aNKGw6sg`To%>gYM&hV};u7rjzf8j8?2U8* zNs6#Yi=SAH+^|LA6POGllia@wk3@xbV?yyy2gHDd3PaRy?op3vw#UP7l|Ux@swTY^ z4};32w-o(H6c zG{pSf?ANVhP{DO7RmI{^@|fYNPf+6SFdy-zAknMM*Baox7yZ|2_}e*M{R2I?I**WU zBbvkHVab7#6=)l4EWiWAv$%bSWl<{4j;)kQ5D4Xip~wTZ-Na3_ohY%9dK|%Up4SJK zmvBD=kg+-iKvBYfuWQCm?Hh76V?tgbG3E59vR@EEft=%dN8gbUnGBK&?Dw1=*CGv2 z0SG8_2eY9(?VnE++D}qT`semq@`%vAA$KS)K}%W;UY? z+pPY|J5jlLcvo9#G39~yyuo#);}6fpjYNVLs{IinFEZC@9RKVs9ORgT3OI%hmkejNI^4J)*5p2O&IrnuiP|6evoH;Jt-;o9TKpWJvO0go-1ok)k-`vIrv>_EYs|hFH_q`;h~g zfvwap#JXKPL_;fp{t~mVL*k3aj12xlWxgqNn=9Q$a)$GA^cwy@*p#5KIzQ;`9q$*uQ)D=bI zs*MH|XdR}2u&U`s0*~P&10m2Wf(LYvbeH4pZa$jv6laMG9Jw3p)D<@Wpy^R*EQ7;@ zhih{a&i$#6&-Q%iJ`XnR_t2T7$cqtbVGf#Wax!D1Hc}aEq|(1KM+67jf7$0s1_dI4 zgMhAJiKnVT2cm{gca^)D9zkVx*c0`>)dSq)FXAhi_85QiewPv&Fy;)DJH^&wRLqA{ zRsPtEZx9+&3=Z9TgS~MJ{W}!#Cau3(W<=q8at^H^$e84A!?70ya&Flby%kRbb&1dH zD(P|T0qTc94atdVmSoNWX%-FR-iQ^{LR+EF_ezfQ$~{1z$3~-S5rxRH9ZXiX1E>c} z8fQ7?ECKaaLrGYM6AsQK-QdqMFuI7U4XBL!9Aun9Vfb2s24-NmhNX^`et;e@c=5TC)Fhvsqpjv9ab*RNd`sK}uT8{iR+Pw*>c8xSHR zO6Hy9zk6+Fu2aW=)3b#snB&!7E@guB>OBhzYzeKA+8v-=&0r6G8ncZ8?IPqBbwcpd zm`F1Gs{|axdvizW#AnbLq`fu(YhiVLQr{z`yF@IzZ$N1Pfhp@9r{+y-V6B7Rm#!X5 z2_5T~JtcTt5BQaORUkwS`@l8&SSu%Jfj?mL6-o&fiE;7=Dgf~8(Mn|bjx4!lxAWmk zJbO!FII zb$oB@_MH8Ucd?BX8*dD4zf0lqy1_OVDga+<(Y_7YA0b*jQt&DZO%uN z_W;>r^w26j`{NhOmv%7tKxTfH6~Xk?R@AX>s!+{**;*}xv?hOd_c*V=RhuH$0Xfm- zvlQ7puF{2I@4UyyZVgb9Fle3O2qV@)J`G3~+GxA2<=w3kdENvu5HNvFkHlof&9QPJ z8r~qTr0i74au*rNDTjz!ZjVv6$$u^b@3UTyh*%p$U<_Ko)0eihf1a^=e0YH#L@w;l z77?ts9FfLw07+GIU~1m~;slJeuh{q%6ruQRiT4%YPP4LX9pSb8ie{G0HS588TcgBWW05 zgpl%<%ZOK61{)7mW~)4b8ZE+*QM=$r?AC~hIx%oWTSb6{(3xRm{ys`%E6ev*krf^C z_RD93D%lGKS*+Jui2Je8oI!W(Qp`7iaY2d^55Dx+(g3Zn4`KEwNYE}pM4c>xMQ1dQ ztXz1iRuKXtk^@26TeF~MYW$-o5V)&r9Gvbg^g`d2Kv+gU_P-Ombp&@3qNVSd|B431 z|6Y*@hF~(9)H989ybYo)H)BAVAW2+~`IQ%RRq(}@<$RIM6mIH$pl`fnG8e2N{q8WD z&ZtCUv&UBNLWPJdnMsc^@i{ZtV7Su;Dk~f|{FpUEenjsL#vjm=jL8S{< z=2IXiA?yE)XvkL0PLD>){B|o|%fru`Zj-rpvMm3TyLCccLlj7e_f7Q?PW1=`>~U6+ z-?G;1E&|LPJ_Os{GNUFd1Fh*k2PDTjYJJ^EY{{>NUh)5Ye%e$H!LGDlLd~<(=uZ&7 zDQ*1Ce$j>`on1vV!Id2(xYO1h8wKi&(FJt>8uxXb)$Yi5PDK9cyY=qMDK-`fi19VC zMrL!I@nK}}z*OH)v~^Kh8-U=+=I^9s8@MJfjdyzTJz06%RBZfxj408Cq0UgO*s!iT zShTg?o|P_9XReB?dh6t`X9fE-|G=z&2^jS*n=#wpD@k`R)uj*i;O#3P@-E`Hk8%HC zr2A~e%ut03&NQ-!T6qv{1J1#{Wn1*a3h`r{OmhN_oO#=i_U%it8GfcKqcL2`!rrNH z7QH`#`m>i187>~4BuH&c5ElI0raNbN&b|2IPC${=^{WYWOQa>m|1IF(e(}3%Xu3eY zPmlLGnGj^bNS;?+k@J~oVqjpReSz?>5#bSr!b-?=P#`3MAb~LXsk2_NU8R(9!3hUj z9Y=5RK)@o7)CInmZ+w3sIXlcuXL7jBTuoi4A=wy=k2R*EjBbkD+>PF?AG0v~30ps} z#6QRxUbbc?0MR7h_27T)#F^Xu?D%MHO`O$0sZ6ag)o2j$W)cs*M+NG`Z)!SapEi{7 zvOb7>BgV@K0lN=acCTH`$;``<=V?5lEjh=b`IEo`cJYEG7hF?}1H8A-c3aK_8@X;d zbPDAOO6~v~%pc1su_vn^{L{-GNdYr{)0HODNJ^h}j_YE!MpoOD0Kqk7OVN<<*h(ch z3O8t)?H>@Ggrub~mwD%s$?yQUCboSQO zSOwV#{1Mtp;AcNUI>+xO)!O!7a|blt`E&F3gCtTerY)}Qx*R?NiW#D>5kto$%eRMQ zi$zd8e%RMuG2zBzlhYW$T}d7S>W-1rjAkeL(DTIhho#}#H697{6-8fq)qw^k%U!y_?b7GmjwlC=*ZrFTAb>U5xok=5iYj%lbEY_1e+jCo^3q;&<7 zkv)Uo=@3Rk8fuF7cBTU8zdD~BT+sLJDxu(8plf84P*Ie#S!S*j`4?)S zF?&EnEUjlz4k)VUXy^J^vA{sUjwrp<)}=m&ic78@+ut-$dC1qUmO3svbWO|UEQ9d4 zB|{Jn9^z`Ji2KlWTnIR@uQ*ynH+g% z48l4H_XwH6g?fr7c^l>ZnmuvCL$1eoHkLN&R88zZ^7S?;@rO|;@9wg@^6D-J;K=I; z*lM!1wb{H>k$SdN-NM-i9jGDBXp1tAt_x@<_$S0_;?*5%@tw#cyEn?)2lShMk`uJN zUd3>?Y>|9c8~%io3!{j=hU7%p4pw@e%U>+I%|5(@ieY+#FH}qx#Fi!Yz!>Zc*ZVw*VcXdHF>_{$;Q-WUE2WNvkPOC`g05 zWl3ZT&dmP$Glsj`?S8wYf+Uq=Y$6#R1cI8=v0=qlNxV-~+Oa^z@|ESt;@D6%d&FB) znn`s$xaJi@#(R5j)xbTM*?bZA=k5XZ;rS|I4=Mh4ZgH%Fk{yOvsvG-H_lM*V&c9oZ zD?`<52ZpDb+z!@Z-pkVx&R9k76WW81l$l6l{P+26%~XNYG(jl`;aoA}BhmB)d5OKQ zs3r<2G$aUZX&%DoZq|u7e(0R9WgGB}l1a>}IY0G?=(yxZDdl7hPuN6QB2m;;YikKp z5OLeW<%Q8?8sXBsq;0)VxqIM~gn~$5cy8=IbF9bOrMOdFCq}A1hDuK$>nVFOnzL(U zOcHb1JT7@(_+2~BH?AY2+8BRE5hG5_P*;Q-kDp&&8irqzqyDW*pyzEFyR9Keq_M45 ze!I~1tB`Tnh}L(AMBTs`fAmU-0p=O(j-6U()L-ukpvMFsnop7-_%$3D?*FO2CTh)>&Au+q%b?n+(Ziqm%hPwnwy%V=k|&wxvk`U_tZI}Y> z+x1qxR2TjIY_ae+u;>&Ksf^f7rAQYQfB1M?qf=RLao57XnFivFkhG|%vY#p)H;5x~ zB<|f370ixu^6S!uqN0?Xe3uEfM%*3lOQQli2!AIu4Yu&=8)fYbLV+I9nKCgZwcetI zA~I+m1!Y3PUea`p)Vx767BIf=l-Df9PsB&mbAJ2$xV7~1?KXU2PhtyKMrjF--MN+{ zr{{Xq^a;i*qdx|a$G;m-=Ro}M^;wLT(OoVsQq1&SS-7MeFW>fd(PHMi_I58z=sZ%FIvaIh zT|vQwQ1Mv|#NHCS@W9OZt4lN zB?x&toM!P?*^lg!XnTH)>DgF6W9N}ls^sk<^^HJk0BPDSJI*`_OQN(KC6mQegRE_~ z2IAPpC@((GwZV6@4MuDkl^zgRQx<~+xasU3)7AD_<=_)1DQWK52PjS;^nWAW=@4Xo4| zVZRMK!QruGLDIg1vwp=S;tAwLQeCnU+_Q+h-WRwv%x@@@$e0;p!FkX|;hAx{&O;nH zzF$k>9YfjjW?@1+mS{Xd1aB5xIY=M*wbNvhvQpewMMM~u30<6ChDc&CkQMK5zFP>q z*$7gq^GlEi*&7^zq~Ot)a9(IdYoWtYS<*yO$Q{`?v$`oed+;z4b~+QK?yvZ8*|p_u znvOU;LX9v$V^uCZB^&TPrH*h8NFwEzq_lf=K>7!t` zh1LD(bDCOTXR)ePe;dmkQ>8!TfO*PR;c8{`T0(VsDFr3BFIcsp^ax~&(D653$h)K~Sh$&g;}=+Ez0J|_a|Dd{_K zlth*~ga5|dKL%O$MBk!lcbB?s+qT_h+wLwKyKG~ZZQC}xx@_CF&3)_lKj%igxDn^Z z`}E?CPb+4uj9hz1u3R}sjvO;rHAe}qJojkIV8EpI`o{dV=DN^$0N0hxWDMel^iM|`&#~7JCe@k|Hlu(*tX>jEaxwz={en%!P7$7cyZis z4^irP@_c{YOAtNzzFrDiR8IC{^D8##tTodg#8QruXPhuSi0n?B_U}8COOsZgFC;zR za16i$l{b2t(g=2H!h`Vyc*>eg{HwdSK@sz#&S-3u!Ky+pB|Pc1@!``O*9)ET9ktfK zQcqAkV9U_xuRT@d@Kf7NnB@9FX-p-chb{PFvZ{gbZ(v8}cNj2yYV!ALn2RdH z@Q&m;i{WC0uN)P-lg7z|yeq%S6$W2)TG2zqCnxo2;b=3G9=Tl^@GEnad} zVY;{{pL6;*Z8F%pw?5s{kGpZf(6Uy(Z=`-WUvLdip4xqE#r1eQLhL?d*n4^H(^5UY zB>__sIbs5x!1#VF4S^iab+&f8edf4zmgj>fbFvL;_9q}+&4M&VMD}uq1O+uEF>XQ; z0N27hz5im5zANsT}LJ<4A$o0rjGoXB&F>tz2apla<_JvIGJEf;=;V*}O zwTepz_Wub<{I5`OGo9Rjj}zAH^!V7C-@^NKykh!4P+`z(n*Rs12n@RaTCjy5!f0*u38e#tZ@+^~Bq<~oYfSID6WrJc zr93_6m)5=gTMKY@U7Ni2I@aYuwJwI@kEnYPKmNfnCp-^MClS zTu#RO6gqpSB=Cq%`a2afeqGtG`ZhmJWo&*z6Lapty|v(zJQzIrw`RdYhc0&u?u5K` z_Qz|i%@l3fZ@%rpJ#j?MZqU53SP9~cUu$d`tq$&ITs~TDJwe1colb106gP~O(Vww@ zj+poE3Pz^4W)IZe7*p69->iCWx8g}?)tOULW0z=tu9;3^qJ9Htz!fwaNYOOmjfJfD zv;$mGc{{|H`Z?LsA*Vp{gFOt>A3Dgh8eOvZj9~tO$@UAzc+hmdC6rClZiWsw#QB>d zkvegTL0xMrFCHe5;Q@dLv%=ZZizS!O6xBuFXC!B7kKJ7i$(QCS)~DeIi`#m{kKr(m zgP-<}y$!~CuReG(Uv?6)m04cwt6Lq$u5)cH;`Es;Cq+5^7aeW zoo#HN?H-tndzX3eA|IhM!B1xY_MJ=#pi7=|>wP~=BSX^pSlxfH2u7WP5t8M$>P_Lh z;0+Xm-pqFGxx%M(OC2=YS|9Xyp3;T#WrX_b8_c{kcw)wOb`*RMDrgXzBb>ow9>S&GJ5(>V=gHf9sL4i6j!`L%K%=ZeNJuF607zai&hzEjgbS;Ut)x707U2B$P$R|}UtwfR5O zc&1#gg`**iA<}0s>JF?r{k)yge9y05+<=#IB47+QE#e|Ixd29iCLb7irzK`u>znlI zjV^cBy`Foiki|`1YCnB#B^&N@S*3ylSDd(RQe#m;k>ef>3i2_rX`m2Ycie0tNb_a; zfIzt>sF!!X%R5B=(maFO^Wg+$^i zTItvhsYnb1>J9s#_w>rmJh@flH7oRiU%l-aMGGm=`T7g~B&Jv2Zk(Bc1C+X__Z||- zg*CJdR}!94$S+|6iVD1ZH=&!jdvm;01uS=eU?Zt1x64N*O=;_pZPy9juD070bRwC= z$1BjKR4nv#N{57I6y7(Skv%EIi;C8p2pQPjcskvv`8wdY;T{asi$h<6Dvb9D>j|+a zoyW6hO~lJf^QC89F9tSr6*dLk#A=RAdP#*0X+YuDO~7Tun3Pvj1q(rT;w=I-An5h` z&6j(7OboZ^egNI69lFsyY(4Rtbl1|Dqe&DB%Q0db)#NahzFmv(Oz&Yp2_wWYUh!fzj1;A7&+JKQY4cU6Hqld>!VF7J552I03KiW+h)`0wsRD z^Y^1H8(NewsWWOitqW zVe(#-0wuV8g#IdKnfd4s4OT&gDd>+I^}=u=+)ZR`+4q~~^>*lRIX{1+M3^cpQ6qNT zKr6oLv{+md{8Rb@Syz(4#nXlB!=pG}^|EWvG9pnjv!D>FyD2=r>gcYM{&xRI-;#&& zsnTqvUNgBzi;%SqPrEH-4#MnQ_UZ1RP84NtiK)K+dmW+CO-;w$AVXG?5|W-pwtkxY z=uB26P-`T_AiFqUsI}388@C=N`&h0fjgmXVE&K&cIzL6mTJIXFL@jgnMGcLS;GGya zA7m{5A&^)PNo@6zBDnLcZmbCFQM>DQk2MFe~MW&tagig_J z>NQ;UdfEGY8DW$TPi{C`Xm~dfsXfe?^Lw)1AC8ZD>OZZYs5_KrC1nL9PODoiayvXZ zEUfvG;h}cJBGx8a_&;EcQx{NQ#sMg(@mwrTr~*91MhC*`CK#=nH-~xL&}1dX@y@rf zt5^{=8gVugz{I{o2DS256_Z5}I&#@s6d_2&rlz7(3SfZ=; zJNH;o9Zl3(8{j$=dK@^`Pwc{w$v<8OCj_V;p|>tooajGP{-Je`l_dSVjjb9*U`Kyo z{aM8uk0Oae7*LgLwRHRg8bOsSB~~l7tw$vezGiBKZLv5`t(1nyf5(*JRya9d-|cvXwsZ;)x6&%qh&9 zFr&rbZ?h+u4g*Yh5p@h7N)!bCclx&(YGK630_)Yx0ESZ^9(90Noy{Mo3uV;{wtx{_ z~VSJUWa(2Uqdm^H7z?v5O9Jzp>1Q)J!QQ@xyNo-|L?TpF8`RH#BRreuGYgsH5Kz#E2H6E;_ zJzZU+pBlU|$SyHy#U%Ki7nD*xSvzo~h|FNDN5$3yWbPzr5^>5kjZO5zX0S26Si}=O zQV9JMSh`>RjYpS%eR|6|qZ1m&FWQgiA#65qSw&Kwu@i_(hXE%)FJqvpTuICzbDM3b`L7U^||lr_|&{XFY5Ae}Q+d?&jMAgDMF95C+f zSpV?q9Ehf7`nmOwFIONwuLp16*bov^8R7bDxc=O$16FTyD{yWDJa2maP6Od!!i+i? zR9ET<^WMYCa!Ju5&|Ag&hl83Zx7^)SMf0ONW1V$r_u=3y?A47g$D21t4pz|g*iNwS zF|^8SYtUch+dxt|e@?!4uk3y}aP+{oz{-#%p`}n~U}reNh=tlOx15Fxfz@L8tCEy8 zY2yWL=VA-X;Y1G8{ah4Rt5&r>M8Zl?Jfn!MOh^{}9>Ku?cj$D=#o#h#hcXXkNJ~!k zs6g&@1lqVMDh!cjceTCnQE=X2d;)E*U$r7-HPX5j4(>Y+)8`&zTALI8oW9ObCxnq^ z*Co4UYIq!?U(~vAhgI;`W>^v$`IUfJ*W}9oH(VJQ#?$UTs`#P7;N~$T{{F+A zI8?t}mfMQSf0P>~zTW>`Jg+!5mF_vQ#ZY~{7Sf#rcTY;0m`#vKPhOft1e$Ewl8lH8 zsf!dCWQ;C-kQKXx&1MLHD^h|;whSYK5)ZT79k}0*miYJg59imfx0#*)Xs3`5U8fo! zX|gIyLN)*lZby~oD!NXZ-?E)X^3k$bK~R!|hI*`|?m7qz4tc&D+s{yelDP%XdvM&a zua2wO=~}2R$7JU{YQJ4APn;V}5@96e-|@{qtifpfv1QI|qwU-sKFu9Q&DsO5k)6G^ zuwD5*Ax73h1x61}TD^D0v8quftXp*~?n(ReLipi>=bZ$uY2xtdG(pB)2k z$BC05Cp8WUQ`y}mH1q*Q|J8*J*f=^}N$H`EmpQM;H6Qs(k7#Mgoqv-MbllpqcB@S| zO*B}F^Qstf>63p-78fw}vM0x&81aV>xLgP)?|!*t;18{k;&qVyu9V->2)VJZ(Qm9e z_OZ&MX`xYNH2cP$G@xSYun*Y$<7o%BeIdmhQVT&|By z;*VjgO$8~WFfMaFL67QrtMcf+%b*}z8jV=(X`XDxQND?;2Z*Tob$(fQR0=%EtSmQL z(`$%F;}5CV?zX}@ZrB?QU(dXtGjK)dX@?KvQ0$ECkc&$of}oU&`pP0m zB>CXnQ4O;v1d}@3c41N80BR1@OvH!zD&S5i^CsvVcoI*Z!JL4snuG) z`tW}3-ty4waM15c%00w2Sc9TuyR(5W`n>s2bY*fmdD-{~SMBy0T}eR-UXIFGgKh%Sn8k+hk&0rz7P6Dm^43iF zg2HyYSU#qc+GQ~^v%4jh)4r2>Cex%!Z5{;*{v~DMsLR>y5APRP*>k}Do%*g#bmHZn zZ`^^e7p=m=9kSy+YdsCEf%zc|w)!AhH+*)|)u$$dV9%DCbcT1)#lF$*aLrLnSHJ)k zAg7a=SKQDCi@Yiz66N)pPinG8^Rbz;sJNm-75h4vPW!XM>(iXv!LfqW$n{XSYiZY* ztBRA-o}rdTJb+XtpVv29cZtdJ$tT9Z*DIci-w*d;OM5gv26DPF67z9<3`?YZ=A>w) zGIJ&cg~xumlUijYJl!d%%Tqpf&)`euBYO~vS@GwWgndj|r50Cmw_N^DCX<9@7wCef z9}lGbtrIaN5#pHQAnFG9E*&}Hq&aJS#x|eD{WM-)yoDIqYx+jX?$9w8x}C zdxvKfEW`ZW2G&%LeEcLZ02fL}Wa|5i69F@=7V=)#OJaLH7W)7;)*DMrFES zhyeW9_Jt&+05@&}d;ICdsuE)*k_v4#-%@ht$6hF(ZVNa;v}1n>t>%Wav4_ikLEF__ zixBu>B7SAK)=2hUwy3I=?AWO~rDw$diMHl#mJ)eLNo6--k{f##HvK`}Cg6s{xU~}+ zGtiQhzn0F*^+yM*lx0^(z`GH-s0+UJ1!A|{ZT376o$ke)h<*$z*O)BUt=G@M4IQV& zN;s{@p(18XMnBgf!WItXhK+gFGq|gF_M9uX-Sh%R<{M3Hm&$VYZsGFrOaaEzoUa!8 z+1Vs2(SZosPC264_l+o|yuHz)!&1rELw&vdb%gocx2IGL;)yQS&|l`)X7QPEy?55? z51T~19xf>iOG9d|?54hO6iGn#^Zx*Zue$*4;z*$-ZMN z;)pryee+~7)ghaj$Ql|he-SZ|A8yT{B3TkA1vP4TT`EJSbmr8=cexq=`7yU@mC^CV z48MDuztGvnbmX=8eqye-jk$Gy+GC)%cMkuWpXMI-ZU1Kgdbsh$ds}pEt=V###8_ls ze3`pDOX^(NPB!)a>@w#lyCK}qA*3UVcou=;cFVgCv5=f#aA^V#W|96sd2mq7|J+`9 z{QHk(U!o|K%B7MC%)olEmKIIJ=OmB$Z|hrV%JZD}jfH2k+?B#XUnH9)E%+})8B*U* z7(SdXJhc=2$BoMuyp(z>c4EHkyK4PC zlYLJFMVb2)5%8irX7t!+ZksG3@ARWr&!JZ_I@~WdXr2W9`l9u23j~{;Q)DV!)^K2aQ9swNaf%Yw} z+o(z@*>-f>r79~M=hlR3&;|Lw-M7~|^K#aU;1FgDj=fG=sGyK$jW%;t`lN%PJPeuB z?H?j?T~aWgeKbtJ4;>LX3~+fY(FeB-M0#o(ZEiY!$dyx?F_-#i1$5~$;pkmcD@8q$ znmTNUAY+d_XGdc|h|TP5zM0*|Tdi=RvPOsEitnBo4sPJc-3?KoWSn{pa;%*cMV>7s z9{=K$rQrNA*0f*MwOGMw=O`0b)g;=i zrjWJuPqcdBQfW3>Miz4{up8d+4A)jD&>*Q`zv(*E0 zMA3?l+D%UK)Bd|&7`jG^N2AT*#8Sg#gH0a-;EnxA@*FZ=4V_~EFgz1pijTVzM|)gZ zWv(*@zE+LtPJL+7F36hX#z&=8grn}sH^hS88ENlaxibiekURdfcbpzvxt<+3xhwYD zk5fx(2$*$)qQ?TZd?zC)?3A+1)(&4aXnRB=&gZo;EYK9pZRc$Ck(Xwjy^;{io2`by z@>H`Qv+TVLSN#n6N_tYV%mD%;&})n9XCHIV3x{62d^%abQRC1959|>9Oo_I??+grx z5j#2|B4>aYXaSG=o|Y-loiTv=>Nwkl$2&OR`WSYf9V805S54I#tCK>sk_Q+FNp++eI}WKg9E%0|QWmmf}v-jQ7u5 z_o08qiUGRrkAKuBRzF0ze6%gm;lDWr!D|oK_41&-$?Fq-xGo)mFewwlleT9FACWLI zhd$A3l-IW9=b+Met4j-QH;0jRNUYQ^hY*(c7Ev-XWpvLeX4UWo=m~QD55)b22XBlD z%X4GShvwCAmphNpr0Ph^3K`3FkL)V$Yqz+ZIe?^FF8?G-0JbY$>Zbl=6MxQw@O4$a zEO;FdN6IWRwfTbTJ)q2vqIV*)TwSC474P5;6$TOjrrf0E>2Z;oo1VVRY5TRNvq#o# zKM&Ju>IDRVL5--gmfnGw_a}Xw^G@=YT2u8Vb#%TB0;T}&MgV*XY&TJ>tKsY=*X}Mt z?OxwvDqiTz;e;KRVZ-$H27M-vmmg}V+3Z|-Y@032Ttt@w?;2(I;5aIW(+(o@og$6} zkUCRAf283+t=a39;%-k3?jW>o-wCHoiua{7iF0(oMi%P{)}n>$tE|y~q}-m=I)An} z286^r$)Oz`7qn6Ctz%CEBSUm+mmn*f^qG+5e!;OVJ*a)q#v#Mo93p2C-~7D%w_t7d zvXPZ$_d-ZV3}?u?O(l?j@YOlgfhxQ4co{B6xEj%V1}MJCa~>*q)O~&1i2ceuHnn~+ zVvYaZ`3$)Ts;(q9vDoncMK<>$GdSezBZsxvgCMTT(rk11+xCa&V{vXiWxKblr5jal zDsx5+=bMaY33IE^Pl9a!#IUf!&r(eQ_`WcPSaED?XI4~)b(k)Ni!nJ}cmP8!WkZ6h zedfMq9*`O)cM!GX^QQ}(=z~uP0kS)?!PTXIM1Ox3R8xhyGg|hYV!;F$Vl4= z3&qeM3V8SUvJ9J`X7AvoSM|Zp7t|1+c4P_t!{3UDe9Za!J@e|$+ep70iY%u}%n7w} zDXUXUb*o#m+rmi=a^+p`1jK~8M&PA8>G`RP-~Fgd5zvL&EJIGSZ~{X@25nUCGlF|z z30?6^N6yzWf?&cnLhye<=X^G<59=L@nqKC#xS%E<~wJJ3*A zB&BMsxv3i3{EJAm9uVhmiw!rr%=**G5psU(1@A1rxEyG72ehabaCzbnNcYR!EJv_D z{5r$uU3+AqF-IifyirhH8nzr~B( z7BP8rGKJI`4Y52%9bs{qb0MlznaV0)3OAJt9Xr?`myEo-a0uoen8wDT3TN>YP48`A zPi@ul$OVr%$mX;m;KJClpDNGTM|iYb@bg{Y%oc2K?`L}(|IA&jwYXcu!Ffu|4-Bru zs7imyO^Bew)%TxP{__m=a9ASyEjSkeadsU3+yyH672n*5UL;grjd}TE8J%$T(OPDw zPWWJdK3nwpO@*Z$rb!#l=n@dTow<|6|I;VYk~2-j z1z!kXe+QU8AQwpmzPXe{K>%Ypi+B%%m@g{I*sValj=k#ADP&`X^`|!pyZN5aFf8{f z0smS}md)$bWcB&X9`7yMHqJjNk!ngs22ibMO(ii=Zc7zEq5x(!ovWs^8lx}N8>|=- zPH#bw54GkZzVua19r*3X0U9Y#<6`Qc!ST8NqQN`!J#_ryvbn)>VII08qTo zps=kb;A0w%C-iNX5G|}lgUZ{t{ny1#&CE>sZ{BNc8|mjgyQCyf7C3_&(6iFlnoTg}>%ZNd3e5TZi>p_Td>$_+Eeu(V z2W~&?J<}D=SdN4%DS|2L6HCb-rJYH z4mIYM9{YBMZ`1YUD*E4Y|agP12yVyBOr#1Xzwp)1D;Cfa+!+V%ZY&yA85Bib)Q?$jLh zsr{nrChCJ^5ouu@jwi)@tCrnv9RFjdKleE-8A}}tWUAZ~hv>|eJc)9@Rq4|?D^fAT z^mJ|?V+e2UH&EQTCXsWhe>*S5QU4zWP$raK&3Wgj@13un`sdmi%Goq&7Fx%Z2S2CH z@)Ny+uq#aOluImwuo&YGt|`h-z6og8C$^k+Y}99mPjeK7diC8OT^4xx`A0}e=>ib@ z2V9ii9)(5r2=XQU{Y`CZo;!j^fePu!Up|zDm!9W(AQF?N0p71EF!HeAf2Ao4;sK9U zSM~-yCz?}y^P6&57)qi_7pFkRyDqs4T z>gyU93;;E-018q0xLiRG5-3(p?%W(pw~L6sza9K9tCX1i4P^AZ*8|A;Z_*9+RjXy< zcnLy%RQOyK9@k4vDq=Z{4m$qn>jBTLuvNtKb%rqMZGL+CxhA(r=6?xpl7+YE)NAy; zYtHh%u)~%f)Bc2pL#JM)?Hp6_KOw&V9cnbO`04~C+E~=kGKAi>0lk_T9P$P6I`dv( zkuMZzHvayvMV=BJsQilV6XX!v?#ph~LO|9fD)GvRxRC#1;BO2t{;=e@;sr|FQg>1xQJfnuyyD}Hmi-m+KHW4nQh<-zrC!7=TRF*G z?np4gcD?1V8BNQ9RGe7~1$dh|%mP2YUCFnBIO?BmjCtE1J;QHg_8e^2ME|#%W^~N) z0~EH0LM`E1cQjwLJJp52i;03z=k5Dr$>y8g+VI;3@7?tDQkv(nE#*2*NQYXpH>FC5 z;E0T!@5rqR=UR>4!F?s=@wCymDLL(_i%XQ6yzc`L5fOqjV_P|4mK!f#TUl&0yq+m^ zB$w;%2=uRkdclRZ&sL)!AWGK(Ch51NLgleK>u2BfCLR8XqpFYE<>Wa-g;N{B-__5bB}xrpk>MtuyLZdUGXO z&oVMA#$>;U7m_qZxH#vIdKv#TwVt(iy!s)+;Od)_wkKn6cv#UnTg98aywIuog1|}e zfw;3C+qy?Z$j+8W1rwsIP{%_XLY(J;mW7L7{AG!78BPg3cLwe5h0X0p<}Ig#i65TF zHdQ@#cpl*De$j`B&F;cLiRV|?;IR8GUG!zovVI#`FcNbHtubZ%zqUdjKbo$_+l)`keA<`uVrWeWS>|GQD-b8oXzSZ)IKsk!I zSnuuM7IzWBFX0?sp~TF~tep}9QQ=UhP)SJAPsICvL$;k$OrZ+~#_Nyj@gLDsLc8G( z_tiQub`jW5wS%2qC$AZ*3X_J4ANAm#ZNJ&tw^j0SE+ocx|H6~9#NY7a)5C=4_jNse zO;(Ea4iu(%h@6rAO9PP|?CFOwa%3C}FP%iqb28XVHPkcywyCnV;K^1aI#zc8BQrw1 zzqtHoC_8%rEBs;MHrc;t2OHmaSScSGt>N@CR7q**knA*2DO!GwHhE=Iud&$vMB?Cx zp$ipKQj}%K>R5X5`7?P120cwp6&}2pfC@W2VeA7!Y0aQ_3sx(+qrKyHIk=GJ?+sA$ zwoqY3sR)HASV_o*@lJCPhhR@yo`RgK*Cnbp)p#etoj%Gc(v>5=inPI0<5+KwIwUao zTai_PeEMhbTrXWdVK;M}sSI#CSFGs-6H?DuKLc56_M9IKk=2Hcs!-+^6o^X| zpW(u!L;K1o3xLtl#ny%YJEe@0uU~2Y1J%aGh1cP4tVZsvLKlh`+h9b>3xLr3O}o0t z@*%Zfl$vt#Ij*{hKSrKw$UX`sWLO-KQWpk@$jWSRaGDTSw-p>;k-dhy7SD0WT*hXc zIjFk=YJ6v?vv9)I=H~{cf}I?%(;Mfk{>yA>pJ@ceyd14l3m<+ay(4$Ts2t(7LcQ(* zPSDm4eg787t=;rq^40ua`w+voV&)Uw)K>B@mO4&PrcveRp~dADb6lYO zv$oWGu#nv9-RM0#o&Xd>5_q7W&5Kl2L;fDE|N26c8N5KhMgvR`tK z{DLv%e;t3v8cTJD>vt|~b^-757?EcpIWbR1@CwU_b3!&g3d54DyJtBQ z#WPPchh;UI?!x4yPDrCGQSaBLen*Ma2k(D%w2Bx znc&>8S#WGtu6A2U(hk9q80sJUwN{(PKH5zgD%b%XF}RQSc)IU;wmWT@G3oK5<*D|@ znG^@R@F6yWe_!EGo;hsfqG&mc%A_g=Hw$ewr@FH1Upe=5Yp4JJB0pa8fMeexdQ|13 zHcMvBFUKAUJLr1COprpbqVS$fj`&^uLUXp4ASub)Te!&SCX^#EE+coepZ!3mgE4l? zd1geBB0{@l-=2$Uf7M^O;m|*T|9dF3ikbWWMSX(lnd8!|;1!idX?^^U(C{#iZ5Bm^ zE2lHwY^=iin2;Da7lccaOH7e>lp%enP<-;>;>baS}V1|*}%Htqcz ze|*5g>!bItEWksp)7@PD#|U+ran^glBKFH;LCxQ=gCTC0ZLA?5&v=%0>qoB-b}PWw zcp~|4Jn{Fqk!%r+Lrf)mHPU`L+o?9klmQ#S=wIuf91Ie_TX%dp_5(AkXf;!)i7=OI zO?lh2biy`lz(hFCEA=!X>}Nd%cF_E%Z3~sl`q%JU3j3^MlCtuo zv__OhFl_s~Ii5F?%?MMuq@7z_C>2YfW!|Z4s`5*JkZE(tQ?{b;&#a#$V(CsNL}BPi z=%T8M=i3IVs`DC(-`8MCN^_~gYQmI%xkSh(I@?bCQ! z(SPW;<^xj#&YlhmFZG3QEhz>3zo$kl){;4Mj-_1uQh7I@Y2)rLS|?o0hm8VL)#V+W zYxYuGg~JoM?XB3Ds0doL`xOA)pCl!o9PKEA({l(N-i6)eNogoS-e^MDuFB+Zg-NSn z@=5NFH@{uX_xP7yb9zLpA>2mn#Ckmu7!B-?<}cl=@H6Z)eY?9qxi22Mw?hlAF~F)r z-?eyFrV0K5I3+VFz8VHap`T@i?I*l?!Jmf*;4DVeusTgY)^*Gm5*_6dQaHcJ>!wPz zdj906MSFUtAT+=Oq$bfm?fw%z;C-Ft(}a*vdtG0`g8f%!Ft_ZKCRkMD1$HV{mU|TI zFh7Sqik|->X=JRLZx2A3^sA zW6PZYX4+eD$AxGoNhW`vAcz`gV&>t{?NWehsSlzGf;o|UCLOy143#=>v$A#;?aM}0 z)uzeDWuS4^=+3WIN+(D863|5qONDX2GF}VM7R(^Qu1wK+T{~bfm*>?TF&1Stnjs2* zJgp_38+1d;J{8kk5CU*|{)sV#C3l%la&4oqr2eTGZk2%o$xKThQg_ukmcewn$1ic41_B|4d(2@0$9HsGdtqZbCIM5cYX=0I4T}`s*g&rH1kt z%XhL?y-v9yyd$nHT3tD}T;EI9p?YJVk5oT73(ZO@l=?V5I`@4iytV7qAk4Z1YEaCh7j5(_t_$V!6%=(tB6-Sc`gGdPI0M-ZNO!l0CONB>;`ibTrWh zEjJ;JFAa3D@K@JA<1D1zK^b*NX(tuU-bQ~C#x-LpONH8GK%jU%Rf@l)2^8uW;Ih(}}L6Al=r zj@(Vw8T}({G&DY?m02Y6sb1{W1V;(8>3piP;RSSQFD2*(f6Y*wUT$%4yur}i0M6Nr ziwy`)6QbK+tPdx9eS)Z?D~2RDtYAR`@O5-FnbQ^n_NQg+eR?*1dsvux{ZSW%Aw=E0uT1l!73a|Ztp#Xf zTVX8*YTEdt=(H7+sl{Lrsv*nPvDgcB>$G7W6?!c!F#L{}Rw$8<3p4K+k~E?XDDv-Y z=p!d7A$tg3-BmkHPc{ z?a#S%f5|zxiG*;Pt!b+)CBmeH=%i|fAydNkCsO)?Z&PF{t_BK6%?`6PrJ{ljE#RS{;XNBVJaUs5OWh;0^t$xP zXFn5v8$?hMg%>n;#(JE_U#OmAlI*^#>6cn!)JhFaHHcx#xp+_OcA|q1(0o^NK*2_$ z1Up1;UjntH6c!h0cJot-8}@+}K3=o$(q+;jhE^OM6UV=qVAchuqGZQ4k|0wb;2}O=-QcQ84!0Em#%6-ukCx?dVwR^z2k)4$(7m z2JaOisDh7zhfn%Pz*Om1WlJ}02j8_#oUoQaV|?l_rlf=+6&O)KPs*G0`@F7aP^Bxn zfmZFkRGGQ3A|8rbM_QxpoFvUlS-@^AZx3zkZ1#{L-^+%~Q2>YZ8lzz6N4nSh#Z*0$ zN#6M9E__={a!#rdVJyf5Jw>_p5WVc|fVAn=o2ntfH}S^XDy-#+o&}KQN!YH``qwr^ zXr=EPc@VE)>fqQ$e3%njY+82US90qyAXFM2^{TguT9#hAUWD63mn-g6 zV)ynpB62o(Zqs2N$ez$;#)|8*zpK+k4mLQk{ea=p0;qwr!|CRTX)Ab}sf-t_UiYF? zl5%ptw8HRq7px_jj|<}=L(kjH#ECoj>TfE6(I62j{(7Vi zj_v1w`!qx-(0MEPR{Z?w)$vT5eWo7+*bFu(35#x4b@1hLd*;v$n`;Q)zUL#2JtJ=~H(MjwzE^ zbBT;M?sIdlXU5;%qs}L9U+`0#mgw!ZFCk2RIANPkay^kdyF_K(d}|Z_1HXH0H6$S3 zsE5&beOtfLY9X07C-ZOhXw2P1z>O0OO?7S6WW;!;Kq{a@-2UjI%gtGiPoyWK_pXU? zy~x7e0WGe9Hg8btMgumh>xz@oVOY8FQ^#8SlWytunHVe(7rh{=ov%7%qq+i}cj=VV ze9a6dR2mnjocKPyHcSIYZwEI`4A!lEXK$Rrxgstt$bT-4y%lH4d(F3N>CR&bWVfBp zCkV+&x1?r9T*A8CWP@9D`Ks#3rF^KbtPq^JfBk4Zd0DeqozXwv07mAOh3CiXZL^e1ql%)%-;+7}V6%OJC<(zc9tTT56?G zmK9t_|J7tWC#=r-@s`V|g|;_L3+q3$4jj|{*A{Nw&(P9&)A3L!rceb46NN(qPiuc}3xDfcG3;#9b{DT;iiV+S#s5hB-+~r&1Bw4j!aji1j`;?hTJ>OM*b@5q? zpUgqu2i|1V?B@aMEH15^2?To|S9)r@6X)T5qt)?Cgu51^7g zQ`5Y>q%@9kmC8mufixwN(Az^yQgbs$*N=txH^yI%d3w_6J!c3)bL%GUwD@v!4Afxx zy$`_bjwHgZQ@K8mr|XyI0N8FuZO-sZ{!J5&EX)_n#S}gRPh7jLnLv;=-HGx(6)WM% z-&{hQb$%B}R)J%n#aAJAxARb$NpfG(y_NXZ=7^aVZ6!1a$2Lk$FMt48z8qCKXBGvf z8Hh%kD-0_ESSo>`_)~Hae3e@j%~32{SN(4u;imC($JOoZ@YQm~_xOqMx)1Yoq=1x# zXghN}cI~dg+W?mR_KY~i;Zf!;b0yBW*6UxLRTy}^H|riCU(I;;$^7W-f$$iDBDsg3 zUgrouXy;3o#sq86gav6KFnhXG!6Nd1+kv!hW))`mUL{f$=ZRj&8Nh?iUl`{O7I6|0 z@A_=(cF}eHJvOp;A|Bd~*t~EgFrs%aUk`rPu3ZBy{+-c+bfvtvR0(V~(BPllG9FuND59a~beJh;qK%LAz7(`xExHBZad`bhZM(>;E7YeOaiZoz z95+(UF(nIeH)`@gRWBm1p{JjW)2%&&(!W&8f$>MM7C=_DyQ3nk;!4Py5aFeFOS+Ux zkPL$+{W})Ez#BAk4rArDhzz?$WvBq-C9WzU&meS*UPk+Z*s=WDp`RTpo=D@*EFI;xFYStNpvK zcSpwC3iI4d9U`=7=D)e9H|{feGoQ&O#9Cwrnj7FY`-MBbn4giGraJAhVm3vHUyjDO zHR_<24}tHRG;O1+MvIdwJM2zs{F;(Hyny1JC1MW$7K&b>Kn0C2_`6{(N9*W%N#U-a z6T<0bpB7SsUl1~J=pAvej^R-0^KE3$$zm<3H|I0OU#a5d_qnh<*lIO(C+{Ab&DMLs z(q&iH+LdQujlP}SB+1&erY#KimJisLRiwa zN6m=1h8AGs0Kk)wCWE{{K!mJBylX=<$%HZg;>cYH4BH5iJfi5zHXYa zj08)I=IY79n6VxJ!;BT;7`}f;(Gn0s+3OpSQTtlIvFmG-$|F-}E*X%hiZZ`QIURic zx=Io$g^2{=8S=9u|M=fuw-NtIDwoXc(LzJJvHG$Wa&DW7EGn5w6gZG!*-q;sqv8|w z!gD@&m|&Pe@FM5Wm;G9%p8n*@pq_d&b$4Gl8Ea74*WyhxBuLBwh>EUJUU4>Im>I!U z5dnd~c+IX1uhtDch{;h6Z;~Qq!+bJ|#YCv?Nwkkh0;>GgA7p&v8g$YQgDtNG91${; zGw5Qn(Z8VKZ_quL!ERMPwLnVNy~=sg5YWxk0fs57eg7A8ZynXv!>$Xqw3Olwr4%T^ z-Q9}2ySuwP6nA%bx8m-u!QEYhyG{E0&Ue>2v(CMDX3fl6lYg_4?Cc~v?<4Q?D2sLc zdw?u3yy9q9$t>5Sdc!IALcsvhFe@T+PQ)Mh05xW*4_*>O1wHuqh$ctz;Ww7>r5ZZ` z+ZwOA3JjRWiFJ{P#Eu!} z8pji*2Ff2oT(yYf%PhUZQ)~@pkQ^DpDm5ms)Lr$CWF^93i>WQK7MetVz&fjD^iPSQ zrP?%o_T=qnS~8*tMeO^yn5P#!)h4l|6I0A$xyx!caD!s^1h56E`1pr5ZI~blFMT1y zReSv|8E+kSYfRo?&Eosa2l6yV1kZbNyvo)VIu!f0B+)hR&u zBaGbueoyD+o{daOmQbkLDMM048A8@?BX2mJwa$aeH!#XWns;RKtMfDc*7`x$b6O;3 zkM56V?ii}V^lY{c$kIx4kGFox$&M<68n<-&xI^121MEVLFu#V?d)@OoI(Ls+n?a-b zxU6F_@aL0@mDxC%t3``>nHG4Ks>CK_e8HZk)t? zz`3)pE>yEWBwHhmW4wjBr(#dmp=UWb=pGsCx{a1Hb51-Ix27KI789QSJCXNE_G=Uz zhcQH>*MT2(tNz_u^pu!-?Ys=c>A7@8(OvbUG%G8^{Frj0hg#Ug5*=`@I$ zynZ1}{-u#(U~t6Bl7DHQnZ1}c)#?mzQs7g+%Mph}ZE~u%Q{2~%h2n*`8qr5w^@Yqx zXDVA%ik}#eOgT&zIbHN)?|>m?wrJpKeLa$lJK7+H(e9+xqv)HtC{Tcb+?^F2k>H7b z$EKL)KprN!ef++N4#`xGscn3ieWveRA__mj%Oi1omC-~SXLFC_rbKE5FTvfxx=Tx; z4C)UE8F9WTaQy=lS$fl4MTg-p-&t6FMDHyo{`h4!OpX_bzhm;Yhi+Fw>NRVwg2RxF zH@c};=3vx{v-HPz&K07Ps%>QvQBd~6nk_Qp`{CgIp99vU{gr~D4o*DBYWr8CtIw2< zty6h5I5O2sRG8Kxzyo^E0gJ|@4k+zvT^8-is^mW_RZ@V$?WVa$C7F@8^+i38kA_im z2@DuBQ$Y9M@smytrl&d+Z3$zKQFtY;UUfK3@p-+%e_RGk>=w{`tle80u7cz=R^n-c zRZZ!_Jr6wJI6R?YxxGSntq4-sqggPUS6j3b>Zs?6=xzx%(3x^Pm~{OluCPN{0|^FhXrr!_-eWy}@8%nMc>rgQPQg^xgq?C?LIhcQ+&_qRuq-*jux+>`TAk>S>|1&C zbp+3%tz2mYl@YRHz#x+8gx1xNBL^o=Yp&&a-H{{Ti(EvrtUz~p5lF)M5LDbP69)LP)# z-F+Hgbnl`u?qQGcp&lgK8rB9$$R<1#aWn>tidn6{0Qc0FGFdB^oDdrjPjnAcJ!|$$ zlLnGZWh|a-h4dE*gDd^}N|{eH1j_=vBSSGQGA??g=*NZqy>gpI*ELmt`QN#k9z5po zQfQ}&<|x)7xf7DI$u`yYPeCs(#qo#j4N*Amp-BBf#E6|;zuiIGpndfBy7KHNsO>7> zU2DVM$ZdKJDNL7zTq$%05qx3k!O80sWh^#3LIQ2v5kEwpiHy0`@}m-2!nw#U|A9Me z9^HwY*!?2Xp!6P6tLB0q#Eed3FX{cN?BFLGQ69C)-PA1No*PdxDGEE@63+(rghqH` zvtU~L%w@2yec@Jo`SdFLabY6DVi;=DhP}$-Mz>NcNR1itM#ApJ%J?EUCj19mta7Gj zaL||A!pth{jk{lg#@uE-77(oCZ(LZ1$)d$+{#h^+bMg;1!-kYu8YRH^z~hiA4Yz7s z{mOv~c!*)O*s>c|wAw0xK0$Gr3mkf;qTQ35km>az)?X(kw=q9vHEQ-E()uBMzZ13> z8e>9b?!J6zBz7NQL@uL}(W6+1&p)2p&Lj6FQ~E+Z=1LS0k7#vOE`_UOt!5VVBU$g%F2`#{6O>t6=+CP~0I}6Ae;!4Bc?E4K+6` z*!+OR&OMm?H)+F%knj*B?=m~)t_qxJ>6OP&U%>wF&!&qt6?LUJ_{4jsLJ-4gG@o`P z`ajD5w**?)r%c{$OWD5lx7zLBwb_{@814A6dM99(rb1dwUtU{G3C3ySG15TasS*7omjZm+Ht1^Wp?AbYwtc&c zovlL~ZG`F^9%!_Qx8VMoh>!(Buh?X9ZTGRhG%n@$&C@3w8>9>! z{Ah*fv9ISucGk#w9RbyGCH#A3UW+&bZ;m^N{!@JcWRqaN&NzkK!l?X!##$vf%J z^E{IExw^q_3ku$J)DVlaU?@>(Mcd1*M+(mwktw=v%;B@qkStmSm zOS3vkOe6&TjQt;>$LuUp+*;DDwZj$suZq>Oo#O5QMbv~=hrC3{*Uk@ zMZy^BN>u66BXiDa|M9K;PcPYK$cOg6Pna_L`kOqbs11MS% zftMY-?zDYO%3kp)VV#>xe_yO9F3k~zsSPHlP$Rx+-6Q3S3Fs&a7_m!@Q~Llt{zT^n z;?y!f^c;2~?_E~-K^sHHzaqypE1@OyrO30#hV^iX&4KB0FlB(ku zbkPAxEtdN;88PCa$e?gXe)f!uk@sSR41v=nROrxBKmShoLs`JY`h8j)s{xtZI~6mP zccQuLOSDgSMCg=|Ca!X?)xsRFZ{?izWCIWlA%U4uf&Y+67rBbDr3VM?|2C<$DgR$d zEe=ID0t0TPizJJR_I-`>+qU)FckCu&U{p8!sNV_gez23pz&5~=kG(isH`|(+kd9Dr_EP$9Eh!hX4xJrc}k%m<@Vl6POmpPyUGaezX;W&yi0KP zK#a`Tt`e^nlCaRy(l$YifGDpz_9~;1$O&(CUiK-5iMRA-R+lWeynN4Uy>;7L6VFPA z+kK{-s%`Gr>Fw|0IE~Rs!nx-*H$s2tKepc6iKpWsoYR&zxTl^wVYGAtH)Cz=SAznT zjFxGotEcTA41^#F^H{v&otT{$w5gg|X!l#-9(TD6lrUJhT#9VtYq~qpGPttVg^P4K zOt|#`RdcM}QB_={uNn9+3-6PCLz)hA7nDXhXL>gkN?KbhG7~ijq7()%NiE5JqaWxxmN0ysP+YW`*9MV|SD17A*LMo1P-*o-^HF+=3MzH+G_~8IEnjqUbP;70XF`T2DlpMp-QHktzR`ymwuXJJ$P}3S${Jg? zX-&poxiVE7{W^-eIu9}>CVrPnMET|NC*kELQ%3cgRo;d>Pc0Kqa%i8cmC(D}~#Ly8o%_4FWQDrGP~`FR7Lx)tQ^ z)l4Q^$h?TMQpoGG1p_>kDAmpTt||eUju>W?o<)`hC-W5+s;uE|MtG_9)`3yE_7-z6 zPV7;C45lzNew&}j$wgsQGdU71wTS72-7&WOlKzWXAH#73VRUhL4D^M*K;293WoC=3=f#8{g?m_2xfYsnCbR{ub)FmDr}HYv z!7j4uLWpx}AdElnS!zkMMWU>vojZZ{?s42j-J7Y67PLB^c1ap-zq}4n-=(9_ZuCW` zjH*;WIV0e`h6Dk`OQODuZmJb50q*1=5vs*b(rBIG{85qv{G*3-F=78n&F;fDx; z<0*=f?G1*LXU)v?0mneOY3$Fd26WA5m~0npK6$d0v?fKjEr&?!eAv%rq7+>lzcS>Q zMB`C&u!^)MyAP^A{An=S;{wKS>Cs$7UE9C7+rgubCM0r{VxUbUu{wqfsy|Dd{6a>c!c}_`14}?^4^w#!gdOe>IX>EgqHZAj#=_(nJM-oo-baXDx z3;!A}obaHw)9Aaxtf4wpOa5-|AaJ+#W0&ClGm1PY7Apc>@&`}iLd@Tr;#@|>iBx#-TfWmb*r-L z+lr`x$>u^k$r%K?*a;=!!PjQG3|Cz}@R)CpfjD>4eef&~#y|bP*A0iL#I?@_N)s8b zJ1wy&lbiidSJaSq$#X?`ggd?qDENO0&~Pd!uvIA&oPC`82RQ`n_WTPvz&4_oeW7xu zfr8N|JBL+sVca5S1*f?dlu1qHEd>-x7R$qG?>S2u80uQSe5F~#^@HEK*=pbYtoU0qv8mBWJv)s2vDbCCbVdLAa!t*&kJs;y4>=y@6Ds+`Hi?MkIZF#YIb zrSCtdX*M~Kk@CRc*ta0Pt@TsK?*?~#*n8F{LlqRE*u}Eobbc|h(C}|`+ow=&g%T&o zl;pvBcL~8wCeSb){Du4R9vR%S%g>|`p{#12giuUL7Op!+)xWd9h*ljffhYc8V)u1( zfD)4UYokG$cpR60YVaHeX?23RnB1+&r7U_k8pS8f-PQzmTQEM!Q14ggm66y+#U()Q zz>xhV!=Jw~5!AZ=Z!Z8a0FXOceGW>rLFbk2ryvx{^=t3T|GBt4nop@Iz(Wn2Sqxx? z{3uAtjgNwRN})6dXl$#O)Bpe`Zm-mE(!lchoHjrY(6>?gH93EJrbLbq5ZfuFRdy~< zsZAH6EYsxwwA5!1nv_!_2qGt#n4=L>EaL}PSj4D_hM<6CKKBEd-mNQG_x`#Lyp%G{ z+;6VvRCoBo~+=FJg(}P%= z@hh78Hj*gYV`Ir<)DB;(Cc7aGH!1$=V>hD~C{Z9k@Aufvk8)Y=Lz2)W#`p`Xn=>T; z(#7J90QzQq;ysZq0E42n0nLYYAk3c$oLOxky?Fi_fIn|LWBqh&^1zIpGjs3 z=$Z(9s+%!@5?KTGnz6wRm|z_}Vw5G2ys@rObM0bVC%PS>*Go#bCt7M1?IdUymq7Tw z=tYt#n6Wv^-DKhe`P^4w;Noy$ggY5riDVFdT=Jd8bN~aTB_78e8vgHH;~L`?=7xlq zGxpRdjhw&VN(qTR9{L14t%||Sdr*<*g7HItBaOV*4?%{kPW47?SV4g|6Edrz+U>CY zNt#mBxJam}^CEr;3+F9ntxuo)PW-TIB3iy^z_&K9gg-^~)IY&5-=*~6SH#oIA-PGa z^if1qCMk+VXyR>%Cfzg3ALG)ho3CrqB_bp>=Z%6Vy-hPaO-Bqnc0bLPhU%)>2|y5m z>%xManC`q*gY}BiQyBl&s)@99xS~y~N6O zAtwuC+$O4JKjeS`p91+u-6JI_!n>USj%_lkq%0qw?%S{xr(ZNfM(2f&rxVSwjd_j; zUMo?@ygmxe-sI1mE)0(~yJF1OStY_Mzg*cPS8l2#N)DG_@Y`EgCEpJU|Gd@2nr9hI zT;m+BA3(3CI5(XNh9m^v}|X4-QVy{iiTI~Gb5g*-`7&XCohkz^}mX# zgkc$BlJ>^6w-3+_z_)-~klN*FLfM(#)~Tbx{way;1UZ3XG4FqoQa_4u2o7xGg?j}f zsxQl+72NR1!}(#LzpkmR(>AFFPEXdAO>L{0vU$+wLBvj_@rZFWiW4M}Eoda+XSD^5 zjcgY}ofFQA9O}yu`xYJ*7>hGL9OMN~JKlJd;w*g3_%!on>O9Qk?L26UvHC-3#NqP7 zXm{?r2PdqJdFwaNGIT*%+9Y@1ev$)*pUeKaZZoEK7!YVwKLo;u1!f6gNk0?nLx4lQ zLYo27)D)YOh}QHkYtF8wyUwR`ABK(k7rhuIzjlwB4YDvsey`Bdcjd*hTdSnVAa)&_ zX=B<~4D{}(cEKXIMwQ34=D+=lSI%tht6w_lawu)kY>5w}%GLrk9=jd#^`ghj76~a$ z;F%XMCehU>N09aHnt`zlLp(YOJ#0K`$gJYq#pQ8rZEDSKYrRjL-?gyqM#bf4Hj4*; z61x?CeNir_2|nP_xCdJk)m%?|H9KGNQy0sRj(q%@ftY~2rdBUDh*M?{z0`}R5m@+) zPJQCu^QIJ5Zw{voQnS^!&skMKs=OSkQD*k%!L>k5McP3GJz3pLoF~xKs+qhDWxb1Q zI~0Q$m0y8A)MTL$nin&y()mxlQgB+;V5dW+H{+%eJYFf02TVHjHK?Y$#UC6tr5KFpDNwc z_C{F>>Tfh<=vC3Ba4FuYJ8>Mk&a2%EuErzNi+4(%r&Cci7g56^$nM_XyE7ulQTKO# z{_*$(dIieSSCu)=mjxMrwCWd=v4G^m$rcLO*)#doy8lrk+0B>9)ST?t9-9N4MOb?B z2RzS%#rgS49m|;Pz{cFQaV3@O1AsKp+Xt7Q*!G*Yo;eXRhz6*ay4B1fd8D-U3Yjz$C2*T zvrVy`)*RQ53T6LHouLT(C9c@$>XqQ^@Oh8d!Q!)jiNWb2uteNsJRN(z(ELEReC$)L z^jG{M=b97$f#%8_ymYaw{q{#{oHl|TvO(PjaGsN&IiminCHsAPRuabV8cT*sO(-k+ zqCeY1eEXI*w(4A{s$rNl6VUr3XGbb)5$0mlVOf@v#q1nX-O*b4!jBwo|Y=n~y4j1UV*txLaBCK?c zt;@c5ROA~Lu5&O+wyYpaTwcvy*~?oW$KD#UT*@PjN>&XQ=K5XfhQ*@g-6>sNZtXJl2LKvc2WC>l{KY`u$w`wG;_tfqv2ZXx!Gb5YcqSr z#DLt8nG#JQ)t22#SN_x|GT&_~OCB!5{{H5^0uG|{Mf{~!_locnBvNvtlBb@kZA$qL zZ0x3n;T8DuTv7y6Mzc7y;9##C>}CoL^s%|!{yC|syNHB+CqWs4{DY+Deloyg7?ijm zs&9L(hi#804y-{p!BlQ;a0SRlHKi=!hB8tUVIBsaTm;c5V{eXyY==d`f_XM6cp{p#A8Go!+%26S zkpw92o_5{lwha{lC295{=!v-qO^doW zRzP4h8_v#eJ2V3TxN}RJ=bPI{yqYzRvs8Mw&FV%N>DQMbH2Jk_)S4Y*TnGG`H9Y5} z%nO9==EKv#)kGp~hf9pXGt|9e>IHOfPqn$Q-2X?4 znY-JjRoUsf_FP#ESL^QT*F_mP@%iEMtfg0SeLF}XX+@= zqrgjodlc(^`aC$o!mN&0XmW)fEX@Bir@ebt;K}{11sMvOyS|%4L_b{e8S_}ClC-q( zPN9T@1fkO@FOD`O8a8v;%}$F~VTdO(wv2ced;t)Aa{?B^l+& zRhg?iG;aL;Ip(Y=@%lRVN1sAWrSocdYl6|j{#-c)5}La_=om}+7)@2GeACZ8_UkqL zPe3I^g0*+lI5pBM8i{lg-D}G!JN7CqYvaYrfQOXFMjB}lPU~9a8nR&LQju)|-tJJR z4O!`FbBA5w)Z`S9A@cv4Lw=VsA+R7#im+n~)M%SegcN0sff} z3clEPIo@IRMH}RA@Y`Y;k*$ppV*Q!-QxEUcDotL*8y>d5U4#(pP|kaPLDn|-cR z2SP}6$SdwJwOJ*vMS*hFL2_H#4*=OEZtFXeNnyy>e-P!TZ99yjkBa|0gS)2AQLn}@ z8=sYgu~u?ZFixw{B*}z-WYby6OvYGSQV@7H%z>pj#f~vrX$|Oe3Qka;c{0ihGS_m zFASR-dtfH8Z3OHa$9lYy!S#5s1(h2OXzUo7t)S=s41mUa9T*mmXe*VSZ62bGBEG66#BTjxPHjj(7$(h(oFLZP5()O5-28TMyD|Dh58$blz9RbaC6)#1+wiF3Ytfd#5ma_yJv3Qz3gW+ z+qx$a1T*TTtATO7kG$})S~Il;E~e)%$pQaMMXb}wOQYlXm_VtMv_yeG)GYBDGtRe| zmuv5Y(m5>Bc!UqFpZFuVW8}CX6e2h9KDs1`DF$_8)Kj-KyLel^GPBNPM(wzNNwAx+ zI*Q7UU_-G1ULdY_<~&BlzS{HuvyOm z-hLh%YBPl#LV2fK}&CiR!c_-Xdl^X=hDfShIM`J8~Dr%-y zk|DL>bi~t=T>lGN8GM;u?o*sL{bLEjEF6`A@iD|c%|@7jVgYZNddV(iww!I3Kp~u^ z_?!%bD;8Gz9dz&37{8-B_?q{+ zSgSvT!!X+)ar%kyD^0AcPOrUwe}EPa4^5^k)~d}n%h^3!rc)2U9YXmqmsodb*CrzH6LWt9WD56FU|z z!*=GRPY^!WAFvAeIVlG-LD-K+t8e_vD;< z^r4AYy=8#C5$i0pO{E&j83E}NItvY!rxf)*z%7xIi0!>3$2DgRyV%~9#_EdM#+$L^ zDD)ReYXb8h>`pN5TekGjIYv=MkB2kQ!EDBmrL^WWD~*;Eue2iWj#6f9D*7k#3}y`O zGl;R)Fxh;s2sduWOo5ItEkjpDUO^);8Lg zLX0AEuGpCwgt}Zk!Ha8qS1V{n{+E~ADKbOdaM3pD_npjCaiH40fRBm zu)WfyHP^*-*JkbzU1Fy@O=I8V)&)YIS!>awmGKt3ruLs#>`XKH02ym2FWcK@ZwYc$ zJIB%JxRVF#_rg9X*DZ8~5ThuMfk63##LewZ8k(7UB|>flJb=0LL4s@0djn;Jl@Z4G zR3|1i5(=syX`|W6oVLgQuglF`?9XPy?U9ojCURmKBKRdI*py-8&dO zxmT29HBQLm@r6?!MWDXCn(Tn88Imt~r6p={b9(i8UZ!%;DzF9banEbYCc-?JPQ){- z+9Mjz54*jY-y~094RQ6|%~Bm2vyxPZLAIj986>ZH3cQ!Gky&`CngTF!cnKzo2}2*R z3w{aQ5WFWeI0@1!M&pZL1I4`v0d9%;o)^CvOVB70!X!QT^a|WYl?_$Bu@38LFO`tw$9}1966;EBwY{O_WU3nrwwKvDIEkq)f^>8l}yRB zTXeXad$5Bya9R#77`T6gV4tUOE7f;&d8eQk%{R5S8hkt?nmh$?mNd+YS}4*pf=nV%1`#uZYEY(uEry&)H<(U@nJ(T)n* zyBj2_F}R0T;PKXYcCu?al)e_O@y3z}i=??yRAWy}4*iS?GP>;RUR}4RT%l$kWYA@E zO!jm|0FWyX_Qdv98fss8MDcpqk7Xs|q-|DwB}p11V#52GRkzD{B}kMnN%DP}tA;Uj zIO=eu-%%>~it6@8f$N%Oe?n6K+DBvdx6I3s-pb1*=liMqOWh-(lQwD*!t218GHAQn z6zgmDKkS6_)xiA;D@Z=l&WmJ;-I)@x;cT$3_r2%z`U}hF|A|`Z&KnMVy_K4$Ru|Ou z5LZ*;ti>A0Dy*>XuA@k(b9gO{x3$}&pBJ}OTfgUAV7k3ms0Ir542 zk3U%A+KBoLj}-eGdDi*-WE)D_2*}34!C`E?KbFo#BC<}K`BXT4lc-x{&r(|`9G8<; z!e#~yO%{?*1k@L~aXam>iyz)3lTu^y;eizlnbIh!-}h-Vt;>CX$bTZiBE8rW^_F9$UKL@;4T)_7@h zrf!QCb>Li(ZasBLy_%dMhb3moBSet$*|Gm_k=8J>FyZyc5m;Dhc6I>&R;XMzdkKkQG*IF@f z%kA{c@D$2Y4ckZfjPQO$*?us+0QlApz($VnCxB+LoEq!ev<~_u%Kv1pMoq~tv~`s) zcZDZTVUNmCAOBWSslg~A+&LCU_L1vwVLqUs(@O71J=0?7GXHtjHlOpIzU-j0_t6q^ zb1H77)rA+D%t?YtxR#bW{K&dv(EFf5x1U5B`TEt4d$q|wh`*|`(Swzgv}ptaOe#WW zH%*&N?%Y&rS&-(bn98*7dVXUYC8oEyLWy1bZoi=}JxRqHf=4W6@CFUu|LD)+zF!YK z-#!<4IO6EAQ61GS5|hdDi62!a71L!vdS&mpvRn)e{Fz$#5k@JkUM90LFE7XR1G!g4 z5JQc;Np;m{^eUyT0g!~BH(_Bm5=25RA@MOk#GgVFF@#*}db(QelW#|j8M`z=b8#gGR3C|$x{3EPg&H}I zle&Em*|@+7-J z1rio6)$(+7MtQI#)l)o%oSyz-g@CO%EDPV1IMn%UNGJN0{~~v%q?| zXHP+8@<|DOV`o8XA+H;0k!&WfXY*(2Ys;tPsmRcupPs7@(mRQV8<{Q2Azk?ordGz;dk!6jVm zNDjB2a;PxBsh!dKnp|^nxZZ7i*H3NRT2j69$L9QFKrYcxP=CZ{QB2smnC{`#k z0*>&}7qs4&podIC6J;TOwg#!_7NgJV(kTg*VXRI=u(#t7%tx21p@-YimcRv6hTyY? zl-SZRRzy$2wHJkt0~oEdu3lVrJYg;qs_KRq4rTM zN;)c32{&UeCWmC$*^j>uWm!|}iCHc8pyQ{eFO}TU`eUpdT2DfwWh|qkV^ScZ2Vs~# z#&FR6941R62ECzihXw^YGQ46-EfVtCSQY(IBq{XmpWxwb>TdYJQDtaB{6e?DG3;HE zQoSUE8B_sOZ8HsDt2+C;WueAmhaAII;l404-?5-znZ5uL#EiwH9JWC{TO@!KF002v! z<8jcR)I^!QmFdzbw~sOLW!JQ$wHd-URsFob5IMQ2g_gf{c2C#Ewl1D}$(5bNU9IKh zBC?*vd$9eKXgdi{Kv&%()fNExSnq~RF!e83q2B*7q6a5QcXkS+6Y&FAiL*Fe!USBF z`t}tSmm`z$IVLcbx1;_0Q46GBf7#Zzh{^bQU2W5l^ph<}39`Zp?nY(kfH#;Iq6$ru zCCCqyqVg;kOi%Bz`Wl}*bbohNhfQ>4=h8kEpX33K&+r`iGVM>y9q_n=W{3hn#cyy= z7U*%y8r-IFufrR3@ZZWf=kN;PkW8zma9hM9C1eusDTh{_FqDe);A(8&M=+ ztm|KZ1wKR^IzHp7sIc2RW7_$D;oXrwn|~QW4fR<6F@pNhKMJ4KHc=DCJ%DRXUsgoh zIHGcuBkam!{i-i+?JK$H#BCiB*i;8?7)g241{Zn0Has=PQ_G=tFnfn}&dfOeuP>T*05F9)?Kc zyiDL z%=)p7f8$c2artvo^Cs4MY|gpWPfc>AK!da0PJ$KrwFPwLjqj^Z7YC;k)YRR>C5AM% z?!8E>nyb*J4kU42T=p|HYKe3;laqC!hZ*G#UT?64k=TPL+8q*6qch5{hHme?CQ^)K zTbbjMSkFg{nVwgMMxAWYztbFp&*n}UXq!q7f27&ccoJI?o=&AuzJL_jvoeM!J5W{A z>@)Ui^|3aLS!-)sE}xuXA5XV*<|EEWFMz0_HS>zU;Y4-2d)vRY4-G^gU8lUieUN~~ zD_qd$c?HS9I7#hIyjk1l4}b2^dO+X7#@UT%eY&2{Ok?bnIZioPvfq<(*9BySy-RHA z6W+a4(bFrSqbVP8aY#BK4@bEwke8JDhleI|B2UG=QLLST|DMS87xuLhfqVit4k7OE zUZ%>u(i)V^w)a((x9pvO6Fc!K^-KXiw?K=h3tm(0HRV$bOz2X1b#m1(5*`#}vgo+Z z4(j{55@K$rvL?v+SOmllniKi38tGk{BxK&w?1!O0f|$T!VBD>Ii&!tY*R~N|SU=S- zv$}TWb(I9l)J%N)XZH|afYzr2QC)DX-SqwqItwIS02hE_M1(f}{X_&>DQu$_VC8op zo~e-n&*E$G6`IYMqS4Tx(P{);f6X62QHrD2IlaWnrDOChxyJ{#@!^l|d{$ z@1fFX^YfQ%9}p|mO1AM~k0ke}?A1`bUqHAvNE4LonxdA4HGW<&p+@v@l&G^i!a%ki zDnYj%y0~NN2lkUwdodNfUa%PSmxMh^QUe?9s4Ry!h3o|J6#vM+$&Ui??`dMgny1pA zi^O2liogN&%L$gPV^=MNKoAwELFsDX9DXbPg^^OF+>v-lNw|N=W}uU-!ZLH(T}dw{ zq9y&YyvSv7Ww=$C33)iN{~juY=n5;ObrEu}GRd}{5`|qaW%p&ttrcMe6O7w0;iCxY z>0{OA{A?Ue1)~twi(>~HnsCsvkvs7t(KJacXTBhqMt6d97GXX!{ek65RjopD#eZUZ zipuD3$%Fhn8= z%;i(HgHr9U*h}+HT4v1MZTYFt{-RW$6E*RafpE78Nu&OIccMgO`E%&ytMIjEDrSaz zW3MD~%{-+sKlLwaTRPj_&`|G2?z)DgvO-yjOodWK7a$WqmzV^wvdGH#@rv~>gEQ(F z=QqjGkMOtX%lDLlSWneOE(wFI^$A~5KUWJYdWgfK4qcZZpSHUlsfiZloKRy7s6^?5 zZV)2vy~HEQvv{ra)kK{BS_;&BY#-Y<%mtlqI2t?xv=+hr#h^ocxDgPFjq{?uLrRn9*KI7Z`` z!0Fm+m0X~fWt~E1gMm%$l(eNzuPtmvOT%F8A&Y#3ltXFi=zt?frOFOPYnva=33Hrw zJ3~g9CY;ViuIBY&-xT4uSJ&w`4oN#}iMGS5$WN#wRc42sEoyjLWGgO08 zMtl8HJ(Wh*)xCeOZPbm`U9?biD$Y98?cd(Ev4kV4+DEdHmAwkeMSG^C(lT_H1BkY+ z=T~U*N^6Y(vBNqmiA$q2dF8~|RZ}=z3!39Clbm9E2d|O)6VyqljC%{ueu%LTr?0Hh z(4CaF)VmmUys!nqDv)n*B@vjK=J$IKcgZC9@-w7x9=HtOYyJJSXQpCNMKSRBd_x`S z&3@whz!;;(HGAykj$Os_%gGUo$&m8)y9qC3>u?gKFbumv4%tK}CWp_U37BN7NeIyT zl!6=O931`v!LKmTl=Gr#U*Qmb$)SjLQi*sv8`ZE*KJkEfgex0l71bs_R>E^cZGT@)q4kL= znEDg@RuzO2Hgo+VY-TICHQ-0^ZjG*o=ifj-)?n*6$4L}cHN6_RU($O0yIulMEjyTM z0j0MfqX|)X!k}^sUTDx@^aL*HvT5R5TL7$kBC4kt|LuAI??@2QX!*~v1ocVIvCpxi zk7E#hKZLH062Se9`9*PgL^X!?5Z~Fc!tioK1$nClXx#*v0pFp8QOF&p#!#k0_jAY( zRr3q?6IFz&m#bwFTE`-eW;h^V*9emCp=4~hRpJpE#*PNkr zG5+}98>_HbD-0V8uijCxqh))5uelo`|IiO^SB68R8gKGqZ~CT&mE)l>1vl1?d%3#o zPllNi(1*O84b+scj;P`rR|fo%Bx^;H1bdH3s$B0l6V?w?L9y_V$I0@!$tI7d^}ztgl>XzTiOfcn)Gxo3ouNKp!(i z+daYvl39GoO?szzceYpz<-TN+{DfA{Y@WlZDJ=ZgiSVL^Xlzh4sizH1u2s=9`exRI z@r*{noCfi=rIJ9yl82A&RF3oLX`Nj!Z+*WaYX6VHD5nwc%(T!rr83jCc`1 z+$2^xC;snumku%jsW_d8jt!AI(*9N`(i+ zxM2k_H6cgG_FfJL`w`zKxy}GZ-l14d<(IT5K(P@C?KH>?hLG@UA_+03`v#+2teh+a z|JOF?l@f7f)4QHQO-QZ)Pj}b|jG{c+vNRNl^Va399ySc1*00ibc&>A-Usa?D3>!c_ zRSXv=oL^C8a4Y{m<1UJ<(*L*Ih4R_NyWI1Lp)zg>8AfV^OB^IeWcBrJ!{X4v1u$#` zq5F%CsaTm11{zm{w$b|#85FD3OBd#p@f12mgqo1>$^=z1vVBFWoEfh~qs&KOu8a^=3P>g&C7`eyoppC~5KZS%=ot@SR^{}|w=0fX zOxQ-IOifR5Zd9Nq&r{(dq8(CRr3_tk_o6Oo2{wVg(j~!^{e@PWb(3nVL0#@CSDJ!^ zh6!!yQ08zpFJ$IY>bnj2o0tFe`7^bSQp?hVI6{A+LqRdAaqaVhpTr`=vUdtdrgP(f>FkDV( z)DZft-p5s(I%_#AQu?ea$cwxXIkTtI>~Ip>;Nq`POX`~&JU%MTSs{3qxBOK#R%wy% zS}8Jdr11Zs?Hz+FjoNm>uw!-XbZpzUZQHifv2EM7I<{@wb~5|@X6Dp6!IUj+}P%YxcUMEtL3Xp2sEfVvKOFCG*xAD|58pQb9YI>WSnxjeC zE8EYMgjf~MW`79R)AdZ|aTR`_8z3bP=>%fKrq=$B5R`s`O=laGQy!wlEg=gdC7kxD zl~jT$2;n8}HU6PJYDitD_%Pihs+-Vdalq9dq>| zEo*1);`w`#w_DjMs4U=o;UST4IE_q10OyMy@3o8VQQ#zV*Ss;vQGVqA)7%dtSGnciVcWQ^c^`is1nuD0Gi z2WHAKvc~t2yrA7O=088T4?vIKmh*?)><@YZhvO{)iD+v@I`PqFQ5h;v_#!p-dpmQM zZv5u+ZKpSDi){V4i{tg;A9y_Kw=OKJ*|i4rn;*sR>t_I#vT6OT05GHb=856j>0C3_ z4%duE;=?l7p7V{r7qBeE-!S?S-|;spRRnK2CY0N@4y-H?*R{8t)A;T1q9OHa-Q zSmFW2oW|hr@U}kFfA|OEv2$Wu?vl=EqUsp{NN5L%$ocubP2JA#m(kRJ$#V0gVa@(S zY5=IFm35lSoAx~P`ooZ|HgLx1gsNolG5d?s zuFwijUzyy!Osu)CCfm~S3TEEpY-uTsdcfD}O&$9{xjTFRCtUO(j^G6qYuf#w%S>mrH%76M)#7{Zd*&i_=KU@(m3><(f9MK5Pdos z@bNqT2SMhQN_YHk%?U@dtLl;)Y^73-tABimOJa&!U~+yci^*{r<5T2R;zFZg5B4OH zwZZtR9D0h`-RD>K;XsWq*pm6QkdxfDx0fy0y9MvLH6Rru;U~Qxqr2kpVH&n3o3SLH znYo(KQ=2L~_b0G?o8c4}uUITyiD;#KWizQhS5^qEWZ|_h01N}72kTR$4C#gGY5}%~ z7pE@{sd-!)?`eg|JVW;z%>U=tB9N^gSw@GM3;)UC<{bB}35o9Kna8>Y(2!`cDBFSl zoFCbd*6wo5?KI7QiIR^TRLw+~DiWYXTncB<&miUN9GMMBk@FF13Gm|%XHNGD3eqa? z4m-GIe;zq!dcRodq~8J#um~`%v%Z0@tlkeSn-7o>Wxr?>HFDJ=wi!>7X%Qc;7e047 zYi~a(w`?*`$btwF6f!!va_S|BzxJF$J9o`z2u2= z@-k<`SqvTD(Ow=@l65Gtjlxw%^0{39#4sIwSD`Q#kU5Bbh$_R}58Br6?yCi9;kzfd zlED_4{AF{^g!uF1bwBw@gp%}<(z!s+Dz&QiSH*n8Pb9T0xh2NB-K1w37tMtz;{Hj% zl;H?h7v`6qrl4Sb3z3G`>-m{4GyKD#?F(U*17FU!C4z=pQ@FM2XDOzEE^V8;TK>_N zT^(m}*)?uvI>R?hN%u1>zAbrGdLR)WV~-t*fv&4{4e#GY>%Jg8d^)`hZJPAv1+lqm zU-BG)_Jd8Y-?BAtB+ZVa1oW_RZ^@Q9;&x=qvhN&Ee9BeGgNgNs@eQ6ewl-QrLB2{R zt)aD!;c%F4_pLJn>DpxE8cFhN1JCTa=HbWw#E_&(!Hd)Rls^={b-o~jtb!u${fZ0a z+ttd-a=n$|D<_5-_GMtna%ia+-l&ky{yCC&Rp)wtW5*1U1^!!4>M|M6p68Vyluk$CM2W$f!n07@B&#rQAvL^q>^%=CS{qJ#*_l2Cu4rsTtW z@=)!Y@!A2kjGe|A2d!MgL0mQRMYxCn%8GpXPC+np)j1stUTilZ@XV44MZvlcG4Z0_ zrnHC#F!ra|auywR^2Nw#@T=r;XBB`5Fus z*4cjQiNetS5!u_>PH&WFrR8xF*NF3?P0f*55Vpi5AJ}Chq5)ww*7hU!E~rt+G_o4Ue6)_?Ru^a>87MH_dLS;3C$*@$*$8M&+0o)Iz?a35;`0B+uoZhH8jI zha^bRTH=Y2atZ>{EV=P*AV^4|)_8hyU7rI*p4FO)Ya5i%VdpD)JrZ*wO<*3i-OY7A zzm$_lN5#Xd+(NybM=93FYEAgdBv6Kkuk)LWRLeR6I|$by)x)dv{iy8+QIj(`LIF|I zf>`;1s3Fe{G1pF4T)RaWjsK;XGE@_v9Em=5Ok8R_c}>Imko7={x4|6qcB+o1yH?7Z&7&=7Lu|233c#fR>t!Q`h8@=U7SMlPuy963&XBxie(#qOMpS2dXOuD5Hvcn)ba00Sy8A;9t88{v%)XU98QBr;HmpIxRKv!nQ6CehLzzl8JWMV7`*CKCH z2~ZWZwZl#;QYd&N2b@%d&bG(`_2R82 zqo1;voA<0>op&FXp4C{-wP`^LV9uGYjd884071?+GFFX z$@YWEZ`6OqNY#a#^0N|B5<(EPmtTSLHiCDzutknb=S{u_pl=`v*+Wb738U@NU4CvT z0eIVBp=!m;HVdmKU~`RQ9rFDm5$H7QivzHy6cR<}vhc$;ggOvXjejug zgwqA&wkAu6hE8sktzBXA_E#K$wgjbjxu>_k*3`}!*-GSYAgK>;FHYBmn{WmPYuyqx zV$Ak7Ta&Xr0uAkEc7gXu=!nlHs?s)N#r51i1uNy7x3?xa$^#DLl6A(76LLmVrl8DE zjj4UZDAB-&e)pZCu7#Ns<4C;jsKfTE;`G-0$kCqo;)s?-{+AkuBnbjd?_aumMA1)Q zdD%RATXH0gj#zJ%W0F7Kqt!+KydGQqBaIyEq5HhgIlE$xU;5I+&faGW$nELal}=aQ z-*kolYY?oP6-DrupFox#_O|y6a?iI5t{!)9%o|^K|GCS|!k}mMebuUU@VAOHu0;C8 zD#W&tOAEdYe&%=?>o(5oCxvb-uNLoD@sdDZ2&w#uJMluQOdjX_i|m}K-oz8fQMYiOt zJ|*qPet*;b2$dV={~6_|eP8n{Ayt&hJErWl8E<-2Hh&0>Ql(2X_y^&7Qbk^d5*i*y z&BqQ52{}1*%HWPEn)Zww)eA_)&R2K@V^0QiF3dXoY0LW6n&39mAJH7Mt7Is zMe7^04>`b(5sDlSU(_ik0cI<}kGB-t(pF!jrRv?5TA-4#ce&>Jx0L|!BjldQu}wSAuGBlhD9lR z#x4*vJ6f)Ph@^Nd1NXx&;;$Dwp;eadCR0K!mJv1Zk>&Qu?VR9Ij}~8s*lbz(uZ+1a zPYI9*_RpmeYRM&qNf(Rl)$T#Y|3e547L{$qLRhCV@UYr+dQvBAVuE;2S+qXb>i>w< zbor#hb9={_pBGZS69E$q1E zt_>1&JHP)%^G%5`q8&Q?G?lgH0a>w9;(EpREh75rFtwBZ10v~$mSXCBwi`srQH7zD zDhV)3M!@TTIRQoq{D3VA!e-CLdS3Q9MNl>P!!=SY1ITS?*aIEbZ&dp1|KLxoAE6*Y)K)^$V*EPo*49dHaSU`tR8m zWQ}rq9G1}Qb5jV`YU*4NQJt!lU{WnKI75`xQo{6>*WF@Zks+Oj#XCheyz~vW^3A&g)kCGy+@XiXo2F4HmNO*^-s zH z7J-|FCoC~#+pSy!Z!Wqd80_>#PB6b8d0P(~Dvt>CtM3QmY`QfY-x!a93M9PW!dpl% z62F=D+p%4v z!fRF!<~a;N?rInMqd@G=2)qK8?2(v6u?d38z2WEMdy}meeN~V+D3)Etlq0Ag(Z;9Qy zJGm=cNLRq0JXw-`W_(J){^CxNlqtVX84BNVbt0IOd}mcBpWx!_>YHU%sV}}JVD&`xn)Xm+sld&~hR9E;$eq6cN{$0= zRDXCt32CX7@MnpAe1uUCJfH9AfM^FH&vACQBAM9nh?{l+k!M7f7-u~|pNn(tUROG( zWj`;h@}iA}Wr_MQ^PY%wV<}E>Oqil74ChG_)1NYRzLZD62S>@}@^G4VdbCB1iaeIm zFH826^BqE$dnyp%=M816BJlijAZ~)M?${KBTX9^sE1y`+Rb@P=zg~P&8=Y2#tlG#P zF|9f*t#^SDV=IwtI-Ls`UJ9x|DYhro8R#_S3X#nAGo{SexQlW_8>*mv(ns*zf&)cYOy7A_Eajgu-l>bi@)2gjU`VAkRNa=b` z){hMhm0?SQakcc9mgj6k19X`(HcKMML5C9AKWSMR=pli!&(nJ#kp_jq_F1#D|lb&ZNtH;*;vTdAb_Ilj+e^U zJ7u`EcefmP>uml(H|L8wgy^TR(+4%4kJLIE@RlY{vAKcS&j>=WZX4aM z5M=SWL~;LEf~^D71d9-9IgXq_t$NN7?w#ztVq;4K7shtzQWk7~D?mVTw)Tj=>^ZUP z%ri%x&*aUhGL*}_bv!nh&=B6sX?(Ed>4VF);tlNo9*CS=^ftzW$u0Zf<1q6%m}S2o z;F)td>w z@;}&f+#|FT*;KTi4QG`S(^p4c)&n76VZRCgJ4n!>q2t)mE!ezMV)c4AlRDeZwgvZR zA+3zd0UI27g8W$kHpn)N=hv^5kssZ#=Klzn`dF0yf1`70pb%dXx^B7dKUgxo<}9x? z7qYVP0#eJYiFNJ9kmX#d?!5DRqy9H&p^2X2918I@vFjH+{L#u$PN$ack-r20&+Mi8 zABkK5jnn@?odwFq21xu+09r8vC0agH9~eMXeF zERlDQ1I^r}LV7v_oXgcQ6Pgo$Vyxv{^whL{tn4oaavMJqh@)g>X}rQWutRpQ_hrQk zxzZmm(lb-m>Y^;j;bbbq*cK#DPI~n#++aOJ#m*Ft=hje*0n>BedE;!1RWYhm!yj(> zyqH<(R`tm!Nv6ur?)$;w95LOL$_>ABcK0AnyvQ}0JN%(h;+4GQQ+lDx$_BO z8gV1G^In0O*}}iOeC>gK*&LohP!*_##7yW94E190G|~A6Xrx+4v9`V64LpzD>YY^i zK2gY5Ig+_PdSz^XR^HyH#&Lc;36ZbQV|@lJb8PI9r~lEil)F7^w=cx}!~cIq;~KBG zxEh2uw0QG#oTVW2>=^9!>usvsBcnyjZ2M44@yynXcWEy^r6H#(cF(c)HuHD3R#Xz~ z(jGKy30HH6!F=rBV6;%@D&Mn0udM7{ynLb5|Q69W}pd($quH4I4X8gXiKyUmHUpBgEB~fp}jzh#x4#4g@-_kr+gG1#*$V{ug z{;k+s%FW`|t4;2@(jJOF9to-?{uki)W-FlBdO>urpsgAIMfkt;^iar~v6PYU(KFjZ zSrazMXcG>=Q{c2TgbTIs=*dl@ z*deo?-Afdl#_-%5{E#Zr%nDVRMz+0*ibrk+4m@NvAzC8M#*wI5VA0f5+={4UzDMz6@u>f|nm zJCS6k`-M9F`sH*2EnHNh0nDG0rWOy$8;$VZmp^8_7ZiBUuJ_jpGQtfecV7aA;ohSA z_YuN}|DW*4bkhIc3O+hL;&Vm1h`~UXp^Ieei*wfQnox+?rAHRP$5d$yR$PTjOt&7K zn3264n)YOJ$E5aX&scEVJCq>zo-2vMdo+_zWI#zhWBzv3hOE(y)|Vm`TlN`x{Vsf? zeVUik7~_(Q8NzmBWN$cj!s|VdK+8tv?^EHJ*kgj{rc^1c;48unGZ;2Y-1WQn@rh+FYn7cmULwfo?J$LCV>WaarH z&*iqKv!h;@$)E`gfvebe_$F?5{gFDBRCz(P6c+uBsS!E8Z7Q!bCdJ#&5y^+NM78Jn zCt&KKl>W6xj=chOonjxYR{tRY*_eIn_NCczZ;|y_4sUep2A>*h{-pll$J62B>!!hc z#p3?5$DP80n0*scp04if=-S!qv$u+~23ea1K!=Cg5!J*Z%J(==k_% z3*62kBpuFQXxWri|M%>*Uy~?$0&iKtn&}_M*L(j0KtEd?38$v6H`gCjH&L^jrm#6K z#SNz_cI-i>L9N!}6#oUlWsc6Ocym4#MSnR42p-oL7M#7{pluVwx(s+_zTb)-o*AX!Kkv@3{0^eOrcXK64%t{)5R?A4q z;g;kY+dFs*+aIq^OldS&aD^wyHlDspJ??C2$`suE2E}2o%bbCDD=b@bH&ppmF6P=m z>WS*W$1A|oXm6kd>!2}I`)GQ*0+l7p+1C%z&oBnw^4%1b$SJ<=t()Ev@ZfGgA$7r# z7%zRl)`;^_gl;?bkj7{O!BNt|jp`It_z~;qd}eN0=5hIU$+Y|#TSD^HnfJe!)#=^+ zQ8x7$`$Iv2OhTTtpPs4{6nK|pJWYIoN-!XxX~-z6gqR;-$$-=cRso-YyfD`c;2aT< z6W6Je*$~pR14&2_zmXcdc2E1D{l8+#MYyKsFx%-1ZaY{YF~C zdRR?pJcV4-SW}zAbTGI$?!B}O1;%xg#B`@Bm!o#d0B>4s_Odlk<>h`w`;^vNdz56f z&H)k;BaC3^*lGm}edX>fv@JOtZMZnPtnfKNQcB!rdsPi0)HAmfJ#~LM8NENo{1b%l zjj53lo)D1!^khpnc_rm&jeog`A)Fn^+`X+>?6AT5$RhA$)j*dl6CR30vpF~T^_WDg z=wg4VE~T9Ua8ACvU0r^y0Ak(Ts%Ce!Gq#HHe_-3Ty$CNLcX#>rAHX^_i*>lHs*k&` zEwpdgg|4Ak?}Wt+zOa)V^P{ewl$o?u6otQz3^_YZefllQkMQ2?67VTQ?PK-F%8C1o z*8r!Q=Hx#tyc8P%3oi!1!mAXXE6FI-z+lT=!D~w%pLSREzDH?g>CBdcw<0tW8BB5Ydg%YA0IyxXz3JectpCsb)U1va)n)Z=|O|XPj;GyAw5l?avN*@{ff3HC#&TT)u;9=uPmnMmeBWMOOR)>Uy8Z077OuH8g z=#NE*0iZi&B>-(A0SQCK&a?f@J5a78lh|8WAAQw2xwaw&F?t}v=NUG5`3Q#0kSl~%=soo zsF#aLg7Q38x88d=2QdWt!dQfe2WCFHP4y5^dZk7SlpIR-mg&7hma`*_XrROR48#1j zFgA_40}L)byU1v7_@AyY9e7kad^+WS9_|ReMKCz*5~xQ_Z2yVn~yAn$uEDt>HcmhGtz<=Z+Wf^DCIxLQ{vU3m^ib2Pw}qvYIk! zHnTRtD^LlCh()$A82&At$oK7~q zt~Z^I@ko7^{Vk&*f+$59I~;+Y3i!zbU(biNJ00<5(9m5Mf6LP!PGwUQq&K#~Gy|a? zg*bQt-u=y)hF?2RhR ziu?wMuj0yZNoaA7iXiS+cY>hAn!Lxw>W-R7cRe>zL4kUolngLPHr9-OLNGHf#(;S8 z(sENy04!q%(|LC{H*-BH3kZ3c4~9Z7hZbu@UMi&ELQ-R`r13ZBGh4*p-M&;c%>_wY zx>Nn;@Y&Whd49$5-SZ;3mZIspru3qhxfXu4=uvvVQ_FkZEfO9Oya2qv5 z4cXWRHV3h=%uL4syPXYAs@&P+J(gTchEosyKpo0@oZ_n!0$;_a*8SHIcALQ*2J3?g z!)~#OG?nz;_y%7LOV(r6x*3|4e`_nuOS>N`TNU3#${(UH~n6QhxK)274E)} zS+cmom0<7q6ubR1o~bzes1I@M4K?}J{&zd*8u6xhw`5VCywZ(Mh|0O!erYF+_33nI zHaLy+#ygbPawR_<8HtF1M0I7rQ6YByOY2BAazxVb>)4h$(`fWGAPu}IomuBS=*F#l zj1fo0}1S~oS1i(~{e+*VM*n&~PC-c*T@ zIHniJi(fS+>Zxe7qCoR@W*?Hvs_&#G0E(YTw5>WQJC28SUXlMpS^hvhvRY%*w(mXn zZ}d3+2BN_r482(ryczFkRe#g<_$cRaAIV0YhOnDSDPi{ssiJ*$hCl>0d%CM{Zp7# z4QpDE;Ks&&!fa?_bo4VZ{-lhokoo;e&m}I;V@J5@k_BJQ#^;9Cv+#p0lcDB%=ho!F z4{G~gf^Rf~Yv|QzFr_K;^4Bc#_r1q3BjZo)s~QK)w!~1oQmOr1Nn=|uO6FS$V{s%V zTW!{Gxl#)sy*xJ4PoOXuCT4nXreAWSJP#8t`sBioEz9=?q$sRDBWyKj1mi;s_Y!0?Fid|!1&ySuxS(}2SSJR^Wfm&VEf;(Lq70Bb;w zS2D|uD)9Ya8fAd_&*zw(qtk-_^H2?q{~05`exmoBE3!8-Fi9wE#}~-#o-%(V(q;Dv ztW@zNXU%`e@3J4W9Bmt88DzNBqv0uAYPFLDICMH9?Cb@nz*$bg^$+-1c-W2uV(A0X z?LJKNZP-BAkJc^g^z~{W&j@XQ@m;04+8sme#23Wq@l>Ju(*)-w-^E`vBR!F=P)l7< zfAE!9yS^5m(m13=yjo`XIJNR0!Ao8y3OZ2q7}EXEYQ6`TroU9Zj{+ug2+HSg$h4gH zrY>irG;qY)A8&rhYRfX+;91c=|Aq& zZgIZXh%wq7PCqj;o%F?4VqLH2>eN2#E{swVEk~P#QQlWFQJFo^r4RT|IE{6l#@No+ zPn;z+y~n%pPmDjzlCEeRy?LRnY~vzsLz6~+!)a6O9k!^lrrU#ODpn4o+vapE?Tj%A z-F9%S+HJuXp=yQ)N@;C)aygixyk)>M{`8AJPH^APPXh-8I>VF4y7VD~c{>FYbuNn0 z(iQ^7gT0aJY$UK>D?G|>LykUtXuh}5noHyeL1OINn+9fthNP~3n;@d4tZAut{&RPn zuHNs2hCw>{POJo7OPT7P&)-D$_p(1xdo+}NBN`AZyPBtOYttX&I80PXdI;{nP`R^r z4>1Enf_et_F868D989i0PSuwXJhSn96|xy@znVX+M}4u2L$htjVW?B)G14uWeQqG6 zU1Nh5Pg$Bg>%5orNY#cFHo4^byNd2tPnO|@tiGN?8F*{BBZojBpn<+Y|4^fi*}4d% z^T|#3NSv-30V_HqTs!>M@ZuACslh+6w6=TnaUvBB1V}mm7&5QOm5^ zjVTxc{h|9~aV=%e_702Xb4xR<)*haGup>J2?C)?xX1)tcz=cP&@zn1<1Dtm6gx!Xh z6YM71B1X6J_1bNR874h&FJMFOt^~H7QxE&phN`rK^Ow~_SNyXFv7 z64L75Wq6VC#1XP1B%5J;1~MK0U3O0uCw1Y zjb-m6TkA;Bpj4tM`Ju8x-F_%sF}hy zcqNw$J7mt*t*MPANsF;JTDhdKwaHg2E1YPg)awk}o6JS0$KG}J&|qNehV>cZPY6Z z@VA;ME3&#V=S?|dGjL}six`gmtrL=L@sDGP)|oi}1!F~1ffj5y4aSCQD7*G8I}uMw z$7BxT)%Q6sl%3(o2cyD4gGh!%ZyNQwt3q*C&;}(n1o{X9B3eGOKO5Rpc)yk#PFag4 zS#ae4#AWwzNrjI8IeAon^az&YiqcA8FM>{v)XAYiEIJp=s-%~D}sJFaz|(Zd{;ce;{m<%FL@?X(Q1?+*!G025Sb#ZV%N*ljrc5Y|rI z{%l)X_8QNxa3P>qnA!Y}S%o_5oWtv^q*Yl>L9~6e4U)j@Ff%&t`~Ytp9D#~?SW^Nd z|9C#0J5P+3d-{j`?D9%VF5A3&xE5Vay&L#p`LVb+GrsSS0qm1oz9LXQJy<4f?ntX@~{k#MUq`(xV(euLKKI*kHfCjX%GF6e82YtfTS!HV1-W8|wg$gL? z7u$C#lTNe~Z*J;4k~**W^8_yh3S+k`a`Oz9=DgCxu!q9t(Hj~=`5`4emCL3zSt#db z8o_%zNatuZwAiZ@^J^^Cu%c`i!$1@g8tbwS9?i1I`SXU!qF9V785VaZPEt+dhq8jp zUW~-mF$Vex-^TZyB~zR}n*y+TK*#G1)ipdVs%KW(=g_&$4C*Bm^46Ec{eoarKp^|V zUHCXO)Wu0tA;^{rD}e+N%N&?ycWVk?A}7*^aIUeGvZq1F&AZfV6gfOCzyxO*&%3uK zn^(}?vV-}v4yAWBww%iu-k0CdA%Wu2m2BNxO^dA`0c^w{ zp2_UPIB_xyP_lOW3hMRq>3Ddu%8<*HX;VGiF1^ucnes63GR8C~{SGBB`L&_T?_PjA zfj;+ObJ@4*(-Vh@nj&kVpslg)cD|~_*^zQ4qq+a|=1lg+v3b>~-&2=D0BOvyJ2h)a z2hR~L8ck{eJFHn*uKEqWY#Rj$OgA0>rmN_)yr z<^t;LySH6r%fS}?v^ag)@Y>S+Pm=^S8gv=m$=*YIVI}mO(#U;Q_`_!PqIG1jz6gu~ zvKt+@Z!D3_!F$1cko?Jfwd2oY;NJ@`*S#tVa4k0cP)z@~L)J@as()kIo$-IdZ_Vei zT$&NOXLeQRJ+xDSM1pl+d3k}oVzdR%r{l{C$R%nDZ=?vv5#B&k6=@BY{x!%0$*cSz zdMPP6SRC;usURLRIfQZ90p|%%L50SpJO1)IVAH>d@i@gS@=t09&xGIXEiI4uf`m{^ zh<7xnJhuWDFR#4&puJ$pKy$LEcz~9@T>lHV(YpVzjE6|GQfIOdE{4B$bqA87GxKkV zh^x-wKz1;?5)=;F-t$3Kn-&jTnQbI0Q7ta33+_gkQeXkI>hlY7k{*CH9^7uQK#kx2 zQFnX$RZ~i8sLA98$?aMU#iqu=JTzztPh!54OArq+GCzDq|DYF>@bKczxy27X!pOGG3 zRJ;Cs{al7#KHGT|8JNF`~4K#s^v$KD>gY2hap@{Hg|ZUSn9#j ztYHXk+d*+Lg}6j}6sk{9zCJB{jdrNi%NjqGcXCq5W9FK;-aR+>{N>rvE(Vo=>vRW2 z8b&S@=hE;8)L5GX5hj=D%HI^sRpvV->+xon+_zOuFVg2@pbV_S`U6eM1Uv12m&dLz zIk|{12|bum3~HW+*Mp?24VR8}P7AguU_<-Gtta|JCG4Nvl)p#FT!c$0Lh(6R!SCi= zZ6#zxDS39ys9Ed7f4yRY8IzV0=5hcg3f^~$U{sH}Ja!7BRi3zS5o2PgDB`WK9li|Ql(W63S%+aK8F zYj59@U%nl>jLDSj9*Uj|hE>Yxv_PJ19TSAOsJKWdp~m3l8irmdAVSBpFg_LXw14iR z_+36=bUV|(@WrJZOEVgXKh{!bqafjT9AoUk>Qd;GB+@(ex|&0v{(2;W;W$CXfc>O| zxZ6LVDR!?@3`fW^OJ~8A2u&bDW=&K{XQpvW^OY8A<yaTrJqcP7i^nE3cT`VzX<&rPn0ComEfa|@pXS9u!3tW984ZRS2(0;+B`^@A1c>8u%<#m)4}XOd%j5SUT+^*g-~3!* z{pD|b+$5C6;9)uO1TYF4q>$(I7@9TRGCpI*U&}5dV>cm2^C6RBRHht3YoHJZA3UUB zO<2J%o}z+{W}LcThUnDpN!GxY(O4jm5)GSfGIzUlxM5(81o+@!1Yw9aG?>gR46L?X zf_#|~biE&Noqj*CwKd=18)#Ppu{zNt>xVjx6r+CRL`QSIhY`mMtwg-*i zVgUn6qOL>qH?HRt5cs>_hn-mE3Ti^Wj&Kz+x({P)0-#PT8Q=ac_L<{|l=A#*lIpYEnARWjYS&|z z=TiI>v>7YT)?_~g>{J9uo``-GT|N6*xcnBn5Fb{MG(qVBs0=2!goq^i7LrYnh<)Jn z0{XfmL>UT_97nIcyu6JBW7kZ%Z)652m;`mq;oA5k4GNAoJk zRA5t*GvqHm4B_A})|?_Ksl3DIB-`8BNdKe|Be8191?z^M4yYdUjbdQuws4h)6e1lh z^lCkCc$)$d?T;g`swoidOukUn*w^=nRz-WRI-cz>SElJKtq|QlXmPgvJFQQ+I^y=? zh`&)zCvks($7iQ87@E*MAI)RWw_{hPQYy_HzTtsYSRQd$!04V%15}frUS!H7i=Vdi zBxU=DxPek4*%Ot4pgoySe`tU8%!1CaQR>~RP6dU1hegwXf>X0MdgHZh#`$k1ruEu$ zNh9uRccW2mXu_w}?!{{G9VB7Ozpn5{17W{dP4i0%kaXSd$%(W3{dU^$;HTFcy6L@Y zH~>n5tVV)UL!!URjMdP>^}(GM^2~r{`H&mB50VhiQpU$RJh;4}au_AXmj~t0QGyy|5OE;0Tsnx5eghgy=M1Q1exHy z(38cFTz`0tq_OV)T<=XK3aC|9Z*TUlkUc9c3=lU*j2AVKwr=U}oDr-er6)wv44h1b z{Rda#-*!QgqUqjXeI)-HVvq!`3@$>Cvm1+k56Tv-wz>kmT{RM3?NuM-Y7u5mO zI*n^xh71p{gBi+wSYQ`DMdVtieL%Ir61gmSng@M(5%EzqIQ-q@h!F%m9Skcqn_@~R zyQ=@yLC`nwht4b5q_?Hp?cQxK013Sz*WYe2psua^_54|g)!-4?0qcMYB`{(u^vlF%gJZ4b-!y|odZMjoQVBK3i(86aSsEIEC|FczHj zA@P)z)fPOUn8wa#i(XzH=7utsVDj=G^aZ|7E!HRkbVz?oD9rSdBf#5uUhgHXG{>&M zajRI7-qDbu#U(Md`PvFtFacWt_+xT-EmAsuPN{3z{f@;La zE8;Z9BQW3Zq{m#)sDI_>_M`va4&k)>?j7pfm~A7h*if39&2TK90 z-Nm9FX6rLokM2fLMqPf?3}x5hvnV{2!b0OU{j?VL$dM9fW7lwE^>J3KDTO4(XL~5V z$~Vp1_deWaojGjgTLs4LJYxxJ#Q$lZ!tG{B7aRU16EvyoFIv~!Riub}uM+d8vxm4` z4|sDg-n`6(rUJdI;09-i#Z&hLO=vAXMP1Vq7PT0n^mlswHl&ZR*(XZcz9Hi z5xe&>t9E~;;cn{0tpakjPJ3~9$u`8R$umE5`C-JyNUMR-CT~$$kbJQ&)grXxE!;pg zPYF$SV2;a#K%y_=9X9L1sEk@tq^*C+QWPSvIaYTpKHqsrhCmG>clTZ?^dOZJx{-A% z79=9A(M$oZk|zvBoCSdL2SZwN~t%OI0Pz zTq#xtTcm)xKi)C+nE1p>p>_2Mz2%)M^_d!83z`~QB9~wV#-HMxp*bS-xEtJHR-xXJ zg4V*TT%^MC5H~fu{;Z#7Q58Ry2Bky?o4a@gGt1U{O zNUSqtFpRx_cu_w4f;Ai(tM@j~f5zu5p`XjMI+T|CpSU%T# zW5Z*n7xI0#&c0GSa&n_x%Y(*e^Yf3*T3LHh9-GmpuNsfnw|f@3U(TGp@!x00 zjJTuxR+oM6oDh2;D%EVD?;gkRGDZG}?z8@k&H{PWqM+bH_xy%)Q$9c6w^!iJ%hdE9 z%O))*=kT0EcNBF6AL=StM>i-gQf)hPw?))hc>$9`Mai)%Ki@CPU7}wi<}dL_G$2Hx zA%2_A5$n0h0mm%mU!F8ixWulYvrIB7%-rVdV!Mz)<&Up7l?Q&k;!?6MSbXmC7>B(p zR~x*4>d?_pdU?9Ww)!l7RxO@ioZ5Chj+dU>UflIKI^y*u>CfSQZig4u@JwGeV^@}3 z)vK_?isRQRes+7W_@*BR}6S+grWUTqU zQ2oz;W%Z*c%``v9Ka78>Q=u;U+;8q7*V)XU#e#C4%|10nFYV5rBB|wmH~$@Q$UXCi zTS)NV&J!@@A?JOLvwr@vKf3q7S(701wWo;(?yo&=&vH{O^`G`1cQfu35ctPK)ZEJX z+LfDuQ!+rXZ9=jbm{B%yZfg$+#HOSxDg!~X_|3=@AaKLAj0`3J_}?2|?0j;fp_%~* NJYD@<);T3K0RVSRBoqJu literal 103904 zcmdqI^LHjuv@IH^)3I&a?AW$#+fF*RZQEaL+jcr;$L39+an2j(y?5^Y1MdE%zFJka zzpAmT_L^(Xxx?jU#bAG8{R9F6f|U>#Rs;e9E&~Drk^cel9ofjdru^Q3ISEQA|M+g+ zKa9h^_c5JC)SZ>=Or6~f98G}CZ0&4JXq}84O-yW^%vDWG14j009vI zNeBxlyJuZ&xj8EjZS>w;ZFQe^2@oKFP95y&JF{Xhdl6jqQ|5cued@TVY( zkVK8&PA2MlqT{(o5dVRo==#Kag%5?`$v+!*$4P$NYkHO4M*6gt?%^sbB`Jx7BBFpo zn#%aTfGYp}Gf7JUSW*E+WGq?PU-5h2krXxWUsziLoZ{b!YD`bQbiBVek~KvjNd*)U3Do64#ozG*Nh*HI?|56nPx=2mtZeIO z!7B8td2jzPrl*+W_;Idt^%d7N_YHmqod#<199`;Sq|!s*OlMEyTHzO$PZ#QO;QDd) z`_xl(!Ml#Kzo+a;F*_|zINp5P&#!W;VS&_fHq`Y=clx(2s3yDCoa_zfLOvrXx3 zOZ5PGIcQTaAd?*(r(^vR@&=EiTAFpQ&*nGpINMG;ZAh_s0+J}Q9sJ#^wnUV}-PRVM zWY4gj5a&XPVnHwuO-8M*F{KMA&HML|C9|)A+HTWT8+5DNKraJ{QnEnXo$1l6w} z5yI$XlS*%qUgP?Qc_oeS_JrXpJcKgOLFi=d_PU+X-#6D2=^Hhtv%!38P0O3!o|GKv zXY%YcWcLByuPx{VP1Yce_!FYzMyQt=<^GnN*ccZicM)p!;tWl|t z`{Pnd*@Hsmo!xQQ@nZv|ImE5{_q*=7L5e}K_LWA}*$2afd++?p-N+eC4hFA3oXf{2 zD!jLlIdiw>@=pD51pB?sam?GFzY_161ZbL13=25~dJ z5JYk>hM(9MQ>A{T&vqa(8sw~AYzLuPjjwcQ6C9^+06@S&HtW-Do>ASi;Pk4G-)#)d zh6AR-)^qev3~)(u6dtV2GhDY~%k}A1Ie|tjd8^Pw>{X?>I<=)BXk&V6q$rJEtPa>s zZOy#SAg3b|VeQ0>s2}05YguRxajbeSC8zp6owwxMG zu8us(^k36_Ku95hGbu{AlrTPd_`zg^l&o2B?Ha<>Y(^)yPB?&w6PV z{B?bsBhfim#0~zj)`j0wuo+ua zL^AdX(C-6ji}!WS8uT;=A)~yRhLGqu#ZA{9Arp^eC^R=Wta}UVDb-*>nCj~6?D=d6 zYdyH0B_9MSNZ%afW0B{U&Hw_*z~BKP=^aRFi`G(kG0eR?vgsEbnlVLy9sHxC@@c2_ z>XYJQ!#CWSZDM=dWMqzMiXy`tA*OCXiE~6K3d;z_M~f`mDtu5NZElG?JE(sbA6EzD zz-|cwabtCxm}MV6TAW+l1}gvv)9WTuED}eg)O557{&7Y#Cm^H_BM;ZQ@9!6&Im~ zgGQG@-xHHVgiRk7#&P&3L4wKYMpC20Gd}8EN9BDoe%?yuh*K(aTa~-I=`a(yJuIwf z=86P(xq|5+PD(f{!QD9ZVzpk#^lq@o=Xe=wn*O2n7`MsOR=}kv0VUQ9|W2YrdJ+hk?8;6MKwBf@qHZqk~ zF#|S>0vc^9<;qhfk-({}G0R?Cn~10;km=c>(tXKOuH>s*7;Pq#0yGm1AyNzV#k*EX zIIF?SoEGY~mI9QW)3%#3`|aSI%Xd$sq7WvxOLCbGkC+Gl4%Mo@yMgWR`X{KKI>Bj8 zB2%SRW2+c9F>+S!Zip!(9(+CSnQGIdNw z*Lj17g2;{vwoG<4Qb!MUn2KUzF=hulUcfjj^`McCB)<~*vfBsctO-9MgaOORc5gKqtakcP1Jr z4$m?VX3Bp2w2Qz@4j1A^WfPbK1FOTdBk~>U8AFx}QAN^>jZ4U~IYz=g1IZ0tgP%mdv z5JfNpxjDvD-cFi6mC59=tm4l;+g=&w<*txFX8Z+}$&PqD&)MYw>M;CsvF6CDQdUOB0^A@jnbM@+!Nyvs8y{Eda(gs#&RV!5u zI^4cw4M>=0zUALFP5lk9^O)B)Syw56t{Fp;rpY=d?f$N$$|swT2#$NU50Jtuz<)L4 zS9}LfZ*~C^rJ>vRKy!yZ?K^?f}x?MJRK>?tgKQ0U1i9n7jyz8tP27$u16p)6qgy!>wHNbjM=x~AUj~kJYpCnye z!`T#U&WayT?t)z)dN3Xx{E*&$_Qd$JiRt<`N~|^med@H=gz5Ms$PB_1l+a`%VTCoF zl$!3^TBvqXucXRkY+d>NJc+Pp&Ocw7Qc!zAqmw(m85Y3zJNsgzF*#|px${L6c{~$n zMC7)^>U)wa0p@D|(em@>Yq{RZ%PWm{2mL`J7w^jUF4y=GEz~pb1J_k!MGUz8TER8r zyQ_;wICuYA043jJCX-dZw7ZchfY89~wa|KE>Y zaG;6rNPf1Mo0u*Y>r;!$SclIf(w;2RB*l^9-vvE=q}E!buP6XH!Nn{Xhvyf0AyKDV z6IR<6pKB^i>twDT(F}-vbSU!m0~H~sjzqcMh6uH7l@hM_c6+?=u%VpKRJ2SO^t?j< zB9%n{9jwK9p^@gfduA0cd6@wCH6IuHD8yIlkOrmrbbEIWOM!YB8!Jb!J5)K>;AH2! znXgdq<(C0w#qsDZvULpv5@2-FM1fhKTCkxt_2W5m274sssT?6IwKJd86I$*OBESDuU&-mdx*rwpol)(4i!9f^p5>GmGFpT896gNnM*0;Jexck< z#ww81lG^Eq@J}PXu)~M=1&u~)N@(AYaPT+624jUP$WjLPL2XsL?eS&W4$gE>T0@L? zkn0sUMzj8(dy2MUBngA>pLUE}DygX%FZRaAvaXk#W7AtB;%q@mooVdhccFJ{ji}b^ z?a9>}`>pOS=%x`Vw817TvEJ8*G@t5Bp$^Du2!8u_3jkodd#aHe`i;3uKPB}}Yha_- z=7JFx;^^0I;dC4y@AmJfDz;?zRFOGev6VT!SyJ}ZYmN$D@cR>~*SvLaq9tVS)1CH7 z+9V5CvSq~_-m`;87f28Mi3LSn!eDgFsm;kLTN~2(X$iF#(wr~yg`eJKj45>_W4JfJ zj}ehXqPfw(D(83bwt^I2m`zrJNGz;Sk0-xq7|7F5u_R&OVM90sOX^8(u z)^2vt2+GIk*WF7IIE_wo+S+~yqv=#|&!N$8Xzf%m213g*FEE)>R?VUj^$U z$(?oV&-~@st?b0OB15l?v?!qUMNItE^J@GmynR$g0*RaHUgl+&oteXgn&5$YZ`WQ@G?j#~5-08NA$Y9hKLsz|jcGzn3tzWG5?CC_=v z@F;HT_}i!_>Remk_E|Ya?vbNbE9~A6V)&`7>bLPYtG79qq#xR zsp@&g>`F>Nr1GI(7lOcp**Jkab-Sml#Njm9(2)6@ww?#j{J$h4$#;H zAu1luYf2!bY;dw>FUQ5Duq6vjtI9z_&=sb7$Rd__rM=8NKl4@~V*_k?ZHt--`Zkk1}l)T9*fINLlFO~1(|mRj$mu(2mOH6aB&kBUgS z|IR=a<3N^8C~f?)n4OhYxYza_;Qn$% z9D$}`dmF`!&TY0T+wLGym7=>K;uC*7_ISEjRIqnQ&S&e$v+sBg;fD=JIIC5dVw=LQ8f@Hsd*LT6!++%+m| zUPK!*WE9y|CMw^9bTLf7hT`jOfs&{_EAy*CSc63XASIt~K6Y$_1S`{N36tCP!Uf&+$X2s6t4J6r#Bp17rpj?_Q+P?|JIPSwV2JL(iPn$$`FCw8#lCEDmv zYcXR2Yzi9bFUSn!U=yoTZR_*@eHs98Xc0bA;@rlcX~q4&^u$NFA?9dI4hwP7O@_{c z2g}xq*Gu(AnRPStX(+l>O~W|8lD;af5oG{U$#QOz8DS@8zVU2*5Pizh+iNEX$1(85 zQJhYA-SEvi(=-#OqgjP?M&-^kW+*If<-hjCkNWM}g>cl!>zpDM%B6;fm>n;!1vKsy zQ0pzjiq8-@50D&izf{lKEdu)VGNNLTL&LN&@Tr@vfzReIVvvmaqjqtPMFZ%F${Sqx zIT;JX#Q;$0PEA{Vhk9D!ndNbv^+#-xNV;hRGB#wCx67Um+EDVt{7|rLkzMaVYtAn@ zwWXO+=YJyh<+GrTltD9+?1h}H_4$L}2L~VbHdvw3sR`1?XImA( zOckHIv{(?6H5csqT@wJNq&=NZFgle%yQiqa?!U$Hyxdq%K^#wsC_$!mu-7uk%$qG6 zzriw^-m_za-4+Cri#;y3&;mbbhH2@&zYGV$d@RnMaLlsfykq;T0+|qp%6V#k^MjP` zDPO3ON4h%wj80G=9z0eTgP1iY=gt`-)aqVli&!`79K(Dw8!R_4s2vBA1=1Mub5Q zPHSv_KJdkRQ2od@ZF1zV8I#LCHyaF`*<$3@vqM)P_rp%UUq^!a3jF>d{mPyoQzB9g zow0l6&^uF`b~@r{S_>R~b8V1a^An~}C6asUwM|R}S%QZ3I!>%E=ameo=jjGp-IhhM z`W%QhkEapXR8L0l$b)YF7&L8}$Ez3G`!i1PWg|$@zwuLuX@8zSmO2Is)W1$WJ}!wA zZ9l9PjP!%D;ccP9a0$WacTU6Jyr2i;B7yn# z?d0MlV|nAL&5)ANWHDddUs=SJc>3aYT0mrN-)wb4lBce#cShUha57!@T~9Nb9_-wO zNzrkqQ34qeQF~Dq2MM{79XC|VpLZn)zDu$rK^>FJbnI8q1=opGxz}*YdyRBY)zr!f zA7ffI!o37$XfG)Z_(&9Uc8!>=&c~2{&#pNQvUvDC6f(##9tVd*>4XFI``8vcdEJAL zJq75vPPnBF_#CQ9@{TaX{FHMQ%w>L4w;^n?N{Bh9OD ztNzzhk(^98Y7Hdm1d6G{37FApvk`52i6nec=2n3eevW@OYVQc0=C`gYBNlP-(-{n+ z!}w)>6X|Hryv+)hxF?*Kg0;^|%`*r)`|{+mF!se8If53z4FUs6-7Y6n2QR z$rah@Gom>*`10#ZO9kr7Z-quXv5=8MqHUBk)!%f;cH#n(IoUm&@$QIuztA&X$0!5a z_HmMQke)=3e}vzB0$+pIir{aB2%@>f{$|@mT43ajdJ%a!2wf?U z;B4J-?EAZ^MHD51IulmzJ@R{-5jr_3JgVmX@$sBaIK$!Li$bFN)v4pbTui<1m|)7K z6fs2wH>(xOOobd!v?z_yHu{!@Mhn-HCHrApdoUw##!!R^sI|!{yC3DwleKiZJ^ewy zMuLkS(RdQUqB|+;yQFppt5v;PTD<|`m)H1UgaMB^@ip_S?KfeJo~p{+ zXhhAc``H`AuaM-|wuzgEQ~6w^@eM5weM-uKT)Z6PyC!^%rgkG+WR%>7rw*z^NPj#u z>Ni8mKW?$Q!I^pzWtx4C7jzwer7XI&b!LJm9@WtjI=RBH^u@FMfGQk&N(Zb^N8Iit z4zxYP-H51AXP6fBo>K#ORqTfj_Z1{9BkT;D^D#Q(`4Sgb5sKHYr8{*l>wi=;%o zxPU(YKK*aKNL;x5tnq>~>IL$1cnRvkDC%-OC*I8JW^A#zO8cF9AeTC)5|V(mMV}}V z3vJuP19)uGs&#`0sm=Sg5a_KCO9mqL*R&Q}S zrCJZ1fG8pDC&BR)u(0sY@1jRm-o;p(jKtynn90KRipC~di>v3=3p$+>2OGdI@J9-$8sJ&eAO z7V9psd$LMYr=?^IFJrRSW%qcwGi4IJryelg)!6l(c&^@GDBCMN>1$g?r)`B0JG383 zn!Z>hpz7rhr%WNN&X6$f!5uqBhs*@80OkMk0<7L>&^&DO$^88sNY`CUG`iz0)a%g1 zaj?->+~CHz=kT@G%0y>J*M(dwa$fk5?XgVmd#T8`s>nq?1Kuc+YmVo|LqB~)6aP@%M12Z-=gev6T z<;UC(W@D!L#sG8brNLr@S|ZEG(52!_lbUctVbV3SuZD7Hms&Vxr~_$oy`PdvrZe^F zR*OVN(gLRTyL^{}%*t&EVg@shRL@Oe2;lX*g^8Ack zLMabxpSCQ--|4ETg;OLo&4w&qPxZ&CE6O36Fw@xNn`04@kM9g@jliO3!S~CF&PmL& zg2SUpKRyo^88OX`>2FkMAA?4hp9i(ZVg;l8~%%nzC-uHHN`;8r`e zz)+bbU#oqMR_zRF%oEPi%=xHJEb*K}F_oM6r%82EXW|lJTD^)VaZ2ap`siLZEEkHu z{)0zUDiHVxsbMEKI}$vVI+`*P9Y)y?MMLw2WilYSud0u~goXJCca~kydr}e)Hj@P( zoS5jAbuM5bzQA3@|laJ_UZp_EOVXb8!i!J{;YHtCK{#n0PQHWs z3k7g%Rn1}smBc%4g!>Ku=NVPx~?7V^#Y7HfD?QHo#~_re+}F%BahoGlJ*naLhHEx zBn_H{{U>^4=Y$A?Gp;nL7n74A`K=i~>*6L9RQIjJWq&koB}@qiWfL9!R;O=j4Q1$b-D!r9abnsecJ&wtnLnwnVt`MCMZA8!F|K)t_`n zmsMiSXbI~Rh6sHc+3n}we%(4Uri?mGM$Nk%>_Raql$qSjnEr-Y7Hh{QhMll~ z#P_Z#!$#fwN@eC}>W^db-Jh1|R}aC2%$;=2zYCw`z-*-A$lm^HoJShzu4}EVq^jk# z^8bmAKfbWQI? z*fIUp=gN>1*~WMSm-%45%o;K)axY~!->VPmuFrn)o(D;x)0(_+7{CA=^~+Ra{r`Aw zyEQCtsOuGRb;e-KUo*S6*1gzW;|}i=u8nUyC}{Lry=mRmCyZ0#h28WD!(b^DwexS` zD8ty5?S%d4awyN#U2zg9Bq43*i?*cW>{gK(|J(dEHl6)zt?dnCOcPJ@$yTmAJ9mCB9Uk-76MV`CW2^+R zX#GjiYea3qd*zl^LXZNHXU!;E*;Sm(N2D1Uh_=ocn+997r-CIaEE+sOfTd7`8{}3h zykg4ux*euXC1H@&!qI$MZ2s|v0?L^^a?Tk2Do#+bL=_UVX8F@CX&soYJ7GI>Ob20{kLl>KHxOPPw@TMmuvv_(3hl}rb2 z2Akw>1!@Wbd?bbp+s&Akwx#QrN=*9!89TWIhsnw;#D8$-SOu8UhEG3JMjhqG0d_G- z#bSWe#{dGh9}ptsdQW7kCgfaJp=2{Go_2g!s%XlN3rE+d`2 zQf_LG$^3cKTZ_3XY60P!h z$)~a?`c|ixl`TOrAJ32tV`%S^+#q;dBD7wtp++sj z8gE-s65?f4X=g-F@0fb!bod~vvJ$y;Vz&)nJaZg;XvY>UaZ2qr*@BeV&BUanj08&L zMa?q^oksazsWavHr2Wr4IPRD7Q~pZ=ZuvgE-+5pXM$I=0I6E!%Ms7vny9D53Mc?sD zNKacat3O@4*D8szBJ=xMVa@T~fdLi&hge%MDk<5wVJ-N(qrc^Jy#L`^RQx}i8vn05 zJeHKmPOH^?VXz|fO{IGTsnqIz7gX@5r*{t!Y^_&@FVedR!Z*PI@! zDYRO{^Tkq2%v9*@jy9K}Sb_he1GK%Ak>U_oD%@zRfz_H%zvMPjPHFyCPEGvV9{SYU zgQk4u$y=Tdc{OY4-O6;)RtSHFZ+)Dh z1XrHZ#j&k3R%+;z>EkgJbDqW+ve9R$Rrx{hhszD;GIPb%2+T(-yk70}J4u3rJ(o{r z5?O5vY-J{Wz5?ng_wEn3D-9{LhrISdVX!|2j7B#RQ-meT%-`r zEQSo9$Qvx}j!3kj(Gs|0$k7}>rxmUb@3-MyJFmHw1t z)D&$SXA^tlOCU`ZO6j;z+?}v-?zfkpNO+?R0SQ}y5(%^Lj13D;?>o23G{1u>QU8kG z#v2u_gE%4pNB{2&LWG3WZi(vBZhbQ<3~OF6PcBZE`QVmVR~Pz>xyZUvd2SY1uQc-Y z=wcKr>B6$uwR$u79(wM6FUDX3Tg09#*MM^FXlzmaTTPk%Z7`M|dm>PJ`-^MWBRHQN zj#%?%Z}mqw6R2=#-9pt1@yB1*U?OOP%)3AnqCKL4fn4Y4U80CWAPagGaw9h*bM<@3 z#st1!3UuWV=>_i}^G^-t>r~R&zWSb(@9K1<`wHVf$*-F8<2qZ}A2el&{c2~PO~ifa zYB2iGKQiY?&3`Sdhn6p%K%VqvNv$x#;Yf(Fuvhq9V^^-&nC_e!McJIi2S&>z;kQN? zExfJOITKE(eF%5h6MN1xrC7WA`=;UVyk+Q=V+p|a7;E)&%H~S!T{H_Qk8Mjng&k)8 z^;+w2gV%!K3qLF|G&El)K|+>gn|X^yZl508IcgXqOp_X#CmH|IZIkZF7T=0nsorSL z8p-DlLydXyX2dyi|10TmedYvS)T!5?aGV^Qqumc)>`^YyrEWMlxe%jcDctu0z5D$E zjE*)4ZU52f=pJ*L=1ic^uhCCg;d3JDpb|-{>r74_U_eX-cKpYIqV)Oj%lE*#kUs5R zLCaFrGmETC>_*^&#W%On-{}nW81z9OB&i%G8e2r4EO@6w1X-b+^@Gfs{AJj5vihV{ z<6ePAFu^@P!Lm6C855$Bk!4UU_)Z=($Hji36$)jraPz_>3uS*kpGOZ|Txo z9I>!MR=XadGD>Log&$&0;coOoBQtu1wxbp$_va&vg#kb(bk4xD3|MwIEGvzZm)vt# zT-zp8OCe^4yv1Kf$gFvI7Xa_w|4hGWlh56ZvbJ~omE+kG+U{o2sb zHC)#M$`AWq>43gs1&AY}&hS@L#!9X5It1O~<3 z-|8n%k)5_cl>y+2{10K=^6+IHEYU&CrsHleQ5ITofQQ5ib&2ENsx>!>tL6V!QDC#q zl5fr5Y}uAtAl(Rc517PdjR!4Hr~gGyl1QX~{W!D%l+d2~_l+6ai7TsxZW=?T1HEE@ z*d)dK9m=mL!0ltYaoP+>4d)Hsj35J2&e#-5(~@VreL3 z@|MfMQS*Yr+7FcQ>mCntffp$}X@5yQ*&fII=TKqAPG?jszvdj6xjIqdgr}HX3K+0t zN-14pj%IJ^El1X}w?*jpRz5Au%z6&`&ZR7F(QITTF2uiAV&Zl9x`c9!w{bD$?lzVo zn0@u>z{$69eB5!pp2QrU6GutEJFE4G*!Tz1b7B_aQkUsjN##MM=aM2F#1f(3*V|}R z&K67O{7H@F{(NU4O^5c*g#`P=>2i%NO5_76`!GJd%TE+94~Szh7=xK>*%k9DZGDfP zh#-hiduM}S3KtMB>WOT!BV1z$v?pSE?0*n#)N{=K3+VW)rc+?10HUG z-(RO97b70``Y%ywG&|!LQtTzUb#oe$o4v07B8@ER5lKfjI$3JKbII|HY3bIR?7OSbIuKY$NJyypRrzg(DAeupT;T$sT% z*va*CoFEj_a-gfQ)%pgchiG_?{!EHh-+1JeXY(J*N)n6BNdAY_#*#0~!JDkt8bVdz zzr#J!JcW3)PbhgQbULqb72n<7u9TZC79Qq+BuVZnqmZ&IS{${lBwIQ0En@tSD{kh6 zz6xp_znElgOin9kFQn*)0XEbo(~xD~UE$|z%D1IV*N4~6wwjQ8`T-(}vZjSj+ok*a zY%VxFUoNjc)R34GVgX(YyweqJoZrBp1Z1&Lm~VJR?iE?P421sOJ4(!fG&YK~R&kaO zpVSiGSZ0_{2b)wa5m1HoPJ?>qVc-T|VE)0L=1B07Ta)Yv|Gjdj=m%ZuH1SrQJ*UGM zu}{!AXugyCq7%zyOG;;Ll<6>iU|BXxhO5kLJ<(xqO=g196MCL@2j+)2?l|gnU~UIE z;Cr!%VbkgR8c~c%E~+Zu$hw_wzU>VHx3#M`v~t128#8B`tBY8cCQI0IGSM|atIi8j zDbLxdd)>k0(g|_|-FMt6R&39#We-t1D1#ox>|rfyl7X6p?ltacNfJ4k{RcifG};qE zfmP37natQ4-kz*1&1Y215;XE3(;?bChNWM=!+Xdr8p%(hl!@-^HTmg3=e(LgXaB=$ z@~wZoe61dXe4Lad^ftAP zZTeg8e?o|puoGLq)OXmOrl_YBQ-1$q-cT%mE1ml~y*;>VHn@W+6b{6DZ~QAb4XSy@ zTk>EhQ4HeSszKu(l3cK+w!wVv-eQ$qc*l~w9bGBkppOUAX`NP`6O?Q%ekI{m`%4b! zzvIlsW5YwP7}%(HL#XEFf#-5NsWaBI{yIh)PUC~ul+BM}@zW-%{dUKxGD2RoIerE(seOF7 zNGaiiJthwxt~-~hJyLKF3*7qP@5WpU6lze%){yZS{V@qtUe;A@a=0 zf4bxH!g=caQ79FKBT($fh#xtJT&x2cVVEOIFo%e%>QLbB5DG&u0&-KJ$hF=0WRHPg zY7F8q8fr?#`0JkAJjA!`a$A}rE1v>%Lp>1WIO>8`O%WqwkK^O>AC!`)f z(c_6k3W}X;cSt`j#qzlOZM{X?;Cu*GXl>`M4R4#+IhUn&%mG2&jq+RceubHPBRtQM zI^MjEcz!|1H)gAx4N!dJziJKQUEouxb*W((2iW0a3tw_5=g`?i;zB?vFHPPqBq6X}_a< z3SZ1G5b;hd2~x;k9IqT?vpGkTV!#>CZYJN%DJq%%yl?KlUz;vQPy41c3|&t!&}K!K z1q>0ZDBhV$x2g4u6mJ$IDY_rGeU4<-pTn)*_l^{2W2KHzWY&7gVyF8D8w}X;CBHQ= zF$a8utq({@83YUEZphJUum8`N@bJGwEmlZO_$mKeJbK9k-ixD<{?h(@A<2KoO5&4+Pl52v6F5_=XwYcnSJ)^=#TF7VcgZG-B#qN)SgN)ZC|!KbkEg9T17hWA6z)WX;xcSYKjl9@t@w`Fy1}v*&WWMD)o>ET7M7AaEwG3W|+Q8PjTG* z_fJrUX`}^LXa<$3e4en^Pz2TEfJuJCR(^I$MNSBaLh%3GD48~>MTY4fqR1H$RBoGh z$Ly_lpdn7l?HC$RBft40faJm;!dmJ!1J`J=5Yzy?Mwj1*tY=4zMYrdAL8Jk+^;_sx zzTNqUXwU&zb^`A9ZsBiGOpa?EPv^^VDOhOxV|%*-`E*5h%Rj3eIq{X#Ce5uR(FX_j zSvu!lTyiaD|E&t>V9k#4x)4;x^9bpTy;1jtJV&ekW4LTpBP6BnxGFnTQEYd@rRG@O zlSBeskj_I&!Y#}#lRgHn%i5FVBa0X>)$sZkquvagqXnAn_5gKJ#bIt+n*d3 zmZDf3DPE_8%mPUAwu|H#Bqb+rNxrW7FeQU~4)4%F-caHb@7K9Qx5W!WAA#`b_!elX zqJ1S%beuVVl}4hlSZP4vuOyI6f_IE=0yxDJ;wBmz#fs8cgcq#$uv63mxTOoWEU)op zq%VIburG?yd?&ud`77Hv7R30*DWP$s!mqC7L`~(T@V6 z2t^cdROqvFtG)n~iO90mI%bS;Pt0fl04- zcJ4OegSOI{k0+6R^>$`A|#=nd#cNGIFtN_ zECV9R(jzVr6&n|4B|1ijzsC(jrz5))<~GsnR-1^R1>0sa*uvzuTzYE{kgqR>NeUjJ zPfPovZ?hLb8W*&V7H%YNhgXi}oPz@Y?RhonOmR zEOU%6ZA<}G(y$9nd#4?bkd)OrqR7()(xZ*MZn(%{ACQ>->TPsIGqoI7>Zjfd3Gb38 zkd@pS2+1M%1Ii`C>7&U7N>RVVkYOk4a;B+V0B55y&Erlj(LyF~8+B!YMF5ng;^`}> zKDMRMwJ7~P5RwxSA$TA;HpQDy2~F-#y6sdMT1mXys1*Q0ro!+^Bt3?#vzI&N_kVc- z7_5K`@h|u_QTepnIJ4@85^*XL$xSxewLQ78eXB7)AH*-MGx+n!Q$Ipc=YX+BqFN0C zl^7KEyKkg%=Yw$V9*YK|VIeHQ7M*6x!NK@d^NjLqFG>tlY*$N)I(1 zrt|d-y?DoemaH^_Mx7d0o#eniWe60pdWFlBzvp5jkFSlT zM8Rkmf0TC7jnIe7GqH<3+7c2M-p_(tIoqDXt@rl!{=qLYgd1N^foJCNcFzf>L~pK% z;;Ui)#IGI{&K9t;hvRBdoQw_u%(1?|huzEN6`Znn#QCCY!hwQ<1|nfZvO)Z7$q9~A zd1$nn_i|$f`uh6z(-=mJ#UgDui~YgSUxbV>-)$P#D5|}YA~ldnkOLM5hKg7;&ExQ} z$c8GQ9@6Cd8hv?6Mx3PI-%X%+&|dyOyN!Gj+WLazfUh#zo$0A7E`xKsHC3$=83c;C+)yn51v9D}WGtN;w2!u^!np+o<0x2MWjHQSeI ziv?$$@@9YN{V(RuIl8iLYxA+HV%xTD+qP}HDyXnx+xCfVqhco&SDc*Ko%eq1ukUSs z-J{o^XY8}~+WU+%)||iRnR5va!f#$2&U#`b-qhxNb?H7?;(i=Zy70aAHppy^DYT>- z>AL3kac|2GP>eD6Hx@r-VS0RE!doZ~=??Q;4?)!jz&`jjl}6LGVNy;*BC7E7#rsr; z)t||w0S1CLtMVV@`&odBLoUp7{VQa~g@>a97iceCD7_g!7< zP3W%mRbX;dSs)FAyf(aw!04;~d`>{`@`^RmWOIuz7!PfWNr+n=8mH#h3UJ+|-EfvUmWGt&>cTl$D&k^on(ocyWx)i(?*?mayxPeL&`3D=@y?k zmY-ZvebH4*;2Csn=_hgT1yQ4pYI_e;@_8TwqZb#GBiCjo1@d9tE=){`&a-?cU}t}} zh~a+PKa{t&OgL>oLdXqndEOG#!a5cDZ+rBtYOnDk#72C~}M;*+5MWkZh{PwU1e@1N;2F}yyCW@@h+;B@jUbhMt6SoI%w0gNH z9u4{1lnG^#3=ZN9*I}YT_Il4j`SkH1^m_eMC`zUuxBtjF-;jl64KB@wq@vyagyfns zdC|3k*y$|cW&8*8nDeoXDiHl!6U&hH>2dA%7-3l9d(r6j&ZbGu+V)E~B zuX5$e6f(5b!q9D!J%AhX3^U_00+2J`$mm$)UeBq4+XpobcPFb1g*Er6p(wg$k!;@RgoJa zezr`i_h0hy1&#Jsh}>xe7a9jV)?j7Ap;xn2NKstilPD2&&D$n(im zL{oVSjIbLQ?JK9Lo)l-ldSC81k)L^K_OF)}IAYLYDsLIkk7vt!Tj}LTM9>XHJRB8+ zEC~^1X;NgTAkd5vY&@8PN7PdN3e{WSfAGqQFMd|(Wrm$Dn^%ovCUuc_`4k&Tk~X+I zwyUvz_vNM4uqY&NDRt!+OtM7}&Qv3>o-p;Rqg#LJMXxe{^1&p5r1P&J@F@OO(9XJ( zhmfQHT3`99o1Ri+!4@$uBsktz1xBSc&~T?97FFb*TQjKJo8a}OYwbs#G;$A}?&-~( z@)JZv=}mA;yb07y_hQx7soDDT&;2i2IPM22Ivzp;7A;OPjdeL=o%#AwuwRJyYG@Wu z?v2g}5Tyi0WT&Fsf!*L$I&EJNdBRG!Mb)E3v=gwH7!i>XJDM+POifqhhZBm;j*YBc zIAfb5?sybrLB4zVHMoa*1mamYNmb+rHSL^ZQXs6JR%Csn zS3Lmk;ZhKA8=ITfvnDQN1!Hl96QJ`9Ey%bUDGBLpf20AiYckUEk?*d;^gUi(s$we+ z+H${ubRU0)cJqDwM^__f)Qy?vsXM9m!-# z`=CrNtA_}7DsrkqNNBkWKaWi{w?Wa~cJk&XHSTp7X6xyeS3}M>_$Bc1$B<$5VN^2# z9~hP3T)UuLDGs^8TT=3KIr?aFWz~uu9MY|75UdOwd6F&LA{$$=5F9lf@J+%TV5$zn z)BcU8oX!&25{_jemp$A-)Y9o!53#?2Z%8w9x*QH$_*h41B95STOiij^6~7lB2+q!w z@BHOjD~clpPTv&DgrDjYfUo$o;YNCMO=-G?pkue_+rYMS@>3Vhrn6uuW%aEknhD=u%%5>vjj>e%4^8=%h zI0B!s7-y!crKU<(-?Dzame1{b82EDrd&_Sb&FzY`dqk3O;8+lHX%z^1jgC)Bh!3Hd z4{~b4P0xPiVJO8#a=}!zxBx{=ODxmm1(6N5U<0a3?T`$|OywbEpFNqTHP3?|+ORpG zMYs@B%%{u567Ol>k5~wF5~Ce#jWk}S?A#mvZ{j(4b#Wva8U!<43({j%OMDc-LYy`c-xv`a$8~g0q+|V_Hw`19kV#i1%b(# zkO7a2RMy+{EW7o=J;J+}AQD4B51d*$n43?Z4HAW25`yEnIn}rvJ@rWLf>E1&nKme6 z^r0u?oe57plrU+zH#Gv3FA;`m8q0GBio!xtJ4%zDBqr@lCz|X0Yt>r_Q z$3M?}kT6`2zDMwr<+tiN{uWAm)JP_kxE6X) zgY2_wWs#CtkyG_oM~pw4cuROF1_!k+3Q*E$3;}8tnMg^ZyK_1+na%V?7I73*VH-T< zN@9EsZ`B$@eQ+AE5wb}uabm}UrBWNZTZzp(LmcyGC@A>k#0UT@<1RCu?~GG=)QoKR z4^W;|Q4kUmvSNAiB$v;^aQ=1fZMSBpM7allNL0uG7ZGUi*KX7R-16fru==6x@d%UDCtdPhKLpscK6zZp!I;noXf)({` zUXI;9ZBKOgpG5S09I)7BJATK8>UQ13X%`@?nh38o!+EZ9ss z{D&3if6U&Tn2}V6?(b*yqUeVmvV&1`G3GW>_49U5#Hxll>CThAM#k*iDi*Asi>5vA zb+}y}Z(u{yhXqcIfUl|WuF1Xk$;DJCp`14TeqOqZ6xE4h7FX$N5ANJR)iRxHy`EgnjwLqOe-giJ_@1S&A3kKB9P&iJ5+~jV zBL9H=G&N_>FL+4)UjDU9MnG&yk-W%?5F3}H!LZ`jev0MONn!xm(}KnJb6NG`7eD4# z4ID~{{C<*fcIerYCdkQvF2-tG$$}UHBGwr>FBR~b6EAjlf4)O0anEAK5hgbCLhDq7 zK^qDi_hT9GFILQ)v!$YCo(d=%>C2RFu{rb=#uM+Mp{{{u1Mx%^#fIXiKW0DPBS2iT zM0*&2XG^xbzPX>b-p$6Y8k`bSO!}tc_D8yVtg_0bKf>QSS~#1P_kFCM8rmIMB0my{>8GIl9h0L}cdgY1A}g{p@M5-ywODRNtb4 zLD1Y2NUOiKq2*InSq)E`+9NMH!maMI6OTu+l0=(+TuF{Y-+%scjwG+lcBL3Z_;C5dm3d>4!nGIYrmVD$rb%w5K4c< zOFh#Yiax$4)}gt;3qyRdnA*L<08LfWNyMJIjKAI2W-8pEUjtW*cgk4CPbE#dYu)I8MFNxM(1_?S-Uje-pmuR7}wj@h>4uE zK1u#a05RHvxHC;_gLGJjjFjEa{?Iu!C)!;V3KMn&zf)2Xi0^l-hCQAiHu z%=vN{o2NLTBlfs@6;&oaAwZheGc!`iazp6^5Y3-t_x3CQ@@tj*#Kum>*#2Iy*-L1f zKjQm&rV1}{5J)CuWgyv@=DpFCr!F;>a+2$a8q{W*Lb4EUbKHp=cGr_5v?YZX%Z52mzL4*FECR z)3a$eZ(|U>oOd&>d}Zj4WfKb4^0%7H*OTOWI^CC|(lNdO(Jv>OwIX71_)+w6tN^N_0r6xlXA>Q?E>Z4#CVQ#iZFd=L z2_#^3+GinZ(tA7DBYtz0t}iWoi`?0dM!Xz7N+yYnrI)SQr7LHX?xLYDeqvxlZ*ih4&0gn0r@i+r3v0W!aD)&^Pygn7y@oK)#~iEn@t-NvYZ_HlXI>j%dzj*=Vq(uP;3jb{-F7czCIaO z_+njZ8u` ziCU^+K_)&aNliM?E+#1%{BH8$jU0NM?j4yK{;+NI2xWy`te~wK*6*TT!pt+|i}au^Pz1DUVa+ z&&H!zUEfpYvYxbajFs7nii<{Yb1AFXN<@hgkL$@l&+w4=j9JQQlM#`qh`iy=`3-7N zKhLLRtOSvek*qL)az@AFZH9FNEr%V*DJ09pBp@RBPZ-jjQzmE3E$#U!<}V}BZM%-l zsw*EAL$}B9`}$n=pfk-B6~4c|QIEbgL_KQPCUAPb-wEcN*G`~o1h#qiGZUg&5xF>E zyU)xDhsxAmei1JcViEX5H;Yq1_tR`eqUBF|u5_soxs|cY8*gT@5MKiOjX=4%1k-Z7 zu&v(i7Lyo`4icUG{?Hv|r+J6|?q}7E<>*I-wm5ZIqt^i^H5xMiscjp*4(g=)e)?j~ z{61guJfY4}O1w+5KCDjT25(1MD?%nGy?ZQd!wB{6#$E9SjwMQxevQvf>^#r8b&}<8 z{`9%EHc5(yas~<{)h5aPQj+)$*cPce5j7=S@4W{wWaqJARC6D(aYtNMfA=;RHi!c&o>F$1-HNibmVX z6ux;gYv58BN-6QUh9W^m({|?lhPPe}dbr|WdA&kaTW^N(@D7soV`Y zrWdni_odw%nacAt9SSx1L5G1FQ78f7?TH>0B6$YH0i*r)`tf4s1xo7rNW1?@VQK2# z>RoeV1FdjWyo2EdMrt@3osU>Wrk|&h_x3|P6+AQfZOUbXJ2G{gdoXSUBsr-5$e3{# z+lUqwq4TY1V<j*?QiEUDmw2!g0d>R<6)WY2^>-u?SryidLF+ui10xMk zv?}9OAIbvpxo$U1q0rd_ z^OyM*;`wyaU(-^mZPQ9t5=j8u%P=?3P_wPYjX6)ZU*+%s1 z-v?zHpP+2UIQghM;Z1Bgp7qfDUbvPfoTD(Mj>(^_wu>_byOIK^Qd=%(@CIJFWp^OD zNm*`0h)yY9Y_U#<8#_`-t@`SId+C1S=~c2q3jy2f`7d68hy^Zt$6uJ^XS7G~oE;Qf zqM5z{yA3Tz%q5=mG9R}Sa!O5=tq+^a+MF*wC2|G>m74nEW_D;4Gr|aF$4ZN~+WfSM zcAFw@a;?Zcvr+N@5@o&K^4FqS9We-M+cPGhlQ2c7VQfK_t zcgOj8>jkN0i5szdaW>q-8Y3wnJUusX!T__?L(yb%L(k2eyxRI1o5u}y^8bHEhW|_D z|Adjb@Pe?8rFz@f9PJx*0R?jYf`|h@fRo_~ zodQwymTn5yL~(#Cm48H!l(+OP9|P@rxJW%P3)# zf4nm8qQsu%u85*UPTWBughcd+M|2I8Cg@wdicp{K)u;pA>;d28dHe&k+-47c-TD@{ zi=#vPy*7c`mj`@CPy3>AAz5*uh|5R-k)#G$E4@xJ$Tacf=9VB7Kw#0}$d7P!VyccJ z!ItrkL;Y5bADmxqp&+dgU~7Sz+>{S_aF~K8o1#hx5wf<__G`^?8NwNPcrK?!BFNXH z_boc;jzYTRWDLqCqA0~5StQPm-im8KFxTY(vQlnIAzYIMp?3+^maBg6mFctxp~LT6 zzY+e@M6DuV8m0I31*P&oL#5Q5_l*{+1nmd0$R7!H0`pxyQql+>!Vp@4%etSAUE%~T$1YZcNB8aVQR@BZ)s8KVFR%s|W@I9t9fF`qKp7=f!BES^6Y zgMEE8S43gEY85HdX2f~>%@MF(msk+a#)I%0UHhIHgZ*>GA@_Q|(fGELCtb>xn46oj zPHZ{f`==1x^hClplFq%3S1xy$7Iyjm+CNwdA7mMu0wLvs-LlZR0&Y&fTpnBe`10tR z3a9o7C-=+X$mgaAZto^VIQlOvoj`VD1WbM(ujNbWJmut{O(>`%)PJR6Ib=IoBY_!$gSW3L zrU6oa-v?IxKk|W9R(16M8;HWJ4NllQ+fERcDBoGMm<)rPnTQt@=jL5ah!-w@S-o$^ z>md`M@^m%3#9(2OLDa94I7+$5qlN#M8Ip4&xv6Y*1txE=cDyl4^j6wg-dm?10~=9L z-Jz=cxc_X(FmvKeODtdAkj@Eyk1W|f6M5FR;-(oNV)zK{{gvJ){*C!N=Re`ABwMH^ ztJ#7;nZG&4T!*m=8R*9k@-P_m9uXt{W){2nXR}xma=-Pb4Gf#Pf0CAw(q0ugnxE>^ zWd0u40~j;NpC!Xa!p?Po|o-}K1T+R=%zGMsOi zA~%_rYQ$igk`7i^>4$rqMc)!NpRcPaO7Qs#_+HuayRm>_;G{26b$4cq&YIG=%)BP+ z)o=NF<>dmU`xw7~*2fi{Hze8ZW69G6s#m*!kYy|3*wn+ijYlv3-@QY*C#C!xo=KhOQd@12ma0NXJU(G z3P$%F82&(*^On=9tOpos^ILBJOD~_Mv!Nn?f;uQv`~$`Je1AKG^oXh{kxPxC(!&$q zk@*gFMhbk8j};s>bHPl@9{FvV4A_*pmxaC$Ur@TtO)5d6C~spnRhHgTH~NN#&}=mcOl4 zjFhh%4#7PLoiQtz?$b0$@bl5P^jcC7{=i`5CYZ624+?z;?;%g*&-;PGJ^tiw%L6ZJ zwcgpQ3k>1gg)oAG*-BCi;wO4psIhXcOkgVj(yIU$ROzIN?1gGM)d8ubgG z)uIoxvn~hpz4?_w2e2j(Jr!UGbN&d5>uLUJkKx?1!T)CFKl8GEHk|sjk^9WFxKsbc z`?&WY__!Aay08GZdUZYWs^+s4+;eqiygp4L_B0C|TBXykPoYou#qu>3qQ=ZD|5!n^ z+vrT6!nM4XGv#fkdS&zts+I5{y3#XeW@^P!!jZ7~6_t5|MrK^9aS7@cvw-vkrLGWpwVhMHBE7dO8=V#~o3K9LmP0t+6xkxLzgHxG*pvnTo;pQh3m!F1QQ3m?lNtBFS`rNONn5o^aB#LvLJIl| z=1|E`2x>`LDd)X^S1&Mf$FnZ~X8B;*x>NhdE`*9C+>pXA(9R=KvSWb7y?SRtSIdN_ z*U^7|h!_N!kpnkyjem6sl>g-tFk!`c@*j*wjl$yP2(AH7;1&q{I`83AYrR2*av(4X zYDvTYBl;-D((~q;{`mGIfN;KBHwIw)R}#ePu8*uuxqEy+_*MjI`+MAc1XN0fPSlM) zW+4fwF&8kF#vFR5STs926FRRw=bsiH6E$4a+jMQ2aty73GW7%)@TXY=K0rMq-idfQLpbdyf^|~A@=j#mT%!2gCFNMW9eh4{@aJ1pJmvc zEHOLPBJZE=s6Dm+l5XB1U0hv@_Z^q2w1J+V+Z3f_B`d%m z8#=~ROk6iSc&UYsvje*-efq^c8Sv(yv-EY?zY0WFk4HZzt2fs0o=g}#mNq2gu3#3? zVXp@D7*kOy*1ni-D%dIUzqmaY8Q1FQKp zM9%S2w2d*2cUb4S{jVaLdoWP69nP)+PsgpPMfQQ;qX7tqy5VIh!;9HE33i%!B35tD zv6J2aLi>}UT_=2EN=4+HjgX|P2G4pjLXy)`6qUx_N>b?1FvTv+y>~H^0$2=ET#Z6?x|BhDMuGRgOzkg-A{`P%Keq2@d z>HL6VICUHfDi!2kixlv4vu_?1Z^F`Y4A<1g<$!OfPZ#k#dUUx*ZJIq|9b2ZWnrjde zQF$*Tff3NnSTaPpJm#q$H*E@0iG~~o$;mR?Ad;ZYh!bvu)(sbO;j#)&J(p!-Y{+ufO!iKJJ6HP~pmqAhpPr?$Gu{$HMoCPptM z3ku;xy%v2ZgwnudeyrC`4LAjZ{r8^_?d$~-Zb%$a=sj09Y+VQ5C6_$qNr0B+wm03J zlPm?lI{ZvSs`|0idCv_6h300XQ?#6}Hs**vkF)R23$`CjxwV4#%lWMd6XOpT`Q}qj zcp8ExbA*=D*TA2x|FOEjVk59aBBt7MvJk(V5ck^@frv?ACKj7HuBB>Ww=LfTN3FPB z9eC7`u$2f;HUaL;C1r2dh4+ar+IYfrR1e1Tp}~-9IYyGjQHH07YV%O`S;iepmu?9X zzR`fm7qSK$eVq-a@bpzMm^RkjJo9Xb{@1F%1jVJcnD@)t!_jRuH8ucae1-@$uf4#i z7|n`B@R!i!*2YTf#R~Llou+-@iLg}()rtP*_)AO5lyr0L&N**QzOV^bfCg;zgD`6iY>h>=e6lhKiCOqto`rD$(!=?t54b62h)Ng8a|M!LEcgqd0_s#|;b{Kjkj z#n=~?H+_+lPon>Aa)?D@bdxn|++qJ(9B5V1qQCWZxX)xh3B;t!q{!|eJlr-hx}8If zEh#M+mAuKKkqfP0ajw`~qIIC?B$KPRu|r zuwS=%{Xm}kVmj`F9T2I4V0}IAs6s{Jv$X7@+endiI?7t9Z_ajp30}DYAj00ntj!TX^dM0uP>v#U*%uf}ly>DdAl zK(@`P+Q9!=C=z)Kqb|T(_TLJSKZjKMg%A9hZupd8 zcdT4g&Qa^tQ8!*GXRG!4De(5h9HCmZexmPJXk!VIw&Aek_e+;!2C)n;f>yL1#e+Ui zwB|k0t$~U8soG-32^F65$#nXIHzT+%#dm7ZgM@bt_(|Q00#>Jt#+wvU)6yNM+(2>6 zKo6GYuku9-DLVj1YDtt z5*8YHgNNV7l_CE?Yc;uG61X8K_Jmbngf@^d8yOIg5O~;chn5BZ-)_?B5!)whleq#CxMKCv$c`TQn;sBWjRH``6+c?+@D6!HH|TN z_`MM7P(q?&X@?e_z#EG~o_WP)%9Yh?4JKI`LZn%pS;EhY7h`Z(`Du3Ay(;jw1=blXQd1HC#G^Qhl>o*#JbI;d37lErLZ znN#s|^?jw|4()`-#ixvg!Zv*ye{@Er8naULyo^W-QZR~lp&=(vsewwog zmIV#9m{V$X%4R;%L}HHrWlJ}oE5&OLqJA$`p-)HM$%rz2Jv;Y*U+bgpaZD~u$BVk0 zoX>q7T{=%Z&bAVn(H`~u;yNDhzZ^Ob8#nVjHotlXMc;_vUfH@@?~X~pW>OpY=VOKU z@`@(%60yhE*XJ@cL;5_&xl9jX2sq&S3_P=yq$}vqJW!Fu-R>Dz@BXe1R!a}dBROtf!XJWnRGYlZ6s=aFT^inF zVX&!blAojZe>(4BabBSR5LnDD)eSB5 zjL!FI1Qq9>m{YWHy85Ac2`{D*)u#@kz8o72~NML z!FaAOnM7mOzbv_rXW|X=R%NNhM4$*liz`K|SWha{N9rp~of8v>9%FnSpB|a0j4V6B zSgS=!mD5ujx*oR>WhXuGi|sDF#ZpZe3AB>)%6^48txcn#7WacW{1f06YkJzZKIfGISH}> zg|gCMeP39D5oSI9qgI9wx`Au9_{N*x&}JVI&&*Z>m!z0ja?w*4S>u%tw*DI#*)LH# znX%vO-P%oDQ#}O|1({evC zw9@Q+E!WJZmc@h)h0NLE2_%AvTSl#P`QWtJ*8FYFoaLpkyn#mfOFUIfM+;Oj7Hl|- zcxsMBw<(izZ1+UMB@}Wwv{S(nF0D56j`T^g^FT^^Ff-E+57NUr2Mb0KH=~wz)sh0j zlXTIuP1hv8OPWR;j_g&&VIv_)q15BoPA|MJf{4M9Bv~694v8Ks8}ZgS*8zZ*NV6)H zy6D#|*_9DOXjW(H?Ql@l!y5}x*|Egg7p3+_aBb_=wAadC0k?h_Kg(mV`O)7UDGUXd zBV`1<@zxqM)O!fT!6sAz*8@q;ogUtIn7ySc+#5G25!--RRTMG3quI�zqS*Uy=xB zeZ$<*XDW$Kiul@=UuwJ$T2-`MAe62yAF)p{V~R%x%$-_t_tab%EP7x}PFo5roM0WA zxKmOC^(GdG>C5q~NKWNYj$2Vt^rH^pX@6IMq*O%fbmz>3H4$?RqL1;({y34)vJ(fp zh2$L4`%v%p2GA~w>M8Se!7@SJ3^sB{AFKT&I)GSTsxf){uIEQuIiD90DywP{X^ETT zUqA;XM7WR)itiVhP4Q02Bl0q7vKPd8yq(V+%Qu&#uz7-90F8!9kqG8spU!m2@3V+7 zlGTuSSGiPAxtV;G*3K4rCkl;aBFSW{6L^w*9WqI#0_1mMKQv+#PG=`T($l@_c|x_e z)S4c3n6jShWGxKv$g>#Gdc6aIBbcHDJcl6SxThnk!29b^jO$3^WwpTWaH1 z_Cpl-2;ZG={kbw|fg0Z_%F>ja`Ufp>u)AAU2E$PMTZWGsLa_nf)c(XQ<9b93!t4_t zgDl|k+ZfIRTFad5aw}kCysItHGhx(l>Pyp)x?2(FE)4K^@S}#S)jy|LDot}h%$ zleI%(P*{5s^>%-%v3wDgf>>%E+cCd;8ux9#FZ(W(vqlsqNW1tDw5#}Ia~1)MA+6S9 zTCA2Vp(2JL9Zour@1Jm%)bJAPwv?7m{k2%P)X zD%i#iZEiE(IPX!iX<_OB;|gt&t(or5JE!vcr-vl9L;jZVCO3!hGzdp;f82ABSW!Ph2TX-SNu$7r9tQ$P{ z>vObH&f+Eg_#DIh5r>}#M0}15>5FYlcSks0%a4uTVf^c?FV+*N@If-a^Ut$ZxT3^y z9})@f$QV5%sa7x0aQ+%CgMoGs?m2{pHsT`!qS!q^HD(u-q4LZ^PD1-C1Z`hkZ znth?8JDF`N=rZI_M-Rt0PS$*QlUz?Jh1YqEtNz_mlGp9tYb)#}C=%krZMV!S*U8%- z&5K$bk{Sw!s|xNB2*5$WRBDmlz~oCy>-82r3`!rdn}CstuyA&*Fgh2?=xqyAbiqu59z2TXE}z;I9EykX#YXz zo*l_e>MA%P;2otoGGnaRj~CB8t^vuqVe(r!V#WEvHX|R2093?@33dl z8?X0mR%gfz&HB@M;)khLhr*xc*U2b!f;x(~l6?-lm;KM|N_ufr=-P=bvTvX6{Q!47 z@v=H$PyBBE%+ma31iVD~H-oOHBuNcxl0y0ujb9*!MrN*(DF~w%SJfKy z5-BsU8=uMe;AjH8ua6tnFV_n=JlT$ON)`|hx85LgUatN?6@i-%MZD0tnOs-~3 zL3dq%S+$_I&S`5XOYQLD@0N>9MQR#*kGLCbIf-i6(PM59SfXd)n{aZuJ63>m%JA|!~7W}a+d&*WLw*m4Oq%hSQK4pIHD1o~U z;1Xholq-Wc_43V`;We=$yKlm3X-)HP(eJV%=RZm4sd;lDz5}aowrL!#sEoD$g}b*3 zj;m?6G;P^pvY46KVrH_Knb~4yCQB+YGcz-j#mvl7iJ7@1wZ8NJXU;^QnU3h_h`E@{ zU9~GRB6IJo%qQ1c?+8(eJB=Z{K7VIYqVMt-BIiC$7mc1DGjWS#=lhi8Ji_^*06?Bq z5JA*H>EnuAoyoC969LBncs>Q+B%ACNTI##^B+|rNPG=hrI&5`g7=Vv)22I^2IFJ+`ljNUf!8t&;H~Iq3b@| z%MQ5U3V5YE7`}9LZ`3i~87`uPsVXG7YP2yrzUe(?IaO$~lIy+A)f73AN+~vu%g6|+ ze+L_qHHrCn42$cClum7czF}u-NF%_{5>&Qg3#xwS(94<3F^$QBuF}m)7S~Q1RW2`y zX>lbeMO?1CqpK2ZowGhrK%OG4f1GQ2qEd~T#2qv9U5RCO#9}w6z(AEt^KA*)t1rdX zWAm%?;10VTyt$^wIXUhlHHOAC#A@2cXgYfeR~i{R!pZS_Bh>472M?)0x9IN7+=cuA z9`)EB9~8$tkFl7ZwQasg;q&|6AgwX@wXRb7@H+n~n9ui`?bqJJq*){H9t=_w0=?95$8>#tqICnIPS?lO=PW@iv@Vt4H?`|UlCjQRV8%qGGAeKCqHN}5;cq%t%`FnkC zd5Y9tj0ft9CNHV-mh7(@5#2G|fU3Qys|>iARNzv|yCIe8T|}YjlHi^7OlWiE$Iw}r zwY{2TN^x4)0?~Jk)not>e#^_y^nPR_DLR{3)7$BC%${Vc={L8-HMEM4Ymzpq+v6=D z7J3%iPt{x-na^ZcIm3&0=`%wTnrp%#=IQ>`+B$mpXFSRz^kc!q03OQb zFYHrLX-XSj*e;gvoe$QEGnZkf39L&pVbDlEx+%*aaBYcvi!#K#KNf7I!xQVz?=v;H!u?cKir4-HK%&wHU+63n+Z>IGk~o^U zZCxPr?dArc7E1>u_GNlUr5y1M2Lkv7#S5Q z(kZ9{DzF*d77TVBe}1hZoJtnv1xgBkSIMkeh@PKrd7OC#-!A`*1|`R!bie_R zOL*+_ny3#K-k+v;d+w&Yf413rZEymI;FG$r=S=>vXGDD82>m_2!8~c ziX-TAQpX7t6ci+5-JwiXgl+B@#vMWbIXG*%r|T#{{G zNG{BFsX67~bqGVd^7pI{Z5d=bYMI_a`Ce_}w3SkJb)bC~s-y6u6vMbiyvD!?B+d!7 z3>F4BYX5(OD#Ww@Yp6m^u6BKYi%OACoRp*|DarVi-gn65 zcUi*~eZ$-t{nws%ps8Y2D6sxt`~yF~KD0f%x`i84L4v6RDnxgo4SSW`rhfhcfE2T(Ag%daeX3Y&L@DutJ7R}wT6VgVSx zI3wfwF|bYio+}7EUXU;~K}8vGz1F3~pY@ce3f&tiEB+=DLR`g*@y}J|8N)l5i2W&9 zxTC0uO#FiISeS;O08)N^^OJjPsDxQU$Y$hc&Q8VWD`WO#R*)it;61OtK7lmr4nnLu zC}uGEErZA?4j+GiDBAC%XzBuw{&@5e&-z)aG{w2NLs1%4Z+1KiXbqQ?WILX$=Xx27 zN5hxc#Yk^h#iHr5mrN*!G_v;4+Hvy^r_o{2S)s?N$LHP^`yDH@@WJyHCX1U@@aG0a>8;yWNK)1m-VfGPgN#M&%P*SxZg9- zmmhFR42bm$m3KNe-{Xcrc|2;TeYW`#>+yxcqO&#*4JE5U7mM90l@s%u(QkG`gj3T8 zVi8D}a&8mqm)tDQ{!L!-k=rVva)Y_lH$ylGr|(XwlT+bCGpDh?yrf$TicF2}!i!Xc zU^&Uu$!Emx4qxH7nDUHp3o~whNk|Ty;EE_~8>Okx9Yr3IK-TH+;)=PHO0*P5Rn&u< zl;WzvNJV{tpyq!hizlcSHh29dtJ}rV)@ah(@pz=djq5lnyI8F`l;xz>YjiS8xp=9_ zFqk{}BdgRvOt7bOVD64qr+2K}A_Sf;|9?HnIEfIE`B!f3zX zouw4hFOW5Jo))}%m?N(PzklhC<=yir%*_Kmd~h)KXDJ5V8sZ^E@=$8+9^MHj1}>4} zmE4G`HX6v&YjReCZa9@Qrf9*)y=6`7431#b6;_Wb1FKaxOUU#E+Qs*gORmXUdY4V^ zY7hpma`PjMAS;@FSxDwOcei-#sUbWIe2OJctj|mxI2*kpHK;h2`!_BFt*>;g21S^> z>OiP+hIZ`@_QUeTbK*<%D;gQy`6$|TrB?H7g+@IM!b`}a2&7~EURQD(H2=4tHXkUfX!{%G?bO)0-lAp#4}l|mHqM3a_G6-J$La( zk}hS{hY_K}wl+E+jyDFI3)-Z#t<>FEcfN749lh3-^#>QpiH?)33xe-zqD%Y(8o{%X zP4BA~UqNDD_wTy@*oY7R&y<30XZp>>h~nA`J*k7`Q*Wtwi1B2sDHjkvez9MOzc1kB z#mE2)mIRaW(d<&N@XxM3}(1AzNwEtuct-gBmom6KTZ;sz^T>BmA3+Uunps4*rnj8&x zY0<6MrnTjngBDKhek$2XZ0FWnzGgdbpW18aQxW+&FLLl`IWnfDLhH*dQpeP~Jrf(9 z+$~huE3SQrEB$w1Cn$qrwl4sBS;r?6+nQfm!%B{2kV#hZACiLtV+xf(6^zN-@kV1ajPU z5LEQ>Z~`xeIE1Qfl}AVxqWJc){@@A&0K%K!cy1+5wq%*J^8pXPQUS&_9P4nqt)ulm z+q)zq5EgTzlq=T;otEBT*@`it+Qm#a|10`z5@NBg6I50dd4#DNSRM}Z_8eY8_~d4GtPloqs zG%T(m;DJ~sP?`u381zN-uLI z84OXT;vK{mbGwy^86CNTsfpGMiG4YgltpC`Yg$gUi6gxfLUwFgcCb-}Z^Oa3RA<|z zW{X#wN|mKpXrb+a(DC(%v6U3{Q@UX7d$?MBUUA~Yo%SpmcGu8_hP&)ftjWmx@Pvnt zKW~Fw`XSm4Yg>?T*P<{?FLpqzyfz~zaf6)!qote-KkwSLS7qLk%*OQ0cxT%(6#7?EO{6rHJFZF>9+j^j@=3DSjs`O+!31?(s&osO(B2gPB z9!?#AJ7+}8c0FLqbFeq^(|&jRVEpsG60AYs`u7wDk}QKi`Oic-oQjcAXc*O#GX1W% zMy#65u6CM`{=lj-9f-F`5!)tAmIHz04fZ6p~3Hj)NBG)93lxbQN4kmz4IZHQ@tSNA} zun4I~URHP26b(rwuG@+%3dS%Ln`o_KiIK;$$*F;mlKdJjGOnbAl4?so!>V3aN>9wrC#Ze&>B^P76M|g9(XvUfs zUFpgFd0S0h_xIx;qKCw}jI5+phM{f)okX5iig_IaFUelh)A{n1%Mv_1xUeTdlSPJ$)i|g+s7(#YU`Yk zLsE3{?M_*l9vTyiF6u>%a4|5#OT(P6=Bcam#C+bq)DEA5+tciLz}JcW_;1f~-3BEI zb@Q=d;`C+KYkO18W#Ph!J9Q^^amMIob{9hK;}bHga&Jnq1qZ*No!c(4UF8%oT-zpi zB!Q{M4?e5t`~#yisYcId4BQT;^tLg&rRj-YKlT;3mw2W!FPNiaoh(rDX>h*s?g*1e*Ucc#h_we zeAqFU!RH+yDi@rWjO#+LVegKQ_jf)+4kb=PVv5-0BHxWvZ;GCXWCzMjWm^2s;N@k) zYRxf&IbAo;a0cOq^`@%^$h)bT{fA?5Z(%~BposkXwB$tnvq1fpM|LCUKw>?qv&3$e z@Jyn*$)XQ=7&B1NFMIzcnM)7M3vD)T@+w-K*bFf~+dcWMQS8=2e5%*$jMR%SR8985 za8(Qbnv(wZ76+5rj;(MjP4Z(HShN=eTZZCasyCCXO?Y9`Gk4T@sf-N(a4Wm zOI*1yp_yiLU+WqO68>no{<_TuE}>4jX7Q@K?qt-1f=YjDYFKM&D`-JhD+hxR;Pw0iG&8$bryWFI2JeDjQy9_-Io}p%fu)g~^GDHe zY;+&--Lod~xm8tE`KjugKvC9~Ls_MKITwlft%PcA*`p&CI?R}fS+3sE z#g}KXL!ewY+p*$mMWLgO>8(0HLy}u=b%(X%)s8s(?)ShLPJOt{wa>u=xWv(a;iL6k z8qqaAN9Vzc=iuS6-PD_Xp(gsQ;lBjkX1iy2UUTzNI$s82sW<-2a^?NLTo);HAaffk zoc8PJC>L#Bu3h`;wopY}|D5LiexhR))Sw9Uxa)yiJ+G-&2uZmlN%t9GEO~5I`|#!@!}znEI2- zuMC~TcR_dC4L-I3Z!u9)6cX$YR2i2}^^OXCYKiWW0C@dM5LjrLL*jCDZ-13-@}}<( zSa!(UohQU6tBa|M_dCu-ukL{8CfeQO=|sa$`v24doE}y(DAF*b5|h~tFI7rmKQeoC zfALCWiJRO53&t0h*>S4dR@jUVS5aVUzEVwR>&V{94yGAYxSR!xi+R{(r{(j8^VHJo z`V41i+&9XH&+3joSkg;lI$h)c#r;B@m?4ImWlFL|-J!l2U&$PwvhnOt6Kr^0=+Hjn zmDQ3pJ2hb>DyjGKissD*-|}ava7!FzxiOCu_TXc%-T8EL1>vfD{Qs9^s+1RkohQRN zCT+Z{(@g&Kd;W68GJJFK2^O_-VV#D7j4ljT6`k9|e#kYWAMY(C#f=b@W2-C}7Y5Jz z9p#?A)f6970Z*3U0QI1j2Zy9#vT+7Ea|<1V?@SiPmhP{umPs#XFJ9QCVy2u&XGg*^ zQ{1dJ?}D?G3AJwio)nATsOrPIF$k{ilYY^o9lzXd6RTH=DBSu0Gw9Eins+393wooZ zMrxx6$svJtFswd*T~Z@70uKvyQI2kTamrdZ^JSKAhG;o}i{cA-GeUM!v1`v|etLs~4SuN2-%6UNiRqD2_tcC{Z)3pV**+AKjn z{EkwB$b^6yQIIfbU_idc?`&1S4!0&O)Oe&Qxja-jmJk{;lQ;+E1A%$3rBk1=tz$&6 zqi zV3)KFGQwrOb?H$w*tMo_1X4=Xy+%&x_K&w{u8@I8Jf34fTqLCOGml1x9m94Fuov2x zyE}q{;%ZrWC!jX9EH;}pv3)MO!nD-zwsSJNVf_+f;_OR+ANYWxI5{r$jzduzaXq&u z8vR~-sPFF>HxK7H4Xh=YxT}~=DF;zfIaOXfLM~MM^VVOVSGFd;*GohIEe4GY8e)sI z3Vco3aTqWFW@hKW)R?F=S3b|3O@}uBdp~^$#S#OYA7hxOe#!TikWs%x_km@SIL`V^ zb%DFsJ`+cuYe6XR{jMw>7l{;gHEB~sXeuoUL+bBg^|DBJL`-(hvSBw#AaADJthGWy zXgRs!UP5U0Qg(yvz3@Zyp}%j4g&eM&;Y+ojx35SLV>Ry`!l17gor zlreA#5OBtT;~f61lalG>bvDkVqm=rWO6aHjb1OqC$PG`j9mnqGW?-h04&|Uzyn1yf zMaiYkXMyXXpdA@sDOs%6C%Fh5?*#6%TB#{2>be$>%+xGd$2x#rhhpkr0fF&5$6j1q zfLdgFwWcN^A}XDi}{4}v~} zQ@E*~0bvog`N3x1`5d_}Q>YZ%a9g{V@0}whOzK$-E`=$Z9S42u6$Cl>`wyMwSVPZ5 z=!5F;sNz+m&EU4Vr3MQvHc5_~lQAeF*<5FY0J5E;%m3w{=iwDLHozC=q#`S{*sS)q z6)tqV$4uRuosWZi2A0%jZWgoO=&|)0N1AUys@x(W8{5NdvBwbNifj62YI1}l?#cr= ziAPhOef$FtuRZrBFTdFWyEoL#*S&am4+g1CJb|I2Nb?m(QpY)q>(RVyw_AgdQ!?MJ z+=4=#R^l$_Q`Iz9OP2w`k7>;jJ&BKLbg!f{vC9DouMN#`(>Abnymnp0VvH-1$SSXR z%+YNX&*vKd-Hj$`;az``xxhBp)!>9S2{QA<45dRt9~OQqDgF&GUZ?(K#7m5R9L8!ICH0rzGi{*3EPswh6*{q52Tl^B>a)_h%Y0eU7r~JY9YMU3+Sy@vZqXEKXE8ibv zmurF_xtb4a{f$ywx5-`S8_o?^V+14IZj}~sKbps4CjbhSN7H6dm+ww>ZeOK1hst*B zpV~rZJVrNxu29cQwXum#ep?^XZQ^G$(=GP+`j93@mw>`EIjO_Hv)Rj)yoK1VFs}xS z^c$j*gZ7J{mdLyIE|i4GjcS!XW=g;+11-gF)!HpXKKYG32{RxM^ z7rE=y-z+bdoA!EvnjctcmN-?G>r`+Hm~76-bw3lAi`#&Xh?GMs=MTux;QTR1UcdPb z&}Pi3a~upG2(v)sp^V{TN=s0brU7NY)A6PFn0ae&D|GEe#_upGS-rB5aqcgd33&#XoGe0YDJKt$)e2u#-Q_ffc$&fN!@YW1d{Q!&xc>-Vkkaq(`P?eCC(T1umiElO6&En>xML3$c-Ws!}4! zaXWiUXWZeWqIEhbm*{QZcL>}{t>JoX(8r_jzl-qoD{bL-7EGr)+I`LER-u@m2pAxX z0nq)qS-2P{p4~UMdTn92A9dT&cj)Ioa97P@aHlE6&z^Fuv{b5{A7FY>>^j!p#QX4V z2!kJ7uFuy* z!(!xoMb>D>*j=K)(5>cal06gavrq_nao;v(0&b)A^mV=uO;L%SMo0FuenzqCYINXD zaCjsaZtm`C#6LYA|4N+Odd!dOhD8@=7@a>ID&}T_srF{GB=7p$jxxmbQqBvmWYH|Y z^rh}`%E)OcE#bkT-`MHz1VhHCGxzmo^@?9ilNZN*p750u%jZ}k|JX?Rntky!bVO(S ztn_q*iaH<^Us?=%rZQD$F6oP%csnq27OEyd%11n5#qiuz{x) zoT_=4&7sN8AJfgZJg+VvP>S+bha^yoG>J z>e4Yt$pQ%^RLE;OC0U^jxV+Ef%r}X;kG8t%&!vj8nl#}c_N8Qp%w8|x9l1alH8VVD za6YC5Kma(F03du5lRGQeX_nV^*FiyGGFxx_@99>jVhDm>uLaUtm zBQ%l2C5bMX28;w(P1x&sB1$g%yBiD!apBy^&6~ZOa&r&e!icV~!2J>$4gwLzHb8W8 z{t@c;%n+xigN70^%3G6r6HzBq*Xwp=HQa(h?pK(3PpLF9q(W_^ax2f$fEIU1DUp>r zWJNcAC*4dF)jDe8f3#~!0bX<$K!PJW*%vTTv#BOMi98*clV!PJXE;&mDqWz*^<{}* z-HrB)6HHZjeRQ^4N@75V7x&1xh-a+PU9z&4ZDG|4f-iZc7fe-Zpl?Gzud*&^9N?#+ z>FX@3j5MP2p76cxS>kspWf+_jQeZ$1Vq&qHNm!_g4~~u?93j`?7b+AqG6jXiy)aIy zJal(@wEE+$90jp!m`uZxKEnE)y#l5i5lDIC9ngnO41oHf@#6~TjSkYZ> z3G@2ohF2~H$&%E!Y@jNtv+azaj@3^GQXdPg>p3DoZCb>d8Or^gllgfb6qlSipGo&# zs7_omKb;9Y)Sus2_vtEDo`aGVNIjSo)tB@MG))??*mPPQ9cpu=03c!G)(TB4aUQuZ z#m1Xc0FkEHMN8K3!xmlwbuphct?3WpJ$;S%Ds)pdrrHbN;e^BNnCIwZbly-tkjAH> z_N{s4%y4QVW^M>&@9&L)Vvips!nv_&n|6E0^Qpg5x1^*n(1(a&=grgo!>9 z(P&v7EnoVf3SvWEY64albWui$4GCz&=8FWzL^v>rFfWhRf@RS?5ZLif?s`igHEsU= zu(A1e2^656r)|3<^gdMDMt)m_*MlJ`eCoAv6cpW-S2PywEi8&?=;0QCO0Bb{jvZXW zmR{0?%jtTOLVA`?)+u}!Fe(1>o4=f<)qRK0m@Y#&~YgR*w5zesbxcSVHL!?;-5e4mI5PVs&J+>j2KGfvkPgL?09 zlAI+a+`#i8RTLU(T!BSvau+(;on0|ZH(BJFo$e@)ZqCkJKb(AWkC%`}sg%wYW|qtu z=W*RuR(d1DO=180I+zrrbrBnUop>i?9VDY0;N*PAq>#p1GcDkFvG<=mbRW-wDP zN81;u*XCK~Zm-qgIj=h}Blw8a*W9q+eO6Fq=dLz@D>~o45W)JJ)e?wDp+f2n8}He_ zeF}{7{mo&bC2g1uFERo2YRc(Wb%(EQFvt573tNG!994t8fq8#UU`*+k*8gBVRFm&u zW3DHOg@$T`8K`PTWO%r|W3=q}Q2UyL=j6k3G5f<7PoK$XaRU?(O0-7=47excG&bEM z`J)dkgUl5kmX+BLu-jnzxMlk%k&=SJoLtCkfsK82hHQ>ZV=uc*kSkr z)ZC6zK6$Li4=oroMU~;_$cgq_q)bFQ{7Zovq=?+iin0t3CzY0Gl$yL<@g1lx2x*}CI|TB7vTJ()5{lbqt_R#~>J_x}yr zz)^(CH04LaEwQWBTUgc1#?$mdGdQxS^yrOGfnji(+|pTV%1RPI z2Y-G_iSotZR`HBDg5l1AJ|FJK*X)V6)P-!mp|nf2tC=Jd9&eOOC@ND}a&Q4rG@P|9 z_Y90fd;z^ClwIAkU&kFP9nWV@4}v`+D~+RTE79Zxpx&31$LFmfX7wg-dfR*5eh?mi zowpE&3%4IawWjyc*3X(@VD2Zw%RS=Ic=Dxrer_(0Wi(<#1DQ0heFcwSQMS`lK}$qV zc+OUXcQnAxD_fRw*Z}PG%H)!94}f+Z79cbkQ(-TXml+mj zz}_Doof)ztL7;%7U&SFw3iXJ4l-q&)W0quOvghhFcK43 z_3EEW@Zffos}BMVxrdHH4tJQ`;S=Hy%$1Rl0J_)#*yfl^< zcqjZBWvIGXyDLl=r|&ETy;sHfg`S72-!Up{mZ%w83rKNFH*I-fUC3)r&$&`YcBg@4 zXHAeuD7(@4L?ohxirKLpj5fHtgPpz8#V@x`<#u;bjLOk$IVENqFC%aWNp_6yi^JVM zskTzs9&jFhR#6lgf};EDJAD~SJwH}r4@2&AJs+Et@4I?V&g3K0R3a!(G?IMpzfn}` z^YTSks}<%_lb6kh=C*84Rp?}2t+e5a)c$ytFEsRYXV+PB@>ec9ibUYP=Jy&Yi(fIO z$ZioDSk7__C0PL*RQHI)m7coTFxTyA4dtHOIoSDwP=mMHm(BUbr9u@=IJiuijV7n) zU&6D`&a>ZjdmHGw!<$cUF%-A@z{B-=v#TfAn+jCBmj83pugYR)vGg^RQoPk6nP0&` zH|1T&k-*JnLQn$2u?_Oa5A0v1rUXc~N_Lg6aB`}wIZw_e^D(0w!<;_YiqLwt43dp$ zqhHezKG;ayi_*TXT|AoOo&?*vxtGoV9z9w(E&=%0geo50qaCr=!4g3v77Pf7-rxV7 z+JZHsV90}{C%yjz2~9mzmOfoFs%*=V;!dG5{i?{deoyVaU^uKbk;CK@^c_O! z^xk^UFxTOu*j%4csn$bO8jxv}?LyvUqonDSJ{(1S4@%pgcuiGU0K2-0&JmKfUX9oi z>!M8QBZgW`FX6r;!*-`yM)006+V8l!d+h6*N%cF)SI>q#%0K2V<0gXG83%qG(W`-WZ`uKTUpaDlqsIDsnOd_G))p%NpL!zHip5KraS5A8N5ws%96_y)wOR!^^&& zkhoho5%fk{oc@Z!VeFU>Sq(Sn&w!py)A$X63)D*HWLOOLS9iEO%PV7?ncoxC9(8TDb zTIhA=R)eL8%k)n9sXNu{O`C@LdC&g$oQ3L}2P!nJ+{7TF(%|*#{(|0@Y{`AQDJfE) zDLz?=ANHBz%&+0^LC60Mv9%l|?n)YrAPMwz@0wNUaU|g*CiiUkL@AB5ro0h{R&D{( zdR&2-XaDgm9D09u?;v5OyVw4#U{ju>V9vCH{2#0l2+U6Nc;SZqkBB}2g3PuE>BC`!tGQ*;b&R|<^Qe;Pi@_t#Q=|n z;=Wj7;0tcWae*n7o9H0Y{=J^7oS!A^JG(FOIouf5N+qXEnycyj6vDg}W_UNgKu`X& zvFgXqfaU&b_bMr7?B=tP(5WT6r;F~~w{3gRyeE9Gccg*hT>Ii-eiHF0)8T>8yR**A z5fWKIPISUf`t4FfCmvY z*~rD_^ZT#qFaD&Yl)yJ$xy>Qhl}t|8i*@GWao+rU1y}S!7`@S+?oW= zW(s9rSnYxRS_}U+p61&K({Ftm^49(>lB1ge`p>z%C+&Vd@gMM#cU7RLJXqAhx)q^{$>05)XD0|f?%m<_S=`ydX6@8JT1hG-pY+% z9)CW*-G3#GUyeLo@wj5i!V{Z*BbUtlr%#@LGnXhD^51br-(e45VRRX&9m`dK|Fu8k z9^`%IiRaTCja~14_LI5EzR=;V#lU-TOpTzV~}?H%K4<7bCQ1N z8e10AGRo`~&rLP;a}cTo)l4Yo__F`jSC8wzTwTTCwP>NkMY=uQns?l-pL*S1ygi|* zWsDgN5v|Tk?246Sq&)xN)e9qk8mU$Xy`?)1KLL6=bq)HQ(ZS~{FnzpV4bs^0``Jas zf_RYgx(=SJ;E#VAz*DhPemEJtYTaRRB#RW6XFP*62k&uv*;g{%PhSVTo<+Xk4BZH-m$rtome9?7KAuXXd0J}k8_6&Z=-9*yedg_3? zSDuS!j;j0B76V1B9><@R`|7BjhEvCFIJXFicUOXI3FhwtFi7o}5`?sNZ!Q02XJAmG zEmMv;T1Tcdhx-$X;s@V*^W{xtjXk*oHR1*ypgA5(?E`9+mo2koJ`NQEWtN1(-uBc( z`QCNNkOjD>6v@`Nx%YPcIM)E6K>uv9vHiL?&&W5*ZeHmYYm+BK0Ffd>jG}{jv3Mxu z8MnjM&c4s8VO!&v{zXQ6uvBpc#B`|f4AlAV$+5Giky;eEX`tiauVby1%6ajT z^5DyGC86wZLVsp9c{Di>V>e*z(nHb0MK?rGqp|aAME|rndZs81QI^~c>?GPm)MbZ2 z*LWdh>h>WdKJ{v%3#4EPeJ63yd{;+F2|!qa^dZI|+I__MtyE9EIr%C3a|N?>G43~8 zgEch~dKn#AUuxqs=uzd#lu6O9P`?g=FEPc_Z^&op1!QCRuU9&=>GDG>*326ZDxVW zNIMpGkV&y=sMcr?x-p0*E~oqUYnFkB_s9`cM88+q7To+CyeI1RGx|TZ0HT+-3#AYp zJg>s|r!&E?LsL8X{$j*i*(3Dam?vHRt0Xv2z`~H@g-Z5l+2@SfiEX?2B%0*<^Py+c zWqBXV8_q4bYKI|+5~jsK#r`uSLP1q_MrtU4g3urOSkiy^p-A_tyfzHqXZR&*xGWNC zr!r=Xz$BN*e1f|}b}}&~#5IgHr3{WrvcTo!jYbDGaaq9|pJJ~xAcrHYQPa6}&)^5R z==z#$JmxFwL@frvpQ3EqXs?S28_){S9_yT|=`2LrI>y#4Y`U>ab1+%7m$Zymi^`0ezKXHOAqV8 zvntehtb^~<(5mdoCwT*yNp1()Lr)U{Hg%|j#D9s1IG6I92JZoWOM}Y*1CaJ{4Wf@w`sutY)Ya(XX$iDop_Au^Zi-(B| z6s$IAYL5z0y9B?a;_KJB`ERQkR+>gzPQ;+Sh!q{ek@L7j(2#1+41;RH(=habs)xaOv^4}ZY$q6(%m&(ps@wb z+%E1?6BWCrZiP+UHU;tiY&OBc@WqEE(fh<^3?7EHgTAD2?Yx^t(@NFb^SOY=iC`k* zl?Rjlg~TK|S^Y=7?h_50>}2LRMhNb&S)n57wE^&f^s2eX*o-u>^*W@WQ@o5fd#3D* zrhIbz-G2A4!r!vq%t>a}5RtMwB8I@w?D}sO3aU9Q>ZgH~*8KzcK;ttWh$k9j>x_|% z4Kh7DR+hA1^T(u76UX7v2&j$}e33Hb&&yU9w=+b^O-QXoB)-b~tf8W%#~G{5VTm;P z>a3-lrZ*gQro6?lh;cHHS1Z>d$h%9-RZ(AS3CvciJ#UM5$PyJWbyTu6;$=r`H!7mF z`wp_RbCU#HT1?Q=>#G}{|GF1*q+<>N4HBovM4K2iCe0I(S3q*8h!-F9Ve>)8Kpz5$ z7Qx}oJFI#abQ3l1;;5{CdajDj;#!Ye^aory;Ph)HWfNDdH$#1qcw7}W6i#h~(g<_` zIo;mZYMjd5MEPt>Thp^hBJzVD?VFcD&_7+@Gg=~;aRItAdxQ7Vrw754NK*tPeNW;>E zBDg{A1UZGiebI8w8ftQ7UZaNs6v89&SHGxSpN9RaR(XSaNGaX&9Fw~_Z zrG-iMSezIWLxCqo&bOpFicmX`(z||mBD``B1H?WBZqo&#bZ~xY8NUFMVOHs z=I!G8Ydq-H2l-}tzrt~Sd+SsJ^iS6VFH^SuTVjG$0(DqFg`q((u3m^08R(Q_8kgV& zO>bk;_n<9uC^eFF}WtYR7n)r7BAYjRhw6r4C z4zbgei`nMd3cpHwTBUsG*wP0&_x@kv;!Jk{TPK_cOg8uZsL{*o6kVkJZsL&Q$j zH`!DgeFf|#IqG|5+8=l=Ny8aQpBe{#k-v*Z9XCaRA++$Xr1YN%7n&epmlOD^6YDQb zWVda__S&$$fyi&P35Xoes)-eqBCogE{f?b<#914gtTx;K2j{fBlJa?piaK~GBMyW& zh432ceCYj~(}J2r(+&Cd9&-~g-r`S&MXn5|htsk{+_$&XLJ}dVrjYC%%gZu+tGNy(yxP|1Vxx z6oo`E3^?PVq9SrCAo1_m9JPe$z;e~y$7FQa7zSfe?rF9r?hrbot1#CqdsF{zXFxT# z)$)Aj`gv!jIb~vq=L7 zc?k{HbUj(Fzdw3)B0=(J$D{`;X48AmR($w<<5{|t5A~orjx?U+HkJyTFC%2nhCko* zQpOXglv0@NX`>McCf-K7`wH=3DQHLa+WtAKrRnY4IbFc{$S5elv6`>{ZG;->eJ*g~ zS>x^d@ZlaFX*4Re{xNx}+ePdlz#g0(NvK77E$`PFYGmUuTiv{(V>Ez*2At?G>BURh( z9rAP1Dw+moFLpP<(NeY9zJY1oeX>x^w#$ddY^-1d36*qpf7XkY2H zM5|_F-f_Mx7WsH0U4R$EZn6q^KKlGk3uxWA)?h&uS4C@@M;>yS^X51ZF715s$wUo; z;*0mbxJJz-;p-#n(Q;>Cw%Ed7RHg{`8NC~UznLf*ITg&5BgQ>{1s1=z*bxzhS+xgv zwo_m&PW$C`XRC?%_Men`s`IrWEQZl9Gc&aooItg>^2o6<>2KZh;c0pOl9V?I;0Z41 zJCsNJrXoa>zqDld^z`nUy#)e@8CpFgLTq05E3b))OUs$8tVi;)mS z>*LlyM8RJPkUGJqR|Ndh1;cugY%JL+s$no9_*klfpFCZhy{%eJ@!6a#oqCzkH}j^( zo~+w|D0GiQ{Qz3OFNuwFqVs7dvL4)$lA9Rx3G542Gj$YYS?awH?**5a49E#9k=Dr1v|Qdjg9DK~kn;{MXH<@K`EBjasu@aI20=0b90 z&k}rHo#oYFm$Ps8=X;1dILLEth0}$53)g3{jHy8pNLDRp;+kjxni<0QOj_%JOk=e0 z^+mUS_InVG9Fq*&BuTN079#kC{7w(!F$D+;c`^j6@Xp?iWpBS;Bw^To)I?l=^y$6b z+Mj*j-C<$*a`>Ttl5qdT-{Ke5mVdUXLnw79X?Jh&l-5y-yQA|f?AyXpgyBuDq#GH} zWeua^N^hkh>CXn_Hb<;IPRO|@|K{iW*J7x-Z!OcHNHoxO&(Brm+rL@P&_?p!9^DOo ztd5XM3Xllt6blxw`Q&&eA6@Z#FN^uF_4Q8|1234l{ z{Nnp?EMvknrzT7uQZDAN$M%2EOA@nZiUe3pSL|*mJJKJ6quM&&q5Yn1q=OgwRV3szj*}^>RQk{gB6QIG3%@OCkZx{SVsSGAfS0&-R57AV?s%ySux)LvV-S!D-w* zNaODA?rtHtySux)-_HMe=G=2;&73v&#jTgUx~scuRdxTqyFPpGgH=C{E}yL6RJGo* z7$MJA|E{t~+6O()%N-tg8zg@&6AVj|h3boR9-=$#sT@Bam<(Ns$=^%mA5TtD4dp>i z=e*`A2<>H0MxBEj7jf7ep_!8u`*p_lM)I;avQ7L9)vISn`>)&y?2z4(q#r)-^DF!F zelAJgJwJ*H!jEPmf(0V;j?!cvon60h|Hg0oWnJQio9<2E!uC@zV8kaPnEBz<=Ry^V zjD%zd_)=#wg5K(QWZ#!mS<(>O$*16T?2UW!Xi9Sf~>#_z4a zdQb$q(YSR!{Y*qpK{q3`+7(6@P`;VZ^1mb)=zRM)WHv@H3tI+GKQV8Pu*q5|zSF#e zxGWd`k99DzrCtKA(XAUXXi5=_@eLlQk0@e{I8NtBMln;36K1J)J-v>ZiZ{nS<&J$_;X#)JE*Ja*1+wk zvo{D4-|UvgmW7A=skLZu1<`Z3r-NYg3e+Q0B)X^0`d;=ETzUt4wpWfe3`jx4lxl+W z9yC4;2%nR2iHpS=DBWnZuT0L4YjQ_b^`cg6>p^8dSUc`dpm4r#U;lCei&XFW?!x@x z)P1)hbskE9r8g2$jlm8|U#WI5eG+}1{n|S>lWu z8Krw?nZsUh>jxS=SEJgzNq{?q8~F|I_NFSra4BX1zNw5NZ?>D?w_>!<%>vJT3X@*5 z$kX|+#yZ^_`E{qvD)OVAA(>U8D6hNfwD0e7+{T`Ln|f8%IlLIU%*@RBmmAl6BYPI} zmAW)lUGLBO1dE7+Nl}i`K?XwGdse6cL#m%F>XQsEM5T4~atOGUOm2!u3Y6u108HAw zbx6@hvr2O{4)s6gGSIuxkK$CQW`@`^UN29;bMBEI`dMvcI3K~P0lur59 z^!-$ni862}m0d54+MGr&iNE4lI%H066e>WYU8LY{lInVWTd8@9A+Sz0o@IN-XHSnj!#x+`-Oq-yC4ENiCD7Sn>SR~j-W z_vIOq9K9?nacN?w9lR6uyn(=u_-yQk0{=EKTKt6kAqd-%WzqrFjjPyTpRu8j(^vi! zzS6kaTNk9fAH3fh#*^;M9@=@p4r3L{nB=7kwYmP+H+ghSQOuqKrbkMP&j z^28|$>sljWI;QW`PW+IX6PsAs*U>uWrn}DrR#Kai)BTWh}iP&mpOj@4#T4Tf8rGy&p zLrn+LKN^wk{`9sI&Z3gnpCS1E;h zl13nrY6d!K#>UR4jnstwY>SaUOgI2_^|6RiJi}7`AjF+}L`Yn(z8%vh{&!B7^!{EW zK`OP}=(+vHstVOAosNgC^!ONLu>cRF*eE_Yvau6No_{tbneidA6v#SCFL_(`wXa~) zfrCJy<`7kAO6Hdz+-|vus9XxggBumdY+5xLG+nRg1ao^%o7GoFoGZP2K|(ePGMmO} zl&L03*67cSme~!4npgCG&c#gcqnK3C`8u41m-;_e#!z)o#bnRbt{zwq zMi>J}7Uj4K;uJXr|FbX_yK&X{rV+_iS>H0W))hULQPAhX6ua>ZT0Rz~k2u3z4%rd_ zn;TNdgU^&ieQSsA)h$95g-{O&OV;v3XTM%0SSVB_@KPawR6MsR*OPCk8JsVlL!uly z*FZimoAL{LU!~h~B_dv7kfbH^#zaG^E^6=XqvFr|TAatwO&I!>JfUhjY=E=OR`B_T0`}5K9I-*HHf=5abdT*(W?B+mD{#cnh4Ce0|L>B!gNGKgu!Qfe~>I6gPcD(6RN=R5Q*1 zp{v4^TQAb0LZl|E&s*-$WWo+$8lSWO%=X0rz;_Q$Z_lRt?Si{d!hix~L1zmH}-va+Y_8r8K- zNCfLFi|+=7zh2|&1!%;lj+c0)X|yl{RpU~P$fHOs=N(!vE31z1`FS!W4PV{+=a>lZ zcW7UnY`w+qVuvZiE2$^Sr6~3mZRRB^4Q?hTzK;;sUp5Js~GJh*MtqNg4k_e#Y@|(^7#cS7d-Agumu$+eF0djam^39T3V>MS2CKo8PLZtrXBY%(DYOqZ9b!! z@vO*kERt(Ci@YPRi;!uzTE8fmJB z13(HydRam)vanO-tm!2U&o-OK@&rMb63?=4$43`WkHK}E@nFwhI5PHz%tJI;g~uB) z%_WD;l^}3VQWEMz&@#shfo~p6fRxLRbWX@Z7}>c)Kxn?JGp7#f$J~;nw4?|fB9=P) z@x|Yh$w~@_G!(<{9Ua!oPq0i_To`$;0Yz2b<2(AFU|ul>0X##2-}4yk z<~==#5Um!Qg$G&j*7N;1SmQnJ{{X{Q>RveNX5rm{a&l=mI z^S5(oQeq;F->(vnp&>k|YiX^I$pw?Y`>D4937IgvJF7I(9G)Jwzaw;4)9Qx&ohtCs zqY&^LAvcra#SlqAiTCGpE;^K;oII&mfhhZjOe_K@SMl)Dd?9Px&%HX!_#-FR*>;Te zVkQHuBf9-=_Dzw|$Nl3mSR7W}xp-HHrWd>X>nkr_ zsq5yxx*xSF4x@!86!o8{(;KmQXcjed@f||E;uKOceg81+rD{Hmsi$d&Sv!k1YF`91 z4vgEq^SA{e@X4)(d@KX^ZyvBiM`BS{@aS+s$n`Qld1e)#TV)QkeGCNZg9F?^$62b2 zAB_nNDhx{mM(02+t_#D}NhBWU<3;tOiPspF<^uhY_QH9Cdia8mG6SYg3LIQ@%w;aO z@&NeN@J6@2(SpQ)pmXG-Q*Sg;pWk@bR-k&T?aXs!$xj5VFU1`qvryt^4pEX}uKZmZ zrhm%lZkK(|w%zUsQwpl!cU3gpno-Ov)Vjvy;z=i76sU#n_B#@BZ`=ro7I|<{5ZV@~ zL?~h-9h70MOt97WOJXwk!DKk>L6MCkmLn^r4?O#jfGT;6993}kleXfgG>l)V5;mE> zpIV6_f`vDKFInB2cefFE_qU_rr0^M#geA(FuJyyPvZ9d?fZ@2gk&PiV*K{reV|_Am z^`^R|uU&X~PD$o79&+}IOTvF{NsTTTxzaH2K$XfSk3sTpen*<~)4H@fzEfWkrfXB6 zmiCiXrEAPCG-Qsu$UM%PP>G4p*X3}Zf7X2=)>CY?9d3GmHNk_zp$Z0}8MD!sg zMY|?~9tx$RoEI$T=JWPbyNx78j#VvA7f75SfXBWuMHO72{sG-Ip zCEWvq#PdxRHmu!L?a8`!Z>R`op+wWp#QVm~PD{+(4IV^2Te$_Sv0=gHqLCcu-XGZ@&EqqP4|V~1fD)-tm;V>LE>P1a{(2t?|WSTSDmnE+H?i! zfx0!8*NdirbRC|=WvH#!bFx=Jd9r4JgV%YfxuBx5Cbtnn4VnAJUjMTrzMku$Abnpo z2Yc5--O4HFIR4(F7`PDxR1`s<2n6(WL!#vol=purz0sE`9A92u3qmhOo$qXtfkCsc z+|7H*tnVAHIQ_i}sHOL{x#6Ke7kNDj#Sk*%Y-gA|I^>Y%ND_;4tXG>cBesRT3k$>a ze3jwC-d*u(M)`8GpTZ2fDCX}9DVgKiv;<3r34~v}4P}dEvj^wo^m`T*bocLEurClr21F{J0A2!rtVHk!axPRIj^3|Y}<=GoheJ@2a5 zlW7muxF+X=!S|0gnNir>=ic9HoF-)q zjzU|b-9O*Z*F&iGmk>4LlP0n%m9Toy=*bQ>`2%5zT3hFA$tjULwikO=VGqT6I7@diksiQx-1I}8n z>eN21kzLW%44sEM!MzUA`iXeQI#?8zyEO(Sqk$q>=)Jp@x(76Gn|Q;js;9yvW530u zU{0E)dZtQYVH=PrIbdS_Z2}rWCk=MO-S+9WQm|TJH_KYojuwNE5@$r%J17 zhLlF=S&IIp3$cV8b;)Zq(mT-WF-}9jlqk-mYTtVdrpZUu)5A>xh&F^B`dXC1u+tR| z>|G>$IBH0?6aj~~rdQ<}`mF*S>i1b6$}#DWXL4Ap+&blz%MtH6n|{qm z97x%sz35G{Z_(KJlQb=W{Xg;J2Eg68!<0C~m*)<7K%{ zX*DtWzCr(*wE`PR7p5cBDXfe>p5`FdllN3n(|A@vG+T$7izJ4i`Xs2iPkl2(gzkA^ zkH3N|cMJZ51!#)xwtc6kU?^JGsTcuBqw~*+TYPQ}l`2BX3(E>@!lt#Yl8=rhRS(-8 zyehCA%x>%Ho#>-<4~TR9tP%%x7CboW^=l>_j(gDXt|Ye8EtPk+KGrq)tD)U}TuA1O zN!A+C(8)$zw@WZEs!qreC`5a%R-)Ba!FxR?RFgz0xYzWs$Pj1zedP5Xd-Pl>XM8XI zwDvJSWYBGi!!oeGWS;~*K#x|BXxd_0e27ZfHx~38vtw343SRoTlZ@D6-#LY;zCh*9 zKE}d`eINR>hkyCorQ*?d7C{|3_o=kCK5Qj*tvfFTcKulUEz?i&A#(C`USjU^jljAg z&DWFL#075wx?gcjbEA0IOL;CbXoz*me8TyAmnpS0GIRo1ku2BNA3v_jugc3u-_slu zli($4%RM}@SxYymO~axBUEJk61?(I26X^u0u&}VyWm}u9mV}e&bt{uibd@d1Y$2o6 zTZ0*5`CK29KAS#FBFuo&)*lZh|ChRm7&fLobTcMVS3g+K30lQs)IO%9Hoc<;esJEO zeMlq`IdE#vs>P2df$LWqD23T;$8>f~c`AwI={!9^Q4W#64;mn3F|@KU=I^7XkrgO9 z?;0Y5l0gaw;VpH^Ll;KMx={Z0^p+MdljG4*QD~Nt7N&wfo(wm2s{0>t)|0;%pGoAG z1)hu203O*-`9b0>xp?Sh|I!7OO0i~Jolb02dH$-7!{PH1Ynt)Yf)%=L_vmbY)7|n; ze|pVkh?RVbPyAB?GPCmJ7Nl%+>U45&1T;ebXK@jkPViqY)5KQ~{nK#+SRI~K+%4_gZ+n1q*>zLnri}!0DN9z6UH3$#DNM-DMEbIx)09M zD|;o+!&kRd7xi9!ZR1MG!1hrV+*Lr}EYF-uWLQ4#N>3-KfX`6|^to-oIWV&6Uw;eg z>kA)0?8HHkF*tb9Ip2TO#3zG%%bKm}e0^xFG#ni+{BC6uigQKC4Lq_24pOl1uPfgb zZlov(Ud!0_YcAxK_aE~dKB?{ z>{0N@M@>r)sAn4$rW+PTrbc8ge87V7Btl0r-f@s{Be%<@End|XxtMN<+&htFRu;Op zBbE;y?;ydgW|1edH~^w=j=I@utCELb@V*3NNBf|+!*fT@*=+N za|%f13n;g}()Qp|&#{&A+^8a|nJdXXOJuf8TW=3;PQy{@j$pC!x3>oM2seF8#@%C8 zpfA_iU6_t@NY@ze2oi*F1z*IGRIVTX^cnXKQN*`FcMUwp3&WXOU{A4R<~vk?>Cnl$ z{$e%x-Ajf`qll)#!=qmjp{Q8x_`>a@Ne4Q?p$`=u*Woo&;l3Qjpd5L*SeI(7)nNX^ zX+5rEJUT0=<&4h@Z6BBLPS!JLqO(+XSGYQiBw&G+^c4Qmx_V>mNM; z-J;fweWL52g$3sJ-1%h<5(q4FqHrYypCk0G4275Zd_KcZlUK1AqG?-}uljKu%`U2; z%b225t#B7Dewy!l#mRB|QNOshtsg6(UE#|mH-GJi5 zBZg-)ryS1Ws|=;Kuac~*I*^c<*#GjoPkKh`R6_*?_mIKBzV7Z8A-e_3P^t8BB4s2e zp^G|e+x6#+1`^#1W?hnN!`+cv4`+0osDmx_GJdvCgiJEsJ+2TPee<`C0IN5K@+GX1 zC0e_O8__H`|Kb(~z=hEUa@8jtH2Gi0FlpFds`+cg4$f{~zn#JuSPL z0tZTaCBF))s;D*t&9nsu&+q`;vd+qG* zXjs{srwg@lbkGuJE2eN8$ZEaEgid|=Od%A9+t&v~ zeuR?jG96So95BigE3Rb-dl0*Dsq;0#nn1x2&<@P$r+nwk5Vx4N;XgbKwKssCDSVgJ zq6)4I5=RN;##7i{cQH3twCiOs0XS~Su|YWXzmNMRV;bIn^bRssEXP7|#v)51Gkki3 zb7JPE@l*R19!OfBQS1Y~mtIl6Iafkak&bp6%#H+#pDAlxvAetOjcy9KQyf^TXF?C& zmVeQ+2GDFj%-?sIAC>grzrg60&Su{XB5FDnwxbX`KC)ShC*${K3M-`otuIU)bwMFo zIQZV2pWwJ(x#4qMLhw%q7Hiq|5^3QMJ+)XYexihf3Jw>Cx7t77pD755DTqdSvpOmZ zg6vxQTypKrKI~CVU;d1(N%uv6Pwm1MtMpBu*bgF0ravQfkNO%TBN|Z_A*MK~30+Mn z1vx+!iJ`ez^38%*F)h+?KyVRaVp@Q-3u3aZb&K@MYRMj%$NkR>zc47?opbKTpa>lk zar#DM${U9pO@wOd6sIJ#1-aA^Sw<-6|LirbrG*q`&)%#gSFho=;L)kTMTWv#yXM!% zx&y_rKaXx&EHBKd@1)dWF@j158y*?WfnlGX4+1-jKU1}iDY z1NV{3e+%584t~Gx3voBmYCZl<3k!lYQ_4q*9)CgCTTasIrM_QyG{ zEZkMuSxFXBNb5Tuwf}VyPN|6#R0Iz~hYz6|SwLVuZuSovAvq!@&CAlQs7B=1i_Lx0 z?@);CI!@W-4nKU5sR^C6-`9hY1*1AE?6z@bx}HK&W#C%*7PHRpoO(YP!}gXo*GmL+ zJAmt)v7@53{vKD?>XspVjUhw{x5c1nl6Lm5EivoNhUF{a;^VNfb&*^S2yp?@!=+2F z_S4`&-_9*|)s4Yk;P~E!-Vf2L2^K{i#hLi3=n&Ju+y)-qt`Mv!H7sU{W-po9)< z92~cbUfml*=IjTk3>9{XfHW0BU85mF5N_Gls<5^*N4)KqlYTlt16!+3__i?w(6ptGx`e0Nmb^ko-cS#T8`b~*`Ri2oN` zA#B@Z8MvA&=id^IOT4RcRb#c$x1krry2v%sW^lCkOUScS%CTqc1V_9SLH89FoOm%m z`Q+RNA#;=IcwZ$xv3|$6c(#bf(28&%W^_;&yjwrpNcV= zqivOe=f2i$|4SeWKY89V^Tpb`;Yp>iP{3Dhm&07AG z@U0j8zTb39Ef0d^y(xraMH@J$&93wFy&v}d@du`LsoRf<)4>ak4}krWr}%e z{}$k_!4Z{oZYgV$q@#p9UEQKamc#f`?--BD z562Z&X<%#&U=MpFkxu(?x?luNf7+rV9)p@fz(S_C4kx(`-9Aur* zAGWtW59u*HTlt8h7umOKEPjK|V1Ve<>B&bo(Qz98j~NS<>py0!*OQ$wpFQrsXoSak z2pHLafEkj1!3=|SC#eKu6rWwj;0cU10FIKwd3Zs=$FS4i*qr-SB=F&X4Na{L(xVT| z0@^0tDS?N@*Q4(CSyV;rYp}!r?3i^pQcX?rpAhWEd=-{rr<3`$(tql@;<5e>XK1xK zpV3)>5RM@6rGGOVlytxTCTTm1%CK~KwRrwb(nkDOCQqX%=>GlRt%*#__g}4DbS)(7 z0j)QHXm>k2oJIoj4nu~Z#|6l=~mr`3?DryOxJxd_Kz?2 zj;Zm2l6&SrfK2Np1ca9tOvy%+0z&+rP-ERkR6(zC`p)3=-YHe??Nr5-$HD*3R&0c# zQO?eIP7gtUSVXv;w#~%1!^davRdM`j6aGw>`H}H4%X!e%-*<6zkT0Sb-}RpUT)X*a zk71Fk&Xd^d7;5`?SNccCOL9GNCu(OtpsZzxj2{|7!i{%{oEs!st4ydCTW954)|k-$ z$82Xl4E}NQ4Hx0Aa2(Q+6Str=zWnM!w6<<={@3N<>#y)q#cJcyn|z@1yU+f==?SH- zrsM}3G5K+iUsoVAP^i{`j8lDVP!oj7%CH^oPC%O+sC*^odZv6N(pVId4>SbxLEh}*~zO(LpvHTezwGv8;h|yJz>6teE!2)Ly4gi z$o8{!iXyz@p})Dpr}>Lp8#=VC=vr`Q*i~z^8LDY}j80uI-`#@0CoLG|a4T@?Fi^ek z`4*EUOGLfG`Ty|Lbe-lzu*4|49iD%0&lqifmY6)RIT9^MY_Ci_yM--8Fc%4&gNz%3 zw7f%Tuh~Kd;~Ge01PCe%x2H3Rq!N4_cA6fm`H7sxs zrbuofxhc&yHaclO#zcken~kP=k>P(IdwWxSb%X^P=FA*~{@OLIas4T#GltIVk27iZ zY8a`X`Ky#d^ZNJ)HwSFr#+d)qsl4D=H^}MdpDI23fnOxzL^Ez`<|(Yrc=(}aw|{Ni zMcU~_vSv5KpXy==Q*~RS0Lj5(I#GI?iKP5TdKMH}ViO=%^y7<9%uk%`%&nPwbjSTh z*(haj9Gt8&pwQIT>Kz<1SyC|vk8%}|p^}`0T%E?C0_x^`dG`}RHQ>j2-RedqzN)7# z6AqoLTJgZl2(t`eLuT^Y!Q6OL;jaH{v3{5LyZ#!r>oFMpx2LO*MZ8y1eNX<>b=~L7 z(NP9Wton?oB7MzQ<(;fND{yJ1EnO=AkdQBbMBV_-7UBzynTMpocxf&%!2yfKW29x& zCEB^1+rF#1Q>Viyj`NX@9V3nrgJCfYGZ#ymR=kuc1pB-Uweo*#tr-+Wed(BEDk=p@sFY#vNp;F-B9!4k!nmN>8=qOie%+c=a-%h|y2 zEGqw^3B6FwdkhA^LeQz`|XgSFbqU`x9y zu2Tugq01diY<8(KP$|3aT(axTT^(zJb8km`^a)Bqe|45Mviv=r;w60VfrgrrhV$vy zHzXt>QCBojqvtP-+8j&5InaO`@}(%(ET`|YB3G7m&)iIJ!Q&cj3U`PQ0sg4|a}9yP z62?vFs+&J+FpJ)Kbc$*33P&(ql}paejDGcgzO>*RSbW`-Cr1tkAGtMIF!J+#gyTke zRHpt!v(3ZJd@LX7uI6QZ`p#jf1KH}xEYfNXT*KE*&V~eQ7;2rx;r=zZ5NnRKMm?}Q zR_&&Yz8p;R*#;6dv8XFg-XeNVq;ERvzC3>B`#d{H}<@89GGTQi zyY~MMe6X9?`Tu)X*YS_N7F#@W2< z;my*R`e$E+skirZ?*#nUurEy}@2wGWXlRk<^-r=}`%vAkcOe~vHtI~?W=6l=c-mS8 zFX^JuPajhY#-pVuxB`ypJ6(KYY`O?9ov*QXEo8T6IES5@1bj_a-1-FL5Dy5R)fA!m zy(-S~Hlk7(HMd*3hsdU2EBLvM`lK!|7VM@lgKq3q8&Z1r?78>LzrP22w5kXP`?VFG z5|J<^T3eE6b{*kBsn6z_mK)uT|DgeQ7tYd^GPK8DN@+{cITWIQ@5G4OJ+wpQ9OkJI zzIwRKwP>SAY2e`TA>WrICc=7!sQAS#^luy@-ySR4B0j->Tutrrcs5RL9QIx$Erh!> zQ+36<+1<@>aHadXc*klPGfV_fTjD43MPpB?T^rfAaaP83;n{>XeHM|<`nJ7UxCF|4|(WNr}ydQz9>7FB3D8HyOkM0>uy2nijIh{O&*q@E_7^R3Ra|i zsfc>8Xu#yx)t%P_-9lxSs|7k)O_)IG34(8|L zGvOdW>T;3JQdj3-x}Tn*eD8e>U6x&d>{D4xQ=^pItlVY57VhiJpZV%67@dY&L~kQSSqY^IqMfj+g89oJRnxnn^Ls9J9Rw!Rza2eHelyZPh*fN4{4s z=gA6efwlDh;=Kv?Gi)>*GGe73^Wtd2?rH3ykZMmJ4!u)8G)x=w4bC)r-_ulzB)EQ7 zo7_3OAeBZZ&CzKI#a?zotk}kolQp71r&}A${b;Q_kL9tJ=<01jA_-07Nvx+^+MJIZ zuizz&8W{S<6!LT;l5#oZ`fht~k?3dq>^fzflppne(`;&{SnDf~;>6uR;kjCruEQ2VmH0->NP#PI?jaqW1|UxAmLS2NHj3ebnCF zz|{;visR9y!gnxQE|jd3Cp)`yt4~0mZ|~1xK`x)k+P;c|)FIW$@fr{H@vrD@bOR4L zpQpFB$T?&F_}d=D{IC{n8)%*3m)^TgFQM%OJFjR%$(Tsxfb!o^K~paXCxEutAS+ZOGdY)9_ZRZ8q`nxkuhrsN9)Fs&T81)IqrqqH>17mKC*>kP+vB-V?oOBC5T7S1cC|gfmkvpt4*v?xq^{xTFf_~9EAz<^$+s^7JpQqF*vfob zY!AW-GPDFb3DL|sk5K%7(pkZN{f^}OdHz?avh0bhhbfjENY=tUb3O%PO!4L2xH;(V zEY4=e-`tV$){@_8@q)_m*ccy`JJWfj{p@9ektYMT0xY*lrD*YWAbj)*hU>Hbc(+Oa z7~pWNv@zgQ>+Z5vPi>|8c~y6)${t;9-|Cu8;??QS+N`E-uO>Y?j*3Vq(H?;mn@+w_!NYC<7WNEUl0=2iXgJx_3``N(v#RFQi?h6qbmNb zTJ^<8?6^tC)z{mB8Ir(t2YMx+%P-uJl#B0~l4*?ko)8vS+t(_+CFB8mC;nAR?aspl zF4zqgzIC}Vmpw)*U+6@t6~v&bXssf$k=NTHW5^)~a$rP*e<9%?%DlNWC0OL<1@Zo= zevi>0{ngx*`fYnpBD;!bTrc5}>+W0RpJ!(zW7Lu;Y?5NVC4XYg-VTjm`41QPh5M?@ zX)l}ThKw4zo=ZeJk-QimrJt9UHlq(y9Wq=hW9N-iZ2!RmL}q-$KmHCqVVYrnQen^p z*Ke_Qq&M@W_;I09q!`>vTOeC*ZNJ|9fmIoCb-yXB9_96Uh_djtK3Nq|rop)*l6lAy z$>*ngG&c*|Jn4Q(Xn~*A>w7?6XSer>-^UazPGR13auc0%L(kgjI>#7F`l?{Stj@Jf z231Htg*08N5BC(97|X(;{HgU))WcS#PdFgi`Ev;rb)RESA5~?C@*CPb3CtIz7loX5g_EEEb;Q0Sl5c?Y`LGu>?f0rCkY3d*6RsGAVven{L^>B+bOC)_nui>QXzh8J53cvvlDK)&bX}or40c7*^%5 z3Ot0Auk!a6RcYTG!79q2w~S?ou5$eqM7@Z;a8Z|=!bFjti?QXqr1Y;mMLua}wV6xA z|9Aq5BtYHtTuV9Lj+ayyjN^=^@dYxciBIq3WVW{zd}4TGO4 z1?-3~H(Gm)iMdxMr2Xojx*7|`eTJUiByq0rN?37QO^Y1w0P>5kwZ!kQucGi&+>a4V zHeNW&@3BFuc^y5?QLme;40H6lD4*43p5ipQ8uQ^Y1#zR5pLX~HL_P4~mcZ{_;+@G#z&hwNTi;_r5V z4Q%iShK04Mx*vkJcxehnU4b58?m&p=l9LCr8I~(ObqFo+O%wLefKi zN<7e(!GpXec=Y$Ft1*XA(*Nu=ayQcz@pyfp`-u969E2P-8y;_|(=Vla=Zwu)So~h}7mx^HNuOy_om)nyXz? z;$WkocPBkDrFTkqg)?0%wP}=1e*8#+&6a`sA#3|!Ye_NfkUT~^n9ddt12?FtnC`FzSirdL>& zjm!8&8re!`1OqhUcEdy0kG`wd$gVj~rW-D9=ZgWExCN!@a0+hjrqo!hVi||Sy%U+1 zVjJ0I-BjqM@k%nd#kBN4?~q|jdW%mV9CGI!3irbYR2L}ncZqo#`n9x9F6_%N%;wW$2oj9OD<6ndrS26hvkM@r$3Bj;&MQXgjes;v(<3e?tSp0; z%4j_J&Yok9rSUJraE0ZrP?4Ew;a1FGZ zEwlVIQPs;}OoBFM%W8jxKV$J)WM_jS@Y23bROVI>+WBTgz?eq~+t1AK&BXuJ zZTH96{tpc;5P@NQ_u|C4jr5L(TN4dctnV(yZ8x8<9$>%p6W=HM)4Dvm4g|5=;!*%sYMZ82zKV&5(zWF<7+QA;$XolCQm-hIuOt&j{3RBxN($p4tt1Gbwc%e?#<(OUcmi@OWy($XK~X)|7|hrs85`R=X5qpssU=y0$D~VX=#GurBG& zLs753*lhNDEoTpr1iv-0={MzoDB~>M-RW3xr5R1F`-#_#LOq8EWU0t5l4$p;;V#>*;1q9Jh8IEqW3qy1&stg^`vo;B@8cTD1i}54&cFr`3 ziDNt7Aj~&&zfc-F-o*(rlwqQN4o7}^Ca(z%A(czQ1SJ+x;}FH5ed^Uz{oF@8x3Nmh zjx?mjE%-@Ql&M)pvH)}p%4roD=o4tCNUt8u$o`arj9`!I<+NM);(v``Perv0dK!FU z^(;5}wwiI2Nhe!)n>3a3PJ3@_&Vcksy;evZQ6Z$cA!W~1di?_>h4uA#y;^73)@Avi z$s%Ke(h$zbp~pf~aIy5)VJTzdd{MO%;;ajX@=xk}WtBooOw3BeB$k750;D0%Vu+}U zbeYJT7v$uSLV#GPJeM$C`y(JR6bSvjaY8Bkh^uAXvG`D=RzjZCbntF0nwLa8eN1k5CQrQ!fQwCom<-~x2&Q2zSu;jZy=||H z9HEB43+d^kWt>RMA)7fOxj-__c`G=ZWW`TtYuIyVG$eQexMdnUHFd*_w{I3FV#yb9 zDCOjRrle^J`$G;)#H8gJ>Q}6O4bp|vKn)Y3>FZG}ZAY`rfDCCs%JB>nabSqEbE%`9 z^5;42T#EAqc)(!GMplfp_-7+ktj+>P8jW_p2cVF1x;`1h9Eh`~=8qbSQyGfin+Oa6 z5+}Bj7#pRM=Vl}@tY}oSeK*8t(~UcYJJ{`w5vhIe5I0o(=CA{>UyK0)jAKa3y7y`pb34AewV4W$D)i|<#4Y; z?XKMS$*Q#Lz}EuOx^wHm6YfLz4{v$G`_hq!)K=XR7^%9M%Z+a)v~IhV{1lx1{a#C2 z7u~7*c}eUz&+RbjRfOZ}`?tQ1g76m}5mBpJ4;4Npv^hbvf{EQ3`bOUKf}bg|F{<&M zu_J<-%R{rGa-yf8JHk74`j>=<(RFZHF~js|yGI-2LkZfI86S$7#X92tycN0BBCgl2})rZJ1taQ|XVtt4_FjLE0U zWNmA%e9@|BZUn{X9$l@9XLOkj+K%$P{%{tziP!sLgE*)^llmSa?x%JmtaT>d05Fb& zhfuh$s{2h8Q}7g~m%?Jvx%^;4#^2CdJc~a@L-ERTDJj_=s+z!Xr!Y`ERzmX5eE3FT zJs2ipmM(2E$tx(M4SACB+fojW(<J~2R% zcaH@o_?ai~)0r=Jg_`jI6uUlh^@V|~kqfAtHg8W9fm=|9|4)oDaG~iYTDO+p;$ZWB zO$V8A?o7BzT1~LekWJATLmK8Ke9B^MWvD`<8e3*r9bTiNPb%~0!7jtZ%=6SQ75o<* z6z<12W!t_YXyp(7;iFwRQUa}R3B+{6>%23pdx>#=x5%vPR<-Fj`KE+eP$QK3d2EpL znn>BB7|P6IsF(~#?P1q>dE2i1$`k{@rdM)%Ka$K^hP}BV&w&PUa0kFF3UB!S{GHsB zIrAf}BXv)|eGteclU#2=H1YX>p=nW-QJay*mvgcnm+$)6qYqGs1J89)DXB)TDFz~| z`V7ZoDs-Kn_0>peXtFMO2EfS?aeHUw*oAX9eu!RRYp_QgEKRU)3eqR#?4pt^Hy9kH z{u7GS;NB@14BN8aq&PZTth4yS@&8@PlPAsjx02`bJF4cBlMX7pALQ-XW$qBY6v5j8 zU~D{B6g;EgoCQ+(yFL{jXjSf=I|Xc<7f@2D{AVd;yez=(QOEv{L&y zx;Dee=T~p8xRGk$Or6)9*GDOF@tIMFG5C6%oQodZm}ci^lF`+p^mOX=`H46j;n)bu zgqwI<5i3QnDjAl#2{>h-k+MV{fzsSU#s2`!U)^WH`|W4TPSgkgAKKnAyt3|1_pMY^ zsiSa zWBm;b^t^4UHm5pC+aIzLzelYA3`wGAz62{Ah#gSYI%!pO8~n`%bFVwb zT)?J4^h+1Yy&ffsfkyh$rQmcYAn0doO%fKk?P&Gd`Lby>_DX3m|&nK(Aiv8(rbW(ykNd(?PvP`A*m7odaE-o}QYFHoM*dMvO+jKZO5ZD|9!Uts3!-Q~LpG@ttz- zdUkO&E{GeMYC;P&VJVqaHlqRGP8USI*E}LhMwk+Zv{X}m9_cAp^M~yEylIFPrAy6_ z#=we+N2_kQ3xNJDe?rB^-{gWF8=oK3&U#T>Z8>Cl$xxF_jDu-Af5A1H!dOrTc*k4Y zVckDI>-i(Y&F~GwlKd4*@njeH`V|#H_>(!>IPzp#UhFzx#rkcW(;1iuk}s2_VE|1o za?3H4#M5nAvoq$?c|yCX=MJ3Vn9{L?NyN>bD0-kj;nB|>Rzf`TtUv{kNUnZC+%$&f z;)d3=bF?uCGQic~q~pWBlztD^yNS=9=DGPzq3j_OiEwLBpGHcmcOM=dNVO(brskt3 zQwf$gTwri(-i$YNa(Pa&lhe8TvhB=zXgz$g5+#;QD?Ei+)Y82 z|I8%HU^AREm8uPc`a8_Xx*5bJaICvPHQ?-PDNU{~o?z<~i(D5dQ_id(x#nO;STqfe zKnuVUF(p{*11&S^wf9vOwGL+qQ;w{$=fB|E&Qo40!#@v=RBOqV62ER6+R@}?(New*e25`j+$+;5dhK%K`YxV$$vW?!&5^B~Lhy&l z;{54LlKnJiwq|@+h@x@H>}~78nKc)8^+qp_Au8%^LMKEFE0YjZ8^Q) z4*NZ(%rwvB2Z_S`=|h$^_=C&0LK_|4Wfx>J-*3S;U7M-#Mj@CgG=$DSCEf{6Z*=ZV zS%(%`n)W|%hOV9cey?MWq)W;DuvQdBNXWjFSN%96b!Cp|o=O+h(_<_2E@dd+77~Ih zyd4yqqNTZH*Sb*4qPs*l2|;fJ{D3tz@@rXmj2k!M4}%oJca8(Jn3cd5z| zuURYcUMzg?u1fioQ!jl+YeB@3ZY|@MY7`Hs6bf(9{&ScFY^*ecF*_L@eG$+`mWN97 zcIdM!I#yGr@_O=3O&PX#B$01d5Hu_JRp6C{6tMga!M~SfO!tffeAp9Xp4AZDzrV{; zHJ~*b6Ul=$aTXg z*gG47rC^cNY~N8opL7>}CiJguIXVogcKXTmOc< zg^Hnvzd1KQge@7>w6eNp; zZSDHS^{6@SwoMP{4M(JV+?3JQk?GX-`Src&;ALip4Cu+AO(fN zFtPMkLM^{i9OFLmi9JO#*~2?Z%i6;iN;B0|RHPKdH2(`gD+8!yBLDx$YXZzNY=4In zArX^|njyTflf|C3smUhY5({e)&O&=f@wyxFP^k6c*+h&REP*JcTLIT+roqW?8x$A9 zv+0?cnHCDt6rWaxAg#{M_^{K#{EdQ{`I8e;^qR;;BL9FntP>HDffp?-?92Z%LIA&4k8+ilX{9mcY>bGH2qLT;5jW}lcd z0fvZes(>qmJD{;0$m@IJH)NgW6oF2^WC@C|jrES;TtAXfJ0CDhD=yh`RbHm@aJ`KpHmL>f#AQ8W~9hNYdF4C;{f%F zT>AaVwC${?B#~_2MD_aoJsBdd2Ug4n0L{`)D>naF7y{XbF;Laoxh|+=S}I21GD8yA z(QDx)6tA6%cCK20U$A5`)@73#qPy3_g6nM2rJE9i4ynwXnroeLl=CUDxHKFfF4c5yyXdY-;<``&!8yfHxgC3^NOSQtS+5w&#~kw) zp4muqoyB0(NB#bqosPFq!M84sdENK7 zwx7b8S2x6Wa!}3*Riac=_K`R({v*s)LDT+D&P4cAN6CZd`F}7ahXoXv`S>|y#Y(~= zCo@9CjK8#5Id}wXtoABmz8bmMh;r;HNEyRP3@`MrHapH$S<_#Ilv5kb0?Tr3Jm^724J6^Jbt!1Ony>f>^73a`?0h2P=){CinWQ+%irB zefN=bi}t>0cilmQ*CM^MyH8F&J4<1wjpS_(V7L-_GUah?j1uuHYH8T`_j%zQUgz>E zDA2FGEGU;xlB=;MA$yI#)r^qpdOV+O%YJfM$3Ivt4H$EeKFK2^pEA!*V($(E>fkK` zC)N7`C%o)l*ZDGGM)SB#QKiSnP0G5yQ28mO!ATAAGt)=oxq9^D2Fvxt3FMgBi@W%(}@;39F^c`(~FQR0OBu zIXLl5qdC$l2YVzEi8$J?n3{lxwK}+kAebpm-hBCy(3*?o?nCkKkDTEq=aIRj&h_cT zyx_(o!Yr{G@iXg_pAlZM`96F73~X;Dq@f711b~I~Fq><#e1HHwIzD!;yn_+qT2^?u zcAy$94V{6OJ1>c8_4CWmNP+EWK!8@-y<+}GU6jfRyh&U$7{gmzZ1LWX7AAXSEe;W3U;uN94zTr{O zQ(WacrV&7krYIInFL@oq5NoCfk3VFYW|tWhOV6L{D-)fOrO zA-Frn&g=>SaY0X&8zGN!!(%+6r>e7j?6l`+lkKlN?wOTa5mr${blglaJ{~`#)uTJ9 zV-(2#>@RuTP-Zoy=7X#6SWFSCj}d7<5VK4}1Tervkr5buK+ok^T5ChEDaEJLoq#%yxymlzn zYgj56j`@;2f^38Hy~a&{l-q+Z(L5$3KFHCB3Lo>+t7vv&7)zFRT|C)Je0s8O57uRW z#;boDWV`oh1)>hk_{b8LCngQg?#3Q(Hx!=?DTHn6(?+7E_J}0+(T%rwBYU$g=uzUw z)>Ziup^W8QSC{;8b4xJ2gk@AEcAxJ016(KgTqFq{8SxE>xE_Ltl+yPIS@SIY_V}8d zX7lJLn)*w7|IO1L9I zeyF2dAD@1KPm~QQUH>GcNXZavA{=d+Ehm9un#uzW@WEcR-`Z&XJfYs1hoFzO*Joyj z$=^{bAOa?tJorFfZc!uMP!Cvja4$n{&XwfzjKy*Z}QVol3#hBL*C$PMnpmz|DrCCw93`o^LD1+Y*6tmORH>_%gTl1gbfyVM5QBP5zMt73Pyr%^bAU+kG(2C3E5=neZoR+E0i z%l_q_mOGihWn!_Xay;Hx5{rDq4$ceO%*x0qZb;vrF2>&0f15Ed9>^=dm!Jx`A8w~WIxa&6Gp+CS{{z3telD zpyML}V-jnG^9DO!3a;5cJi_K|#b&zy0~n{1Nl_%m+S*eZ)60BQSWbl`)BSh;k2(x+ zlF#H38n1IAqFS6j>`LoB-NwHY@QchYQv81)RC#oU|BO(hW$;^K`)id?_pVeEVGx`S zJox%JBR!su?n7MsfvO~p+zds89FvIGDl#<1k*k?m13n;;>pFgq z$;!1v@|SB=NBGb0m8;Z?O8=>p|NXy$Qr~u|>Dd;)8L1l=aR33`|Dg4!Ggf@;swj|x zBi%vH0uI_U48Jv0i%cFgoYAn1Dop50Q4@qv;y^c;IOQ$$#)-R z6^u!W8e?J)R-t=s#Mg|65SEM6$KlA%BDdhma4@=20ouCfd|y0)#B1NaChRr(y)!b>i@*Nxjc;qen`8!J$c17si~Ea7EyH4U0MR?Two2N-OCn z(4~rmVYA+;@iS%9~gVfU1MS3A@jw zay+<2DhcOvUemxgKwSIYxq3j(*sN&gB3#*A-@EmRm@3Sp$NV?5VY~8oqnU(>nE-;5 znPT|QN-1Z6Dn0c11`gr0fc?0^d*VxoNWZCjaBcUUk>#6F(OZb+<%lx9{4&6Sv*LlX zzuo$fKF6@!9QhHcBw)VLy=cx0Z7gWdNpIfLIDBu=cg$o@USva1Ziooz?dCpzV>!dO1Q{tb)jHX^jp8yO(O_>H2U4|z6LR5H)Vs^4o}T^r zDMB@%up$4OKSuuUKT* z9KmrE%xcw}DjDo1f4_bYPX8bn6LU2#e-TEXtgMj35HymR>g|&%c&}|1lrUP~RY!M; zBdNX>XNd61&gVj$eVI_dbxk35*0|1zx9d4HYlu=FG^skL5s=JPSM)pWIu{0(s#r+N zw2+yL5{qzyzLf;Z4M3UID;WHqQtbrTpxDK+Ohq&`g-L(MYV5I1+lU+|seB#G=7`%$ z>L?T{uvIn#NcfDWj1^=CUw2MR)8s)!F|4#ChZ9wCmv^gK2kNRAX{O zf`c~7#ENAIa$avye==={{tubV88N|d=5rk2u zb&7==KyZUG@DHGWEK1#Kis?Fx|5q^Y-!QOfW4RX*A5`(~#tsFmAp+c*Y|8woBH{q0 zBo`-sB*y9~9cV*@N0htF6yZrm^=H;5903qvc^spPTUS<>kZh za2N3sCVTjs8(z@@7o$_~2W_Y*Hm=8JtVJP{4*OnKKaYqp+(4@qu}pT$b-vuF&S0tx z2MjSPwK7rbnyOtlbQddGy#XeD!J@fwfvi3EXOtSO)HSe7Eh^;3?aZe%Ia*q+1)_Ub=-!&5YKwdLTJo_O(8 z+G$59#Cdoc?bdK)e;;4;4GKo%+OH9vjkARs@}H$%(w@Of-8SKULzv57o0FO5yfsXP z>PNrBy=P2&ROU}jjFwv{fS`e6uv%q@B!LEe2XZy+CbH5ZcX$X)dgkH*!5M|MP->oV zaNt8QSYss3+0l)(0<#^;9^;`A8(p7+pJ8S%9*X38q|!%0XR^sh-JNdqYjgnBB3^5w z?`|DGIv(2n(HQa5G7}^)DQ}iPt9A`0S971w6=-Z6eo6Hxv!^kr%h53U)(*!vqg_#jdh|Sr zFa5UYM?d_$rM58>k||nV*_u$HWNp-9fM#V5%lQ~YaGD7koQg8kA&`Fbyu-(#7N<^q z_g(GY`X``JjZ-_DKS09@nat2sfvG!W%uAd}l_;X5Ykgi-^+k}K)tcp-f;;-70Z-Vv zItDrRQ_xY%f~@meas1UMOT?Di)ab?C^GzE9C1;Ut`EtVLL+JMMVkHPOsdC#1EdA+1W&D)d;2WTj8-vf=5<3s?2+T2Js~gq(52>$vG=kCE7|D3HiRT{DuDeUe0hZNlZw-- za7lV5eZl}rcZY*hZpUrrr1-yY2Nf|{7?L`7!0P)|4u^>GK}V>Ndk3BgIdCw0`vu)t z(BI$}B6=tJ=qkW%E!U9>qBpynb_*qSGo>2~(B%>JQ#7>~}TG zXk2xmOJuC}pjO*iKOVh1l1CLOLgSH>{{rSS^%aWfw7T8|IM&f0h-o+&y^U6r`n*GD zinFt0ocBphzDM${fz4NELLF~M=)Hy2^chgK-YMaee(cpOnFKvtai3CJ(MuWE{m zO&P6;6K&b-89f~K`NJXu5sE!dA8BwocKl19lWoc#sjUZa}=3d?C8n6mPeb+!s$GQ!`Vxc>TR)6D5{% z%gGU`&aGOZ9Gi%7)H#@!SK;dNmS0adZCH7f4{-oLvnOZws66z0E|`5>N)Z-58TZ)U zXK8lvu3BMdz44sdX^^^L53cT16}doX$2QZip!Cd-Vt+KdRb|??FfZ?aBT+)|3~)1Y z1`E^V09yv4U-NT-Sa4JwYJBc%w!k@f(J+6fsT3!`K!b=*ifu@g1fXl3Uv?&Yb}#4) zH zw`=kTw)(agBtzf^Nt!tG2w}dYhTJ8q%?Nh--f z+N05JZq*4=zOOLJ;O9MU2S!3)Y<0r2LD_Q3u2f4gaeX80;OxGjs#tPb1pb6ihDAkVZz`= zDgyjY0~qq>&rDd(zP*F6Wkn=yHh1iy+#0`=%|bLub;rXSri9<$LsxuNX=N_B>60Jz z+)SShY^*nI6Dv4FL6mnsm0)FN(0B^|EAmtvu&8=eIrxG1$?k+nJGkYNXT(sE*GB8! zfbi5*ESU|&(?jt}pZN8T-XJZxH*jfTvT$jm^=1khbdT`Ol8Z=<_d_~PT0eDiqQ?@Y zEqHlqJYjPOtVc#FQ`@Bk71TJ^bvL?STXkZ2?_kN(V89!H6037URrhq=?)cAqhPcV) z1gDKkxyK!N{RMl5yh}@zg0`z?L#Puv(#6D0@7Qa^u$+k-cyvd45(bQ6PeHq(yAXb6 z#>6|G;uok_=r3+SXmQX-Kx`(DTZhp_z(5LN?Wyp-ub>z7C2q*87 zD%2ob@6R8r81#P*3IE%nP0zOr^@1RP<{%Xk5*9`PFi!%0!c)1P7MuN+{a4@vfGvCA z0)T3hXD6JC@ozTpShroyVtBj~OqIG+NjItO6{U31fmdws`;UM*MV%=XP)x{{&IwIwo5_mBBu36Py6q7!&Q9jugg}gOgvLXNP5*+3*K@uhSaP z9rnEh{)3JiYn=S!A$EK)YW3IlI)E14x?cOwb8^$arbMo5ll`djCV6J0saXL}Uaf#4 z7DwRXj9of^hxdvw3FztxncUJIe(+)^LFtk_O66^4Yk^lNqqw5v^pG~Rqu#+z_(#qN z{?Bp-!!Ks>OHKd2NdDX6x*BT!BKOd7>HJ4|&g(hYl)0IafWa6VoT9yJUL{Wvia3(Qe zo%&j-BbQ7OFJ#W!0^tkRnpwnK)vCn7P`Fg|<`PG}brfaN3;LRl1OcX2q$$zhQnBf7 zgIF^B)s?TfMkT@D@o_m``Wi{qG6MAis$VN{v-!DEEGd+`rx?TwYMm5jbN~rFJ{?6Z z);#?_o}pr!N+~W5M4^Nd&rndtqhRYwHHl_45kZ_geh57Qg{DkZO2PkG=`5Zfb{ z6=X8^CWhe(95)gC+d4yLk1-*I-*! z+&l$JKdM2z$8$l?apHnd=5qtjKvP7Q_{AS}7Q)k=1m^kr1M?2CLrw_I&_2FjNpDMd2j zW{bAIaIRsh^}}khQo6TI)$CMb#in+#KoLQDvPygG({21tmJPTd@TR{!<9wqniIXBo ze(PAQ&T+z8kzvwmwVQWMRjF##53Bm>!_VQUcBRddKr}T}In0rvRo5C>E(-Io9W3yt zM+$mdrX+h5Lf553DaOxO_2A4$EQyTjaKZ_Z{_X%wcBjC*n>v?%ilquC%bRJv%8%!d4rhKU12IVD{67waHL?qVH4OQ^(G%VV1zUUd!$;?E z9G8k1oRoNO@|U8DSezVDvY4ENX5@l38$-;^&0oz4@1!8LE{dw(mbo6W)&`8IG-K?# zZUz7;6vSdjmi=&EfzCJhq_|7Cd9MijRnhLmnP-}Of*o42kjc<%jn%hNkRbD?y^woe zdV=RP?(?@C+FY}dOUgw@8g_V*Uq)B$ePyJbVDFa~Cmpf=AV2)Eqp3TD*u;!y^C|Fu z6#sn{lal5Z;|iwY2G`^K@R{bj%HY9`zvpwcwY!>p66OK+Cj|L5-gI@h&LMrdkzwcP z=r}o^QfJ5I?g4th^%0}{3EI3Tfaw*EG0~Z5_k4&n1%7&eYlf)#mrcFNgdp5 ztS7z#{N}&q7i(=i7ebr}UwHTSBWzi6I7Xu!>wE?^s+OJ7*Tb!kR=lzPd>u3G`=pb_ zO2FVFxx|j0$&q?WW7QP?{^1`O$l6I;x^*aWW;O7pepS%p`{O(2#_~UyEGc2XRQ)B3 z19@X*S|0Tc%Ao)m2tOr$fezD}XDtSZMJ}?qBo0)W;v}yB_8Z2f(!_0X%5kE=AiSeu zs^XS7JgG2mGZ8vi_t{2XjB?Tx%)Y4<)}&z!rj(Np{}F-Wa2C%SfJ;vs17*h$1S_Z~ zL~OG6Yt)p8u!4r5sffToWtbwSz;;KGcc&y8YodY>Vv7m*c%~Ga5g23ctxgr{u5EDC z;O)2G{N9y*JSyrROC&kz@*KTrX z>clf%tHgR0rnJ_F#;dJE*Khfv@yP>(3Z5UY~<{VVoLFCDv#2etIh; zqN8T6eAGSWLQ$WS3S;I>!0>Dx)Kwg+LWAKeP}#jDJKq8u#<}(6b(gZYgG6|DT!b$U zeahk`?9G|hADD-4`uia;$=htaI2QA;wQhlb>)U>q zQqs|hDpy7m`VD>=3`U^wRB2_DT%>oY5n-~yb>JQDqJVoH&#l(`#p`t=o{~xatcgLX94(4(qG<9V6cA#z`Km1A2oS* zZe(2;^L1A=U@W)#HojTd^}{%7G-PY-@mxApa-QCR=2l5OgjyeLK)2>il`Z9k|mM}!F^r9WUD=5Lo}8VxQ&e5$rrMv z#+Y9|3ZYDuM_*R(k;t2V%`2kPm7r{*^Pa!%C^*;+4OP)l+;;V4SB_4H^f;U8=PpI% zCYAwPUP`H`v&tSkI1v8i*^_Sg#u+=TyR^J&|M>zo*RkA^K^_`|9Ts~dwf?y`TKY9s z|C(k-%)UD1*+~TdLe04d&EU;IOi86!7aY~JMON?h6tnGfzgA*6)>Q0%E0kLWj2fji zm2!x;w|5tJf;;B47;DPcJ$xm?c#e0A^}{qc}6cei$?Eul#14u;`c4v3t?7p2zi!~T`=VMs7ZQcsUq zt%;n0(uzOvn*tY9Dti{Qx?-;?&CdQ|=s=jf%158I8rX8It0n9jf8?*cyTa8l-ub6a z^$zq>7>_VqbqGR8bQmmwirvmiot02&&$rOdhmIOr5`+Z89m5Lz2Z#=s!bh)+1~(-- z+GZfnNb*^PSXwn#**r^CC{;id468h;U@;lD9;=sB#n{5ihw;_}R^u|1{zxDiL))Gj z3jS3T>EVrFUa!?L-J;h_Y(CE0OupwY1Q-RKUYsua#@o2G)nhYh{fp9>cus}@Y?=rC z(;1^SG4Ox)0^Ekbc|aqWBBQfCWC@5#Np%*XusL7jUaU5>9pMr!iH*>vO%yMXTVA0H z?=jV}UQNd(7$qURS0l-Qf(8f+o#bU|V;^nC|BNa)87`{FsP|Z5=eaIA=1<~C`wpsDgw#1ZbW%)Zm}V1uDK37CD(XelAWC` zgDDo^1D{f((c&EQouEgNtY4plKsf=E-#r!k#qm3Fn^-%89`fCg!ld#EvE^2K|3DZh z&ExTUY#7WpSs57_(t`M(zy%hs&`T0q9A=Ez0*aA2UK$3+eV$3{sEv$ix?hD-KLO(l z4)G|)7chG5MhGUd9WPcN>hA&P%Q&0IbCufPh=7qZFx-=s6_F6JQ@CSL zFk|6rR8Ac?t?eqwuo9Vw1MXc=ZWk>+J)^&Yo+MbrC0!F;-?9?$Muow@zfzIZqO#j_ zqqXo{a&et4CUjc4_pgo(NQ@b=^+@Ll-ENZH{b>2LD!4^JmAACLJSKv_9FfWDZ*)4{ zHN6rax|-yO?tR_b!+XU;cvvH41BKnaxO$9!t}=Xem#a03RAx?_BTkJ;Si8Vj|cJx zck`NR+XCBZXV0$pDJFgV148kwGa)P-H_CgaW<|@9>#Rt*YZcXK#8<9|bB1P^4Kbgn zK-%ken#OQo4u2;jY&p18d&K@VK`=@v65>C|4ihE9PqI=mC z+O#ZzsN%eZ{ekgnSYFFdFkZpJ3U@i%FaBi7WI>>%au*+3?n$9?@%+VY>}HO#i5Z;2 zEZ<&wA*qh;LL9DxJQ_gzxyJ4$j~rpUhoVmVR79yeGRS153nq-h4)LzZZAWKf$#VV5 zFQypSrWN|_yZ{M@vF+#H5(&3GBnG5O`lf;b&H@9>m+;DtMEE~9(cto(1F1O|E??Q< zJDvOjuH`V)>+s8PB;2 znlAT6KxPwP2OhdnUj4u_qh@ZJ$i50Yu&JN^bDwx%`5{s zqk-a6^7Y2R7_(Ny(4d-=Tr|LAYGMCC5s~n771S)jfA9^O@8{^Hdh{z<*X#-|o+x>_ zTNP1|1fOBV(VeP%O8YTGi?_Q6^dEMnTs2jr@&`40rAh_MH{vX>7p4qT7u_;uouiNM zRT3Xz#qOEK<<|`oo&_*mj$lwsnF?+vRLB_;2eRXney<;XC-X-PHnlufC%#^FfY`@m z_o8!+Nop+qC}hSPhen|)Mjh=!Vk-+Vszj|p3a{TecDP!OVE2hI&d*DKu4~PP2V$Xh zc9n*cpv;xvjKnz;Cy`8;uEqH*k!aazl+@*%8;1odFsIbJ4CW4o48kil`df7_bq_r{ zfcdkmR2cA*9kGILCw3v`gP&7W&*0&TN!jhOP++O{@_IImw`yqOkljV1sY5?>;r5-* zLzf@g7mkEA49j;rzAu&3u|6!6wL4HJA8a|bS$QZ#C&q`5lzeY61BFLTekzgedC4m8 zw51arfzMn(mwlVO@?k97HPC#OdoD(2G*!5*Bf^U0N+?z+fkzr^(>0m#&OUrB7GM&7 z!Wjxqxvu``AEAQ)?`zf%Oy2`%u|zD^P)ATW;_XXrx$tO>QXSs>K|rktTyhRWTLSO6 z%D0c~qOD&!;gygiM5W`@Z=ulWn2b+@V9;(P800KlUh`_dp&bF9p(u9DZ1^ z&8p#kJnM^Y;fff8hTQy?(5IQ!o6sSiGVMXwMYKFq`Ujz$kazX6!ruT$zlK|%Ta_=s zZcU1TQcF*huz|{e{7|#5t4PuZ0_WiQkNHMxRvojP>`I%CI6g|#gh6jx-HJUEv|mK( zz50;Kn+?sT23**;{j@Q(>2~m}Pa9wTv)cFu$-Ul1Rwzs6U?kZA?RGK=?wAa*z(s7c z*yh?dl+DveCJakR+@Lr!Pko1DvdW?#QWwE2Rt+3!Jfj{f2CJ!Fbis;PEJSx!@_NmV zUGXC;cJrt|1r1XZtODU2CB^-iBx^eEGFth>)m{y3bgphVma_8&)223uA!z$kDoC|^ z_Oh6aB6U8q;V|7z@b2D{_}{wy$VE07LzInFuX}EzO!S<-faq>&Zhk=Wu0Ej7{zP{l zgXkwVozWMzqbE!Aa&URl7BXN!r$rY(Zc}ifw;nK|)@bf-!HO#`t0`1{GgJ|$g9w7L zW@QfCV4u?cE`jp+3)yI&Z<#k%9|?wP?M`RWj(2q72fV&a5>9vT^am!JN5*nBgn~Q@ zanlb@$s!dNBMi}6u&o5(>EpUS4Os4}hHHa+`#6z} zHw1Ah4s(TyoXPt*!XbY<7JH1gC#u}6CUjO86!ypzYsYmP*C zW$DIC4Wc*l4C+ohLGmcg);kP z`)mG|?EWztFdpmy4YJ>ZV7P6WZt+nFrmih0%mmiK4l6pf-UqdVJy%_`tSO08ljF2! zmvQliEDb+=-la2BZ~rtRAS8*XjY1SIA_<-uboLyWvHlo|HN>$ZI^U+H9$42AU2>bt z;!jPGoH$ zsH!S^y@;D`ybCue9hbkcm)-_$<2y%9(_LZ5J92C_5rFuMbo z_O`=YKeoj0*i!>f-{4^^*k=0WdhI=Nbm7_{SYyK){5a9~WF3P9tF5e93`Y_ZGt&OZ zcfV9pwM{Q;1(3N@U$|4uJwB-Vue*J=L;Na%Tf#rH^_|egXC>cRBc7kjzemN`gWV(Y(@0XW zIou11gLy?jbvJoR6H~DZj`F+agXWG87mKqoY^I$V2eJY%=i30p#DBx1blTh z;!eKwMmZBdJV3JHfoib-7MKz%{!0^Gz51of&pgvaTqTg|!Z4h`@)pst;w5!HPpH~N zdTG&7rkgxy)r;`#(T(n1Xe4XtfTjfzS_EyLUAg?HB0pyjwKTK&r5E)uY%9)e|e+JFLWOnAQzxAoP z9=aJTEHgSU^DFRu5MsG@fc(%`6}ql=@X+lEj92mb!sy?|U=eqbJF^e=m zygol1i1tWw+h`xqcBaUuB6~lQX>-{oCqlqVgLXRlvgM$)`5rWCxgN0vUjqJIFHh1* z2lHoR@r2>c4M;S){Y80kNI>uMd^DGRYZQ>K%(mlfPWSfMXz)@iPpIvdbgFcNpkVjBfss`rH0;DSa8ef0a@A zrCk(3OukrPM8h4O9kW~!cgW^Zf|3pwpw_Ht|DV*FX?_iSe4;>ws>${)9g-d8#oyh+ z5$UL-t3rn%hk_ql8h4S&aEQZVPA5*~j9b+ZZ0mTEf{n(C}5xBBWM1`%Oqxv zAC@vz@e<4Ls=1^*6~=P*tRiUriNW_l2%g@`H4dpv_P!E;$YZk$LJ}Et%?peLv(b6f zeP#7aM>fu>F>~kqB+jKPi=`(9)Z==3LGQf~c-&n1+V_3~cO__Y1~i*||LN;Dk=>2S z*>r0QFnLVRqpTvS{34{$(`LC8Xted!yx*ac4qXZ@!?}QZ(@*8 zcLE&;#Xu>jL3ILz4o}1e4J>Orr{2}k5b~-j0@-iqUZtSNF#<4cgNucCQ_R+tiWoGE z``BOcjWi5J7H@czP+e2BhBNVS{HD1GCi(dz#^evW-F}ePpt&Whp~#u0!<>WhuLh)N z7rx?cS6?n9yEW4@`xOxNwz0o8wZ_YUq*z+pc63Z4gfm3_k^4$M?C&W8wOHFy?tQ_f zE)Po3mxHCWv3p4g?>i4}$R~whOufLQvAwgD4hKUw6|8LrSGu^%@<7zOJ|)hzVUWl* zN)-kqp%2fvXB!rs`6dR8#eYt5-%=$$+z;lQsyOBY|4;If_j+I5%QY;LrV!|!^&Sp^ z-7O!3s`u(-SSSz>$oof$cUpq~>SkJ~=j3rscY{WOdl$IO$PiG4zK>Z;Xnak~uO=tD zqr5AX78md~zNT8!M+^|@l?chTO^_B5@02@0M(9hg!#h%ISoA~JwQki8C7>xMOS4o- zDkraK-ZP<*t9zSoR4eGNZj7Y6{ZBS&v;8%fj@bRh2p=p=Sy9(hCzGfkG06eyjp7{8 zgtsv$^Q-G$W;Da~w>gbXf%#=dtVo%mk_SpqUzX5W^$dt)O}_$cyk3m>mLvQ1k}w6B!H zPr5>oFe_7PrT3oV1kTZQC(hfsEo0mIqh>HKXhG$6K5eAL2bS`0;SVc)AMp+32bV2t zrW&b5%6fl9@;Gz*^GAx9T(oyWP4E=q6n5dWs?Kprj2Mi$drDT&m5)wHoW^vXDh#g- zl`k{aQ}Bd{uDihX+aqgJv-2yZY%Y{To3!D8ukJJQ*@GQK5scl+%aMZX!qWg92~u7H z4YaHD!BmEwiI+h(Ikvgm@rtzxH*MYjut z&VoHUXsj^Va>6f*#klRsQh(kT49gAun!+O@*}{-^yWZwqZ7_41;uWh*hy{Gz$d)Ot zZ!$&>S{T}G=8#ZKQIjmUFh~s}A!b60;XJ(GvOEdd?GMBKv(1sYJNh;kBW=R01JU&J zC#yW`oZY7sm*qVraaW4DbH#VRrj*~rgwd9bIU{a3vlo>%@FC^sv%auTNE%P8t#Qk( z%{ZA;rZS)HXGH*ws+3F>amy}nIQ(FAAPf-|qEZZxcn_@tc9^!m=p@F9M5nf_U!1^@ z)=T2R{Y^Zj+2al#g$B8OInPdL;NRs zVt}OWT}WtX57$&uz~CSj!%=K?&L`y}@|WiYpbY^CdN0owH!HE;y@IuWt|H?s79UE= z1-Jlcz--WMXu-b(EK%8#Ped_Dv>43whAjD{1_sp6p9>FyS-1To?UOs2Z>%n=f*W`} z^OQY{y1S2POqH9XGh>PMAJ-2-`x`D|!3xw@YXdoTG0XMN8B$1LbrcljRvdO-kl+$Nt(E*|s)$OZpZQbw13#22>6wOt%cuLEtVxA(<3EwB zH;wh@OwL9Z5{yKct1Y!07jui6oM; znr<1Xud#=wDUp;{9XD|z17o^H56DyxISsfv0wMF{5yGM+mf+f5O&%`gAZqGxJoP2|&A| zL%V2RduJa_aL*y@76lbu8UeERQoix`ZQHtb;k=f?6`tfrbx;nx%~;%y`GE642Q znSSB6VbGwizfuijh=EUT4b+A>=i+MV&-fGw>|4Xa)g5@}?&X5dC6RCDHC3a4PguL5 z2b*!%EhH*8(|>8l%|!ASPmFhN&hRC#Wikn=HNB;Axvpn1sJr>K zCSzBBY;x-NH~-|iYBl+AGHbregXJ`(QLNatSZn^!V~fo?ymyDvNzX{~t#B4DCI?cc9@I zkQ8m}z|-UH<8CoCTd%xJV|0`d_)Rtt2Np5p1Zu<5klqi}r}6IwtqBoDc@IV-e;dHHi^?&o5Oti%w0KABWkROK8-tbPa?n|`m1=N61_GG(RfoFL&{_P2g>lq5%6o%#V#u3u zpjcT`;5uUs+?J-VO2&;X z$-alUlS60wi#Ogj+e!zIky30qFBCL z^zY7=U7h|CS9?D)L~a)ilh{7~8A5#t5vC@auacZgLR3`l-fR2sXlq0BSch7f>W0tq||Z-==cZznF$%%`I#i@IA%14A(8q&`|l zr%5tO8T4`q0W>)qvH%mZwGU^ReKd0vaxQff(!VIn#IaFV+?-Ho*h()S{lu+`FJcP; zCxy?20rHZGAr`EA(Ie=>BM!Y0dbZR7C6Vdwr0VG;N8yJMQu&S;e`IQ-bcjTkYGw%SkpC4S6mY=tMB6K%(Im?j}d#azAw9p;TnQtPKqzO+3WngzhboSX`6TD0c%L;|^ z?HGKe;zLGwDK~3tkn@p&Q4u1#Xjq|>q|k?&I34y*(dzxQND9)BI))lWgI_k8(aFdB ztba0RgmCeQ4e0bz(|_1SmsJQ!qU#RKtqX@|R~waONfUB~f8sQR#3v1w{NWdd7hX1L zX|qBn_Sv)UlM9Kb#R;bhQwgCh4F^p+g9-{(^guw>X1Pls#Uw6@v$n z^G~;@d=kX(wI=ILokXy(={}CxcN_%z6m@8bK5OMSnpI zN4W5L75?Fd54>uE(m*9cDkc_LX`UAKxoH(JCI+{fND|DY>^%>l5TrSsY$NdcNQnpRx?(vvJUR~Rd7=dM{L+56<(eRM`lDgi~bg(A?>j1v2Y<~vVHLHgJN4;*j84dN8gZMUx6G&riOI-)D;P>5eJckW4&vggfZ{fWgXPx1^h7W>Rf}9 z(@z-At!7gU?Da~+)!Pf?Hcrfnsc%CTRE)fQSQD*=>|?R zLzOr9(AFkF6ir+{cNo-moeyK)YVV6W2dW^ucCD`V??7`QPc81kf99Fc5)(r9gjhIj zA330(P^wJFtASY!!if|)!A$l@!EuT*9xmo&a}ftVpXqou+5JMUuU!w6+DdSQ>U&`- zDgR)xT?;{!l${>^J*T$R3&AuNei`PYp)f-`K#vF>W(>kv??=Q`(`@=4SUwA3a)F3? zVk63&k=YV#uk#1At*z``?nw-$nK>HPgJLBnct z@x0Tr!66+@OnS^yV@A$5IGop-bx{yh{ z+Dfu!?BR8R|4j*O^@!Q|jRB)F;T z0_`%Wp8k0`o;ni8{*2`-thjAr0M zs=emjm^SmfHvQ!Tg&j|Cu=L~0WHMnAH+Q4KUr6h-;R=F7@{8B;DWTpJ<)hSwc&P#% z)I7GN+6%5%A#)(}Y&XE^zzZMSY12nEM5P}X&N^d@t+=lyVERi$JtbJWT9`QPZx}xZ z2+@N3lYZZjo7LugfHVZgd#(>aw!F~9M$tGds2OITb1FAN3?i6{gQ2rxUw&9U)8LN{ zJH3`nR{`>cK75Hteq`Aq>}n!Ji%lT3Bjs}hDizZ&PnW|Fa31L1hEQOBtNj7Rr4Vvr zn4~vJs5#@LIyjGQNE~KzwB!Dz*L)iN?~bbeG6O+RD;%lv5~k2Og)j`rvN1ic~kdsLrm_+l%9au z{POPv5eVo6ys>wJShTv4uYD#AkI6wQ(!}dZ@n93Vq=GA!E(Hcp4u)aA8#Qb>J(KJg za^!?||Afk&gmk4HWY$PGh^G?uCvkT^Wr>0U<)9AE3c{xm7<4=tk#ImPt==FsYFYNF zVym|hxS5m33F6Q2v;-^ROpO$%7BWY%%|2Lt9Yvq}924>*zD)xs+6GY&L?)VVf{uXX8|Q@ zZ174H^g=H{ARwPFfLj;g(W)mCs*HfSr2-cxNC0urMNx%fNfpM_Ww&My4B^gZIpk#Z zZxd!?i;=mg^4_gvp$lm)0qtMH z2mCNpRRl`V>ZQ!j>a}u7JpxXfaMU;gW9?|I(i5UnmQh|~IV*W8NgrpE&YU2M#=XA(-|i@+Ri6jjyPWw)=~ zDBxwhUMvn8K%UC0eC7D~wwuo_U$GK(-Eq++Bi8itM8I8&^Dt7s8a(Z7u$vJI_mc7U z5w}&|0L2Y4U?ub3YlT=W@)hN3rP$n~vin_^3s!TfX`WNNBP3I})ob1T!Q`%z8IaFy z1&~uyxn0jE$PHvXnO$$})t9ReyX=*(Y5l|fG1MZ<$Rw=K_b>hhsxZfMPOdB`;E36O z$5q(skaK!?gOwzYea0~?MOFE`vA!x8v=T6-ry`GQY@zHAjZ*A?xu8A&2 zYk62XF+%@^`k;Gk_XH52#FIa&jcRc~YS_`0t`3@Q@9ft9XAV1#I|*viqv@4~?iky- zxM}-)b3TsDrMyYA>J$@P{n_Ps$mocINcoKTEZc z^A!!S%F?V%C)nBE)-%6ERH%7lY+@rj4tJ9aZg-pW)NXfZ7!<`j{uJP?Lv<&|eCLp8 zvDQWgfhG2jd$;fVaI3iu_nn7Vmc~}tF__-0AOPG(cN|w-TP`|7ud8H(mKc=(G^D>; zS27+>UR1b2w#QfVGmZzP-e3*bA3tHNM&k_MPXb zJ1ebeLz{6Hg=hmH{^mbI$56;4lTI$MeHyLOV1(N$q!x25*?a0-d4He`TxTz`tgN}W z$-BT~{@MwUkQ*O8I~RrRGHyhf&3p`$sy{?CQQMi0Z)B;rnF1L$v5iGMTS)DZD`CBIX9 zFS#T~n-lY#Q{9|)7G2r_n7v_6`s|_}2MRkUgp%DJDL;=K+pvM0aB)HxOV=3^j(O-w z9Y27wQ_`k@i{m_VJ+i%2sM({~@LrN#K~wE32{BT~GIHZxOVro@uH%INtgSWLIHvw$SSI}Bo6yNv4x(?IM(+x(uv0RisPtt zc@qPag*nl_ojHkQ#=E1m&hLm5N^8Y`j)9pbiwyX$ik(#Xcf^UNVKkT2@uqRGIpoaQ zVkntsqriXC<TOExWn8oj`mH_T*AOq<_nKia#@FtQG+jeri!zvyVgoSMc9$m z6cwMpBqPif9bHkDr?Lr&4;&tGUppIL!M~u#2UQPD-p-l>Xal}fug}OdA z@KI!%66$5o4=tnJ-$cx6xP``gyRaHg-s9lT|3(#D(e6HrutT!xJ}1;1oI8~Bg?^Fo zo^YqN*T2JmTXjZ%5#J=y$r8+o`Cd_mr^GP2NP@mqM8DMUnz`u3dq>wHhB_XnX@2<@ zZB+9X+kN3%8+x0+$|kCd;EI@Pu1OR3R~|- z=ZoVz6t@YFgOMRdHYv2OEBfnD(aU9yqegMA;X#vB^l44O?n`@6*M^-pYEJQ)0Gx{f;c(}fN z$(PSm&xws_OoM!%bS1JD4Te&IgZ|Cnl!hU?FqGk^w%cf*Qrj9<@Km2Bz=B)S+l^3a zL>P+5B%#Tp%R*~ahEu~LMBJR@FHI{-zb_|k;(^!r^V@3((xLVEKs>}}-^LOlD|S%b zQw0@wSGR2Tc-x)V{*}?s;n2d&yi)syS=g8*&#Jo&i*n>la~jLb~m171iOiJXO=hYB;&uD`w(*<&MS9JZ6Qb_~;H@ zYw5A1l?p?SK+k1x6gVL|=Skj;pKx%AGnSO85``^2=)=zaA%BC~Hv)w|+16~a5v zw}J$wyo8(8WoY=dHb_)%J$}sR zm%{2Eg`A0RCS!~tepJ|}He$mevwlxRN_Xq9I3lP_G<~!%#6GHZb#vX6Jw3|TSJRo0 zmy;yd?n>T?2oibHfC@lFwBW>J~1QQa6uI+&U8Spi^_c`FqMZEn<>sd*6ic zY>3D=i#;~ZcVn3DXB{IMO3$4{=)>o}Ji8j(+C3#P3$6VVO;{&;2#r@7bHSUWZ&a__ z2z`Uf=**h29E!T@SD*IArdhuYu%w3cs7~zIV2Lc(dp6OIFqA;|3(QrR2`@l9r8?so z_C_*xGnv6UjOp}8mRYZO9M&)+u;cr84D0H2hV{)pX109`BZ`w5OXF+r#4zODZS@#O z+I;N^jjXmy`WY9*Pk>bR)*~p1HYC%7{Zco`R5Jc}sl z`%o4izro^;wqgl4+XvogdqTicJLV|YoEuAl4oCDvPg&5qcx zo*XYFTM_Dv95J|ky~EE7twnaIh_~QK&NEXXY%-0!j(A)`Qk(9_cYkm0Ay%oQ`*_n2 zKj9OXdedm7bgnO5Sge)cpVAnf$ED^;Vp&2yIVvywa)Dju>0Fd)YqpSsf5G%Z+}JWt zmx_ZscoXxQUAz*<$(zGS{%}|Sb!)aAIj_@ZAK=78uB2`(*Z4SDmuiB7fVb^v3)ktE z+Ygpbe@;X@H4;)6L^?{1tJPAPu=5E5PNhyF884*k3j{0jk8J-tr^DuNO8TZj^na+Ku^6KSpY+9H1Ss7y$5 ztKVDcp48U9LX901MRmHB!NwuoUzw~Dh5+MoB1rs`v52BqHDtjZ2W>adRT^v#YW0&xYlQh~4b>T4W3VYtLRK5EG$; z;P=LKR%pVSvSo4>BZ^|AaP4C4^((q)BKKyv+tkBxvh&ZjxxgPxqT5A5pSFl&tKD zMGw5XNZrBv)!|V^b;F+{s>D+gNcA41Xn@u1T!FleF9nqn0fuzrq6jnu_qKyG6F`l7 zn>4A!FhAon^{sn?kgP0BVitw%i>I6nhucpvTBZ71R7#Sx;A0J0D-K>=)t5;7Vbv6w zpU%5mL0k#%G`cqTE3eHayC)FdH}hElnh>T{g_V72&ZZMlR2k^`7oT9UbMk#j`Xz)% zi)e{eJoG<3-8<=I+FGu*v2wsioh|3W#$IS8*X>Pr)w1i$=E#nBQVdh;%B_ZMP5#-A zS*%2cDy>4B@TuQH-Kj#chHp*u0LP}G(MDQd)wjC+(C@tyOYlP_kZL>7Q_l)Pc@lnp z*pY)%f<4Ov>#!IZtnXHvyOVOGBT#ema|9h_86IX#{n#Ex#%GbO`X1Q6NaC?T3Ay3{ z<<+!SbCfeM&>3y%?j~H3L6EhE!g7P^5OaT}z|m8%W?GrFz)r%RoDOrT7Y%1*{Mnj2 z+(-pM9dEg&Ha+caiyr+VrWR=v91&THZ8fc2vBu-x_F(hCfem(VM;lF`W_o5~F46Ah zme1hV`tGnTt!B%M7_^w5txbS>9=w<>SE-aE>%w*)fqO1c!z*L>F8O@{-j?jcdReSzOhqB^ejDbl=?Gs>*oWmeyG%qj#@;OhnK8DhCV5%_jx~W|%-O3PYLQF~ z)~&p1`w7AILam;Z5>l@$k*l%~jDIp2PCPcEt&jrq$@Hb}n)BlN1uVS$HSt^_fwkDh z14|4eZS=HN@}1Y&p>523>%*7yuTsuBI2?C;+AJ6WHFoXsru@)hRQfceKZ@m zQ;7W%4cCgi^cUpJcB?Sxv9|s@v9{pjssGSOD3ew1X{HxYC{dDRhqVUfipCR06F)PQXf9H(^!}HZ8bkJeyHsEzLb`EW#tnb} z?M7iZ+_Xi1{-}R>&8=F|P$vDZ2L&kP!_m>>*OX1xiw=J{32ypJMP+r)e{T>)P zSgbiP=2hp)DBNH)qUU=d??veyNM1U77ek}}HQOs} z9>Bq#{aiHQ2CE3y>W-(gG*~B3&kyTLpi(w^?tPr%p^a>`-g}y0A5%`<1V>X+5~|1_ z(le^9ClxoI#qVk8x) z*p5IJTi^#MHuR$arACi0V}qFldN=S-?5pHRJZX%^mc-HCGFPLbs_}rFn?;a)+Xi`1>4yZR*4Dv zSy1(?Ca8vV(gRV7nuWp;74Z+Pk&JS_3c*?^1_ui)?WOAl$4o&G1BvuOXZJt@i61|N zNX9AzAQS8G^hPdA!1ew1O}KXd?Y2Vm5j3Mg;vd5F?7O41KS$cTt%bi$5KN8@9M9~q z@v7Oy?!<03og1TR7d)`fKg+`;RG-?<6=7F#SfJh_%db1I9ku zLLP4JWwEDRU`1>=MksD){FxVi9tcTEO%jPyy}H*#Fv@Jj^6MPF;bI#vo$K}vN~C6V@y%@KaUa3 z!410VfVwl~#iIcPe}Gew(xdbxz=#@r%$>8^;W_Xn8(|D?Zge4RpIXNK> zj22vGx}fzu8aZ&KTm2k<483{%*{Emt{ECMvIu4&w(HFV%veq!*e56|QTJ0Y#1qSKk z+07}ljt3*_I$IDn{oLv}J4^pz2L1!Dzsoh({*# zyRwVuQ-Hfu8^gkc&^^u{`#G-u!9NfPlV*EmcZ6MhV~E&#BIoz1_RCy-gMYBmJ3KM# zIFS{$jK;q(D-@&gwqQ6?dqa2fs`^_dqnI3yb#Nc>W1+io2_@6&z5OYiKT+%HdSQk| z{8hG~F%La33E;f&1Z+1$xA=XbYpZF6*S|MMe^udQ!E9kL)yI*s%V9-o_KFgn9${fJ zo5EJTDh$B#6Z`87`0|13SN-)rUcn3h{D71tc-OCL+XVV}gWz}32IbpF$pg)OGa@s) zM+mO;AYxXj6}c!0ah}}w1V7ruTv|jZ%olQ>rng5!D_d^l$SebzEk+D=ncXnoNNqDb z2_aMyXfaDUt(Iqlu2N3GB?0pWkWD`7QLrB)Ohod z&YhvpnT(v9T`cUe;M!@qFFqwQnwYMu|IK)8ny1dn>}^BPN@um|}ZB;*Qc0 zN^toms{S^HS{6Z0rR!svoz}e>HnXifAul)5x-P`LAIjPG4DrlyDhAx&c<;52t|PjU zLVgEk19|NVuj<{GwM$HJ^@bPc$@e1vxCkCrM}FZB5J-aw7Txkhj>pVCUl z8}IQF(BvA2gl<$tGZ7dbw|5U7jsSi@3w(BdPe#l+F`ZSrWkK4{S=&w5pD*65+^miv z?Vs2Ux8N&pp?%YO2nt`kFbi0nAicdfk^9qO`7*W3^`lmpsWo{~YGe;=zfK6$ZrnAR z`-gE-4Z>d_WX~7D8GIdpcdou-^Tc10Ip?h6i8zbC0^y%;SH0gkOK>`3bVK_t^^N;E zx_2mn;vEy5K9N%8@j@>z)(g&NET1pLwI^PzNz6i3UkOjXaE0aNSASl9e!R_=tCTWB zj$UacBqWrNj__9;-ctJ90sbOmBTRlr0?0VDcfqR90)wL43|EZ|_rmt|Vw)K*j%l&^GeVSdhd& zMxbVAe{@*=ex2lQWQ70pWH$f=AS*jz%q$`%ouYrB~J@)oU877O2#S2ARk)9;otu|{Bw9v+4MgB$nLm3x7p0fb6*<*wQD zUJVkZ=KYqs^TK__HN#sJEhUlaAiP5#s*}LJCvPS(Yw-wEZvk|D@6K>|q+=v2SSg%5tEDOzoJZM98~q)>Mz-$suvvlnq%LO^swH|(@1`i zuc)|Io$}o?b(2pyULAkxXEabe+-=kqMEyL^WN4G$qmwvDX-@D*>_7YJ$9QF%Pg2UM zU&7dp&R)*iJiYk}bNw5=8GRsdv#{WJ+yq4BH^cqjGY^E~>37c%9_?#zA`@sB#%hn; zqkoXq4pI8iJoofG)kI-}(%WPP=*j66ur2qo&7s+#>*=^31E8(*6BvwELAx7o63Zg^z2jW+m+=?PhEsP@wm}GE#wZut z5v6*#|N6^W^>r;K8jLWM*ckHUt>^7b|9b!SBSJ`}&U=Ho3(X##;Nc=nK|VQ{$;{wl zrN-T~8zQJjCx}h|KFnxC!x`_1r$NJqdF(panZE-LdK6Y)@TvT5`zG(I{xa=pmj1{K z?t}@A2R6^P-wz1rN0F4M5TK&yNqS^-)bJ!vE{pxf*2u_+)9G-6$8SV`l;4cd{zziy zf!f%y)xIf95(@piWuKZXQEc|Bpp$aWWkL--F?sGYE@uKvc&Gn{$By~sE)@U@2=N3Q4x;#2?;h9XpqbJ3jvIAT8u7V%ZIp{=(6yN;SGKa)LmL8~ z=Rc^z&~B*7!CFK|xVK?R6~Gyi*CUOKIb;%Qou;|&TYsU(P8h9 zDmwR@M%(!L{aZzdJuEGA#&Fvg2z zagAw`f`M1#;aZk2&8+do^KE^`M2L~;D@5&v^>;FN<3EN)PtG3Qb_!Uzeh0F_n;b|q1UcrstBA?NREd=;PvIDUMOpoH-GwI?T_mZ2O2^w_uK9g05AZ2 zYS#hO!)XtSJ0ky>J2K05^DG~hJ+7n^3Z@XP8>Am=Z6xWj;OZv0fVev)#|%I1iJ62@ zk#&A{a5dDbV1NpWc=7_*vIrdt3c&821sNr!JPm61GC%Yu$mMjgsI)p0L~yo;K;1-= z7Egze((+_mn8#_>Ir>cT(>79&_Ah6kE&J4c#hHXY2Mski5)4D^M&|SzIHehbse-n4 zhv(Z|Z7d6&XaLf}Pu2^@2U@llaJ1%FTjzSFRq`_I>q#GS2BWUF?2o@cetdtc*5dAz zG3RJgD05uKkot8;LPf)pqQ;^nle~Pxq;g1&5ih)$+M(P=ChIS zl+~)_E)DrIeWS{?O!+DHg>VohC4Xje$4?gY@AK{*569P)+`BmL1r-d z$NBokyv$8!Bu7WQHxM|&Y|B}yD4UQBj7!!k<^K;baQn&E2Vkx z0*Gwp?`)W_ukZcc)ui223XCEWrPa?9?{#*k&}lv~kqjn6W#bD$NE{Zc&aV;La>q{U zY-80Kxeu%xom8?r*)vIuoQxB%I5NS6 zHY!l3+!}^f5z;1P&-Vd$^$Y(VlG~HoaIwsYDW{bsQw5Gt|O2|hdp}bJMb%lPQ-$<>fUd)lmt>yv^WXK&Yx=5C;t%AFr zjwm(K{)JPDw6UvEpcM3kKGWJ3zse--QsBie9Q<~L*T8>b?!kitsm^qArsu}Oo(=!j z7Q);uLe4P(%NHFvHy)9S8vc`By;AQ59qLX^crakJzGbT3plW!vchv;=h4+R@HvuMj z;E87W2`sqciYgGgKbg%w14wX?bE=Yf(uY(398Ggv{Zje?-P9W0b z!iMMv?$D8wA5CXhzGYZ#Vhu4J37S`FNFSUSXS)S(%T^~f2o)Xj=nGh~9Fy+_{W*^_ zggW!*faLPn_*Kov3z;vcHk?Llf0yxzq(Wz8?-smx2&~6Ylq9D<7!0}vn>EYh`4`U7 z9KDexgH1+1fX>|bDuZ)i5N{X}6qhi(`DX3$rwKX!U~Khz{Zs4mb}gyxdEC%u*W6aq z;O_&fwrp46vrsRgKRBHCZ{#}3Kzh1CZbz3w^i?z7L$*4j@)Dl%2#LLCFyr^C=^ro1 zKPa({jGUPhr$~uTYSk6hX$K<2qUwsqWNxHcbDNM$cXyH89O?8P>DXq#wY%!L;VmsO zZr-36DBV#dmh6T?n2qyUdSs>q51YMBYOuj{#Z6sR9b#4UI}Pq6(ovH@wOIS3yURz$ zqz5m{i5QL9TP9zAtlOr#<%+G`Tr6{H09gc<8a<^r|1!%NZpFjj(>4IV;kUblFp!n7 zg4jMk1yD~H_$Nh?q$fl=kA_#4pDW5fW##;57~9ts|8z!lgM6CMz;+>w7b z*YeAXcHLyJb9DZ814=NT%n?YDUOZl&CI$X-zL1DZbo?1xgU;o5L1MB&jD%toKs@MK z8{-8^2uMXDBqE_hO>_o-d&&y~hFLh{fvdg{``rZ`+A{+}jr0Qf^t~TPuG%k40yI-- z*=t)?3-&8}p3~)Jvx7S1s_}Ss1SIg2&@6OGSa3Q*qmH8y22BHk6qhFi1f*hn^H_Zv z&L1i!0gW{j{IQ8>oa{AoeU}Ktyjni~$0&Z*&ZuUXQ=*>HLV( z6o~SGJ$BelH?kdoNCv<;s*<46DE=V*_jzzdBENRVrEuBy%GYMW&Cu^zJ0#= zF_H+RIzrg>!vtKYPJCnr7zzNQd1nvoKrgb>D5MCa^YPazoukeK?S(L+|_Cpod@{_$jUA zMpLq8p-6y)ssprufP@qM1Lah1cD?+F1LPRblgKpMf6~7$DFbbPpsojYnDikhk_wG! zMBMZrkvt}X6A$|Yi)%Mpa z3jIELv}r7ruHbKK0BT(u)F2oTvXMuql`tcpCx&k(JJe3>3+K(SxqG`Drk+-go@L*c z>k}GA!TZx?>Jyo@b9yf<6D)a=n?G9(zD@`igLvV~fXxUf;a?Q$6naj^?d`vY?#7E! z`)~Jy=VCNI4{B>@d3k#{AKKDd+z|_qN zN!Yp<22+r+EHjX@b#_Rpw~tT3LYVN%vD{)Ab-%;O&W#Z3xlNMUPDhWcAh4*-)j6TL zB;^>ICx}gn>4Ik3Ig2_jqX_5)sciD+BmI*DR4C*qq=Gh^Ovu{uwYO3khuMB=G@xgg zB^=*+`#Hn^a5z{VTuFx1a668hdh#GnTAq(Tn+3J=>&3f?ux4D40j8pXI5TSa9eJ-t zgVKPCnm`9Ey~Ur->PrcMa2`My25C*dcK}AZL6~n9Nu)Bg6A}PAyQ;5!C@fmeT3snw zJ}OBCW*{r%?Z`xFG3&Unj>+Oq2+>@ld&9i45pD|wTL}&x9j@OAR2VN8?G#HiB z2NfuK<_tCgHxGnFw9VBQtu_ubIN*bL=f;0JoBIC)6`LYg=Qk<|`Xf_O$Y)6Jlkwfh zY1q|N{o4&6WBXmJNqH{%jkC#8-*X_DF~WRxLW&>+n-GO8@WAr{!oWa7GLq7>poKVr znH@sFpeSlSK@VwPJEcp>@UvYR2%0>F4*N^rlJQpfW(w%rwd6AuaAh63#drR5?oZfmPg z2i4vg$*+8!7ILGCcaK}QiL<}worKH2BO|yC7OSaSJEOp&Wk0LP7P0a8&e+WIdwH4* z1u1!792X{~A2#!}#ZV&GBjy70-sZlWd76W`q20*?hZZ7GT+*BEOhH#wGm?dEfN0f= z3`;IGqeK76p01{+9d^x3jDt@GV?A#n&6;c8dJasIgd%Qk7G7;Jh79%0Q1TDV-D_z~ zH`!@XKQ3oPqtHT1BU{vy)qZ-QnVo27YMhhSUB2&bcAP#b1Mf6b{gVn zNY16-l6Y-NyJnqT{*X$CyuRQoksjoUaAmX6;XO91EC50(Bz34QXUn@cBV`m}Hv91s-+7Lj3IHHgYRf3n0W5GYoAvtx zE!C^5_zOm{>oc!Po_^&H4N=c)ur%J~mp0OYZgPzne_upoL7|J0P&)29m9x+$3?YlP zoAq(!a$;yaeH}Y$(=pwpc~)|7{i98zL}m8YF6C)}B1!nd3g_(VW}=y|oxPs}LeZyo z9`>IFH|lE8oQvu*bXB;wYg%};Rxl|N)LsiYnLi7kEw*~j%@4cjbYiLv)$i0?iOS!P z9n8ZObM%9yoV6*F7sSv!JmZPP&^RrbZjmJ=Zz0nsvLA(YmP3fKrPPLGttK ziz~xqq#WjqsT148Jj75)VG*Z|>OxZGLjC&TXU|?9>cpFx;P%do$f$g&VtV16i^r-_ z&ELCHwAJN}y)e)=^fmh7$}>$c85~xf@SAKn178Oh}5wnqmpz z=cM6Q9y=EkRS=U?o^g07JYBzlL3Y4`{&Nz`YiM2SR5XmxueraeH4nlo4)0caw5>nh zHi5(v!OhifCUfOZ466&)`Vt*74oh>vl~v~ zWT@A!W>wpsNL&$bOLE#13x!3rrv+WV`%qKdX_Eaq57K$I!hmpJQ7i%|R=eb@_d`9V zw?t$pbEyVtW^omZ7<;Z*l_90Dw%!?P^jg02ov7s~@+;8d_p7;FSe5{0WRLn&8(r(K z&2as47gFT@R+poLM^eMCd9WHZ*37rFl|}+bl0KwieT+i2*c=PfG$&G5vwW;|jq8Sx z!k0(q2xQ`6x6f)7{ZclTQ}2~T&~)yA0gg0LB3_og9DtBV2T-v#-9YU;3p7&kN&6f9 zYrd_}&o%e!u-2e{=r#c=o1Gu71{|Ug?$&Hn?qxLvLN>5Fl`Aj$u4H(PKg(0R8x<(K zFDA+XWfq1Jl-1uDMk&F1kg8YkV-3l?m-j;2;6$4PHc{s^b(y2FqCe~jgEpEM(pMYx!l2&| zbcn9LZH46cBo+3oPQNc-=hKDq3EkB98Z<1djLhisA}jj1ISz$Ev-(gGry0v*WgU9E z4?XAK{$lG)G`BZbf!DR6ni^~k@FiFD0;t6>IgyhB2m$N8CLD?$vSTB>+zMj;yD`qB zxqMN{jyZo^ex+z<(W!J}+F#6ZW%Fr&q9R!xWe+P(C_5z#|B9X{x&wewF0$M?Y%+f3 zvF~lgY)8*#!7{z(wG@RC#z|piNF3=mY!iQDagw{!J#33dY*rfH$K*?1fMRi zqJLyWgomuzKO~)(yCKfAqfFV~YOwA#8(*OVf diff --git a/localization/ekf_localizer/schema/sub/pose_measurement.sub_schema.json b/localization/ekf_localizer/schema/sub/pose_measurement.sub_schema.json index 8b931d5f68d12..d2bc313d4dc75 100644 --- a/localization/ekf_localizer/schema/sub/pose_measurement.sub_schema.json +++ b/localization/ekf_localizer/schema/sub/pose_measurement.sub_schema.json @@ -23,7 +23,7 @@ "pose_gate_dist": { "type": "number", "description": "Limit of Mahalanobis distance used for outliers detection", - "default": 10000.0 + "default": 49.5 } }, "required": [ diff --git a/localization/ekf_localizer/schema/sub/twist_measurement.sub_schema.json b/localization/ekf_localizer/schema/sub/twist_measurement.sub_schema.json index 727830a90a288..7b80133cb38aa 100644 --- a/localization/ekf_localizer/schema/sub/twist_measurement.sub_schema.json +++ b/localization/ekf_localizer/schema/sub/twist_measurement.sub_schema.json @@ -18,7 +18,7 @@ "twist_gate_dist": { "type": "number", "description": "Limit of Mahalanobis distance used for outliers detection", - "default": 10000.0 + "default": 46.1 } }, "required": ["twist_additional_delay", "twist_smoothing_steps", "twist_gate_dist"], From f059d1b54908a7616fa9b826098f5970af6939a9 Mon Sep 17 00:00:00 2001 From: Takamasa Horibe Date: Tue, 30 Apr 2024 10:11:42 +0900 Subject: [PATCH 02/27] chore(autoware_auto_perception_rviz_plugin): improve distant object visibility (#6903) --- .../object_polygon_detail.hpp | 6 ++++- .../object_polygon_display_base.hpp | 14 +++++++++- .../object_polygon_detail.cpp | 26 ++++++++++++++----- 3 files changed, 37 insertions(+), 9 deletions(-) diff --git a/common/autoware_auto_perception_rviz_plugin/include/autoware_auto_perception_rviz_plugin/object_detection/object_polygon_detail.hpp b/common/autoware_auto_perception_rviz_plugin/include/autoware_auto_perception_rviz_plugin/object_detection/object_polygon_detail.hpp index 8c6ade475217a..4f545d194b2c2 100644 --- a/common/autoware_auto_perception_rviz_plugin/include/autoware_auto_perception_rviz_plugin/object_detection/object_polygon_detail.hpp +++ b/common/autoware_auto_perception_rviz_plugin/include/autoware_auto_perception_rviz_plugin/object_detection/object_polygon_detail.hpp @@ -57,6 +57,9 @@ struct ObjectPropertyValues float alpha{0.999F}; }; +// Control object marker visualization +enum class ObjectFillType { Skeleton, Fill }; + // Map defining colors according to value of label field in ObjectClassification msg const std::map< autoware_auto_perception_msgs::msg::ObjectClassification::_label_type, ObjectPropertyValues> @@ -87,7 +90,8 @@ get_shape_marker_ptr( const autoware_auto_perception_msgs::msg::Shape & shape_msg, const geometry_msgs::msg::Point & centroid, const geometry_msgs::msg::Quaternion & orientation, const std_msgs::msg::ColorRGBA & color_rgba, const double & line_width, - const bool & is_orientation_available = true); + const bool & is_orientation_available = true, + const ObjectFillType fill_type = ObjectFillType::Skeleton); AUTOWARE_AUTO_PERCEPTION_RVIZ_PLUGIN_PUBLIC visualization_msgs::msg::Marker::SharedPtr get_2d_shape_marker_ptr( diff --git a/common/autoware_auto_perception_rviz_plugin/include/autoware_auto_perception_rviz_plugin/object_detection/object_polygon_display_base.hpp b/common/autoware_auto_perception_rviz_plugin/include/autoware_auto_perception_rviz_plugin/object_detection/object_polygon_display_base.hpp index 4290fdff49bb3..1093f6e4f2414 100644 --- a/common/autoware_auto_perception_rviz_plugin/include/autoware_auto_perception_rviz_plugin/object_detection/object_polygon_display_base.hpp +++ b/common/autoware_auto_perception_rviz_plugin/include/autoware_auto_perception_rviz_plugin/object_detection/object_polygon_display_base.hpp @@ -112,6 +112,12 @@ class AUTOWARE_AUTO_PERCEPTION_RVIZ_PLUGIN_PUBLIC ObjectPolygonDisplayBase m_confidence_interval_property->addOption("95%", 2); m_confidence_interval_property->addOption("99%", 3); + m_object_fill_type_property = new rviz_common::properties::EnumProperty( + "Object Fill Type", "skeleton", "Change object fill type in visualization", this); + m_object_fill_type_property->addOption( + "skeleton", static_cast(detail::ObjectFillType::Skeleton)); + m_object_fill_type_property->addOption("Fill", static_cast(detail::ObjectFillType::Fill)); + // iterate over default values to create and initialize the properties. for (const auto & map_property_it : detail::kDefaultObjectPropertyValues) { const auto & class_property_values = map_property_it.second; @@ -189,9 +195,13 @@ class AUTOWARE_AUTO_PERCEPTION_RVIZ_PLUGIN_PUBLIC ObjectPolygonDisplayBase const bool & is_orientation_available) const { const std_msgs::msg::ColorRGBA color_rgba = get_color_rgba(labels); + const auto fill_type = + static_cast(m_object_fill_type_property->getOptionInt()); + if (m_display_type_property->getOptionInt() == 0) { return detail::get_shape_marker_ptr( - shape_msg, centroid, orientation, color_rgba, line_width, is_orientation_available); + shape_msg, centroid, orientation, color_rgba, line_width, is_orientation_available, + fill_type); } else if (m_display_type_property->getOptionInt() == 1) { return detail::get_2d_shape_marker_ptr( shape_msg, centroid, orientation, color_rgba, line_width, is_orientation_available); @@ -526,6 +536,8 @@ class AUTOWARE_AUTO_PERCEPTION_RVIZ_PLUGIN_PUBLIC ObjectPolygonDisplayBase rviz_common::properties::EnumProperty * m_simple_visualize_mode_property; // Property to set confidence interval of state estimations rviz_common::properties::EnumProperty * m_confidence_interval_property; + // Property to set visualization type + rviz_common::properties::EnumProperty * m_object_fill_type_property; // Property to enable/disable label visualization rviz_common::properties::BoolProperty m_display_label_property; // Property to enable/disable uuid visualization diff --git a/common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp b/common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp index 8be9d1c01332e..7631acffafdf9 100644 --- a/common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp +++ b/common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp @@ -495,23 +495,37 @@ visualization_msgs::msg::Marker::SharedPtr get_shape_marker_ptr( const autoware_auto_perception_msgs::msg::Shape & shape_msg, const geometry_msgs::msg::Point & centroid, const geometry_msgs::msg::Quaternion & orientation, const std_msgs::msg::ColorRGBA & color_rgba, const double & line_width, - const bool & is_orientation_available) + const bool & is_orientation_available, const ObjectFillType fill_type) { auto marker_ptr = std::make_shared(); marker_ptr->ns = std::string("shape"); + marker_ptr->color = color_rgba; + marker_ptr->scale.x = line_width; using autoware_auto_perception_msgs::msg::Shape; if (shape_msg.type == Shape::BOUNDING_BOX) { - marker_ptr->type = visualization_msgs::msg::Marker::LINE_LIST; - calc_bounding_box_line_list(shape_msg, marker_ptr->points); + if (fill_type == ObjectFillType::Skeleton) { + marker_ptr->type = visualization_msgs::msg::Marker::LINE_LIST; + calc_bounding_box_line_list(shape_msg, marker_ptr->points); + } else if (fill_type == ObjectFillType::Fill) { + marker_ptr->type = visualization_msgs::msg::Marker::CUBE; + marker_ptr->scale = shape_msg.dimensions; + marker_ptr->color.a = 0.75f; + } if (is_orientation_available) { calc_bounding_box_direction_line_list(shape_msg, marker_ptr->points); } else { calc_bounding_box_orientation_line_list(shape_msg, marker_ptr->points); } } else if (shape_msg.type == Shape::CYLINDER) { - marker_ptr->type = visualization_msgs::msg::Marker::LINE_LIST; - calc_cylinder_line_list(shape_msg, marker_ptr->points); + if (fill_type == ObjectFillType::Skeleton) { + marker_ptr->type = visualization_msgs::msg::Marker::LINE_LIST; + calc_cylinder_line_list(shape_msg, marker_ptr->points); + } else if (fill_type == ObjectFillType::Fill) { + marker_ptr->type = visualization_msgs::msg::Marker::CYLINDER; + marker_ptr->scale = shape_msg.dimensions; + marker_ptr->color.a = 0.75f; + } } else if (shape_msg.type == Shape::POLYGON) { marker_ptr->type = visualization_msgs::msg::Marker::LINE_LIST; calc_polygon_line_list(shape_msg, marker_ptr->points); @@ -523,8 +537,6 @@ visualization_msgs::msg::Marker::SharedPtr get_shape_marker_ptr( marker_ptr->action = visualization_msgs::msg::Marker::MODIFY; marker_ptr->pose = to_pose(centroid, orientation); marker_ptr->lifetime = rclcpp::Duration::from_seconds(0.15); - marker_ptr->scale.x = line_width; - marker_ptr->color = color_rgba; return marker_ptr; } From 766b1b14b77300fdd3d0900506f40429560ad891 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Tue, 30 Apr 2024 12:02:45 +0900 Subject: [PATCH 03/27] fix(avoidance): fix logic to check if it is parked vehicle (#6731) * fix(avoidance): fix logic to check if it is parked vehicle Signed-off-by: satoshi-ota * fix(avoidance): unexpected parked judgement for vehicle on opposite lane Signed-off-by: satoshi-ota * fix(avoidance): add & Signed-off-by: satoshi-ota * fix(avoidance): clang-tidy Signed-off-by: satoshi-ota --------- Signed-off-by: satoshi-ota --- .../src/utils.cpp | 104 ++++++++++-------- 1 file changed, 60 insertions(+), 44 deletions(-) diff --git a/planning/behavior_path_avoidance_module/src/utils.cpp b/planning/behavior_path_avoidance_module/src/utils.cpp index 5ed85dde776a0..39375df157959 100644 --- a/planning/behavior_path_avoidance_module/src/utils.cpp +++ b/planning/behavior_path_avoidance_module/src/utils.cpp @@ -418,33 +418,41 @@ bool isParkedVehicle( bool is_left_side_parked_vehicle = false; if (!isOnRight(object)) { - auto [object_shiftable_distance, sub_type] = [&]() { - const auto most_left_road_lanelet = - route_handler->getMostLeftLanelet(object.overhang_lanelet); - const auto most_left_lanelet_candidates = - route_handler->getLaneletMapPtr()->laneletLayer.findUsages( - most_left_road_lanelet.leftBound()); - - lanelet::ConstLanelet most_left_lanelet = most_left_road_lanelet; - const lanelet::Attribute sub_type = - most_left_lanelet.attribute(lanelet::AttributeName::Subtype); - - for (const auto & ll : most_left_lanelet_candidates) { - const lanelet::Attribute sub_type = ll.attribute(lanelet::AttributeName::Subtype); - if (sub_type.value() == "road_shoulder") { - most_left_lanelet = ll; - } + const auto most_left_lanelet = [&]() { + auto same_direction_lane = + route_handler->getMostLeftLanelet(object.overhang_lanelet, true, true); + const lanelet::Attribute & sub_type = + same_direction_lane.attribute(lanelet::AttributeName::Subtype); + if (sub_type == "road_shoulder") { + return same_direction_lane; } - const auto center_to_left_boundary = distance2d( - to2D(most_left_lanelet.leftBound().basicLineString()), - to2D(toLaneletPoint(centerline_pos)).basicPoint()); + const auto opposite_lanes = route_handler->getLeftOppositeLanelets(same_direction_lane); + if (opposite_lanes.empty()) { + return same_direction_lane; + } - return std::make_pair( - center_to_left_boundary - 0.5 * object.object.shape.dimensions.y, sub_type); + return static_cast(opposite_lanes.front().invert()); }(); - if (sub_type.value() != "road_shoulder") { + const auto center_to_left_boundary = distance2d( + to2D(most_left_lanelet.leftBound().basicLineString()), + to2D(toLaneletPoint(centerline_pos)).basicPoint()); + + double object_shiftable_distance = + center_to_left_boundary - 0.5 * object.object.shape.dimensions.y; + + const lanelet::Attribute & sub_type = + most_left_lanelet.attribute(lanelet::AttributeName::Subtype); + if (sub_type == "road_shoulder") { + // assuming it's parked vehicle if its CoG is within road shoulder lanelet. + if (boost::geometry::within( + to2D(toLaneletPoint(object_pos)).basicPoint(), + most_left_lanelet.polygon2d().basicPolygon())) { + return true; + } + } else { + // assuming there is 0.5m road shoulder even if it's not defined explicitly in HDMap. object_shiftable_distance += parameters->object_check_min_road_shoulder_width; } @@ -458,33 +466,41 @@ bool isParkedVehicle( bool is_right_side_parked_vehicle = false; if (isOnRight(object)) { - auto [object_shiftable_distance, sub_type] = [&]() { - const auto most_right_road_lanelet = - route_handler->getMostRightLanelet(object.overhang_lanelet); - const auto most_right_lanelet_candidates = - route_handler->getLaneletMapPtr()->laneletLayer.findUsages( - most_right_road_lanelet.rightBound()); - - lanelet::ConstLanelet most_right_lanelet = most_right_road_lanelet; - const lanelet::Attribute sub_type = - most_right_lanelet.attribute(lanelet::AttributeName::Subtype); - - for (const auto & ll : most_right_lanelet_candidates) { - const lanelet::Attribute sub_type = ll.attribute(lanelet::AttributeName::Subtype); - if (sub_type.value() == "road_shoulder") { - most_right_lanelet = ll; - } + const auto most_right_lanelet = [&]() { + auto same_direction_lane = + route_handler->getMostRightLanelet(object.overhang_lanelet, true, true); + const lanelet::Attribute & sub_type = + same_direction_lane.attribute(lanelet::AttributeName::Subtype); + if (sub_type == "road_shoulder") { + return same_direction_lane; } - const auto center_to_right_boundary = distance2d( - to2D(most_right_lanelet.rightBound().basicLineString()), - to2D(toLaneletPoint(centerline_pos)).basicPoint()); + const auto opposite_lanes = route_handler->getRightOppositeLanelets(same_direction_lane); + if (opposite_lanes.empty()) { + return same_direction_lane; + } - return std::make_pair( - center_to_right_boundary - 0.5 * object.object.shape.dimensions.y, sub_type); + return static_cast(opposite_lanes.front().invert()); }(); - if (sub_type.value() != "road_shoulder") { + const auto center_to_right_boundary = distance2d( + to2D(most_right_lanelet.rightBound().basicLineString()), + to2D(toLaneletPoint(centerline_pos)).basicPoint()); + + double object_shiftable_distance = + center_to_right_boundary - 0.5 * object.object.shape.dimensions.y; + + const lanelet::Attribute & sub_type = + most_right_lanelet.attribute(lanelet::AttributeName::Subtype); + if (sub_type == "road_shoulder") { + // assuming it's parked vehicle if its CoG is within road shoulder lanelet. + if (boost::geometry::within( + to2D(toLaneletPoint(object_pos)).basicPoint(), + most_right_lanelet.polygon2d().basicPolygon())) { + return true; + } + } else { + // assuming there is 0.5m road shoulder even if it's not defined explicitly in HDMap. object_shiftable_distance += parameters->object_check_min_road_shoulder_width; } From b63083817b8a804cdfc6aa647d90ebe25210d8b2 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Tue, 30 Apr 2024 12:03:53 +0900 Subject: [PATCH 04/27] fix(avoidance): don't avoid merging/deviating vehicle whose overhang distance is larger than threshold (#6808) * fix(avoidance): add target filtering threshold for merging/deviating vehicle Signed-off-by: satoshi-ota * fix(avoidance): apply logic only for non-parked vehicle Signed-off-by: satoshi-ota * fix(avoidance): align logger namespace Signed-off-by: satoshi-ota --------- Signed-off-by: satoshi-ota --- .../config/avoidance.param.yaml | 4 ++ .../data_structs.hpp | 3 ++ .../schema/avoidance.schema.json | 13 ++++++ .../src/debug.cpp | 1 + .../src/utils.cpp | 40 +++++++++++++++++++ 5 files changed, 61 insertions(+) diff --git a/planning/behavior_path_avoidance_module/config/avoidance.param.yaml b/planning/behavior_path_avoidance_module/config/avoidance.param.yaml index c85fdd5a2351a..dc42af0412254 100644 --- a/planning/behavior_path_avoidance_module/config/avoidance.param.yaml +++ b/planning/behavior_path_avoidance_module/config/avoidance.param.yaml @@ -132,6 +132,10 @@ th_shiftable_ratio: 0.8 # [-] min_road_shoulder_width: 0.5 # [m] FOR DEVELOPER + # for merging/deviating vehicle + merging_vehicle: + th_overhang_distance: 0.0 # [m] + # params for avoidance of vehicle type objects that are ambiguous as to whether they are parked. avoidance_for_ambiguous_vehicle: enable: true # [-] diff --git a/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/data_structs.hpp b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/data_structs.hpp index 8516cc61f860b..58ada91df9e96 100644 --- a/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/data_structs.hpp +++ b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/data_structs.hpp @@ -189,6 +189,9 @@ struct AvoidanceParameters double time_threshold_for_ambiguous_vehicle{0.0}; double distance_threshold_for_ambiguous_vehicle{0.0}; + // for merging/deviating vehicle + double th_overhang_distance{0.0}; + // parameters for safety check area bool enable_safety_check{false}; bool check_current_lane{false}; diff --git a/planning/behavior_path_avoidance_module/schema/avoidance.schema.json b/planning/behavior_path_avoidance_module/schema/avoidance.schema.json index eee34edbc0e0c..91f9519596bb1 100644 --- a/planning/behavior_path_avoidance_module/schema/avoidance.schema.json +++ b/planning/behavior_path_avoidance_module/schema/avoidance.schema.json @@ -681,6 +681,18 @@ ], "additionalProperties": false }, + "merging_vehicle": { + "type": "object", + "properties": { + "th_overhang_distance": { + "type": "number", + "description": "Distance threshold between overhang point and ego lane's centerline. If the nearest overhang point of merging/deviating vehicle is less than this param, the module never avoid it. (Basically, the ego stops behind of it.)", + "default": 0.5 + } + }, + "required": ["th_overhang_distance"], + "additionalProperties": false + }, "parked_vehicle": { "type": "object", "properties": { @@ -803,6 +815,7 @@ "object_check_return_pose_distance", "max_compensation_time", "detection_area", + "merging_vehicle", "parked_vehicle", "avoidance_for_ambiguous_vehicle", "intersection" diff --git a/planning/behavior_path_avoidance_module/src/debug.cpp b/planning/behavior_path_avoidance_module/src/debug.cpp index 7d029277fcbc4..4595a77a84b3b 100644 --- a/planning/behavior_path_avoidance_module/src/debug.cpp +++ b/planning/behavior_path_avoidance_module/src/debug.cpp @@ -578,6 +578,7 @@ MarkerArray createDebugMarkerArray( addObjects(data.other_objects, std::string("TooNearToGoal")); addObjects(data.other_objects, std::string("ParallelToEgoLane")); addObjects(data.other_objects, std::string("MergingToEgoLane")); + addObjects(data.other_objects, std::string("DeviatingFromEgoLane")); addObjects(data.other_objects, std::string("UnstableObject")); addObjects(data.other_objects, std::string("AmbiguousStoppedVehicle")); addObjects(data.other_objects, std::string("AmbiguousStoppedVehicle(wait-and-see)")); diff --git a/planning/behavior_path_avoidance_module/src/utils.cpp b/planning/behavior_path_avoidance_module/src/utils.cpp index 39375df157959..b711dcb91236d 100644 --- a/planning/behavior_path_avoidance_module/src/utils.cpp +++ b/planning/behavior_path_avoidance_module/src/utils.cpp @@ -583,6 +583,46 @@ bool isNeverAvoidanceTarget( } } + if (object.behavior == ObjectData::Behavior::MERGING) { + object.reason = "MergingToEgoLane"; + if ( + isOnRight(object) && !object.is_parked && + object.overhang_points.front().first > parameters->th_overhang_distance) { + RCLCPP_DEBUG( + rclcpp::get_logger(logger_namespace), + "merging vehicle. but overhang distance is larger than threshold."); + return true; + } + if ( + !isOnRight(object) && !object.is_parked && + object.overhang_points.front().first < -1.0 * parameters->th_overhang_distance) { + RCLCPP_DEBUG( + rclcpp::get_logger(logger_namespace), + "merging vehicle. but overhang distance is larger than threshold."); + return true; + } + } + + if (object.behavior == ObjectData::Behavior::DEVIATING) { + object.reason = "DeviatingFromEgoLane"; + if ( + isOnRight(object) && !object.is_parked && + object.overhang_points.front().first > parameters->th_overhang_distance) { + RCLCPP_DEBUG( + rclcpp::get_logger(logger_namespace), + "deviating vehicle. but overhang distance is larger than threshold."); + return true; + } + if ( + !isOnRight(object) && !object.is_parked && + object.overhang_points.front().first < -1.0 * parameters->th_overhang_distance) { + RCLCPP_DEBUG( + rclcpp::get_logger(logger_namespace), + "deviating vehicle. but overhang distance is larger than threshold."); + return true; + } + } + if (object.is_on_ego_lane) { const auto right_lane = planner_data->route_handler->getRightLanelet(object.overhang_lanelet, true, false); From 00d82229b48d12d4b371cce4213a04e1f34f76ff Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Tue, 30 Apr 2024 20:37:24 +0900 Subject: [PATCH 05/27] fix(bpp): change wrong function parameter's type for safety check (#6906) fix(bpp): change wrong function argument's type for safety check Signed-off-by: Muhammad Zulfaqar Azmi --- .../utils/path_safety_checker/safety_check.hpp | 4 ++-- .../src/utils/path_safety_checker/safety_check.cpp | 6 +++--- 2 files changed, 5 insertions(+), 5 deletions(-) diff --git a/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/path_safety_checker/safety_check.hpp b/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/path_safety_checker/safety_check.hpp index 53c4706e49c10..f28685b2d914e 100644 --- a/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/path_safety_checker/safety_check.hpp +++ b/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/path_safety_checker/safety_check.hpp @@ -54,11 +54,11 @@ bool isTargetObjectFront( Polygon2d createExtendedPolygon( const Pose & base_link_pose, const vehicle_info_util::VehicleInfo & vehicle_info, - const double lon_length, const double lat_margin, const double is_stopped_obj, + const double lon_length, const double lat_margin, const bool is_stopped_obj, CollisionCheckDebug & debug); Polygon2d createExtendedPolygon( const Pose & obj_pose, const Shape & shape, const double lon_length, const double lat_margin, - const double is_stopped_obj, CollisionCheckDebug & debug); + const bool is_stopped_obj, CollisionCheckDebug & debug); PredictedPath convertToPredictedPath( const std::vector & path, const double time_resolution); diff --git a/planning/behavior_path_planner_common/src/utils/path_safety_checker/safety_check.cpp b/planning/behavior_path_planner_common/src/utils/path_safety_checker/safety_check.cpp index 6390c45376b37..ceedb202209f3 100644 --- a/planning/behavior_path_planner_common/src/utils/path_safety_checker/safety_check.cpp +++ b/planning/behavior_path_planner_common/src/utils/path_safety_checker/safety_check.cpp @@ -90,7 +90,7 @@ bool isTargetObjectFront( Polygon2d createExtendedPolygon( const Pose & base_link_pose, const vehicle_info_util::VehicleInfo & vehicle_info, - const double lon_length, const double lat_margin, const double is_stopped_obj, + const double lon_length, const double lat_margin, const bool is_stopped_obj, CollisionCheckDebug & debug) { const double & base_to_front = vehicle_info.max_longitudinal_offset_m; @@ -131,7 +131,7 @@ Polygon2d createExtendedPolygon( Polygon2d createExtendedPolygon( const Pose & obj_pose, const Shape & shape, const double lon_length, const double lat_margin, - const double is_stopped_obj, CollisionCheckDebug & debug) + const bool is_stopped_obj, CollisionCheckDebug & debug) { const auto obj_polygon = tier4_autoware_utils::toPolygon2d(obj_pose, shape); if (obj_polygon.outer().empty()) { @@ -189,7 +189,7 @@ Polygon2d createExtendedPolygon( Polygon2d createExtendedPolygonAlongPath( const PathWithLaneId & planned_path, const Pose & base_link_pose, const vehicle_info_util::VehicleInfo & vehicle_info, const double lon_length, - const double lat_margin, const double is_stopped_obj, CollisionCheckDebug & debug) + const double lat_margin, const bool is_stopped_obj, CollisionCheckDebug & debug) { const double & base_to_front = vehicle_info.max_longitudinal_offset_m; const double & width = vehicle_info.vehicle_width_m; From 8fe16858655728ae45cc63f13f1a73ab5ab7cce6 Mon Sep 17 00:00:00 2001 From: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> Date: Wed, 1 May 2024 00:36:51 +0900 Subject: [PATCH 06/27] feat(autoware_overlay_rviz_plugin): get the current traffic light (#6899) Signed-off-by: Maxime CLEMENT --- .../include/signal_display.hpp | 4 +-- .../include/traffic_display.hpp | 5 ++-- .../src/signal_display.cpp | 26 +++++++++---------- .../src/traffic_display.cpp | 6 ++--- 4 files changed, 20 insertions(+), 21 deletions(-) diff --git a/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/include/signal_display.hpp b/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/include/signal_display.hpp index 4fa39f2c5a903..ec1acb9a5dc68 100644 --- a/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/include/signal_display.hpp +++ b/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/include/signal_display.hpp @@ -102,7 +102,7 @@ private Q_SLOTS: turn_signals_sub_; rclcpp::Subscription::SharedPtr hazard_lights_sub_; - rclcpp::Subscription::SharedPtr traffic_sub_; + rclcpp::Subscription::SharedPtr traffic_sub_; rclcpp::Subscription::SharedPtr speed_limit_sub_; std::mutex property_mutex_; @@ -117,7 +117,7 @@ private Q_SLOTS: const autoware_auto_vehicle_msgs::msg::HazardLightsReport::ConstSharedPtr & msg); void updateSpeedLimitData(const tier4_planning_msgs::msg::VelocityLimit::ConstSharedPtr msg); void updateTrafficLightData( - const autoware_perception_msgs::msg::TrafficSignalArray::ConstSharedPtr msg); + const autoware_perception_msgs::msg::TrafficSignal::ConstSharedPtr msg); void drawWidget(QImage & hud); }; } // namespace autoware_overlay_rviz_plugin diff --git a/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/include/traffic_display.hpp b/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/include/traffic_display.hpp index 20410a78edc44..efa30f37ccb3e 100644 --- a/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/include/traffic_display.hpp +++ b/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/include/traffic_display.hpp @@ -24,7 +24,6 @@ #include #include -#include #include #include @@ -40,8 +39,8 @@ class TrafficDisplay TrafficDisplay(); void drawTrafficLightIndicator(QPainter & painter, const QRectF & backgroundRect); void updateTrafficLightData( - const autoware_perception_msgs::msg::TrafficSignalArray::ConstSharedPtr & msg); - autoware_perception_msgs::msg::TrafficSignalArray current_traffic_; + const autoware_perception_msgs::msg::TrafficSignal::ConstSharedPtr & msg); + autoware_perception_msgs::msg::TrafficSignal current_traffic_; private: QImage traffic_light_image_; diff --git a/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/signal_display.cpp b/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/signal_display.cpp index b2995327eb472..3b1536919512b 100644 --- a/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/signal_display.cpp +++ b/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/signal_display.cpp @@ -111,8 +111,9 @@ void SignalDisplay::onInitialize() speed_limit_topic_property_->initialize(rviz_ros_node); traffic_topic_property_ = std::make_unique( - "Traffic Topic", "/perception/traffic_light_recognition/traffic_signals", - "autoware_perception/msgs/msg/TrafficSignalArray", "Topic for Traffic Light Data", this, + "Traffic Topic", + "/planning/scenario_planning/lane_driving/behavior_planning/debug/traffic_signal", + "autoware_perception/msgs/msg/TrafficSignal", "Topic for Traffic Light Data", this, SLOT(topic_updated_traffic())); traffic_topic_property_->initialize(rviz_ros_node); } @@ -159,10 +160,10 @@ void SignalDisplay::setupRosSubscriptions() updateHazardLightsData(msg); }); - traffic_sub_ = rviz_node_->create_subscription( + traffic_sub_ = rviz_node_->create_subscription( traffic_topic_property_->getTopicStd(), rclcpp::QoS(rclcpp::KeepLast(10)).durability_volatile().reliable(), - [this](const autoware_perception_msgs::msg::TrafficSignalArray::SharedPtr msg) { + [this](const autoware_perception_msgs::msg::TrafficSignal::SharedPtr msg) { updateTrafficLightData(msg); }); @@ -237,7 +238,7 @@ void SignalDisplay::onDisable() } void SignalDisplay::updateTrafficLightData( - const autoware_perception_msgs::msg::TrafficSignalArray::ConstSharedPtr msg) + const autoware_perception_msgs::msg::TrafficSignal::ConstSharedPtr msg) { std::lock_guard lock(property_mutex_); @@ -506,14 +507,13 @@ void SignalDisplay::topic_updated_traffic() // resubscribe to the topic traffic_sub_.reset(); auto rviz_ros_node = context_->getRosNodeAbstraction().lock(); - traffic_sub_ = - rviz_ros_node->get_raw_node() - ->create_subscription( - traffic_topic_property_->getTopicStd(), - rclcpp::QoS(rclcpp::KeepLast(10)).durability_volatile().reliable(), - [this](const autoware_perception_msgs::msg::TrafficSignalArray::SharedPtr msg) { - updateTrafficLightData(msg); - }); + traffic_sub_ = rviz_ros_node->get_raw_node() + ->create_subscription( + traffic_topic_property_->getTopicStd(), + rclcpp::QoS(rclcpp::KeepLast(10)).durability_volatile().reliable(), + [this](const autoware_perception_msgs::msg::TrafficSignal::SharedPtr msg) { + updateTrafficLightData(msg); + }); } } // namespace autoware_overlay_rviz_plugin diff --git a/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/traffic_display.cpp b/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/traffic_display.cpp index 4fea8f78b80da..a1b991e4742e3 100644 --- a/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/traffic_display.cpp +++ b/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/traffic_display.cpp @@ -48,7 +48,7 @@ TrafficDisplay::TrafficDisplay() } void TrafficDisplay::updateTrafficLightData( - const autoware_perception_msgs::msg::TrafficSignalArray::ConstSharedPtr & msg) + const autoware_perception_msgs::msg::TrafficSignal::ConstSharedPtr & msg) { current_traffic_ = *msg; } @@ -70,8 +70,8 @@ void TrafficDisplay::drawTrafficLightIndicator(QPainter & painter, const QRectF backgroundRect.top() + circleRect.height() + 30)); painter.drawEllipse(circleRect); - if (!current_traffic_.signals.empty()) { - switch (current_traffic_.signals[0].elements[0].color) { + if (!current_traffic_.elements.empty()) { + switch (current_traffic_.elements[0].color) { case 1: painter.setBrush(QBrush(tl_red_)); painter.drawEllipse(circleRect); From 162f33161344a2d043c05299294ae7031851d8d7 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Wed, 1 May 2024 13:04:56 +0900 Subject: [PATCH 07/27] fix(avoidance): add missing parameter declaration (#6908) Signed-off-by: satoshi-ota --- .../behavior_path_avoidance_module/parameter_helper.hpp | 5 +++++ .../schema/avoidance.schema.json | 2 +- planning/behavior_path_avoidance_module/src/manager.cpp | 5 +++++ 3 files changed, 11 insertions(+), 1 deletion(-) diff --git a/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/parameter_helper.hpp b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/parameter_helper.hpp index e115e676b1dbf..25101537850ae 100644 --- a/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/parameter_helper.hpp +++ b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/parameter_helper.hpp @@ -131,6 +131,11 @@ AvoidanceParameters getParameter(rclcpp::Node * node) getOrDeclareParameter(*node, ns + "min_road_shoulder_width"); } + { + const std::string ns = "avoidance.target_filtering.merging_vehicle."; + p.th_overhang_distance = getOrDeclareParameter(*node, ns + "th_overhang_distance"); + } + { const std::string ns = "avoidance.target_filtering.avoidance_for_ambiguous_vehicle."; p.enable_avoidance_for_ambiguous_vehicle = getOrDeclareParameter(*node, ns + "enable"); diff --git a/planning/behavior_path_avoidance_module/schema/avoidance.schema.json b/planning/behavior_path_avoidance_module/schema/avoidance.schema.json index 91f9519596bb1..7c0205d2473e5 100644 --- a/planning/behavior_path_avoidance_module/schema/avoidance.schema.json +++ b/planning/behavior_path_avoidance_module/schema/avoidance.schema.json @@ -686,7 +686,7 @@ "properties": { "th_overhang_distance": { "type": "number", - "description": "Distance threshold between overhang point and ego lane's centerline. If the nearest overhang point of merging/deviating vehicle is less than this param, the module never avoid it. (Basically, the ego stops behind of it.)", + "description": "Distance threshold to ignore merging/deviating vehicle to/from ego driving lane. The distance represents how the object polygon overlaps ego lane, and it's calculated from polygon overhang point and lane centerline. If the distance is more than this param, the module never avoid the object. (Basically, the ego stops behind of it.)", "default": 0.5 } }, diff --git a/planning/behavior_path_avoidance_module/src/manager.cpp b/planning/behavior_path_avoidance_module/src/manager.cpp index dbff6f60365f3..7772bd9c2ad35 100644 --- a/planning/behavior_path_avoidance_module/src/manager.cpp +++ b/planning/behavior_path_avoidance_module/src/manager.cpp @@ -124,6 +124,11 @@ void AvoidanceModuleManager::updateModuleParams(const std::vector(parameters, ns + "backward_distance", p->object_check_backward_distance); } + { + const std::string ns = "avoidance.target_filtering.merging_vehicle."; + updateParam(parameters, ns + "th_overhang_distance", p->th_overhang_distance); + } + { const std::string ns = "avoidance.avoidance.lateral.avoidance_for_ambiguous_vehicle."; updateParam(parameters, ns + "enable", p->enable_avoidance_for_ambiguous_vehicle); From 62d26be2861475ab9b570c095203f47ae944078d Mon Sep 17 00:00:00 2001 From: Tomoya Kimura Date: Wed, 1 May 2024 15:16:48 +0900 Subject: [PATCH 08/27] fix(trajectory_follower_node): fix config file of plot juggler (#6910) * fix(trajectory_follower_node): fix config file of plot juggler Signed-off-by: tomoya.kimura * fix spells Signed-off-by: tomoya.kimura * fix: ignore spell check for "ROS2" Signed-off-by: tomoya.kimura * fix spells Signed-off-by: tomoya.kimura --------- Signed-off-by: tomoya.kimura --- .../plot_juggler_trajectory_follower.xml | 101 ++++++++++-------- 1 file changed, 55 insertions(+), 46 deletions(-) diff --git a/control/trajectory_follower_node/config/plot_juggler_trajectory_follower.xml b/control/trajectory_follower_node/config/plot_juggler_trajectory_follower.xml index 6956db84aff56..ab127c2d47b97 100644 --- a/control/trajectory_follower_node/config/plot_juggler_trajectory_follower.xml +++ b/control/trajectory_follower_node/config/plot_juggler_trajectory_follower.xml @@ -1,5 +1,5 @@ - + @@ -9,37 +9,37 @@ - + - + - + - + - + - + - + @@ -50,12 +50,12 @@ - + - + @@ -66,12 +66,12 @@ - + - + @@ -84,22 +84,22 @@ - + - + - + - + @@ -110,12 +110,12 @@ - + - + @@ -141,52 +141,52 @@ - + - + - + - + - + - + - + - + - + - + @@ -197,7 +197,7 @@ - + @@ -209,22 +209,22 @@ - + - + - + - + @@ -241,33 +241,42 @@ - + - + + - + + + + - + + - - - - - - + + + + - - + + + + + + + + - + From 38ab80e06e835ab7d889f636703a03ea8a94d198 Mon Sep 17 00:00:00 2001 From: Shumpei Wakabayashi <42209144+shmpwk@users.noreply.github.com> Date: Wed, 1 May 2024 18:57:45 +0900 Subject: [PATCH 09/27] chore(component_state_monitor): relax pose_estimator_pose timeout (#6916) --- system/component_state_monitor/config/topics.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/system/component_state_monitor/config/topics.yaml b/system/component_state_monitor/config/topics.yaml index f056892849fbc..6e8ef1b6ed445 100644 --- a/system/component_state_monitor/config/topics.yaml +++ b/system/component_state_monitor/config/topics.yaml @@ -61,7 +61,7 @@ transient_local: false warn_rate: 2.0 error_rate: 1.0 - timeout: 1.0 + timeout: 1.3 - module: perception mode: [online, logging_simulation] From 7f9a32209239af06eeab2f190ca83cdf2b06eac3 Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Wed, 1 May 2024 19:57:31 +0900 Subject: [PATCH 10/27] docs(tier4_simulated_clock_rviz_plugin): update how to use (#6914) * docs(tier4_simulated_clock_rviz_plugin): update how to use Signed-off-by: Muhammad Zulfaqar Azmi * fixed tabbed warning Signed-off-by: Muhammad Zulfaqar Azmi * fix warning not working Signed-off-by: Muhammad Zulfaqar Azmi * Fix bullet list Signed-off-by: Muhammad Zulfaqar Azmi --------- Signed-off-by: Muhammad Zulfaqar Azmi --- .../README.md | 39 ++++++++++++++----- 1 file changed, 29 insertions(+), 10 deletions(-) diff --git a/common/tier4_simulated_clock_rviz_plugin/README.md b/common/tier4_simulated_clock_rviz_plugin/README.md index 73e53b69279ff..a6218f32b988c 100644 --- a/common/tier4_simulated_clock_rviz_plugin/README.md +++ b/common/tier4_simulated_clock_rviz_plugin/README.md @@ -10,18 +10,37 @@ This plugin allows publishing and controlling the simulated ROS time. | -------- | --------------------------- | -------------------------- | | `/clock` | `rosgraph_msgs::msg::Clock` | the current simulated time | -## HowToUse +## How to use the plugin + +1. Launch [planning simulator](https://autowarefoundation.github.io/autoware-documentation/main/tutorials/ad-hoc-simulation/planning-simulation/#1-launch-autoware) with `use_sim_time:=true`. + + ```shell + ros2 launch autoware_launch planning_simulator.launch.xml map_path:=$HOME/autoware_map/sample-map-planning vehicle_model:=sample_vehicle sensor_model:=sample_sensor_kit use_sim_time:=true + ``` + + > Warning + > If you launch the planning simulator without adding the `tier4_simulated_clock_rviz_plugin`, your simulation will not be running. You'll not even be able to place the initial and the goal poses. + +2. Start rviz and select panels/Add new panel. -1. Start rviz and select panels/Add new panel. ![select_panel](./images/select_panels.png) -2. Select tier4_clock_rviz_plugin/SimulatedClock and press OK. + +3. Select tier4_clock_rviz_plugin/SimulatedClock and press OK. + ![select_clock_plugin](./images/select_clock_plugin.png) -3. Use the added panel to control how the simulated clock is published. + +4. Use the added panel to control how the simulated clock is published. + ![use_clock_plugin](./images/use_clock_plugin.png) - - Pause button: pause/resume the clock. - - Speed: speed of the clock relative to the system clock. - - Rate: publishing rate of the clock. - - Step button: advance the clock by the specified time step. - - Time step: value used to advance the clock when pressing the step button d). - - Time unit: time unit associated with the value from e). +
    +
  1. Pause button: pause/resume the clock.
  2. +
  3. Speed: speed of the clock relative to the system clock.
  4. +
  5. Rate: publishing rate of the clock.
  6. +
  7. Step button: advance the clock by the specified time step.
  8. +
  9. Time step: value used to advance the clock when pressing the step button d).
  10. +
  11. Time unit: time unit associated with the value from e).
  12. +
+ + > Warning + > If you set the time step too large, your simulation will go haywire. From 52f4b3e145a34d301ab98d4aafe56fffe95cc5e7 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Thu, 2 May 2024 11:18:40 +0900 Subject: [PATCH 11/27] refactor(avoidance): rebuild object info list (#6913) * refactor(avoidance): rebuild object info structure Signed-off-by: satoshi-ota * refactor(avoidance): add helper function to unify same process Signed-off-by: satoshi-ota * refactor(avoidance): remove unused header Signed-off-by: satoshi-ota --------- Signed-off-by: satoshi-ota --- .../src/scene.cpp | 2 +- .../data_structs.hpp | 32 ++++++++- .../behavior_path_avoidance_module/debug.hpp | 3 +- .../behavior_path_avoidance_module/helper.hpp | 14 ++++ .../src/debug.cpp | 66 +++++++++---------- .../src/scene.cpp | 27 +++----- .../src/shift_line_generator.cpp | 21 +++--- .../src/utils.cpp | 54 ++++++++------- 8 files changed, 122 insertions(+), 97 deletions(-) diff --git a/planning/behavior_path_avoidance_by_lane_change_module/src/scene.cpp b/planning/behavior_path_avoidance_by_lane_change_module/src/scene.cpp index 6a41eccc22ba3..1ae1685a7e610 100644 --- a/planning/behavior_path_avoidance_by_lane_change_module/src/scene.cpp +++ b/planning/behavior_path_avoidance_by_lane_change_module/src/scene.cpp @@ -164,7 +164,7 @@ void AvoidanceByLaneChange::fillAvoidanceTargetObjects( [](const auto & object) { ObjectData other_object; other_object.object = object; - other_object.reason = "OutOfTargetArea"; + other_object.info = ObjectInfo::OUT_OF_TARGET_AREA; return other_object; }); } diff --git a/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/data_structs.hpp b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/data_structs.hpp index 58ada91df9e96..e71039dfa3c34 100644 --- a/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/data_structs.hpp +++ b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/data_structs.hpp @@ -53,6 +53,34 @@ using behavior_path_planner::utils::path_safety_checker::CollisionCheckDebug; using route_handler::Direction; +enum class ObjectInfo { + NONE = 0, + // ignore reasons + OUT_OF_TARGET_AREA, + FURTHER_THAN_THRESHOLD, + FURTHER_THAN_GOAL, + IS_NOT_TARGET_OBJECT, + IS_NOT_PARKING_OBJECT, + TOO_NEAR_TO_CENTERLINE, + TOO_NEAR_TO_GOAL, + MOVING_OBJECT, + UNSTABLE_OBJECT, + CROSSWALK_USER, + ENOUGH_LATERAL_DISTANCE, + LESS_THAN_EXECUTION_THRESHOLD, + PARALLEL_TO_EGO_LANE, + MERGING_TO_EGO_LANE, + DEVIATING_FROM_EGO_LANE, + // unavoidable reasons + NEED_DECELERATION, + SAME_DIRECTION_SHIFT, + INSUFFICIENT_DRIVABLE_SPACE, + INSUFFICIENT_LONGITUDINAL_DISTANCE, + INVALID_SHIFT_LINE, + // others + AMBIGUOUS_STOPPED_VEHICLE, +}; + struct ObjectParameter { bool is_avoidance_target{false}; @@ -423,8 +451,8 @@ struct ObjectData // avoidance target // overhang points (sort by distance) std::vector> overhang_points{}; - // unavoidable reason - std::string reason{}; + // object detail info + ObjectInfo info{ObjectInfo::NONE}; // lateral avoid margin std::optional avoid_margin{std::nullopt}; diff --git a/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/debug.hpp b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/debug.hpp index f49f457ddd066..0308237e7f90b 100644 --- a/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/debug.hpp +++ b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/debug.hpp @@ -31,6 +31,7 @@ using behavior_path_planner::AvoidancePlanningData; using behavior_path_planner::AvoidLineArray; using behavior_path_planner::DebugData; using behavior_path_planner::ObjectDataArray; +using behavior_path_planner::ObjectInfo; using behavior_path_planner::PathShifter; using behavior_path_planner::ShiftLineArray; using geometry_msgs::msg::Pose; @@ -47,7 +48,7 @@ MarkerArray createPredictedVehiclePositions(const PathWithLaneId & path, std::st MarkerArray createTargetObjectsMarkerArray(const ObjectDataArray & objects, const std::string & ns); -MarkerArray createOtherObjectsMarkerArray(const ObjectDataArray & objects, const std::string & ns); +MarkerArray createOtherObjectsMarkerArray(const ObjectDataArray & objects, const ObjectInfo & info); MarkerArray createDebugMarkerArray( const AvoidancePlanningData & data, const PathShifter & shifter, const DebugData & debug); diff --git a/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/helper.hpp b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/helper.hpp index 8d95e724045ba..e5a0a9b801b61 100644 --- a/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/helper.hpp +++ b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/helper.hpp @@ -343,6 +343,20 @@ class AvoidanceHelper parameters_->closest_distance_to_wait_and_see_for_ambiguous_vehicle; } + static bool isAbsolutelyNotAvoidable(const ObjectData & object) + { + if (object.is_avoidable) { + return false; + } + + // can avoid it after deceleration. + if (object.info == ObjectInfo::NEED_DECELERATION) { + return false; + } + + return true; + } + bool isReady(const AvoidLineArray & new_shift_lines, const double current_shift_length) const { if (std::abs(current_shift_length) < 1e-3) { diff --git a/planning/behavior_path_avoidance_module/src/debug.cpp b/planning/behavior_path_avoidance_module/src/debug.cpp index 4595a77a84b3b..1f68114dd8420 100644 --- a/planning/behavior_path_avoidance_module/src/debug.cpp +++ b/planning/behavior_path_avoidance_module/src/debug.cpp @@ -21,8 +21,6 @@ #include #include -#include - #include #include @@ -176,7 +174,8 @@ MarkerArray createObjectInfoMarkerArray(const ObjectDataArray & objects, std::st marker.id = uuidToInt32(object.object.object_id); marker.pose.position.z += 2.0; std::ostringstream string_stream; - string_stream << object.reason << (object.is_parked ? "(PARKED)" : ""); + string_stream << magic_enum::enum_name(object.info) << (object.is_parked ? "(PARKED)" : ""); + string_stream << (object.is_ambiguous ? "(WAIT AND SEE)" : ""); marker.text = string_stream.str(); marker.color = createMarkerColor(1.0, 1.0, 1.0, 0.999); marker.scale = createMarkerScale(0.6, 0.6, 0.6); @@ -441,14 +440,12 @@ MarkerArray createTargetObjectsMarkerArray(const ObjectDataArray & objects, cons return msg; } -MarkerArray createOtherObjectsMarkerArray(const ObjectDataArray & objects, const std::string & ns) +MarkerArray createOtherObjectsMarkerArray(const ObjectDataArray & objects, const ObjectInfo & info) { - using behavior_path_planner::utils::convertToSnakeCase; - - const auto filtered_objects = [&objects, &ns]() { + const auto filtered_objects = [&objects, &info]() { ObjectDataArray ret{}; for (const auto & o : objects) { - if (o.reason != ns) { + if (o.info != info) { continue; } ret.push_back(o); @@ -460,18 +457,20 @@ MarkerArray createOtherObjectsMarkerArray(const ObjectDataArray & objects, const MarkerArray msg; msg.markers.reserve(filtered_objects.size() * 2); + std::ostringstream string_stream; + string_stream << magic_enum::enum_name(info); + + std::string ns = string_stream.str(); + transform(ns.begin(), ns.end(), ns.begin(), tolower); + appendMarkerArray( createObjectsCubeMarkerArray( - filtered_objects, "others_" + convertToSnakeCase(ns) + "_cube", - createMarkerScale(3.0, 1.5, 1.5), createMarkerColor(0.0, 1.0, 0.0, 0.8)), + filtered_objects, "others_" + ns + "_cube", createMarkerScale(3.0, 1.5, 1.5), + createMarkerColor(0.0, 1.0, 0.0, 0.8)), &msg); + appendMarkerArray(createObjectInfoMarkerArray(filtered_objects, "others_" + ns + "_info"), &msg); appendMarkerArray( - createObjectInfoMarkerArray(filtered_objects, "others_" + convertToSnakeCase(ns) + "_info"), - &msg); - appendMarkerArray( - createOverhangLaneletMarkerArray( - filtered_objects, "others_" + convertToSnakeCase(ns) + "_overhang_lanelet"), - &msg); + createOverhangLaneletMarkerArray(filtered_objects, "others_" + ns + "_overhang_lanelet"), &msg); return msg; } @@ -528,7 +527,6 @@ MarkerArray createDebugMarkerArray( using marker_utils::showPolygon; using marker_utils::showPredictedPath; using marker_utils::showSafetyCheckInfo; - using tier4_planning_msgs::msg::AvoidanceDebugFactor; const auto current_time = rclcpp::Clock{RCL_ROS_TIME}.now(); MarkerArray msg; @@ -564,24 +562,22 @@ MarkerArray createDebugMarkerArray( // ignore objects { - addObjects(data.other_objects, AvoidanceDebugFactor::OBJECT_IS_BEHIND_THRESHOLD); - addObjects(data.other_objects, AvoidanceDebugFactor::OBJECT_IS_IN_FRONT_THRESHOLD); - addObjects(data.other_objects, AvoidanceDebugFactor::OBJECT_IS_NOT_TYPE); - addObjects(data.other_objects, AvoidanceDebugFactor::OBJECT_BEHIND_PATH_GOAL); - addObjects(data.other_objects, AvoidanceDebugFactor::TOO_NEAR_TO_CENTERLINE); - addObjects(data.other_objects, AvoidanceDebugFactor::NOT_PARKING_OBJECT); - addObjects(data.other_objects, std::string("MovingObject")); - addObjects(data.other_objects, std::string("CrosswalkUser")); - addObjects(data.other_objects, std::string("OutOfTargetArea")); - addObjects(data.other_objects, std::string("NotNeedAvoidance")); - addObjects(data.other_objects, std::string("LessThanExecutionThreshold")); - addObjects(data.other_objects, std::string("TooNearToGoal")); - addObjects(data.other_objects, std::string("ParallelToEgoLane")); - addObjects(data.other_objects, std::string("MergingToEgoLane")); - addObjects(data.other_objects, std::string("DeviatingFromEgoLane")); - addObjects(data.other_objects, std::string("UnstableObject")); - addObjects(data.other_objects, std::string("AmbiguousStoppedVehicle")); - addObjects(data.other_objects, std::string("AmbiguousStoppedVehicle(wait-and-see)")); + addObjects(data.other_objects, ObjectInfo::FURTHER_THAN_THRESHOLD); + addObjects(data.other_objects, ObjectInfo::IS_NOT_TARGET_OBJECT); + addObjects(data.other_objects, ObjectInfo::FURTHER_THAN_GOAL); + addObjects(data.other_objects, ObjectInfo::TOO_NEAR_TO_CENTERLINE); + addObjects(data.other_objects, ObjectInfo::IS_NOT_PARKING_OBJECT); + addObjects(data.other_objects, ObjectInfo::MOVING_OBJECT); + addObjects(data.other_objects, ObjectInfo::CROSSWALK_USER); + addObjects(data.other_objects, ObjectInfo::OUT_OF_TARGET_AREA); + addObjects(data.other_objects, ObjectInfo::ENOUGH_LATERAL_DISTANCE); + addObjects(data.other_objects, ObjectInfo::LESS_THAN_EXECUTION_THRESHOLD); + addObjects(data.other_objects, ObjectInfo::TOO_NEAR_TO_GOAL); + addObjects(data.other_objects, ObjectInfo::PARALLEL_TO_EGO_LANE); + addObjects(data.other_objects, ObjectInfo::MERGING_TO_EGO_LANE); + addObjects(data.other_objects, ObjectInfo::DEVIATING_FROM_EGO_LANE); + addObjects(data.other_objects, ObjectInfo::UNSTABLE_OBJECT); + addObjects(data.other_objects, ObjectInfo::AMBIGUOUS_STOPPED_VEHICLE); } // shift line pre-process diff --git a/planning/behavior_path_avoidance_module/src/scene.cpp b/planning/behavior_path_avoidance_module/src/scene.cpp index b70b606d8f279..a8eeb413237b1 100644 --- a/planning/behavior_path_avoidance_module/src/scene.cpp +++ b/planning/behavior_path_avoidance_module/src/scene.cpp @@ -31,7 +31,6 @@ #include #include "tier4_planning_msgs/msg/detail/avoidance_debug_msg_array__struct.hpp" -#include #include #include @@ -52,7 +51,6 @@ using tier4_autoware_utils::calcLateralDeviation; using tier4_autoware_utils::getPoint; using tier4_autoware_utils::getPose; using tier4_autoware_utils::toHexString; -using tier4_planning_msgs::msg::AvoidanceDebugFactor; namespace { @@ -119,9 +117,8 @@ bool AvoidanceModule::isExecutionRequested() const } return std::any_of( - avoid_data_.target_objects.begin(), avoid_data_.target_objects.end(), [](const auto & o) { - return o.is_avoidable || o.reason == AvoidanceDebugFactor::TOO_LARGE_JERK; - }); + avoid_data_.target_objects.begin(), avoid_data_.target_objects.end(), + [this](const auto & o) { return !helper_->isAbsolutelyNotAvoidable(o); }); } bool AvoidanceModule::isExecutionReady() const @@ -136,10 +133,9 @@ bool AvoidanceModule::isExecutionReady() const bool AvoidanceModule::isSatisfiedSuccessCondition(const AvoidancePlanningData & data) const { - const bool has_avoidance_target = - std::any_of(data.target_objects.begin(), data.target_objects.end(), [](const auto & o) { - return o.is_avoidable || o.reason == AvoidanceDebugFactor::TOO_LARGE_JERK; - }); + const bool has_avoidance_target = std::any_of( + data.target_objects.begin(), data.target_objects.end(), + [this](const auto & o) { return !helper_->isAbsolutelyNotAvoidable(o); }); if (has_avoidance_target) { return false; @@ -337,7 +333,7 @@ void AvoidanceModule::fillAvoidanceTargetObjects( for (const auto & object : object_outside_target_lane.objects) { ObjectData other_object = createObjectData(data, object); - other_object.reason = "OutOfTargetArea"; + other_object.info = ObjectInfo::OUT_OF_TARGET_AREA; data.other_objects.push_back(other_object); } @@ -367,8 +363,6 @@ void AvoidanceModule::fillAvoidanceTargetObjects( debug_info.object_id = toHexString(o.object.object_id); debug_info.longitudinal_distance = o.longitudinal; debug_info.lateral_distance_from_centerline = o.to_centerline; - debug_info.allow_avoidance = o.reason == ""; - debug_info.failed_reason = o.reason; debug_info_array.push_back(debug_info); }; @@ -530,12 +524,11 @@ void AvoidanceModule::fillEgoStatus( * if the both of following two conditions are satisfied, the module surely avoid the object. * Condition1: there is risk to collide with object without avoidance. * Condition2: there is enough space to avoid. - * In TOO_LARGE_JERK condition, it is possible to avoid object by deceleration even if the flag + * In NEED_DECELERATION condition, it is possible to avoid object by deceleration even if the flag * is_avoidable is FALSE. So, the module inserts stop point for such a object. */ for (const auto & o : data.target_objects) { - const auto enough_space = o.is_avoidable || o.reason == AvoidanceDebugFactor::TOO_LARGE_JERK; - if (o.avoid_required && enough_space) { + if (o.avoid_required && !helper_->isAbsolutelyNotAvoidable(o)) { data.avoid_required = true; data.stop_target_object = o; data.to_stop_line = o.to_stop_line; @@ -1667,9 +1660,7 @@ void AvoidanceModule::insertPrepareVelocity(ShiftedPath & shifted_path) const return; } - const auto enough_space = - object.value().is_avoidable || object.value().reason == AvoidanceDebugFactor::TOO_LARGE_JERK; - if (!enough_space) { + if (helper_->isAbsolutelyNotAvoidable(object.value())) { return; } diff --git a/planning/behavior_path_avoidance_module/src/shift_line_generator.cpp b/planning/behavior_path_avoidance_module/src/shift_line_generator.cpp index 9137048945fa1..8a5b14db8e889 100644 --- a/planning/behavior_path_avoidance_module/src/shift_line_generator.cpp +++ b/planning/behavior_path_avoidance_module/src/shift_line_generator.cpp @@ -19,14 +19,11 @@ #include -#include - namespace behavior_path_planner::utils::avoidance { using tier4_autoware_utils::generateUUID; using tier4_autoware_utils::getPoint; -using tier4_planning_msgs::msg::AvoidanceDebugFactor; namespace { @@ -182,7 +179,7 @@ AvoidOutlines ShiftLineGenerator::generateAvoidOutline( // prepare distance is not enough. unavoidable. if (avoidance_distance < 1e-3) { - object.reason = AvoidanceDebugFactor::REMAINING_DISTANCE_LESS_THAN_ZERO; + object.info = ObjectInfo::INSUFFICIENT_LONGITUDINAL_DISTANCE; return std::nullopt; } @@ -200,10 +197,10 @@ AvoidOutlines ShiftLineGenerator::generateAvoidOutline( // avoidance distance is not enough. unavoidable. if (!isBestEffort(parameters_->policy_deceleration)) { if (avoidance_distance < helper_->getMinAvoidanceDistance(avoiding_shift) + LON_DIST_BUFFER) { - object.reason = AvoidanceDebugFactor::REMAINING_DISTANCE_LESS_THAN_ZERO; + object.info = ObjectInfo::INSUFFICIENT_LONGITUDINAL_DISTANCE; return std::nullopt; } else { - object.reason = AvoidanceDebugFactor::TOO_LARGE_JERK; + object.info = ObjectInfo::NEED_DECELERATION; return std::nullopt; } } @@ -213,7 +210,7 @@ AvoidOutlines ShiftLineGenerator::generateAvoidOutline( avoidance_distance, helper_->getLateralMaxJerkLimit(), helper_->getAvoidanceEgoSpeed()); if (std::abs(feasible_relative_shift_length) < parameters_->lateral_execution_threshold) { - object.reason = "LessThanExecutionThreshold"; + object.info = ObjectInfo::LESS_THAN_EXECUTION_THRESHOLD; return std::nullopt; } @@ -224,7 +221,7 @@ AvoidOutlines ShiftLineGenerator::generateAvoidOutline( if ( avoidance_distance < helper_->getMinAvoidanceDistance(feasible_shift_length) + LON_DIST_BUFFER) { - object.reason = AvoidanceDebugFactor::REMAINING_DISTANCE_LESS_THAN_ZERO; + object.info = ObjectInfo::INSUFFICIENT_LONGITUDINAL_DISTANCE; return std::nullopt; } @@ -238,7 +235,7 @@ AvoidOutlines ShiftLineGenerator::generateAvoidOutline( 0.5 * data_->parameters.vehicle_width + lateral_hard_margin; if (infeasible) { RCLCPP_DEBUG(rclcpp::get_logger(""), "feasible shift length is not enough to avoid. "); - object.reason = AvoidanceDebugFactor::TOO_LARGE_JERK; + object.info = ObjectInfo::NEED_DECELERATION; return std::nullopt; } @@ -254,7 +251,7 @@ AvoidOutlines ShiftLineGenerator::generateAvoidOutline( AvoidOutlines outlines; for (auto & o : data.target_objects) { if (!o.avoid_margin.has_value()) { - o.reason = AvoidanceDebugFactor::INSUFFICIENT_LATERAL_MARGIN; + o.info = ObjectInfo::INSUFFICIENT_DRIVABLE_SPACE; if (o.avoid_required && is_forward_object(o)) { break; } else { @@ -266,7 +263,7 @@ AvoidOutlines ShiftLineGenerator::generateAvoidOutline( const auto desire_shift_length = helper_->getShiftLength(o, is_object_on_right, o.avoid_margin.value()); if (utils::avoidance::isSameDirectionShift(is_object_on_right, desire_shift_length)) { - o.reason = AvoidanceDebugFactor::SAME_DIRECTION_SHIFT; + o.info = ObjectInfo::SAME_DIRECTION_SHIFT; if (o.avoid_required && is_forward_object(o)) { break; } else { @@ -377,7 +374,7 @@ AvoidOutlines ShiftLineGenerator::generateAvoidOutline( } else if (is_valid_shift_line(al_avoid) && is_valid_shift_line(al_return)) { outlines.emplace_back(al_avoid, al_return); } else { - o.reason = "InvalidShiftLine"; + o.info = ObjectInfo::INVALID_SHIFT_LINE; continue; } diff --git a/planning/behavior_path_avoidance_module/src/utils.cpp b/planning/behavior_path_avoidance_module/src/utils.cpp index b711dcb91236d..657214bd61c95 100644 --- a/planning/behavior_path_avoidance_module/src/utils.cpp +++ b/planning/behavior_path_avoidance_module/src/utils.cpp @@ -27,7 +27,6 @@ #include #include -#include #include #include @@ -62,7 +61,6 @@ using tier4_autoware_utils::calcYawDeviation; using tier4_autoware_utils::createQuaternionFromRPY; using tier4_autoware_utils::getPose; using tier4_autoware_utils::pose2transform; -using tier4_planning_msgs::msg::AvoidanceDebugFactor; using tier4_planning_msgs::msg::AvoidanceDebugMsg; namespace @@ -569,14 +567,14 @@ bool isNeverAvoidanceTarget( { if (object.is_within_intersection) { if (object.behavior == ObjectData::Behavior::NONE) { - object.reason = "ParallelToEgoLane"; + object.info = ObjectInfo::PARALLEL_TO_EGO_LANE; RCLCPP_DEBUG( rclcpp::get_logger(logger_namespace), "object belongs to ego lane. never avoid it."); return true; } if (object.behavior == ObjectData::Behavior::MERGING) { - object.reason = "MergingToEgoLane"; + object.info = ObjectInfo::MERGING_TO_EGO_LANE; RCLCPP_DEBUG( rclcpp::get_logger(logger_namespace), "object belongs to ego lane. never avoid it."); return true; @@ -584,7 +582,7 @@ bool isNeverAvoidanceTarget( } if (object.behavior == ObjectData::Behavior::MERGING) { - object.reason = "MergingToEgoLane"; + object.info = ObjectInfo::MERGING_TO_EGO_LANE; if ( isOnRight(object) && !object.is_parked && object.overhang_points.front().first > parameters->th_overhang_distance) { @@ -604,7 +602,7 @@ bool isNeverAvoidanceTarget( } if (object.behavior == ObjectData::Behavior::DEVIATING) { - object.reason = "DeviatingFromEgoLane"; + object.info = ObjectInfo::DEVIATING_FROM_EGO_LANE; if ( isOnRight(object) && !object.is_parked && object.overhang_points.front().first > parameters->th_overhang_distance) { @@ -629,7 +627,7 @@ bool isNeverAvoidanceTarget( const auto left_lane = planner_data->route_handler->getLeftLanelet(object.overhang_lanelet, true, false); if (right_lane.has_value() && left_lane.has_value()) { - object.reason = AvoidanceDebugFactor::NOT_PARKING_OBJECT; + object.info = ObjectInfo::IS_NOT_PARKING_OBJECT; RCLCPP_DEBUG( rclcpp::get_logger(logger_namespace), "object isn't on the edge lane. never avoid it."); return true; @@ -638,7 +636,7 @@ bool isNeverAvoidanceTarget( if (isCloseToStopFactor(object, data, planner_data, parameters)) { if (object.is_on_ego_lane && !object.is_parked) { - object.reason = AvoidanceDebugFactor::NOT_PARKING_OBJECT; + object.info = ObjectInfo::IS_NOT_PARKING_OBJECT; RCLCPP_DEBUG( rclcpp::get_logger(logger_namespace), "object is close to stop factor. never avoid it."); return true; @@ -666,11 +664,11 @@ bool isObviousAvoidanceTarget( } if (!object.is_parked) { - object.reason = AvoidanceDebugFactor::NOT_PARKING_OBJECT; + object.info = ObjectInfo::IS_NOT_PARKING_OBJECT; } if (object.behavior == ObjectData::Behavior::MERGING) { - object.reason = "MergingToEgoLane"; + object.info = ObjectInfo::MERGING_TO_EGO_LANE; } return false; @@ -683,13 +681,13 @@ bool isSatisfiedWithCommonCondition( { // Step1. filtered by target object type. if (!isAvoidanceTargetObjectType(object.object, parameters)) { - object.reason = AvoidanceDebugFactor::OBJECT_IS_NOT_TYPE; + object.info = ObjectInfo::IS_NOT_TARGET_OBJECT; return false; } // Step2. filtered stopped objects. if (filtering_utils::isMovingObject(object, parameters)) { - object.reason = AvoidanceDebugFactor::MOVING_OBJECT; + object.info = ObjectInfo::MOVING_OBJECT; return false; } @@ -698,12 +696,12 @@ bool isSatisfiedWithCommonCondition( fillLongitudinalAndLengthByClosestEnvelopeFootprint(data.reference_path_rough, ego_pos, object); if (object.longitudinal < -parameters->object_check_backward_distance) { - object.reason = AvoidanceDebugFactor::OBJECT_IS_BEHIND_THRESHOLD; + object.info = ObjectInfo::FURTHER_THAN_THRESHOLD; return false; } if (object.longitudinal > forward_detection_range) { - object.reason = AvoidanceDebugFactor::OBJECT_IS_IN_FRONT_THRESHOLD; + object.info = ObjectInfo::FURTHER_THAN_THRESHOLD; return false; } @@ -719,7 +717,7 @@ bool isSatisfiedWithCommonCondition( : std::numeric_limits::max(); if (object.longitudinal > to_goal_distance) { - object.reason = AvoidanceDebugFactor::OBJECT_BEHIND_PATH_GOAL; + object.info = ObjectInfo::FURTHER_THAN_GOAL; return false; } @@ -727,7 +725,7 @@ bool isSatisfiedWithCommonCondition( if ( object.longitudinal + object.length / 2 + parameters->object_check_goal_distance > to_goal_distance) { - object.reason = "TooNearToGoal"; + object.info = ObjectInfo::TOO_NEAR_TO_GOAL; return false; } } @@ -742,7 +740,7 @@ bool isSatisfiedWithNonVehicleCondition( { // avoidance module ignore pedestrian and bicycle around crosswalk if (isWithinCrosswalk(object, planner_data->route_handler->getOverallGraphPtr())) { - object.reason = "CrosswalkUser"; + object.info = ObjectInfo::CROSSWALK_USER; return false; } @@ -751,7 +749,7 @@ bool isSatisfiedWithNonVehicleCondition( object.to_centerline = lanelet::utils::getArcCoordinates(data.current_lanelets, object_pose).distance; if (std::abs(object.to_centerline) < parameters->threshold_distance_object_is_on_center) { - object.reason = AvoidanceDebugFactor::TOO_NEAR_TO_CENTERLINE; + object.info = ObjectInfo::TOO_NEAR_TO_CENTERLINE; return false; } @@ -788,14 +786,14 @@ bool isSatisfiedWithVehicleCondition( // from here, filtering for ambiguous vehicle. if (!parameters->enable_avoidance_for_ambiguous_vehicle) { - object.reason = "AmbiguousStoppedVehicle"; + object.info = ObjectInfo::AMBIGUOUS_STOPPED_VEHICLE; return false; } const auto stop_time_longer_than_threshold = object.stop_time > parameters->time_threshold_for_ambiguous_vehicle; if (!stop_time_longer_than_threshold) { - object.reason = "AmbiguousStoppedVehicle(wait-and-see)"; + object.info = ObjectInfo::AMBIGUOUS_STOPPED_VEHICLE; return false; } @@ -804,25 +802,25 @@ bool isSatisfiedWithVehicleCondition( calcDistance2d(object.init_pose, current_pose) > parameters->distance_threshold_for_ambiguous_vehicle; if (is_moving_distance_longer_than_threshold) { - object.reason = "AmbiguousStoppedVehicle"; + object.info = ObjectInfo::AMBIGUOUS_STOPPED_VEHICLE; return false; } if (object.is_within_intersection) { if (object.behavior == ObjectData::Behavior::DEVIATING) { - object.reason = "AmbiguousStoppedVehicle(wait-and-see)"; + object.info = ObjectInfo::AMBIGUOUS_STOPPED_VEHICLE; object.is_ambiguous = true; return true; } } else { if (object.behavior == ObjectData::Behavior::MERGING) { - object.reason = "AmbiguousStoppedVehicle(wait-and-see)"; + object.info = ObjectInfo::AMBIGUOUS_STOPPED_VEHICLE; object.is_ambiguous = true; return true; } if (object.behavior == ObjectData::Behavior::DEVIATING) { - object.reason = "AmbiguousStoppedVehicle(wait-and-see)"; + object.info = ObjectInfo::AMBIGUOUS_STOPPED_VEHICLE; object.is_ambiguous = true; return true; } @@ -833,7 +831,7 @@ bool isSatisfiedWithVehicleCondition( } } - object.reason = AvoidanceDebugFactor::NOT_PARKING_OBJECT; + object.info = ObjectInfo::IS_NOT_PARKING_OBJECT; return false; } @@ -847,12 +845,12 @@ bool isNoNeedAvoidanceBehavior( const auto shift_length = calcShiftLength( isOnRight(object), object.overhang_points.front().first, object.avoid_margin.value()); if (!isShiftNecessary(isOnRight(object), shift_length)) { - object.reason = "NotNeedAvoidance"; + object.info = ObjectInfo::ENOUGH_LATERAL_DISTANCE; return true; } if (std::abs(shift_length) < parameters->lateral_execution_threshold) { - object.reason = "LessThanExecutionThreshold"; + object.info = ObjectInfo::LESS_THAN_EXECUTION_THRESHOLD; return true; } @@ -1702,7 +1700,7 @@ void filterTargetObjects( constexpr double STOP_TIME_THRESHOLD = 3.0; // [s] if (filtering_utils::isUnknownTypeObject(o)) { if (o.stop_time < STOP_TIME_THRESHOLD) { - o.reason = "UnstableObject"; + o.info = ObjectInfo::UNSTABLE_OBJECT; data.other_objects.push_back(o); continue; } From 23f99a74585658e5da6b6940222034e19b2d5fec Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Thu, 2 May 2024 20:15:43 +0900 Subject: [PATCH 12/27] feat(mission_planner): publish initial and goal poses to logs (#6918) * feat(mission_planner): publish initial and goal poses to logs Signed-off-by: Muhammad Zulfaqar Azmi * refactoring to a function Signed-off-by: Muhammad Zulfaqar Azmi --------- Signed-off-by: Muhammad Zulfaqar Azmi --- .../src/mission_planner/mission_planner.cpp | 17 +++++++++++++++++ .../src/mission_planner/mission_planner.hpp | 2 ++ 2 files changed, 19 insertions(+) diff --git a/planning/mission_planner/src/mission_planner/mission_planner.cpp b/planning/mission_planner/src/mission_planner/mission_planner.cpp index e9a0108cdaa24..4cc646526a0ac 100644 --- a/planning/mission_planner/src/mission_planner/mission_planner.cpp +++ b/planning/mission_planner/src/mission_planner/mission_planner.cpp @@ -87,6 +87,17 @@ MissionPlanner::MissionPlanner(const rclcpp::NodeOptions & options) logger_configure_ = std::make_unique(this); } +void MissionPlanner::publish_pose_log(const Pose & pose, const std::string & pose_type) +{ + const auto & p = pose.position; + RCLCPP_INFO( + this->get_logger(), "%s pose - x: %f, y: %f, z: %f", pose_type.c_str(), p.x, p.y, p.z); + const auto & quaternion = pose.orientation; + RCLCPP_INFO( + this->get_logger(), "%s orientation - qx: %f, qy: %f, qz: %f, qw: %f", pose_type.c_str(), + quaternion.x, quaternion.y, quaternion.z, quaternion.w); +} + void MissionPlanner::check_initialization() { auto logger = get_logger(); @@ -247,6 +258,9 @@ void MissionPlanner::on_set_lanelet_route( change_route(route); change_state(RouteState::SET); res->status.success = true; + + publish_pose_log(odometry_->pose.pose, "initial"); + publish_pose_log(req->goal_pose, "goal"); } void MissionPlanner::on_set_waypoint_route( @@ -292,6 +306,9 @@ void MissionPlanner::on_set_waypoint_route( change_route(route); change_state(RouteState::SET); res->status.success = true; + + publish_pose_log(odometry_->pose.pose, "initial"); + publish_pose_log(req->goal_pose, "goal"); } void MissionPlanner::change_route() diff --git a/planning/mission_planner/src/mission_planner/mission_planner.hpp b/planning/mission_planner/src/mission_planner/mission_planner.hpp index 8016851d5a7d3..6752ceb4eaa8b 100644 --- a/planning/mission_planner/src/mission_planner/mission_planner.hpp +++ b/planning/mission_planner/src/mission_planner/mission_planner.hpp @@ -122,6 +122,8 @@ class MissionPlanner : public rclcpp::Node const Header & header, const std::vector & waypoints, const Pose & goal_pose, const UUID & uuid, const bool allow_goal_modification); + void publish_pose_log(const Pose & pose, const std::string & pose_type); + rclcpp::TimerBase::SharedPtr data_check_timer_; void check_initialization(); From 47409143cfe0af0cccaae9194c403ae7802e9a36 Mon Sep 17 00:00:00 2001 From: Yuxuan Liu <619684051@qq.com> Date: Fri, 3 May 2024 13:24:38 +0900 Subject: [PATCH 13/27] feat(pull_request_templates): improve the pull request template to enhance requirements on documenting interface changes (#6896) improve the pull request template to enhance requirements on documenting interface changes Signed-off-by: Yuxuan Liu Co-authored-by: Yuxuan Liu --- .github/PULL_REQUEST_TEMPLATE/small-change.md | 4 ++++ .github/PULL_REQUEST_TEMPLATE/standard-change.md | 13 +++++++++++++ 2 files changed, 17 insertions(+) diff --git a/.github/PULL_REQUEST_TEMPLATE/small-change.md b/.github/PULL_REQUEST_TEMPLATE/small-change.md index 2ff933c43a349..e15fdd992d114 100644 --- a/.github/PULL_REQUEST_TEMPLATE/small-change.md +++ b/.github/PULL_REQUEST_TEMPLATE/small-change.md @@ -15,6 +15,10 @@ Not applicable. Not applicable. +## Interface changes + + + ## Pre-review checklist for the PR author The PR author **must** check the checkboxes below when creating the PR. diff --git a/.github/PULL_REQUEST_TEMPLATE/standard-change.md b/.github/PULL_REQUEST_TEMPLATE/standard-change.md index 7aedefd0a7bf1..391af629751e0 100644 --- a/.github/PULL_REQUEST_TEMPLATE/standard-change.md +++ b/.github/PULL_REQUEST_TEMPLATE/standard-change.md @@ -18,6 +18,19 @@ +### ROS Topic Changes + + + + + + +### ROS Parameter Changes + + + + + ## Effects on system behavior From b307b3dbeed39dec00d2fb9cc635009e1ede41ee Mon Sep 17 00:00:00 2001 From: Yoshi Ri Date: Sat, 4 May 2024 12:53:55 +0900 Subject: [PATCH 14/27] chore(radar_track_msgs_converter): change radar tracks subscription qos to besteffort (#6864) feat: change radar tracks subscription qos to besteffort Signed-off-by: yoshiri --- .../radar_tracks_msgs_converter_node.cpp | 2 +- .../radar_tracks_noise_filter_node.cpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/perception/radar_tracks_msgs_converter/src/radar_tracks_msgs_converter_node/radar_tracks_msgs_converter_node.cpp b/perception/radar_tracks_msgs_converter/src/radar_tracks_msgs_converter_node/radar_tracks_msgs_converter_node.cpp index c7f2bb5bdc60d..084e939ff40a9 100644 --- a/perception/radar_tracks_msgs_converter/src/radar_tracks_msgs_converter_node/radar_tracks_msgs_converter_node.cpp +++ b/perception/radar_tracks_msgs_converter/src/radar_tracks_msgs_converter_node/radar_tracks_msgs_converter_node.cpp @@ -87,7 +87,7 @@ RadarTracksMsgsConverterNode::RadarTracksMsgsConverterNode(const rclcpp::NodeOpt // Subscriber sub_radar_ = create_subscription( - "~/input/radar_objects", rclcpp::QoS{1}, + "~/input/radar_objects", rclcpp::QoS{1}.best_effort(), std::bind(&RadarTracksMsgsConverterNode::onRadarTracks, this, _1)); sub_odometry_ = create_subscription( "~/input/odometry", rclcpp::QoS{1}, diff --git a/sensing/radar_tracks_noise_filter/src/radar_tracks_noise_filter_node/radar_tracks_noise_filter_node.cpp b/sensing/radar_tracks_noise_filter/src/radar_tracks_noise_filter_node/radar_tracks_noise_filter_node.cpp index 5bd143a42eced..82a0a21ff6fdc 100644 --- a/sensing/radar_tracks_noise_filter/src/radar_tracks_noise_filter_node/radar_tracks_noise_filter_node.cpp +++ b/sensing/radar_tracks_noise_filter/src/radar_tracks_noise_filter_node/radar_tracks_noise_filter_node.cpp @@ -56,7 +56,7 @@ RadarTrackCrossingNoiseFilterNode::RadarTrackCrossingNoiseFilterNode( // Subscriber sub_tracks_ = create_subscription( - "~/input/tracks", rclcpp::QoS{1}, + "~/input/tracks", rclcpp::QoS{1}.best_effort(), std::bind(&RadarTrackCrossingNoiseFilterNode::onTracks, this, std::placeholders::_1)); // Publisher From aab29f7c35132527c8efe72e254bde96f251d6bc Mon Sep 17 00:00:00 2001 From: Yoshi Ri Date: Mon, 6 May 2024 11:07:55 +0900 Subject: [PATCH 15/27] feat(probabilistic_occupancy_grid_map): add downsample filter option to ogm creation (#6865) * feat: add downsample filter to ogm creation Signed-off-by: yoshiri * feat: add downsample to multi_lidar ogm creation Signed-off-by: yoshiri * chore: update package.xml and readme and param file Signed-off-by: yoshiri * chore: update readme document Signed-off-by: yoshiri * chore: fix downsample size Signed-off-by: yoshiri * chore: fix cspell error Signed-off-by: yoshiri * feat: add test_depend Signed-off-by: yoshiri --------- Signed-off-by: yoshiri --- .../README.md | 20 +++++ ...tcloud_based_occupancy_grid_map.param.yaml | 6 +- ...tcloud_based_occupancy_grid_map.param.yaml | 4 + ...ntcloud_based_occupancy_grid_map.launch.py | 82 ++++++++++++++++++- ...ntcloud_based_occupancy_grid_map.launch.py | 69 ++++++++++++++-- .../package.xml | 2 + .../pointcloud-based-occupancy-grid-map.md | 32 ++++++-- 7 files changed, 198 insertions(+), 17 deletions(-) diff --git a/perception/probabilistic_occupancy_grid_map/README.md b/perception/probabilistic_occupancy_grid_map/README.md index 084c55d80d629..97d66bf9f648c 100644 --- a/perception/probabilistic_occupancy_grid_map/README.md +++ b/perception/probabilistic_occupancy_grid_map/README.md @@ -72,6 +72,26 @@ Additional argument is shown below: | `input_obstacle_pointcloud` | `false` | only for laserscan based method. If true, the node subscribe obstacle pointcloud | | `input_obstacle_and_raw_pointcloud` | `true` | only for laserscan based method. If true, the node subscribe both obstacle and raw pointcloud | +### Downsample input pointcloud(Optional) + +If you set `downsample_input_pointcloud` to `true`, the input pointcloud will be downsampled and following topics are also used. This feature is currently only for the pointcloud based occupancy grid map. + +- pointcloud_based_occupancy_grid_map method + +```yaml +# downsampled raw and obstacle pointcloud +/perception/occupancy_grid_map/obstacle/downsample/pointcloud +/perception/occupancy_grid_map/raw/downsample/pointcloud +``` + +- multi_lidar_pointcloud_based_point_cloud + +```yaml +# downsampled raw and obstacle pointcloud +/perception/occupancy_grid_map/obstacle/downsample/pointcloud +/perception/occupancy_grid_map//raw/downsample/pointcloud +``` + ### Test This package provides unit tests using `gtest`. diff --git a/perception/probabilistic_occupancy_grid_map/config/multi_lidar_pointcloud_based_occupancy_grid_map.param.yaml b/perception/probabilistic_occupancy_grid_map/config/multi_lidar_pointcloud_based_occupancy_grid_map.param.yaml index f9a1c4f930001..878bea4cd8ced 100644 --- a/perception/probabilistic_occupancy_grid_map/config/multi_lidar_pointcloud_based_occupancy_grid_map.param.yaml +++ b/perception/probabilistic_occupancy_grid_map/config/multi_lidar_pointcloud_based_occupancy_grid_map.param.yaml @@ -12,6 +12,10 @@ map_length_x: 150.0 # [m] map_length_y: 150.0 # [m] + # downsample input pointcloud + downsample_input_pointcloud: true + downsample_voxel_size: 0.25 # [m] + # each grid map parameters ogm_creation_config: height_filter: @@ -20,7 +24,7 @@ max_height: 2.0 enable_single_frame_mode: true # use sensor pointcloud to filter obstacle pointcloud - filter_obstacle_pointcloud_by_raw_pointcloud: true + filter_obstacle_pointcloud_by_raw_pointcloud: false grid_map_type: "OccupancyGridMapFixedBlindSpot" OccupancyGridMapFixedBlindSpot: diff --git a/perception/probabilistic_occupancy_grid_map/config/pointcloud_based_occupancy_grid_map.param.yaml b/perception/probabilistic_occupancy_grid_map/config/pointcloud_based_occupancy_grid_map.param.yaml index 8077bdec5008e..922d4be6d519f 100644 --- a/perception/probabilistic_occupancy_grid_map/config/pointcloud_based_occupancy_grid_map.param.yaml +++ b/perception/probabilistic_occupancy_grid_map/config/pointcloud_based_occupancy_grid_map.param.yaml @@ -8,6 +8,10 @@ min_height: -1.0 max_height: 2.0 + # downsample input pointcloud + downsample_input_pointcloud: true + downsample_voxel_size: 0.25 # [m] + enable_single_frame_mode: false # use sensor pointcloud to filter obstacle pointcloud filter_obstacle_pointcloud_by_raw_pointcloud: false diff --git a/perception/probabilistic_occupancy_grid_map/launch/multi_lidar_pointcloud_based_occupancy_grid_map.launch.py b/perception/probabilistic_occupancy_grid_map/launch/multi_lidar_pointcloud_based_occupancy_grid_map.launch.py index dccddfbe54196..b112dd0a84b83 100644 --- a/perception/probabilistic_occupancy_grid_map/launch/multi_lidar_pointcloud_based_occupancy_grid_map.launch.py +++ b/perception/probabilistic_occupancy_grid_map/launch/multi_lidar_pointcloud_based_occupancy_grid_map.launch.py @@ -92,6 +92,57 @@ def get_ogm_creation_config(total_config: dict, list_iter: int) -> dict: return ogm_creation_config +# generate downsample node +def get_downsample_filter_node(setting: dict) -> ComposableNode: + plugin_str = setting["plugin"] + voxel_size = setting["voxel_size"] + node_name = setting["node_name"] + return ComposableNode( + package="pointcloud_preprocessor", + plugin=plugin_str, + name=node_name, + remappings=[ + ("input", setting["input_topic"]), + ("output", setting["output_topic"]), + ], + parameters=[ + { + "voxel_size_x": voxel_size, + "voxel_size_y": voxel_size, + "voxel_size_z": voxel_size, + } + ], + extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], + ) + + +def get_downsample_preprocess_nodes(voxel_size: float, raw_pointcloud_topics: list) -> list: + nodes = [] + for i in range(len(raw_pointcloud_topics)): + raw_pointcloud_topic: str = raw_pointcloud_topics[i] + frame_name: str = raw_pointcloud_topic.split("/")[ + -2 + ] # `/sensing/lidar/top/pointcloud` -> `top + processed_pointcloud_topic: str = frame_name + "/raw/downsample/pointcloud" + raw_settings = { + "plugin": "pointcloud_preprocessor::PickupBasedVoxelGridDownsampleFilterComponent", + "node_name": "raw_pc_downsample_filter_" + frame_name, + "input_topic": raw_pointcloud_topic, + "output_topic": processed_pointcloud_topic, + "voxel_size": voxel_size, + } + nodes.append(get_downsample_filter_node(raw_settings)) + obstacle_settings = { + "plugin": "pointcloud_preprocessor::PickupBasedVoxelGridDownsampleFilterComponent", + "node_name": "obstacle_pc_downsample_filter", + "input_topic": LaunchConfiguration("input/obstacle_pointcloud"), + "output_topic": "/perception/occupancy_grid_map/obstacle/downsample/pointcloud", + "voxel_size": voxel_size, + } + nodes.append(get_downsample_filter_node(obstacle_settings)) + return nodes + + def launch_setup(context, *args, **kwargs): """Launch fusion based occupancy grid map creation nodes. @@ -118,20 +169,39 @@ def launch_setup(context, *args, **kwargs): LaunchConfiguration("pointcloud_container_name").perform(context), ) + # Down sample settings + downsample_input_pointcloud: bool = total_config["downsample_input_pointcloud"] + downsample_voxel_size: float = total_config["downsample_voxel_size"] + + # get obstacle pointcloud + obstacle_pointcloud_topic: str = ( + "/perception/occupancy_grid_map/obstacle/downsample/pointcloud" + if downsample_input_pointcloud + else LaunchConfiguration("input/obstacle_pointcloud").perform(context) + ) + for i in range(number_of_nodes): # load parameter file ogm_creation_config = get_ogm_creation_config(total_config, i) ogm_creation_config["updater_type"] = LaunchConfiguration("updater_type").perform(context) ogm_creation_config.update(updater_config) + raw_pointcloud_topic: str = fusion_config["raw_pointcloud_topics"][i] + frame_name: str = raw_pointcloud_topic.split("/")[ + -2 + ] # assume `/sensing/lidar/top/pointcloud` -> `top + if downsample_input_pointcloud: + raw_pointcloud_topic = "raw/downsample/pointcloud" + # generate composable node node = ComposableNode( package="probabilistic_occupancy_grid_map", plugin="occupancy_grid_map::PointcloudBasedOccupancyGridMapNode", - name="occupancy_grid_map_node_in_" + str(i), + name="occupancy_grid_map_node", + namespace=frame_name, remappings=[ - ("~/input/obstacle_pointcloud", LaunchConfiguration("input/obstacle_pointcloud")), - ("~/input/raw_pointcloud", fusion_config["raw_pointcloud_topics"][i]), + ("~/input/obstacle_pointcloud", obstacle_pointcloud_topic), + ("~/input/raw_pointcloud", raw_pointcloud_topic), ("~/output/occupancy_grid_map", fusion_config["fusion_input_ogm_topics"][i]), ], parameters=[ogm_creation_config], @@ -139,6 +209,12 @@ def launch_setup(context, *args, **kwargs): ) gridmap_generation_composable_nodes.append(node) + if downsample_input_pointcloud: + downsample_nodes = get_downsample_preprocess_nodes( + downsample_voxel_size, fusion_config["raw_pointcloud_topics"] + ) + gridmap_generation_composable_nodes.extend(downsample_nodes) + # 2. launch occupancy grid map fusion node gridmap_fusion_node = [ ComposableNode( diff --git a/perception/probabilistic_occupancy_grid_map/launch/pointcloud_based_occupancy_grid_map.launch.py b/perception/probabilistic_occupancy_grid_map/launch/pointcloud_based_occupancy_grid_map.launch.py index 29435c4ea8e24..c58e747f84af2 100644 --- a/perception/probabilistic_occupancy_grid_map/launch/pointcloud_based_occupancy_grid_map.launch.py +++ b/perception/probabilistic_occupancy_grid_map/launch/pointcloud_based_occupancy_grid_map.launch.py @@ -26,6 +26,47 @@ import yaml +def get_downsample_filter_node(setting: dict) -> ComposableNode: + plugin_str = setting["plugin"] + voxel_size = setting["voxel_size"] + node_name = setting["node_name"] + return ComposableNode( + package="pointcloud_preprocessor", + plugin=plugin_str, + name=node_name, + remappings=[ + ("input", setting["input_topic"]), + ("output", setting["output_topic"]), + ], + parameters=[ + { + "voxel_size_x": voxel_size, + "voxel_size_y": voxel_size, + "voxel_size_z": voxel_size, + } + ], + extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], + ) + + +def get_downsample_preprocess_nodes(voxel_size: float) -> list: + raw_settings = { + "plugin": "pointcloud_preprocessor::PickupBasedVoxelGridDownsampleFilterComponent", + "node_name": "raw_pc_downsample_filter", + "input_topic": LaunchConfiguration("input/raw_pointcloud"), + "output_topic": "raw/downsample/pointcloud", + "voxel_size": voxel_size, + } + obstacle_settings = { + "plugin": "pointcloud_preprocessor::PickupBasedVoxelGridDownsampleFilterComponent", + "node_name": "obstacle_pc_downsample_filter", + "input_topic": LaunchConfiguration("input/obstacle_pointcloud"), + "output_topic": "obstacle/downsample/pointcloud", + "voxel_size": voxel_size, + } + return [get_downsample_filter_node(raw_settings), get_downsample_filter_node(obstacle_settings)] + + def launch_setup(context, *args, **kwargs): # load parameter files param_file = LaunchConfiguration("param_file").perform(context) @@ -38,7 +79,21 @@ def launch_setup(context, *args, **kwargs): with open(updater_param_file, "r") as f: occupancy_grid_map_updater_params = yaml.safe_load(f)["/**"]["ros__parameters"] - composable_nodes = [ + # composable nodes + composable_nodes = [] + + # add downsample process + downsample_input_pointcloud: bool = pointcloud_based_occupancy_grid_map_node_params[ + "downsample_input_pointcloud" + ] + if downsample_input_pointcloud: + voxel_grid_size: float = pointcloud_based_occupancy_grid_map_node_params[ + "downsample_voxel_size" + ] + downsample_preprocess_nodes = get_downsample_preprocess_nodes(voxel_grid_size) + composable_nodes.extend(downsample_preprocess_nodes) + + composable_nodes.append( ComposableNode( package="probabilistic_occupancy_grid_map", plugin="occupancy_grid_map::PointcloudBasedOccupancyGridMapNode", @@ -46,11 +101,15 @@ def launch_setup(context, *args, **kwargs): remappings=[ ( "~/input/obstacle_pointcloud", - LaunchConfiguration("input/obstacle_pointcloud"), + LaunchConfiguration("input/obstacle_pointcloud") + if not downsample_input_pointcloud + else "obstacle/downsample/pointcloud", ), ( "~/input/raw_pointcloud", - LaunchConfiguration("input/raw_pointcloud"), + LaunchConfiguration("input/raw_pointcloud") + if not downsample_input_pointcloud + else "raw/downsample/pointcloud", ), ("~/output/occupancy_grid_map", LaunchConfiguration("output")), ], @@ -60,8 +119,8 @@ def launch_setup(context, *args, **kwargs): {"updater_type": LaunchConfiguration("updater_type")}, ], extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], - ), - ] + ) + ) occupancy_grid_map_container = ComposableNodeContainer( name=LaunchConfiguration("individual_container_name"), diff --git a/perception/probabilistic_occupancy_grid_map/package.xml b/perception/probabilistic_occupancy_grid_map/package.xml index a90ae78b03597..3efed07535504 100644 --- a/perception/probabilistic_occupancy_grid_map/package.xml +++ b/perception/probabilistic_occupancy_grid_map/package.xml @@ -34,6 +34,7 @@ tier4_autoware_utils visualization_msgs + pointcloud_preprocessor pointcloud_to_laserscan ament_cmake_gtest @@ -44,6 +45,7 @@ launch_testing launch_testing_ament_cmake launch_testing_ros + pointcloud_preprocessor ament_cmake diff --git a/perception/probabilistic_occupancy_grid_map/pointcloud-based-occupancy-grid-map.md b/perception/probabilistic_occupancy_grid_map/pointcloud-based-occupancy-grid-map.md index 7d2efb3468f3a..d8d69ed7866b6 100644 --- a/perception/probabilistic_occupancy_grid_map/pointcloud-based-occupancy-grid-map.md +++ b/perception/probabilistic_occupancy_grid_map/pointcloud-based-occupancy-grid-map.md @@ -77,18 +77,34 @@ $$ | ----------------------------- | ------------------------- | ------------------ | | `~/output/occupancy_grid_map` | `nav_msgs::OccupancyGrid` | occupancy grid map | +### Related topics + +If you set `downsample_input_pointcloud` to `true`, the input pointcloud will be downsampled and following topics are also used. + +- pointcloud_based_occupancy_grid_map method + +```yaml +# downsampled raw and obstacle pointcloud +/perception/occupancy_grid_map/obstacle/downsample/pointcloud +/perception/occupancy_grid_map/raw/downsample/pointcloud +``` + ## Parameters ### Node Parameters -| Name | Type | Description | -| ------------------- | ------ | -------------------------------------------------------------------------------------------------------------------------------- | -| `map_frame` | string | map frame | -| `base_link_frame` | string | base_link frame | -| `use_height_filter` | bool | whether to height filter for `~/input/obstacle_pointcloud` and `~/input/raw_pointcloud`? By default, the height is set to -1~2m. | -| `map_length` | double | The length of the map. -100 if it is 50~50[m] | -| `map_resolution` | double | The map cell resolution [m] | -| `grid_map_type` | string | The type of grid map for estimating `UNKNOWN` region behind obstacle point clouds | +| Name | Type | Description | +| ----------------------------- | ------ | -------------------------------------------------------------------------------------------------------------------------------- | +| `map_frame` | string | map frame | +| `base_link_frame` | string | base_link frame | +| `use_height_filter` | bool | whether to height filter for `~/input/obstacle_pointcloud` and `~/input/raw_pointcloud`? By default, the height is set to -1~2m. | +| `map_length` | double | The length of the map. -100 if it is 50~50[m] | +| `map_resolution` | double | The map cell resolution [m] | +| `grid_map_type` | string | The type of grid map for estimating `UNKNOWN` region behind obstacle point clouds | +| `scan_origin` | string | The origin of the scan. It should be a sensor frame. | +| `pub_debug_grid` | bool | Whether to publish debug grid maps | +| `downsample_input_pointcloud` | bool | Whether to downsample the input pointclouds. The downsampled pointclouds are used for the ray tracing. | +| `downsample_voxel_size` | double | The voxel size for the downsampled pointclouds. | ## Assumptions / Known limits From 76de4ddfb07f0a14bd5b9a90a6c475c7b05b77ad Mon Sep 17 00:00:00 2001 From: Ryuta Kambe Date: Mon, 6 May 2024 21:54:03 +0900 Subject: [PATCH 16/27] fix(behavior_path_planner_common): fix warning of containerOutOfBounds (#6926) Signed-off-by: Ryuta Kambe --- planning/behavior_path_planner_common/src/utils/path_utils.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/planning/behavior_path_planner_common/src/utils/path_utils.cpp b/planning/behavior_path_planner_common/src/utils/path_utils.cpp index 1d51426793de8..b064e0a172824 100644 --- a/planning/behavior_path_planner_common/src/utils/path_utils.cpp +++ b/planning/behavior_path_planner_common/src/utils/path_utils.cpp @@ -447,6 +447,8 @@ std::vector splineTwoPoints( std::vector base_s, std::vector base_x, const double begin_diff, const double end_diff, std::vector new_s) { + assert(base_s.size() == 2 && base_x.size() == 2); + const double h = base_s.at(1) - base_s.at(0); const double c = begin_diff; From ebe360db793194253e4f0805c274f2e17743ebba Mon Sep 17 00:00:00 2001 From: ralwing <58466562+ralwing@users.noreply.github.com> Date: Mon, 6 May 2024 16:51:37 +0200 Subject: [PATCH 17/27] fix: do not use c++20 char8_t keyword (#3629) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit fix: do not use c++20 keyword as a type alias Signed-off-by: Grzegorz GÅ‚owacki --- .../include/autoware_auto_common/common/types.hpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/common/autoware_auto_common/include/autoware_auto_common/common/types.hpp b/common/autoware_auto_common/include/autoware_auto_common/common/types.hpp index 1c7dfe48c7ec8..83b8287ff60d4 100644 --- a/common/autoware_auto_common/include/autoware_auto_common/common/types.hpp +++ b/common/autoware_auto_common/include/autoware_auto_common/common/types.hpp @@ -37,7 +37,9 @@ namespace types // We don't currently require code to comply to MISRA, but we should try to where it is // easily possible. using bool8_t = bool; +#if __cplusplus < 201811L || !__cpp_char8_t using char8_t = char; +#endif using uchar8_t = unsigned char; // If we ever compile on a platform where this is not true, float32_t and float64_t definitions // need to be adjusted. From 28d384ec88142966409d20246ad388f846d2a370 Mon Sep 17 00:00:00 2001 From: Ryuta Kambe Date: Tue, 7 May 2024 08:26:40 +0900 Subject: [PATCH 18/27] fix(control_performance_analysis): fix bug of ignoredReturnValue (#6921) Signed-off-by: Ryuta Kambe --- .../src/control_performance_analysis_core.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/control/control_performance_analysis/src/control_performance_analysis_core.cpp b/control/control_performance_analysis/src/control_performance_analysis_core.cpp index 1ceef81e10c56..f4ed125956bfa 100644 --- a/control/control_performance_analysis/src/control_performance_analysis_core.cpp +++ b/control/control_performance_analysis/src/control_performance_analysis_core.cpp @@ -401,7 +401,7 @@ std::pair ControlPerformanceAnalysisCore::calculateClosestPose() if ( !interpolated_pose_ptr_ || !interpolated_velocity_ptr_ || !interpolated_acceleration_ptr_ || !interpolated_steering_angle_ptr_) { - std::make_pair(false, interp_point.pose); + return std::make_pair(false, interp_point.pose); } return std::make_pair(true, interp_point.pose); From 4200be3a278e174e5067a3425bc7b7e7fa72d48e Mon Sep 17 00:00:00 2001 From: Ryuta Kambe Date: Tue, 7 May 2024 10:21:55 +0900 Subject: [PATCH 19/27] fix(perception_online_evaluator): fix bug of constStatement (#6922) --- .../src/metrics/detection_count.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/evaluator/perception_online_evaluator/src/metrics/detection_count.cpp b/evaluator/perception_online_evaluator/src/metrics/detection_count.cpp index eed3206d48890..047d278334eb1 100644 --- a/evaluator/perception_online_evaluator/src/metrics/detection_count.cpp +++ b/evaluator/perception_online_evaluator/src/metrics/detection_count.cpp @@ -68,7 +68,7 @@ void DetectionCounter::addObjects( } const auto timestamp = objects.header.stamp; - unique_timestamps_.insert(timestamp).second; + unique_timestamps_.insert(timestamp); for (const auto & object : objects.objects) { const auto uuid = toHexString(object.object_id); @@ -119,7 +119,7 @@ void DetectionCounter::updateDetectionMap( const std::string uuid, const std::uint8_t classification, const std::string & range, const rclcpp::Time & timestamp) { - seen_uuids_[classification][range].insert(uuid).second; + seen_uuids_[classification][range].insert(uuid); // Record the detection time for averaging time_series_counts_[classification][range].push_back(timestamp); From ccbe319d575d2eed2ac16bb714d05f193d737925 Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Tue, 7 May 2024 11:20:55 +0900 Subject: [PATCH 20/27] refactor(bpp): path shifter clang tidy and logging level configuration (#6917) Signed-off-by: Muhammad Zulfaqar Azmi --- .../config/logger_config.yaml | 2 + .../utils/path_shifter/path_shifter.hpp | 18 ++++---- .../src/utils/path_shifter/path_shifter.cpp | 45 ++++++++++--------- 3 files changed, 36 insertions(+), 29 deletions(-) diff --git a/common/tier4_logging_level_configure_rviz_plugin/config/logger_config.yaml b/common/tier4_logging_level_configure_rviz_plugin/config/logger_config.yaml index b033711da6dac..6b1214b133af4 100644 --- a/common/tier4_logging_level_configure_rviz_plugin/config/logger_config.yaml +++ b/common/tier4_logging_level_configure_rviz_plugin/config/logger_config.yaml @@ -33,6 +33,8 @@ Planning: logger_name: planning.scenario_planning.lane_driving.behavior_planning.behavior_path_planner - node_name: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner logger_name: tier4_autoware_utils + - node_name: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner + logger_name: behavior_path_planner.path_shifter behavior_path_planner_avoidance: - node_name: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner diff --git a/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/path_shifter/path_shifter.hpp b/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/path_shifter/path_shifter.hpp index 67f581123057e..880e55b64d170 100644 --- a/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/path_shifter/path_shifter.hpp +++ b/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/path_shifter/path_shifter.hpp @@ -94,9 +94,9 @@ class PathShifter void setLongitudinalAcceleration(const double longitudinal_acc); /** - * @brief Add shift point. You don't have to care about the start/end_idx. + * @brief Add shift line. You don't have to care about the start/end_idx. */ - void addShiftLine(const ShiftLine & point); + void addShiftLine(const ShiftLine & line); /** * @brief Set new shift point. You don't have to care about the start/end_idx. @@ -143,7 +143,7 @@ class PathShifter //////////////////////////////////////// static double calcFeasibleVelocityFromJerk( - const double lateral, const double jerk, const double distance); + const double lateral, const double jerk, const double longitudinal_distance); static double calcLateralDistFromJerk( const double longitudinal, const double jerk, const double velocity); @@ -196,12 +196,12 @@ class PathShifter std::pair, std::vector> calcBaseLengths( const double arclength, const double shift_length, const bool offset_back) const; - std::pair, std::vector> getBaseLengthsWithoutAccelLimit( - const double arclength, const double shift_length, const bool offset_back) const; + static std::pair, std::vector> getBaseLengthsWithoutAccelLimit( + const double arclength, const double shift_length, const bool offset_back); - std::pair, std::vector> getBaseLengthsWithoutAccelLimit( + static std::pair, std::vector> getBaseLengthsWithoutAccelLimit( const double arclength, const double shift_length, const double velocity, - const double longitudinal_acc, const double total_time, const bool offset_back) const; + const double longitudinal_acc, const double total_time, const bool offset_back); /** * @brief Calculate path index for shift_lines and set is_index_aligned_ to true. @@ -235,9 +235,9 @@ class PathShifter */ bool checkShiftLinesAlignment(const ShiftLineArray & shift_lines) const; - void addLateralOffsetOnIndexPoint(ShiftedPath * path, double offset, size_t index) const; + static void addLateralOffsetOnIndexPoint(ShiftedPath * path, double offset, size_t index); - void shiftBaseLength(ShiftedPath * path, double offset) const; + static void shiftBaseLength(ShiftedPath * path, double offset); void setBaseOffset(const double val) { diff --git a/planning/behavior_path_planner_common/src/utils/path_shifter/path_shifter.cpp b/planning/behavior_path_planner_common/src/utils/path_shifter/path_shifter.cpp index 7a74ca598de8f..38eafb2f38d7d 100644 --- a/planning/behavior_path_planner_common/src/utils/path_shifter/path_shifter.cpp +++ b/planning/behavior_path_planner_common/src/utils/path_shifter/path_shifter.cpp @@ -116,7 +116,13 @@ bool PathShifter::generate( } for (const auto & shift_line : shift_lines_) { - int idx_gap = shift_line.end_idx - shift_line.start_idx; + if (shift_line.end_idx < shift_line.start_idx) { + RCLCPP_WARN_STREAM_THROTTLE( + logger_, clock_, 3000, "Invalid indices: end_idx is less than start_idx"); + return false; + } + + const auto idx_gap = shift_line.end_idx - shift_line.start_idx; if (idx_gap <= 1) { RCLCPP_WARN_STREAM_THROTTLE( logger_, clock_, 3000, @@ -185,7 +191,7 @@ void PathShifter::applyLinearShifter(ShiftedPath * shifted_path) const // For all path.points, for (size_t i = 0; i < shifted_path->path.points.size(); ++i) { // Set shift length. - double ith_shift_length; + double ith_shift_length = 0.0; if (i < shift_line.start_idx) { ith_shift_length = 0.0; } else if (shift_line.start_idx <= i && i <= shift_line.end_idx) { @@ -235,7 +241,8 @@ void PathShifter::applySplineShifter(ShiftedPath * shifted_path, const bool offs logger_, "base_distance = %s, base_length = %s", toStr(base_distance).c_str(), toStr(base_length).c_str()); - std::vector query_distance, query_length; + std::vector query_distance; + std::vector query_length; // For all path.points, // Note: start_idx is not included since shift = 0, @@ -257,7 +264,7 @@ void PathShifter::applySplineShifter(ShiftedPath * shifted_path, const bool offs } } - if (offset_back == true) { + if (offset_back) { // Apply shifting after shift for (size_t i = shift_line.end_idx; i < shifted_path->path.points.size(); ++i) { addLateralOffsetOnIndexPoint(shifted_path, delta_shift, i); @@ -272,7 +279,7 @@ void PathShifter::applySplineShifter(ShiftedPath * shifted_path, const bool offs } std::pair, std::vector> PathShifter::getBaseLengthsWithoutAccelLimit( - const double arclength, const double shift_length, const bool offset_back) const + const double arclength, const double shift_length, const bool offset_back) { const auto s = arclength; const auto l = shift_length; @@ -286,14 +293,13 @@ std::pair, std::vector> PathShifter::getBaseLengthsW std::pair, std::vector> PathShifter::getBaseLengthsWithoutAccelLimit( const double arclength, const double shift_length, const double velocity, - const double longitudinal_acc, const double total_time, const bool offset_back) const + const double longitudinal_acc, const double total_time, const bool offset_back) { - const auto & s = arclength; - const auto & l = shift_length; - const auto & v0 = velocity; - const auto & a = longitudinal_acc; - const auto & T = total_time; - const double t = T / 4; + const auto s = arclength; + const auto l = shift_length; + const auto v0 = velocity; + const auto a = longitudinal_acc; + const auto t = total_time / 4; const double s1 = std::min(v0 * t + 0.5 * a * t * t, s); const double v1 = v0 + a * t; @@ -322,7 +328,7 @@ std::pair, std::vector> PathShifter::calcBaseLengths return getBaseLengthsWithoutAccelLimit(arclength, shift_length, offset_back); } - const auto & S = arclength; + const auto S = arclength; const auto L = std::abs(shift_length); const auto T = a > acc_threshold ? (-v0 + std::sqrt(v0 * v0 + 2 * a * S)) / a : S / v0; const auto lateral_a_max = 8.0 * L / (T * T); @@ -512,8 +518,7 @@ void PathShifter::removeBehindShiftLineAndSetBaseOffset(const size_t nearest_idx setBaseOffset(new_base_offset); } -void PathShifter::addLateralOffsetOnIndexPoint( - ShiftedPath * path, double offset, size_t index) const +void PathShifter::addLateralOffsetOnIndexPoint(ShiftedPath * path, double offset, size_t index) { if (fabs(offset) < 1.0e-8) { return; @@ -527,10 +532,10 @@ void PathShifter::addLateralOffsetOnIndexPoint( path->shift_length.at(index) += offset; } -void PathShifter::shiftBaseLength(ShiftedPath * path, double offset) const +void PathShifter::shiftBaseLength(ShiftedPath * path, double offset) { - constexpr double BASE_OFFSET_THR = 1.0e-4; - if (std::abs(offset) > BASE_OFFSET_THR) { + constexpr double base_offset_thr = 1.0e-4; + if (std::abs(offset) > base_offset_thr) { for (size_t i = 0; i < path->path.points.size(); ++i) { addLateralOffsetOnIndexPoint(path, offset, i); } @@ -563,11 +568,11 @@ double PathShifter::calcShiftTimeFromJerk(const double lateral, const double jer } double PathShifter::calcFeasibleVelocityFromJerk( - const double lateral, const double jerk, const double longitudinal) + const double lateral, const double jerk, const double longitudinal_distance) { const double j = std::abs(jerk); const double l = std::abs(lateral); - const double d = std::abs(longitudinal); + const double d = std::abs(longitudinal_distance); if (j < 1.0e-8) { return 1.0e10; // TODO(Horibe) maybe invalid arg? } From 1fecd17b3a4ca71634de83de5603c0e2636e646a Mon Sep 17 00:00:00 2001 From: badai nguyen <94814556+badai-nguyen@users.noreply.github.com> Date: Tue, 7 May 2024 11:30:11 +0900 Subject: [PATCH 21/27] fix(occupancy_grid_map_outlier_filter): add intensity field (#6797) * fix(occupancy_grid_map_outlier_filter): add intensity field Signed-off-by: badai-nguyen * fix: add intensity Signed-off-by: badai-nguyen * fix: using empty padding field Signed-off-by: badai-nguyen * refactor Signed-off-by: badai-nguyen * Revert "refactor" This reverts commit d16b3e0721b63f4085de128ed72aa7b8671701b2. * refactor Signed-off-by: badai-nguyen * fix: radius filter Signed-off-by: badai-nguyen * chore: typo Signed-off-by: badai-nguyen * fix: typo Signed-off-by: badai-nguyen --------- Signed-off-by: badai-nguyen --- ...upancy_grid_map_outlier_filter_nodelet.hpp | 21 +- ...upancy_grid_map_outlier_filter_nodelet.cpp | 252 ++++++++++++------ 2 files changed, 175 insertions(+), 98 deletions(-) diff --git a/perception/occupancy_grid_map_outlier_filter/include/occupancy_grid_map_outlier_filter/occupancy_grid_map_outlier_filter_nodelet.hpp b/perception/occupancy_grid_map_outlier_filter/include/occupancy_grid_map_outlier_filter/occupancy_grid_map_outlier_filter_nodelet.hpp index 1d7d01bfbab55..0faa40255a1ca 100644 --- a/perception/occupancy_grid_map_outlier_filter/include/occupancy_grid_map_outlier_filter/occupancy_grid_map_outlier_filter_nodelet.hpp +++ b/perception/occupancy_grid_map_outlier_filter/include/occupancy_grid_map_outlier_filter/occupancy_grid_map_outlier_filter_nodelet.hpp @@ -46,18 +46,16 @@ using geometry_msgs::msg::Pose; using nav_msgs::msg::OccupancyGrid; using sensor_msgs::msg::PointCloud2; using std_msgs::msg::Header; -using PclPointCloud = pcl::PointCloud; class RadiusSearch2dFilter { public: explicit RadiusSearch2dFilter(rclcpp::Node & node); void filter( - const PclPointCloud & input, const Pose & pose, PclPointCloud & output, - PclPointCloud & outlier); + const PointCloud2 & input, const Pose & pose, PointCloud2 & output, PointCloud2 & outlier); void filter( - const PclPointCloud & high_conf_input, const PclPointCloud & low_conf_input, const Pose & pose, - PclPointCloud & output, PclPointCloud & outlier); + const PointCloud2 & high_conf_input, const PointCloud2 & low_conf_input, const Pose & pose, + PointCloud2 & output, PointCloud2 & outlier); private: float search_radius_; @@ -79,22 +77,25 @@ class OccupancyGridMapOutlierFilterComponent : public rclcpp::Node const PointCloud2::ConstSharedPtr & input_pointcloud); void filterByOccupancyGridMap( const OccupancyGrid & occupancy_grid_map, const PointCloud2 & pointcloud, - PclPointCloud & high_confidence, PclPointCloud & low_confidence, PclPointCloud & out_ogm); + PointCloud2 & high_confidence, PointCloud2 & low_confidence, PointCloud2 & out_ogm); void splitPointCloudFrontBack( const PointCloud2::ConstSharedPtr & input_pc, PointCloud2 & front_pc, PointCloud2 & behind_pc); + void initializerPointCloud2(const PointCloud2 & input, PointCloud2 & output); + void finalizePointCloud2(const PointCloud2 & input, PointCloud2 & output); + void concatPointCloud2(PointCloud2 & output, const PointCloud2 & input); private: class Debugger { public: explicit Debugger(OccupancyGridMapOutlierFilterComponent & node); - void publishOutlier(const PclPointCloud & input, const Header & header); - void publishHighConfidence(const PclPointCloud & input, const Header & header); - void publishLowConfidence(const PclPointCloud & input, const Header & header); + void publishOutlier(const PointCloud2 & input, const Header & header); + void publishHighConfidence(const PointCloud2 & input, const Header & header); + void publishLowConfidence(const PointCloud2 & input, const Header & header); private: void transformToBaseLink( - const PclPointCloud & input, const Header & header, PointCloud2 & output); + const PointCloud2 & input, const Header & header, PointCloud2 & output); rclcpp::Publisher::SharedPtr outlier_pointcloud_pub_; rclcpp::Publisher::SharedPtr low_confidence_pointcloud_pub_; rclcpp::Publisher::SharedPtr high_confidence_pointcloud_pub_; diff --git a/perception/occupancy_grid_map_outlier_filter/src/occupancy_grid_map_outlier_filter_nodelet.cpp b/perception/occupancy_grid_map_outlier_filter/src/occupancy_grid_map_outlier_filter_nodelet.cpp index 65eb336269fe4..bbd138030d76f 100644 --- a/perception/occupancy_grid_map_outlier_filter/src/occupancy_grid_map_outlier_filter_nodelet.cpp +++ b/perception/occupancy_grid_map_outlier_filter/src/occupancy_grid_map_outlier_filter_nodelet.cpp @@ -116,19 +116,23 @@ RadiusSearch2dFilter::RadiusSearch2dFilter(rclcpp::Node & node) } void RadiusSearch2dFilter::filter( - const PclPointCloud & input, const Pose & pose, PclPointCloud & output, PclPointCloud & outlier) + const PointCloud2 & input, const Pose & pose, PointCloud2 & output, PointCloud2 & outlier) { - const auto & xyz_cloud = input; pcl::PointCloud::Ptr xy_cloud(new pcl::PointCloud); - xy_cloud->points.resize(xyz_cloud.points.size()); - for (size_t i = 0; i < xyz_cloud.points.size(); ++i) { - xy_cloud->points[i].x = xyz_cloud.points[i].x; - xy_cloud->points[i].y = xyz_cloud.points[i].y; + int point_step = input.point_step; + int x_offset = input.fields[pcl::getFieldIndex(input, "x")].offset; + int y_offset = input.fields[pcl::getFieldIndex(input, "y")].offset; + xy_cloud->points.resize(input.data.size() / point_step); + for (size_t i = 0; i < input.data.size() / point_step; ++i) { + std::memcpy(&xy_cloud->points[i].x, &input.data[i * point_step + x_offset], sizeof(float)); + std::memcpy(&xy_cloud->points[i].y, &input.data[i * point_step + y_offset], sizeof(float)); } std::vector k_indices(xy_cloud->points.size()); std::vector k_distances(xy_cloud->points.size()); kd_tree_->setInputCloud(xy_cloud); + size_t output_size = 0; + size_t outlier_size = 0; for (size_t i = 0; i < xy_cloud->points.size(); ++i) { const float distance = std::hypot(xy_cloud->points[i].x - pose.position.x, xy_cloud->points[i].y - pose.position.y); @@ -139,42 +143,57 @@ void RadiusSearch2dFilter::filter( kd_tree_->radiusSearch(i, search_radius_, k_indices, k_distances, min_points_threshold); if (min_points_threshold <= points_num) { - output.points.push_back(xyz_cloud.points.at(i)); + std::memcpy(&output.data[output_size], &input.data[i * point_step], point_step); + output_size += point_step; } else { - outlier.points.push_back(xyz_cloud.points.at(i)); + std::memcpy(&outlier.data[outlier_size], &input.data[i * point_step], point_step); + outlier_size += point_step; } } + output.data.resize(output_size); + outlier.data.resize(outlier_size); } void RadiusSearch2dFilter::filter( - const PclPointCloud & high_conf_input, const PclPointCloud & low_conf_input, const Pose & pose, - PclPointCloud & output, PclPointCloud & outlier) + const PointCloud2 & high_conf_xyz_cloud, const PointCloud2 & low_conf_xyz_cloud, + const Pose & pose, PointCloud2 & output, PointCloud2 & outlier) { - const auto & high_conf_xyz_cloud = high_conf_input; - const auto & low_conf_xyz_cloud = low_conf_input; // check the limit points number - if (low_conf_xyz_cloud.points.size() > max_filter_points_nb_) { + if (low_conf_xyz_cloud.width > max_filter_points_nb_) { RCLCPP_WARN( rclcpp::get_logger("OccupancyGridMapOutlierFilterComponent"), "Skip outlier filter since too much low_confidence pointcloud!"); return; } - + int x_offset = low_conf_xyz_cloud.fields[pcl::getFieldIndex(low_conf_xyz_cloud, "x")].offset; + int y_offset = low_conf_xyz_cloud.fields[pcl::getFieldIndex(low_conf_xyz_cloud, "y")].offset; + int point_step = low_conf_xyz_cloud.point_step; pcl::PointCloud::Ptr xy_cloud(new pcl::PointCloud); - xy_cloud->points.resize(low_conf_xyz_cloud.points.size() + high_conf_xyz_cloud.points.size()); - for (size_t i = 0; i < low_conf_xyz_cloud.points.size(); ++i) { - xy_cloud->points[i].x = low_conf_xyz_cloud.points[i].x; - xy_cloud->points[i].y = low_conf_xyz_cloud.points[i].y; + xy_cloud->points.resize(low_conf_xyz_cloud.width + high_conf_xyz_cloud.width); + for (size_t i = 0; i < low_conf_xyz_cloud.width; ++i) { + std::memcpy( + &xy_cloud->points[i].x, &low_conf_xyz_cloud.data[i * point_step + x_offset], sizeof(float)); + std::memcpy( + &xy_cloud->points[i].y, &low_conf_xyz_cloud.data[i * point_step + y_offset], sizeof(float)); } - for (size_t i = low_conf_xyz_cloud.points.size(); i < xy_cloud->points.size(); ++i) { - xy_cloud->points[i].x = high_conf_xyz_cloud.points[i - low_conf_xyz_cloud.points.size()].x; - xy_cloud->points[i].y = high_conf_xyz_cloud.points[i - low_conf_xyz_cloud.points.size()].y; + + for (size_t i = low_conf_xyz_cloud.width; i < xy_cloud->points.size(); ++i) { + size_t high_conf_xyz_cloud_index = i - low_conf_xyz_cloud.width; + std::memcpy( + &xy_cloud->points[i].x, + &high_conf_xyz_cloud.data[high_conf_xyz_cloud_index * point_step + x_offset], sizeof(float)); + std::memcpy( + &xy_cloud->points[i].y, + &high_conf_xyz_cloud.data[high_conf_xyz_cloud_index * point_step + y_offset], sizeof(float)); } std::vector k_indices(xy_cloud->points.size()); std::vector k_distances(xy_cloud->points.size()); kd_tree_->setInputCloud(xy_cloud); - for (size_t i = 0; i < low_conf_xyz_cloud.points.size(); ++i) { + + size_t output_size = 0; + size_t outlier_size = 0; + for (size_t i = 0; i < low_conf_xyz_cloud.data.size() / low_conf_xyz_cloud.point_step; ++i) { const float distance = std::hypot(xy_cloud->points[i].x - pose.position.x, xy_cloud->points[i].y - pose.position.y); const int min_points_threshold = std::min( @@ -184,11 +203,20 @@ void RadiusSearch2dFilter::filter( kd_tree_->radiusSearch(i, search_radius_, k_indices, k_distances, min_points_threshold); if (min_points_threshold <= points_num) { - output.points.push_back(low_conf_xyz_cloud.points.at(i)); + std::memcpy( + &output.data[output_size], &low_conf_xyz_cloud.data[i * low_conf_xyz_cloud.point_step], + low_conf_xyz_cloud.point_step); + output_size += low_conf_xyz_cloud.point_step; } else { - outlier.points.push_back(low_conf_xyz_cloud.points.at(i)); + std::memcpy( + &outlier.data[outlier_size], &low_conf_xyz_cloud.data[i * low_conf_xyz_cloud.point_step], + low_conf_xyz_cloud.point_step); + outlier_size += low_conf_xyz_cloud.point_step; } } + + output.data.resize(output_size); + outlier.data.resize(outlier_size); } OccupancyGridMapOutlierFilterComponent::OccupancyGridMapOutlierFilterComponent( @@ -234,61 +262,52 @@ OccupancyGridMapOutlierFilterComponent::OccupancyGridMapOutlierFilterComponent( if (enable_debugger) { debugger_ptr_ = std::make_shared(*this); } - published_time_publisher_ = std::make_unique(this); } void OccupancyGridMapOutlierFilterComponent::splitPointCloudFrontBack( const PointCloud2::ConstSharedPtr & input_pc, PointCloud2 & front_pc, PointCloud2 & behind_pc) { + int x_offset = input_pc->fields[pcl::getFieldIndex(*input_pc, "x")].offset; + int point_step = input_pc->point_step; size_t front_count = 0; size_t behind_count = 0; - for (sensor_msgs::PointCloud2ConstIterator x(*input_pc, "x"); x != x.end(); ++x) { - if (*x < 0.0) { + for (size_t global_offset = 0; global_offset < input_pc->data.size(); + global_offset += point_step) { + float x; + std::memcpy(&x, &input_pc->data[global_offset + x_offset], sizeof(float)); + if (x < 0.0) { + std::memcpy( + &behind_pc.data[behind_count * point_step], &input_pc->data[global_offset], + input_pc->point_step); behind_count++; } else { + std::memcpy( + &front_pc.data[front_count * point_step], &input_pc->data[global_offset], + input_pc->point_step); front_count++; } } - - sensor_msgs::PointCloud2Modifier front_pc_modifier(front_pc); - sensor_msgs::PointCloud2Modifier behind_pc_modifier(behind_pc); - front_pc_modifier.setPointCloud2FieldsByString(1, "xyz"); - behind_pc_modifier.setPointCloud2FieldsByString(1, "xyz"); - front_pc_modifier.resize(front_count); - behind_pc_modifier.resize(behind_count); - - sensor_msgs::PointCloud2Iterator fr_iter(front_pc, "x"); - sensor_msgs::PointCloud2Iterator be_iter(behind_pc, "x"); - - for (sensor_msgs::PointCloud2ConstIterator in_iter(*input_pc, "x"); - in_iter != in_iter.end(); ++in_iter) { - if (*in_iter < 0.0) { - *be_iter = in_iter[0]; - be_iter[1] = in_iter[1]; - be_iter[2] = in_iter[2]; - ++be_iter; - } else { - *fr_iter = in_iter[0]; - fr_iter[1] = in_iter[1]; - fr_iter[2] = in_iter[2]; - ++fr_iter; - } - } - - front_pc.header = input_pc->header; - behind_pc.header = input_pc->header; + front_pc.data.resize(front_count * point_step); + behind_pc.data.resize(behind_count * point_step); } void OccupancyGridMapOutlierFilterComponent::onOccupancyGridMapAndPointCloud2( const OccupancyGrid::ConstSharedPtr & input_ogm, const PointCloud2::ConstSharedPtr & input_pc) { stop_watch_ptr_->toc("processing_time", true); // Transform to occupancy grid map frame - PointCloud2 ogm_frame_pc{}; - PointCloud2 input_front_pc{}; + PointCloud2 input_behind_pc{}; - PointCloud2 ogm_frame_input_behind_pc{}; + PointCloud2 input_front_pc{}; + initializerPointCloud2(*input_pc, input_front_pc); + initializerPointCloud2(*input_pc, input_behind_pc); + // Split pointcloud into front and behind of the vehicle to reduce the calculation cost splitPointCloudFrontBack(input_pc, input_front_pc, input_behind_pc); + finalizePointCloud2(*input_pc, input_front_pc); + finalizePointCloud2(*input_pc, input_behind_pc); + + PointCloud2 ogm_frame_pc{}; + PointCloud2 ogm_frame_input_behind_pc{}; if ( !transformPointcloud(input_front_pc, *tf2_, input_ogm->header.frame_id, ogm_frame_pc) || !transformPointcloud( @@ -296,16 +315,22 @@ void OccupancyGridMapOutlierFilterComponent::onOccupancyGridMapAndPointCloud2( return; } // Occupancy grid map based filter - PclPointCloud high_confidence_pc{}; - PclPointCloud low_confidence_pc{}; - PclPointCloud out_ogm_pc{}; - PclPointCloud ogm_frame_behind_pc; - pcl::fromROSMsg(ogm_frame_input_behind_pc, ogm_frame_behind_pc); + PointCloud2 high_confidence_pc{}; + PointCloud2 low_confidence_pc{}; + PointCloud2 out_ogm_pc{}; + initializerPointCloud2(ogm_frame_pc, high_confidence_pc); + initializerPointCloud2(ogm_frame_pc, low_confidence_pc); + initializerPointCloud2(ogm_frame_pc, out_ogm_pc); + // split front pointcloud into high and low confidence and out of map pointcloud filterByOccupancyGridMap( *input_ogm, ogm_frame_pc, high_confidence_pc, low_confidence_pc, out_ogm_pc); // Apply Radius search 2d filter for low confidence pointcloud - PclPointCloud filtered_low_confidence_pc{}; - PclPointCloud outlier_pc{}; + PointCloud2 filtered_low_confidence_pc{}; + PointCloud2 outlier_pc{}; + initializerPointCloud2(low_confidence_pc, outlier_pc); + initializerPointCloud2(low_confidence_pc, filtered_low_confidence_pc); + initializerPointCloud2(low_confidence_pc, outlier_pc); + if (radius_search_2d_filter_ptr_) { auto pc_frame_pose_stamped = getPoseStamped( *tf2_, input_ogm->header.frame_id, input_pc->header.frame_id, input_ogm->header.stamp); @@ -313,26 +338,29 @@ void OccupancyGridMapOutlierFilterComponent::onOccupancyGridMapAndPointCloud2( high_confidence_pc, low_confidence_pc, pc_frame_pose_stamped.pose, filtered_low_confidence_pc, outlier_pc); } else { - outlier_pc = low_confidence_pc; + std::memcpy(&outlier_pc.data[0], &low_confidence_pc.data[0], low_confidence_pc.data.size()); + outlier_pc.data.resize(low_confidence_pc.data.size()); } // Concatenate high confidence pointcloud from occupancy grid map and non-outlier pointcloud - PclPointCloud concat_pc = - high_confidence_pc + filtered_low_confidence_pc + out_ogm_pc + ogm_frame_behind_pc; - // Convert to ros msg + PointCloud2 ogm_frame_filtered_pc{}; + concatPointCloud2(ogm_frame_filtered_pc, high_confidence_pc); + concatPointCloud2(ogm_frame_filtered_pc, filtered_low_confidence_pc); + concatPointCloud2(ogm_frame_filtered_pc, out_ogm_pc); + concatPointCloud2(ogm_frame_filtered_pc, ogm_frame_input_behind_pc); + finalizePointCloud2(ogm_frame_pc, ogm_frame_filtered_pc); { - PointCloud2 ogm_frame_filtered_pc{}; auto base_link_frame_filtered_pc_ptr = std::make_unique(); - pcl::toROSMsg(concat_pc, ogm_frame_filtered_pc); ogm_frame_filtered_pc.header = ogm_frame_pc.header; if (!transformPointcloud( ogm_frame_filtered_pc, *tf2_, base_link_frame_, *base_link_frame_filtered_pc_ptr)) { return; } pointcloud_pub_->publish(std::move(base_link_frame_filtered_pc_ptr)); - published_time_publisher_->publish_if_subscribed( - pointcloud_pub_, ogm_frame_filtered_pc.header.stamp); } if (debugger_ptr_) { + finalizePointCloud2(ogm_frame_pc, high_confidence_pc); + finalizePointCloud2(ogm_frame_pc, filtered_low_confidence_pc); + finalizePointCloud2(ogm_frame_pc, outlier_pc); debugger_ptr_->publishHighConfidence(high_confidence_pc, ogm_frame_pc.header); debugger_ptr_->publishLowConfidence(filtered_low_confidence_pc, ogm_frame_pc.header); debugger_ptr_->publishOutlier(outlier_pc, ogm_frame_pc.header); @@ -349,24 +377,75 @@ void OccupancyGridMapOutlierFilterComponent::onOccupancyGridMapAndPointCloud2( } } +void OccupancyGridMapOutlierFilterComponent::initializerPointCloud2( + const PointCloud2 & input, PointCloud2 & output) +{ + output.point_step = input.point_step; + output.data.resize(input.data.size()); +} + +void OccupancyGridMapOutlierFilterComponent::finalizePointCloud2( + const PointCloud2 & input, PointCloud2 & output) +{ + output.header = input.header; + output.point_step = input.point_step; + output.fields = input.fields; + output.height = input.height; + output.is_bigendian = input.is_bigendian; + output.is_dense = input.is_dense; + output.width = output.data.size() / output.point_step / output.height; + output.row_step = output.data.size() / output.height; +} + +void OccupancyGridMapOutlierFilterComponent::concatPointCloud2( + PointCloud2 & output, const PointCloud2 & input) +{ + size_t output_size = output.data.size(); + output.data.resize(output.data.size() + input.data.size()); + std::memcpy(&output.data[output_size], &input.data[0], input.data.size()); +} void OccupancyGridMapOutlierFilterComponent::filterByOccupancyGridMap( const OccupancyGrid & occupancy_grid_map, const PointCloud2 & pointcloud, - PclPointCloud & high_confidence, PclPointCloud & low_confidence, PclPointCloud & out_ogm) + PointCloud2 & high_confidence, PointCloud2 & low_confidence, PointCloud2 & out_ogm) { - for (sensor_msgs::PointCloud2ConstIterator x(pointcloud, "x"), y(pointcloud, "y"), - z(pointcloud, "z"); - x != x.end(); ++x, ++y, ++z) { - const auto cost = getCost(occupancy_grid_map, *x, *y); + int x_offset = pointcloud.fields[pcl::getFieldIndex(pointcloud, "x")].offset; + int y_offset = pointcloud.fields[pcl::getFieldIndex(pointcloud, "y")].offset; + size_t high_confidence_size = 0; + size_t low_confidence_size = 0; + size_t out_ogm_size = 0; + + for (size_t global_offset = 0; global_offset < pointcloud.data.size(); + global_offset += pointcloud.point_step) { + float x; + float y; + std::memcpy(&x, &pointcloud.data[global_offset + x_offset], sizeof(float)); + std::memcpy(&y, &pointcloud.data[global_offset + y_offset], sizeof(float)); + + const auto cost = getCost(occupancy_grid_map, x, y); if (cost) { if (cost_threshold_ < *cost) { - high_confidence.push_back(pcl::PointXYZ(*x, *y, *z)); + std::memcpy( + &high_confidence.data[high_confidence_size], &pointcloud.data[global_offset], + pointcloud.point_step); + high_confidence_size += pointcloud.point_step; } else { - low_confidence.push_back(pcl::PointXYZ(*x, *y, *z)); + std::memcpy( + &low_confidence.data[low_confidence_size], &pointcloud.data[global_offset], + pointcloud.point_step); + low_confidence_size += pointcloud.point_step; } } else { - out_ogm.push_back(pcl::PointXYZ(*x, *y, *z)); + std::memcpy( + &out_ogm.data[out_ogm_size], &pointcloud.data[global_offset], pointcloud.point_step); + out_ogm_size += pointcloud.point_step; } } + high_confidence.data.resize(high_confidence_size); + low_confidence.data.resize(low_confidence_size); + out_ogm.data.resize(out_ogm_size); + finalizePointCloud2(pointcloud, high_confidence); + finalizePointCloud2(pointcloud, low_confidence); + finalizePointCloud2(pointcloud, out_ogm); } OccupancyGridMapOutlierFilterComponent::Debugger::Debugger( @@ -382,14 +461,14 @@ OccupancyGridMapOutlierFilterComponent::Debugger::Debugger( } void OccupancyGridMapOutlierFilterComponent::Debugger::publishOutlier( - const PclPointCloud & input, const Header & header) + const PointCloud2 & input, const Header & header) { auto output_ptr = std::make_unique(); transformToBaseLink(input, header, *output_ptr); outlier_pointcloud_pub_->publish(std::move(output_ptr)); } void OccupancyGridMapOutlierFilterComponent::Debugger::publishHighConfidence( - const PclPointCloud & input, const Header & header) + const PointCloud2 & input, const Header & header) { auto output_ptr = std::make_unique(); transformToBaseLink(input, header, *output_ptr); @@ -397,7 +476,7 @@ void OccupancyGridMapOutlierFilterComponent::Debugger::publishHighConfidence( } void OccupancyGridMapOutlierFilterComponent::Debugger::publishLowConfidence( - const PclPointCloud & input, const Header & header) + const PointCloud2 & input, const Header & header) { auto output_ptr = std::make_unique(); transformToBaseLink(input, header, *output_ptr); @@ -405,11 +484,8 @@ void OccupancyGridMapOutlierFilterComponent::Debugger::publishLowConfidence( } void OccupancyGridMapOutlierFilterComponent::Debugger::transformToBaseLink( - const PclPointCloud & pcl_input, const Header & header, PointCloud2 & output) + const PointCloud2 & ros_input, [[maybe_unused]] const Header & header, PointCloud2 & output) { - PointCloud2 ros_input{}; - pcl::toROSMsg(pcl_input, ros_input); - ros_input.header = header; transformPointcloud(ros_input, *(node_.tf2_), node_.base_link_frame_, output); } From dc62238a84e8f87450be8fdee5298a82af7f964b Mon Sep 17 00:00:00 2001 From: Yuki TAKAGI <141538661+yuki-takagi-66@users.noreply.github.com> Date: Tue, 7 May 2024 12:33:27 +0900 Subject: [PATCH 22/27] feat(crosswalk)!: change ego min assumed speed (#6904) Signed-off-by: Yuki Takagi --- .../config/crosswalk.param.yaml | 1 + planning/behavior_velocity_crosswalk_module/src/manager.cpp | 2 ++ .../src/scene_crosswalk.cpp | 4 +--- .../src/scene_crosswalk.hpp | 1 + 4 files changed, 5 insertions(+), 3 deletions(-) diff --git a/planning/behavior_velocity_crosswalk_module/config/crosswalk.param.yaml b/planning/behavior_velocity_crosswalk_module/config/crosswalk.param.yaml index f8b9e5dbf1327..67b923a8d4cd8 100644 --- a/planning/behavior_velocity_crosswalk_module/config/crosswalk.param.yaml +++ b/planning/behavior_velocity_crosswalk_module/config/crosswalk.param.yaml @@ -43,6 +43,7 @@ ego_pass_later_margin_x: [0.0] # [[s]] time to vehicle margin vector for object pass first situation (the module judges that ego don't have to stop at TTV + MARGIN < TTC condition) ego_pass_later_margin_y: [13.0] # [[s]] time to collision margin vector for object pass first situation (the module judges that ego don't have to stop at TTV + MARGIN < TTC condition) ego_pass_later_additional_margin: 0.5 # [s] additional time margin for object pass first situation to suppress chattering + ego_min_assumed_speed: 2.0 # [m/s] assumed speed to calculate the time to collision point no_stop_decision: # parameters to determine if it is safe to attempt stopping before the crosswalk max_offset_to_crosswalk_for_yield: 0.0 # [m] maximum offset from ego's front to crosswalk for yield. Positive value means in front of the crosswalk. diff --git a/planning/behavior_velocity_crosswalk_module/src/manager.cpp b/planning/behavior_velocity_crosswalk_module/src/manager.cpp index aeff5e27cea7b..ad56df5f76944 100644 --- a/planning/behavior_velocity_crosswalk_module/src/manager.cpp +++ b/planning/behavior_velocity_crosswalk_module/src/manager.cpp @@ -90,6 +90,8 @@ CrosswalkModuleManager::CrosswalkModuleManager(rclcpp::Node & node) getOrDeclareParameter>(node, ns + ".pass_judge.ego_pass_later_margin_y"); cp.ego_pass_later_additional_margin = getOrDeclareParameter(node, ns + ".pass_judge.ego_pass_later_additional_margin"); + cp.ego_min_assumed_speed = + getOrDeclareParameter(node, ns + ".pass_judge.ego_min_assumed_speed"); cp.max_offset_to_crosswalk_for_yield = getOrDeclareParameter( node, ns + ".pass_judge.no_stop_decision.max_offset_to_crosswalk_for_yield"); cp.min_acc_for_no_stop_decision = diff --git a/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp b/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp index 86038c721604d..0f9c753523f13 100644 --- a/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp +++ b/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp @@ -810,8 +810,6 @@ CollisionPoint CrosswalkModule::createCollisionPoint( const geometry_msgs::msg::Vector3 & obj_vel, const std::optional object_crosswalk_passage_direction) const { - constexpr double min_ego_velocity = 1.38; // [m/s] - const auto estimated_velocity = std::hypot(obj_vel.x, obj_vel.y); const auto velocity = std::max(planner_param_.min_object_velocity, estimated_velocity); @@ -824,7 +822,7 @@ CollisionPoint CrosswalkModule::createCollisionPoint( // Hence, here, we use the length that would be appropriate for the ego_pass_first judge. collision_point.time_to_collision = std::max(0.0, dist_ego2cp - planner_data_->vehicle_info_.min_longitudinal_offset_m) / - std::max(ego_vel.x, min_ego_velocity); + std::max(ego_vel.x, planner_param_.ego_min_assumed_speed); collision_point.time_to_vehicle = std::max(0.0, dist_obj2cp) / velocity; return collision_point; diff --git a/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp b/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp index bc89936fe883a..e9fdc38304603 100644 --- a/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp +++ b/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp @@ -135,6 +135,7 @@ class CrosswalkModule : public SceneModuleInterface std::vector ego_pass_later_margin_x; std::vector ego_pass_later_margin_y; double ego_pass_later_additional_margin; + double ego_min_assumed_speed; double max_offset_to_crosswalk_for_yield; double min_acc_for_no_stop_decision; double max_jerk_for_no_stop_decision; From 985b7352d8fc5235aceb2ac0818011e3176d863b Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Tue, 7 May 2024 15:15:44 +0900 Subject: [PATCH 23/27] perf(lane_change): rework object filter (#6847) * refactor(lane_change): rework object filter Signed-off-by: Muhammad Zulfaqar Azmi * Use preceeding lanes Signed-off-by: Muhammad Zulfaqar Azmi * style(pre-commit): autofix * fix preceding lanes Signed-off-by: Zulfaqar Azmi * Adds flow chart Signed-off-by: Zulfaqar Azmi * prioritize on coming object check instead Signed-off-by: Muhammad Zulfaqar Azmi * Fix flow chart and rearrange code to early return Signed-off-by: Muhammad Zulfaqar Azmi * Colorize flow chart Signed-off-by: Muhammad Zulfaqar Azmi --------- Signed-off-by: Muhammad Zulfaqar Azmi Signed-off-by: Zulfaqar Azmi Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../src/scene.cpp | 4 +- .../src/util.cpp | 4 +- .../README.md | 165 +++++++ .../scene.hpp | 33 +- .../utils/data_structs.hpp | 16 +- .../utils/debug_structs.hpp | 2 +- .../utils/utils.hpp | 5 + .../src/scene.cpp | 425 ++++++++++-------- .../src/utils/utils.cpp | 22 + .../path_safety_checker/objects_filtering.hpp | 22 + .../path_safety_checker/safety_check.hpp | 3 +- .../utils/utils.hpp | 4 + .../path_safety_checker/objects_filtering.cpp | 15 +- .../path_safety_checker/safety_check.cpp | 5 +- .../src/utils/utils.cpp | 24 +- .../pull_out_planner_base.hpp | 4 +- .../src/start_planner_module.cpp | 4 +- 17 files changed, 524 insertions(+), 233 deletions(-) diff --git a/planning/behavior_path_avoidance_by_lane_change_module/src/scene.cpp b/planning/behavior_path_avoidance_by_lane_change_module/src/scene.cpp index 1ae1685a7e610..d7d7fa8b60513 100644 --- a/planning/behavior_path_avoidance_by_lane_change_module/src/scene.cpp +++ b/planning/behavior_path_avoidance_by_lane_change_module/src/scene.cpp @@ -145,7 +145,9 @@ void AvoidanceByLaneChange::fillAvoidanceTargetObjects( const auto [object_within_target_lane, object_outside_target_lane] = utils::path_safety_checker::separateObjectsByLanelets( *planner_data_->dynamic_object, data.current_lanelets, - utils::path_safety_checker::isPolygonOverlapLanelet); + [](const auto & obj, const auto & lane) { + return utils::path_safety_checker::isPolygonOverlapLanelet(obj, lane); + }); // Assume that the maximum allocation for data.other object is the sum of // objects_within_target_lane and object_outside_target_lane. The maximum allocation for diff --git a/planning/behavior_path_goal_planner_module/src/util.cpp b/planning/behavior_path_goal_planner_module/src/util.cpp index a43592deb3c4e..dab0867a7e29b 100644 --- a/planning/behavior_path_goal_planner_module/src/util.cpp +++ b/planning/behavior_path_goal_planner_module/src/util.cpp @@ -145,7 +145,9 @@ PredictedObjects extractObjectsInExpandedPullOverLanes( route_handler, left_side, backward_distance, forward_distance, bound_offset); const auto [objects_in_lanes, others] = utils::path_safety_checker::separateObjectsByLanelets( - objects, lanes, utils::path_safety_checker::isPolygonOverlapLanelet); + objects, lanes, [](const auto & obj, const auto & lanelet) { + return utils::path_safety_checker::isPolygonOverlapLanelet(obj, lanelet); + }); return objects_in_lanes; } diff --git a/planning/behavior_path_lane_change_module/README.md b/planning/behavior_path_lane_change_module/README.md index 62f35a053958a..9cbd864be9dbb 100644 --- a/planning/behavior_path_lane_change_module/README.md +++ b/planning/behavior_path_lane_change_module/README.md @@ -319,6 +319,171 @@ The detection area for the target lane can be expanded beyond its original bound +##### Object filtering + +```plantuml +@startuml +skinparam defaultTextAlignment center +skinparam backgroundColor #WHITE + +title NormalLaneChange::filterObjects Method Execution Flow + +start + +group "Filter Objects by Class" { +:Iterate through each object in objects list; +while (has not finished iterating through object list) is (TRUE) + if (current object type != param.object_types_to_check?) then (TRUE) + #LightPink:Remove current object; +else (FALSE) + :Keep current object; +endif +end while +end group + +if (object list is empty?) then (TRUE) + :Return empty result; + stop +else (FALSE) +endif + +group "Filter Oncoming Objects" #PowderBlue { +:Iterate through each object in target lane objects list; +while (has not finished iterating through object list?) is (TRUE) +:check object's yaw with reference to ego's yaw.; +if (yaw difference < 90 degree?) then (TRUE) + :Keep current object; +else (FALSE) +if (object is stopping?) then (TRUE) + :Keep current object; +else (FALSE) + #LightPink:Remove current object; +endif +endif +endwhile +end group + +if (object list is empty?) then (TRUE) + :Return empty result; + stop +else (FALSE) +endif + +group "Filter Objects Ahead Terminal" #Beige { +:Calculate lateral distance from ego to current lanes center; + +:Iterate through each object in objects list; +while (has not finished iterating through object list) is (TRUE) + :Get current object's polygon; + :Initialize distance to terminal from object to max; + while (has not finished iterating through object polygon's vertices) is (TRUE) + :Calculate object's lateral distance to end of lane; + :Update minimum distance to terminal from object; + end while + if (Is object's distance to terminal exceeds minimum lane change length?) then (TRUE) + #LightPink:Remove current object; + else (FALSE) + endif +end while +end group + +if (object list is empty?) then (TRUE) + :Return empty result; + stop +else (FALSE) +endif + +group "Filter Objects By Lanelets" #LightGreen { + +:Iterate through each object in objects list; +while (has not finished iterating through object list) is (TRUE) + :lateral distance diff = difference between object's lateral distance and ego's lateral distance to the current lanes' centerline.; + if (Object in target lane polygon, and lateral distance diff is more than half of ego's width?) then (TRUE) + :Add to target_lane_objects; + else (FALSE) + if (Object overlaps with backward target lanes?) then (TRUE) + :Add to target_lane_objects; + else (FALSE) + if (Object in current lane polygon?) then (TRUE) + :Add to current_lane_objects; + else (FALSE) + :Add to other_lane_objects; + endif + endif + endif +end while + +:Return target lanes object, current lanes object and other lanes object; +end group + +:Generate path from current lanes; + +if (path empty?) then (TRUE) + :Return empty result; + stop +else (FALSE) +endif + +group "Filter Target Lanes' objects" #LightCyan { + +:Iterate through each object in target lane objects list; +while (has not finished iterating through object list) is (TRUE) + :check object's velocity; + if(velocity is within threshold?) then (TRUE) + :Keep current object; + else (FALSE) + :check whether object is ahead of ego; + if(object is ahead of ego?) then (TRUE) + :keep current object; + else (FALSE) + #LightPink:remove current object; + endif + endif +endwhile +end group + +group "Filter Current Lanes' objects" #LightYellow { + +:Iterate through each object in current lane objects list; +while (has not finished iterating through object list) is (TRUE) + :check object's velocity; + if(velocity is within threshold?) then (TRUE) + :check whether object is ahead of ego; + if(object is ahead of ego?) then (TRUE) + :keep current object; + else (FALSE) + #LightPink:remove current object; + endif + else (FALSE) + #LightPink:remove current object; + endif +endwhile +end group + +group "Filter Other Lanes' objects" #Lavender { + +:Iterate through each object in other lane objects list; +while (has not finished iterating through object list) is (TRUE) + :check object's velocity; + if(velocity is within threshold?) then (TRUE) + :check whether object is ahead of ego; + if(object is ahead of ego?) then (TRUE) + :keep current object; + else (FALSE) + #LightPink:remove current object; + endif + else (FALSE) + #LightPink:remove current object; + endif +endwhile +end group + +:Trasform the objects into extended predicted object and return them as lane_change_target_objects; +stop + +@enduml +``` + ##### Collision check in prepare phase The ego vehicle may need to secure ample inter-vehicle distance ahead of the target vehicle before attempting a lane change. The flag `enable_collision_check_at_prepare_phase` can be enabled to gain this behavior. The following image illustrates the differences between the `false` and `true` cases. diff --git a/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/scene.hpp b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/scene.hpp index 7a76daff4bc55..1df5a7567b198 100644 --- a/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/scene.hpp +++ b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/scene.hpp @@ -30,10 +30,12 @@ using behavior_path_planner::utils::path_safety_checker::ExtendedPredictedObject using behavior_path_planner::utils::path_safety_checker::PoseWithVelocityAndPolygonStamped; using behavior_path_planner::utils::path_safety_checker::PoseWithVelocityStamped; using behavior_path_planner::utils::path_safety_checker::PredictedPathWithPolygon; +using data::lane_change::LanesPolygon; using geometry_msgs::msg::Point; using geometry_msgs::msg::Pose; using geometry_msgs::msg::Twist; using route_handler::Direction; +using utils::path_safety_checker::ExtendedPredictedObjects; class NormalLaneChange : public LaneChangeBase { @@ -115,10 +117,26 @@ class NormalLaneChange : public LaneChangeBase const lanelet::ConstLanelets & current_lanes, const lanelet::ConstLanelets & target_lanes) const; - LaneChangeTargetObjects getTargetObjects( + ExtendedPredictedObjects getTargetObjects( + const LaneChangeLanesFilteredObjects & predicted_objects, + const lanelet::ConstLanelets & current_lanes) const; + + LaneChangeLanesFilteredObjects filterObjects( const lanelet::ConstLanelets & current_lanes, const lanelet::ConstLanelets & target_lanes) const; + void filterOncomingObjects(PredictedObjects & objects) const; + + void filterAheadTerminalObjects( + PredictedObjects & objects, const lanelet::ConstLanelets & current_lanes) const; + + void filterObjectsByLanelets( + const PredictedObjects & objects, const lanelet::ConstLanelets & current_lanes, + const lanelet::ConstLanelets & target_lanes, + std::vector & current_lane_objects, + std::vector & target_lane_objects, + std::vector & other_lane_objects) const; + PathWithLaneId getPrepareSegment( const lanelet::ConstLanelets & current_lanes, const double backward_path_length, const double prepare_length) const override; @@ -154,18 +172,11 @@ class NormalLaneChange : public LaneChangeBase bool isValidPath(const PathWithLaneId & path) const override; PathSafetyStatus isLaneChangePathSafe( - const LaneChangePath & lane_change_path, const LaneChangeTargetObjects & target_objects, - const utils::path_safety_checker::RSSparams & rss_params, const bool is_stuck, + const LaneChangePath & lane_change_path, + const ExtendedPredictedObjects & collision_check_objects, + const utils::path_safety_checker::RSSparams & rss_params, CollisionCheckDebugMap & debug_data) const; - LaneChangeTargetObjectIndices filterObject( - const PredictedObjects & objects, const lanelet::ConstLanelets & current_lanes, - const lanelet::ConstLanelets & target_lanes, - const lanelet::ConstLanelets & target_backward_lanes) const; - - std::vector filterObjectsInTargetLane( - const LaneChangeTargetObjects & objects, const lanelet::ConstLanelets & target_lanes) const; - //! @brief Check if the ego vehicle is in stuck by a stationary obstacle. //! @param obstacle_check_distance Distance to check ahead for any objects that might be //! obstructing ego path. It makes sense to use values like the maximum lane change distance. diff --git a/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/data_structs.hpp b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/data_structs.hpp index fdaa15ff9bef9..0947f0e5aff94 100644 --- a/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/data_structs.hpp +++ b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/data_structs.hpp @@ -20,6 +20,7 @@ #include #include +#include #include #include @@ -195,11 +196,11 @@ struct LaneChangeTargetObjectIndices std::vector other_lane{}; }; -struct LaneChangeTargetObjects +struct LaneChangeLanesFilteredObjects { - std::vector current_lane{}; - std::vector target_lane{}; - std::vector other_lane{}; + utils::path_safety_checker::ExtendedPredictedObjects current_lane{}; + utils::path_safety_checker::ExtendedPredictedObjects target_lane{}; + utils::path_safety_checker::ExtendedPredictedObjects other_lane{}; }; enum class LaneChangeModuleType { @@ -216,6 +217,13 @@ struct PathSafetyStatus bool is_safe{true}; bool is_object_coming_from_rear{false}; }; + +struct LanesPolygon +{ + std::optional current; + std::optional target; + std::vector target_backward; +}; } // namespace behavior_path_planner::data::lane_change #endif // BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__DATA_STRUCTS_HPP_ diff --git a/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/debug_structs.hpp b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/debug_structs.hpp index 37d436f9949a2..fbdd742a8457b 100644 --- a/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/debug_structs.hpp +++ b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/debug_structs.hpp @@ -35,7 +35,7 @@ struct Debug LaneChangePaths valid_paths; CollisionCheckDebugMap collision_check_objects; CollisionCheckDebugMap collision_check_objects_after_approval; - LaneChangeTargetObjects filtered_objects; + LaneChangeLanesFilteredObjects filtered_objects; geometry_msgs::msg::Polygon execution_area; geometry_msgs::msg::Pose ego_pose; lanelet::ConstLanelets current_lanes; diff --git a/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/utils.hpp b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/utils.hpp index cd4f55599d964..2d427213141b4 100644 --- a/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/utils.hpp +++ b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/utils.hpp @@ -46,6 +46,7 @@ using behavior_path_planner::utils::path_safety_checker::ExtendedPredictedObject using behavior_path_planner::utils::path_safety_checker::PoseWithVelocityAndPolygonStamped; using behavior_path_planner::utils::path_safety_checker::PoseWithVelocityStamped; using behavior_path_planner::utils::path_safety_checker::PredictedPathWithPolygon; +using data::lane_change::LanesPolygon; using data::lane_change::PathSafetyStatus; using geometry_msgs::msg::Point; using geometry_msgs::msg::Pose; @@ -292,6 +293,10 @@ bool isWithinTurnDirectionLanes(const lanelet::ConstLanelet & lanelet, const Pol double calcPhaseLength( const double velocity, const double maximum_velocity, const double acceleration, const double time); + +LanesPolygon createLanesPolygon( + const lanelet::ConstLanelets & current_lanes, const lanelet::ConstLanelets & target_lanes, + const std::vector & target_backward_lanes); } // namespace behavior_path_planner::utils::lane_change namespace behavior_path_planner::utils::lane_change::debug diff --git a/planning/behavior_path_lane_change_module/src/scene.cpp b/planning/behavior_path_lane_change_module/src/scene.cpp index 1e84fd41b3215..5a2ba24475eb0 100644 --- a/planning/behavior_path_lane_change_module/src/scene.cpp +++ b/planning/behavior_path_lane_change_module/src/scene.cpp @@ -39,6 +39,8 @@ namespace behavior_path_planner { using motion_utils::calcSignedArcLength; using utils::lane_change::calcMinimumLaneChangeLength; +using utils::lane_change::createLanesPolygon; +using utils::path_safety_checker::isPolygonOverlapLanelet; using utils::traffic_light::getDistanceToNextTrafficLight; NormalLaneChange::NormalLaneChange( @@ -276,7 +278,7 @@ void NormalLaneChange::insertStopPoint( } const double stop_point_buffer = lane_change_parameters_->backward_length_buffer_for_end_of_lane; - const auto target_objects = getTargetObjects(status_.current_lanes, status_.target_lanes); + const auto target_objects = filterObjects(status_.current_lanes, status_.target_lanes); double stopping_distance = distance_to_terminal - lane_change_buffer - stop_point_buffer; const auto is_valid_start_point = std::invoke([&]() -> bool { @@ -842,226 +844,270 @@ PathWithLaneId NormalLaneChange::getPrepareSegment( return prepare_segment; } -LaneChangeTargetObjects NormalLaneChange::getTargetObjects( +ExtendedPredictedObjects NormalLaneChange::getTargetObjects( + const LaneChangeLanesFilteredObjects & filtered_objects, + const lanelet::ConstLanelets & current_lanes) const +{ + ExtendedPredictedObjects target_objects = filtered_objects.target_lane; + const auto is_stuck = isVehicleStuck(current_lanes); + const auto chk_obj_in_curr_lanes = lane_change_parameters_->check_objects_on_current_lanes; + if (chk_obj_in_curr_lanes || is_stuck) { + target_objects.insert( + target_objects.end(), filtered_objects.current_lane.begin(), + filtered_objects.current_lane.end()); + } + + const auto chk_obj_in_other_lanes = lane_change_parameters_->check_objects_on_other_lanes; + if (chk_obj_in_other_lanes) { + target_objects.insert( + target_objects.end(), filtered_objects.other_lane.begin(), filtered_objects.other_lane.end()); + } + + return target_objects; +} + +LaneChangeLanesFilteredObjects NormalLaneChange::filterObjects( const lanelet::ConstLanelets & current_lanes, const lanelet::ConstLanelets & target_lanes) const { - const auto current_pose = getEgoPose(); - const auto & route_handler = *getRouteHandler(); + const auto & current_pose = getEgoPose(); + const auto & route_handler = getRouteHandler(); const auto & common_parameters = planner_data_->parameters; auto objects = *planner_data_->dynamic_object; utils::path_safety_checker::filterObjectsByClass( objects, lane_change_parameters_->object_types_to_check); - // get backward lanes - const auto backward_length = lane_change_parameters_->backward_lane_length; - const auto target_backward_lanes = behavior_path_planner::utils::getBackwardLanelets( - route_handler, target_lanes, current_pose, backward_length); + if (objects.objects.empty()) { + return {}; + } - lane_change_debug_.current_lanes = current_lanes; - lane_change_debug_.target_lanes = target_lanes; - lane_change_debug_.target_backward_lanes = target_backward_lanes; + filterOncomingObjects(objects); - // filter objects to get target object index - const auto target_obj_index = - filterObject(objects, current_lanes, target_lanes, target_backward_lanes); + if (objects.objects.empty()) { + return {}; + } - LaneChangeTargetObjects target_objects; - target_objects.current_lane.reserve(target_obj_index.current_lane.size()); - target_objects.target_lane.reserve(target_obj_index.target_lane.size()); - target_objects.other_lane.reserve(target_obj_index.other_lane.size()); + filterAheadTerminalObjects(objects, current_lanes); - // objects in current lane - const auto is_check_prepare_phase = check_prepare_phase(); - for (const auto & obj_idx : target_obj_index.current_lane) { - const auto extended_object = utils::lane_change::transform( - objects.objects.at(obj_idx), common_parameters, *lane_change_parameters_, - is_check_prepare_phase); - target_objects.current_lane.push_back(extended_object); + if (objects.objects.empty()) { + return {}; } - // objects in target lane - for (const auto & obj_idx : target_obj_index.target_lane) { - const auto extended_object = utils::lane_change::transform( - objects.objects.at(obj_idx), common_parameters, *lane_change_parameters_, - is_check_prepare_phase); - target_objects.target_lane.push_back(extended_object); - } + std::vector target_lane_objects; + std::vector current_lane_objects; + std::vector other_lane_objects; + + filterObjectsByLanelets( + objects, current_lanes, target_lanes, current_lane_objects, target_lane_objects, + other_lane_objects); + + const auto is_within_vel_th = [](const auto & object) -> bool { + constexpr double min_vel_th = 1.0; + constexpr double max_vel_th = std::numeric_limits::max(); + return utils::path_safety_checker::filter::velocity_filter(object, min_vel_th, max_vel_th); + }; - // objects in other lane - for (const auto & obj_idx : target_obj_index.other_lane) { - const auto extended_object = utils::lane_change::transform( - objects.objects.at(obj_idx), common_parameters, *lane_change_parameters_, - is_check_prepare_phase); - target_objects.other_lane.push_back(extended_object); + const auto path = + route_handler->getCenterLinePath(current_lanes, 0.0, std::numeric_limits::max()); + + if (path.points.empty()) { + return {}; } - return target_objects; + const auto is_ahead_of_ego = [&path, ¤t_pose](const auto & object) { + const auto obj_polygon = tier4_autoware_utils::toPolygon2d(object).outer(); + + double max_dist_ego_to_obj = std::numeric_limits::lowest(); + for (const auto & polygon_p : obj_polygon) { + const auto obj_p = tier4_autoware_utils::createPoint(polygon_p.x(), polygon_p.y(), 0.0); + const auto dist_ego_to_obj = calcSignedArcLength(path.points, current_pose.position, obj_p); + max_dist_ego_to_obj = std::max(dist_ego_to_obj, max_dist_ego_to_obj); + } + return max_dist_ego_to_obj >= 0.0; + }; + + utils::path_safety_checker::filterObjects( + target_lane_objects, [&](const PredictedObject & object) { + return (is_within_vel_th(object) || is_ahead_of_ego(object)); + }); + + utils::path_safety_checker::filterObjects( + other_lane_objects, [&](const PredictedObject & object) { + return is_within_vel_th(object) && is_ahead_of_ego(object); + }); + + utils::path_safety_checker::filterObjects( + current_lane_objects, [&](const PredictedObject & object) { + return is_within_vel_th(object) && is_ahead_of_ego(object); + }); + + LaneChangeLanesFilteredObjects lane_change_target_objects; + + const auto is_check_prepare_phase = check_prepare_phase(); + std::for_each(target_lane_objects.begin(), target_lane_objects.end(), [&](const auto & object) { + auto extended_predicted_object = utils::lane_change::transform( + object, common_parameters, *lane_change_parameters_, is_check_prepare_phase); + lane_change_target_objects.target_lane.push_back(extended_predicted_object); + }); + + std::for_each(current_lane_objects.begin(), current_lane_objects.end(), [&](const auto & object) { + auto extended_predicted_object = utils::lane_change::transform( + object, common_parameters, *lane_change_parameters_, is_check_prepare_phase); + lane_change_target_objects.current_lane.push_back(extended_predicted_object); + }); + + std::for_each(other_lane_objects.begin(), other_lane_objects.end(), [&](const auto & object) { + auto extended_predicted_object = utils::lane_change::transform( + object, common_parameters, *lane_change_parameters_, is_check_prepare_phase); + lane_change_target_objects.other_lane.push_back(extended_predicted_object); + }); + + lane_change_debug_.filtered_objects = lane_change_target_objects; + + return lane_change_target_objects; } -LaneChangeTargetObjectIndices NormalLaneChange::filterObject( +void NormalLaneChange::filterOncomingObjects(PredictedObjects & objects) const +{ + const auto & current_pose = getEgoPose(); + + const auto is_same_direction = [&](const PredictedObject & object) { + const auto & object_pose = object.kinematics.initial_pose_with_covariance.pose; + return !utils::path_safety_checker::isTargetObjectOncoming(current_pose, object_pose); + }; + + // Perception noise could make stationary objects seem opposite the ego vehicle; check the + // velocity to prevent this. + const auto is_stopped_object = [](const auto & object) -> bool { + constexpr double min_vel_th = -0.5; + constexpr double max_vel_th = 0.5; + return utils::path_safety_checker::filter::velocity_filter(object, min_vel_th, max_vel_th); + }; + + utils::path_safety_checker::filterObjects(objects, [&](const PredictedObject & object) { + const auto same_direction = is_same_direction(object); + if (same_direction) { + return true; + } + + return is_stopped_object(object); + }); +} + +void NormalLaneChange::filterAheadTerminalObjects( + PredictedObjects & objects, const lanelet::ConstLanelets & current_lanes) const +{ + const auto & current_pose = getEgoPose(); + const auto & route_handler = getRouteHandler(); + const auto minimum_lane_change_length = utils::lane_change::calcMinimumLaneChangeLength( + route_handler, current_lanes.back(), *lane_change_parameters_, direction_); + + const auto dist_ego_to_current_lanes_center = + lanelet::utils::getLateralDistanceToClosestLanelet(current_lanes, current_pose); + + // ignore object that are ahead of terminal lane change start + utils::path_safety_checker::filterObjects(objects, [&](const PredictedObject & object) { + const auto obj_polygon = tier4_autoware_utils::toPolygon2d(object).outer(); + // ignore object that are ahead of terminal lane change start + auto distance_to_terminal_from_object = std::numeric_limits::max(); + for (const auto & polygon_p : obj_polygon) { + const auto obj_p = tier4_autoware_utils::createPoint(polygon_p.x(), polygon_p.y(), 0.0); + Pose polygon_pose; + polygon_pose.position = obj_p; + polygon_pose.orientation = object.kinematics.initial_pose_with_covariance.pose.orientation; + const auto dist = utils::getDistanceToEndOfLane(polygon_pose, current_lanes); + distance_to_terminal_from_object = std::min(dist_ego_to_current_lanes_center, dist); + } + + return (minimum_lane_change_length > distance_to_terminal_from_object); + }); +} + +void NormalLaneChange::filterObjectsByLanelets( const PredictedObjects & objects, const lanelet::ConstLanelets & current_lanes, - const lanelet::ConstLanelets & target_lanes, - const lanelet::ConstLanelets & target_backward_lanes) const + const lanelet::ConstLanelets & target_lanes, std::vector & current_lane_objects, + std::vector & target_lane_objects, + std::vector & other_lane_objects) const { - const auto current_pose = getEgoPose(); + const auto & current_pose = getEgoPose(); const auto & route_handler = getRouteHandler(); const auto & common_parameters = planner_data_->parameters; - const auto minimum_lane_change_length = calcMinimumLaneChangeLength( - route_handler, current_lanes.back(), *lane_change_parameters_, direction_); + const auto check_optional_polygon = [](const auto & object, const auto & polygon) { + return polygon && isPolygonOverlapLanelet(object, *polygon); + }; - // Guard - if (objects.objects.empty()) { - return {}; - } + // get backward lanes + const auto backward_length = lane_change_parameters_->backward_lane_length; + const auto target_backward_lanes = + utils::getPrecedingLanelets(*route_handler, target_lanes, current_pose, backward_length); - // Get path - const auto path = - route_handler->getCenterLinePath(current_lanes, 0.0, std::numeric_limits::max()); - const auto target_path = - route_handler->getCenterLinePath(target_lanes, 0.0, std::numeric_limits::max()); + { + lane_change_debug_.current_lanes = current_lanes; + lane_change_debug_.target_lanes = target_lanes; + + // TODO(Azu) change the type to std::vector + lane_change_debug_.target_backward_lanes.clear(); + std::for_each( + target_backward_lanes.begin(), target_backward_lanes.end(), + [&](const lanelet::ConstLanelets & target_backward_lane) { + lane_change_debug_.target_backward_lanes.insert( + lane_change_debug_.target_backward_lanes.end(), target_backward_lane.begin(), + target_backward_lane.end()); + }); + } - const auto current_polygon = - utils::lane_change::createPolygon(current_lanes, 0.0, std::numeric_limits::max()); const auto expanded_target_lanes = utils::lane_change::generateExpandedLanelets( target_lanes, direction_, lane_change_parameters_->lane_expansion_left_offset, lane_change_parameters_->lane_expansion_right_offset); - const auto target_polygon = utils::lane_change::createPolygon( - expanded_target_lanes, 0.0, std::numeric_limits::max()); + + const auto lanes_polygon = + createLanesPolygon(current_lanes, expanded_target_lanes, target_backward_lanes); const auto dist_ego_to_current_lanes_center = lanelet::utils::getLateralDistanceToClosestLanelet(current_lanes, current_pose); - std::vector> target_backward_polygons; - for (const auto & target_backward_lane : target_backward_lanes) { - // Check to see is target_backward_lane is in current_lanes - // Without this check, current lane object might be treated as target lane object - const auto is_current_lane = [&](const lanelet::ConstLanelet & current_lane) { - return current_lane.id() == target_backward_lane.id(); - }; - - if (std::any_of(current_lanes.begin(), current_lanes.end(), is_current_lane)) { - continue; - } - lanelet::ConstLanelets lanelet{target_backward_lane}; - auto lane_polygon = - utils::lane_change::createPolygon(lanelet, 0.0, std::numeric_limits::max()); - target_backward_polygons.push_back(lane_polygon); + { + const auto reserve_size = objects.objects.size(); + current_lane_objects.reserve(reserve_size); + target_lane_objects.reserve(reserve_size); + other_lane_objects.reserve(reserve_size); } - LaneChangeTargetObjectIndices filtered_obj_indices; - for (size_t i = 0; i < objects.objects.size(); ++i) { - const auto & object = objects.objects.at(i); - const auto obj_velocity_norm = std::hypot( - object.kinematics.initial_twist_with_covariance.twist.linear.x, - object.kinematics.initial_twist_with_covariance.twist.linear.y); - const auto extended_object = utils::lane_change::transform( - object, common_parameters, *lane_change_parameters_, check_prepare_phase()); - - const auto obj_polygon = tier4_autoware_utils::toPolygon2d(object); - - // calc distance from the current ego position - double max_dist_ego_to_obj = std::numeric_limits::lowest(); - double min_dist_ego_to_obj = std::numeric_limits::max(); - const auto obj_polygon_outer = obj_polygon.outer(); - for (const auto & polygon_p : obj_polygon_outer) { - const auto obj_p = tier4_autoware_utils::createPoint(polygon_p.x(), polygon_p.y(), 0.0); - const double dist_ego_to_obj = calcSignedArcLength(path.points, current_pose.position, obj_p); - max_dist_ego_to_obj = std::max(dist_ego_to_obj, max_dist_ego_to_obj); - min_dist_ego_to_obj = std::min(dist_ego_to_obj, min_dist_ego_to_obj); - } - - const auto is_lateral_far = [&]() { + for (const auto & object : objects.objects) { + const auto is_lateral_far = std::invoke([&]() -> bool { const auto dist_object_to_current_lanes_center = lanelet::utils::getLateralDistanceToClosestLanelet( current_lanes, object.kinematics.initial_pose_with_covariance.pose); const auto lateral = dist_object_to_current_lanes_center - dist_ego_to_current_lanes_center; return std::abs(lateral) > (common_parameters.vehicle_width / 2); - }; - - // ignore object that are ahead of terminal lane change start - { - double distance_to_terminal_from_object = std::numeric_limits::max(); - for (const auto & polygon_p : obj_polygon_outer) { - const auto obj_p = tier4_autoware_utils::createPoint(polygon_p.x(), polygon_p.y(), 0.0); - Pose polygon_pose; - polygon_pose.position = obj_p; - polygon_pose.orientation = object.kinematics.initial_pose_with_covariance.pose.orientation; - const double dist = utils::getDistanceToEndOfLane(polygon_pose, current_lanes); - if (dist < distance_to_terminal_from_object) { - distance_to_terminal_from_object = dist; - } - } - if (minimum_lane_change_length > distance_to_terminal_from_object) { - continue; - } - } + }); - // ignore static object that are behind the ego vehicle - if (obj_velocity_norm < 1.0 && max_dist_ego_to_obj < 0.0) { + if (check_optional_polygon(object, lanes_polygon.target) && is_lateral_far) { + target_lane_objects.push_back(object); continue; } - // check if the object intersects with target lanes - if (target_polygon && boost::geometry::intersects(target_polygon.value(), obj_polygon)) { - // TODO(watanabe): ignore static parked object that are in front of the ego vehicle in target - // lanes - - if (max_dist_ego_to_obj >= 0 || is_lateral_far()) { - filtered_obj_indices.target_lane.push_back(i); - continue; - } - } - - const auto check_backward_polygon = [&obj_polygon](const auto & target_backward_polygon) { - return target_backward_polygon && - boost::geometry::intersects(target_backward_polygon.value(), obj_polygon); - }; + const auto is_overlap_target_backward = std::invoke([&]() -> bool { + const auto check_backward_polygon = [&object](const auto & target_backward_polygon) { + return isPolygonOverlapLanelet(object, target_backward_polygon); + }; + return std::any_of( + lanes_polygon.target_backward.begin(), lanes_polygon.target_backward.end(), + check_backward_polygon); + }); // check if the object intersects with target backward lanes - if ( - !target_backward_polygons.empty() && - std::any_of( - target_backward_polygons.begin(), target_backward_polygons.end(), check_backward_polygon)) { - filtered_obj_indices.target_lane.push_back(i); + if (is_overlap_target_backward) { + target_lane_objects.push_back(object); continue; } - // check if the object intersects with current lanes - if ( - current_polygon && boost::geometry::intersects(current_polygon.value(), obj_polygon) && - max_dist_ego_to_obj >= 0.0) { + if (check_optional_polygon(object, lanes_polygon.current)) { // check only the objects that are in front of the ego vehicle - filtered_obj_indices.current_lane.push_back(i); + current_lane_objects.push_back(object); continue; } - // ignore all objects that are behind the ego vehicle and not on the current and target - // lanes - if (max_dist_ego_to_obj < 0.0) { - continue; - } - - filtered_obj_indices.other_lane.push_back(i); + other_lane_objects.push_back(object); } - - return filtered_obj_indices; -} - -std::vector NormalLaneChange::filterObjectsInTargetLane( - const LaneChangeTargetObjects & objects, const lanelet::ConstLanelets & target_lanes) const -{ - const auto target_polygon = - utils::lane_change::createPolygon(target_lanes, 0.0, std::numeric_limits::max()); - std::vector filtered_objects{}; - if (target_polygon) { - for (auto & obj : objects.target_lane) { - const auto obj_polygon = tier4_autoware_utils::toPolygon2d(obj.initial_pose.pose, obj.shape); - if (boost::geometry::intersects(target_polygon.value(), obj_polygon)) { - filtered_objects.push_back(obj); - } - } - } - - return filtered_objects; } PathWithLaneId NormalLaneChange::getTargetSegment( @@ -1241,8 +1287,8 @@ bool NormalLaneChange::getLaneChangePaths( return false; } - const auto target_objects = getTargetObjects(current_lanes, target_lanes); - lane_change_debug_.filtered_objects = target_objects; + const auto filtered_objects = filterObjects(current_lanes, target_lanes); + const auto target_objects = getTargetObjects(filtered_objects, current_lanes); const auto prepare_durations = calcPrepareDuration(current_lanes, target_lanes); @@ -1466,13 +1512,11 @@ bool NormalLaneChange::getLaneChangePaths( } candidate_paths->push_back(*candidate_path); - std::vector filtered_objects = - filterObjectsInTargetLane(target_objects, target_lanes); if ( - !is_stuck && - utils::lane_change::passParkedObject( - route_handler, *candidate_path, filtered_objects, lane_change_buffer, is_goal_in_route, - *lane_change_parameters_, lane_change_debug_.collision_check_objects)) { + !is_stuck && utils::lane_change::passParkedObject( + route_handler, *candidate_path, filtered_objects.target_lane, + lane_change_buffer, is_goal_in_route, *lane_change_parameters_, + lane_change_debug_.collision_check_objects)) { debug_print( "Reject: parking vehicle exists in the target lane, and the ego is not in stuck. Skip " "lane change."); @@ -1485,8 +1529,7 @@ bool NormalLaneChange::getLaneChangePaths( } const auto [is_safe, is_object_coming_from_rear] = isLaneChangePathSafe( - *candidate_path, target_objects, rss_params, is_stuck, - lane_change_debug_.collision_check_objects); + *candidate_path, target_objects, rss_params, lane_change_debug_.collision_check_objects); if (is_safe) { debug_print("ACCEPT!!!: it is valid and safe!"); @@ -1653,13 +1696,12 @@ PathSafetyStatus NormalLaneChange::isApprovedPathSafe() const const auto & current_lanes = status_.current_lanes; const auto & target_lanes = status_.target_lanes; - const auto target_objects = getTargetObjects(current_lanes, target_lanes); - lane_change_debug_.filtered_objects = target_objects; + const auto filtered_objects = filterObjects(current_lanes, target_lanes); + const auto target_objects = getTargetObjects(filtered_objects, current_lanes); CollisionCheckDebugMap debug_data; - const bool is_stuck = isVehicleStuck(current_lanes); const auto safety_status = isLaneChangePathSafe( - path, target_objects, lane_change_parameters_->rss_params_for_abort, is_stuck, debug_data); + path, target_objects, lane_change_parameters_->rss_params_for_abort, debug_data); { // only for debug purpose lane_change_debug_.collision_check_objects.clear(); @@ -1891,8 +1933,8 @@ bool NormalLaneChange::calcAbortPath() } PathSafetyStatus NormalLaneChange::isLaneChangePathSafe( - const LaneChangePath & lane_change_path, const LaneChangeTargetObjects & target_objects, - const utils::path_safety_checker::RSSparams & rss_params, const bool is_stuck, + const LaneChangePath & lane_change_path, const ExtendedPredictedObjects & collision_check_objects, + const utils::path_safety_checker::RSSparams & rss_params, CollisionCheckDebugMap & debug_data) const { PathSafetyStatus path_safety_status; @@ -1915,21 +1957,8 @@ PathSafetyStatus NormalLaneChange::isLaneChangePathSafe( const auto debug_predicted_path = utils::path_safety_checker::convertToPredictedPath(ego_predicted_path, time_resolution); - auto collision_check_objects = target_objects.target_lane; const auto current_lanes = getCurrentLanes(); - if (lane_change_parameters_->check_objects_on_current_lanes || is_stuck) { - collision_check_objects.insert( - collision_check_objects.end(), target_objects.current_lane.begin(), - target_objects.current_lane.end()); - } - - if (lane_change_parameters_->check_objects_on_other_lanes) { - collision_check_objects.insert( - collision_check_objects.end(), target_objects.other_lane.begin(), - target_objects.other_lane.end()); - } - const auto expanded_target_lanes = utils::lane_change::generateExpandedLanelets( lane_change_path.info.target_lanes, direction_, lane_change_parameters_->lane_expansion_left_offset, diff --git a/planning/behavior_path_lane_change_module/src/utils/utils.cpp b/planning/behavior_path_lane_change_module/src/utils/utils.cpp index bf08d97dcfe5a..ab9a0b7176fdb 100644 --- a/planning/behavior_path_lane_change_module/src/utils/utils.cpp +++ b/planning/behavior_path_lane_change_module/src/utils/utils.cpp @@ -1198,6 +1198,28 @@ double calcPhaseLength( const auto length_with_max_velocity = maximum_velocity * duration; return std::min(length_with_acceleration, length_with_max_velocity); } + +LanesPolygon createLanesPolygon( + const lanelet::ConstLanelets & current_lanes, const lanelet::ConstLanelets & target_lanes, + const std::vector & target_backward_lanes) +{ + LanesPolygon lanes_polygon; + + lanes_polygon.current = + utils::lane_change::createPolygon(current_lanes, 0.0, std::numeric_limits::max()); + lanes_polygon.target = + utils::lane_change::createPolygon(target_lanes, 0.0, std::numeric_limits::max()); + + for (const auto & target_backward_lane : target_backward_lanes) { + auto lane_polygon = utils::lane_change::createPolygon( + target_backward_lane, 0.0, std::numeric_limits::max()); + + if (lane_polygon) { + lanes_polygon.target_backward.push_back(*lane_polygon); + } + } + return lanes_polygon; +} } // namespace behavior_path_planner::utils::lane_change namespace behavior_path_planner::utils::lane_change::debug diff --git a/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/path_safety_checker/objects_filtering.hpp b/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/path_safety_checker/objects_filtering.hpp index e33c2596ab04d..a0b2d0afa0fa8 100644 --- a/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/path_safety_checker/objects_filtering.hpp +++ b/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/path_safety_checker/objects_filtering.hpp @@ -69,6 +69,12 @@ bool isCentroidWithinLanelet(const PredictedObject & object, const lanelet::Cons */ bool isPolygonOverlapLanelet(const PredictedObject & object, const lanelet::ConstLanelet & lanelet); +bool isPolygonOverlapLanelet( + const PredictedObject & object, const tier4_autoware_utils::Polygon2d & lanelet_polygon); + +bool isPolygonOverlapLanelet( + const PredictedObject & object, const lanelet::BasicPolygon2d & lanelet_polygon); + /** * @brief Filters objects based on various criteria. * @@ -279,6 +285,15 @@ void filterObjects(PredictedObjects & selected, PredictedObjects & removed, Func selected.objects.erase(partitioned, selected.objects.end()); } +template +void filterObjects( + std::vector & selected, std::vector & removed, Func filter) +{ + auto partitioned = std::partition(selected.begin(), selected.end(), filter); + removed.insert(removed.end(), partitioned, selected.end()); + selected.erase(partitioned, selected.end()); +} + /** * @brief Filters objects in the 'objects' container based on the provided filter function. * @@ -296,6 +311,13 @@ void filterObjects(PredictedObjects & objects, Func filter) [[maybe_unused]] PredictedObjects removed_objects{}; filterObjects(objects, removed_objects, filter); } + +template +void filterObjects(std::vector & objects, Func filter) +{ + [[maybe_unused]] std::vector removed_objects{}; + filterObjects(objects, removed_objects, filter); +} } // namespace behavior_path_planner::utils::path_safety_checker #endif // BEHAVIOR_PATH_PLANNER_COMMON__UTILS__PATH_SAFETY_CHECKER__OBJECTS_FILTERING_HPP_ diff --git a/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/path_safety_checker/safety_check.hpp b/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/path_safety_checker/safety_check.hpp index f28685b2d914e..c4cfed01450b7 100644 --- a/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/path_safety_checker/safety_check.hpp +++ b/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/path_safety_checker/safety_check.hpp @@ -43,7 +43,8 @@ using tier4_autoware_utils::Polygon2d; using vehicle_info_util::VehicleInfo; bool isTargetObjectOncoming( - const geometry_msgs::msg::Pose & vehicle_pose, const geometry_msgs::msg::Pose & object_pose); + const geometry_msgs::msg::Pose & vehicle_pose, const geometry_msgs::msg::Pose & object_pose, + const double angle_threshold = M_PI_2); bool isTargetObjectFront( const geometry_msgs::msg::Pose & ego_pose, const Polygon2d & obj_polygon, diff --git a/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/utils.hpp b/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/utils.hpp index b25238a49333c..b61ef0579cab0 100644 --- a/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/utils.hpp +++ b/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/utils.hpp @@ -299,6 +299,10 @@ lanelet::ConstLanelets extendPrevLane( lanelet::ConstLanelets extendLanes( const std::shared_ptr route_handler, const lanelet::ConstLanelets & lanes); +std::vector getPrecedingLanelets( + const RouteHandler & route_handler, const lanelet::ConstLanelets & target_lanes, + const Pose & current_pose, const double backward_length); + lanelet::ConstLanelets getBackwardLanelets( const RouteHandler & route_handler, const lanelet::ConstLanelets & target_lanes, const Pose & current_pose, const double backward_length); diff --git a/planning/behavior_path_planner_common/src/utils/path_safety_checker/objects_filtering.cpp b/planning/behavior_path_planner_common/src/utils/path_safety_checker/objects_filtering.cpp index b8014deee9500..83b1affa763a4 100644 --- a/planning/behavior_path_planner_common/src/utils/path_safety_checker/objects_filtering.cpp +++ b/planning/behavior_path_planner_common/src/utils/path_safety_checker/objects_filtering.cpp @@ -66,8 +66,21 @@ bool isCentroidWithinLanelet(const PredictedObject & object, const lanelet::Cons bool isPolygonOverlapLanelet(const PredictedObject & object, const lanelet::ConstLanelet & lanelet) { - const auto object_polygon = tier4_autoware_utils::toPolygon2d(object); const auto lanelet_polygon = utils::toPolygon2d(lanelet); + return isPolygonOverlapLanelet(object, lanelet_polygon); +} + +bool isPolygonOverlapLanelet( + const PredictedObject & object, const tier4_autoware_utils::Polygon2d & lanelet_polygon) +{ + const auto object_polygon = tier4_autoware_utils::toPolygon2d(object); + return !boost::geometry::disjoint(lanelet_polygon, object_polygon); +} + +bool isPolygonOverlapLanelet( + const PredictedObject & object, const lanelet::BasicPolygon2d & lanelet_polygon) +{ + const auto object_polygon = tier4_autoware_utils::toPolygon2d(object); return !boost::geometry::disjoint(lanelet_polygon, object_polygon); } diff --git a/planning/behavior_path_planner_common/src/utils/path_safety_checker/safety_check.cpp b/planning/behavior_path_planner_common/src/utils/path_safety_checker/safety_check.cpp index ceedb202209f3..e1884e57f7221 100644 --- a/planning/behavior_path_planner_common/src/utils/path_safety_checker/safety_check.cpp +++ b/planning/behavior_path_planner_common/src/utils/path_safety_checker/safety_check.cpp @@ -43,9 +43,10 @@ void appendPointToPolygon(Polygon2d & polygon, const geometry_msgs::msg::Point & } bool isTargetObjectOncoming( - const geometry_msgs::msg::Pose & vehicle_pose, const geometry_msgs::msg::Pose & object_pose) + const geometry_msgs::msg::Pose & vehicle_pose, const geometry_msgs::msg::Pose & object_pose, + const double angle_threshold) { - return std::abs(calcYawDeviation(vehicle_pose, object_pose)) > M_PI_2; + return std::abs(calcYawDeviation(vehicle_pose, object_pose)) > angle_threshold; } bool isTargetObjectFront( diff --git a/planning/behavior_path_planner_common/src/utils/utils.cpp b/planning/behavior_path_planner_common/src/utils/utils.cpp index e2a0db1c3f75f..5282509b973db 100644 --- a/planning/behavior_path_planner_common/src/utils/utils.cpp +++ b/planning/behavior_path_planner_common/src/utils/utils.cpp @@ -1513,8 +1513,7 @@ lanelet::ConstLanelets getExtendedCurrentLanesFromPath( return lanes; } -// TODO(Azu): In the future, get back lanelet within `to_back_dist` [m] from queried lane -lanelet::ConstLanelets getBackwardLanelets( +std::vector getPrecedingLanelets( const RouteHandler & route_handler, const lanelet::ConstLanelets & target_lanes, const Pose & current_pose, const double backward_length) { @@ -1529,18 +1528,21 @@ lanelet::ConstLanelets getBackwardLanelets( } const auto & front_lane = target_lanes.front(); - const auto preceding_lanes = route_handler.getPrecedingLaneletSequence( + return route_handler.getPrecedingLaneletSequence( front_lane, std::abs(backward_length - arc_length.length), {front_lane}); +} - lanelet::ConstLanelets backward_lanes{}; - const auto num_of_lanes = std::invoke([&preceding_lanes]() { - size_t sum{0}; - for (const auto & lanes : preceding_lanes) { - sum += lanes.size(); - } - return sum; - }); +lanelet::ConstLanelets getBackwardLanelets( + const RouteHandler & route_handler, const lanelet::ConstLanelets & target_lanes, + const Pose & current_pose, const double backward_length) +{ + const auto preceding_lanes = + getPrecedingLanelets(route_handler, target_lanes, current_pose, backward_length); + const auto calc_sum = [](size_t sum, const auto & lanes) { return sum + lanes.size(); }; + const auto num_of_lanes = + std::accumulate(preceding_lanes.begin(), preceding_lanes.end(), 0u, calc_sum); + lanelet::ConstLanelets backward_lanes{}; backward_lanes.reserve(num_of_lanes); for (const auto & lanes : preceding_lanes) { diff --git a/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/pull_out_planner_base.hpp b/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/pull_out_planner_base.hpp index 3089134a16500..9a2749759d03e 100644 --- a/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/pull_out_planner_base.hpp +++ b/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/pull_out_planner_base.hpp @@ -79,7 +79,9 @@ class PullOutPlannerBase *dynamic_objects, parameters_.th_moving_object_velocity); auto [pull_out_lane_stop_objects, others] = utils::path_safety_checker::separateObjectsByLanelets( - stop_objects, pull_out_lanes, utils::path_safety_checker::isPolygonOverlapLanelet); + stop_objects, pull_out_lanes, [](const auto & obj, const auto & lane) { + return utils::path_safety_checker::isPolygonOverlapLanelet(obj, lane); + }); utils::path_safety_checker::filterObjectsByClass( pull_out_lane_stop_objects, parameters_.object_types_to_check_for_path_generation); diff --git a/planning/behavior_path_start_planner_module/src/start_planner_module.cpp b/planning/behavior_path_start_planner_module/src/start_planner_module.cpp index be6b6acef64bd..e9105f1fbd25f 100644 --- a/planning/behavior_path_start_planner_module/src/start_planner_module.cpp +++ b/planning/behavior_path_start_planner_module/src/start_planner_module.cpp @@ -1135,7 +1135,9 @@ PredictedObjects StartPlannerModule::filterStopObjectsInPullOutLanes( // filter for objects located in pull out lanes and moving at a speed below the threshold auto [stop_objects_in_pull_out_lanes, others] = utils::path_safety_checker::separateObjectsByLanelets( - stop_objects, pull_out_lanes, utils::path_safety_checker::isPolygonOverlapLanelet); + stop_objects, pull_out_lanes, [](const auto & obj, const auto & lane) { + return utils::path_safety_checker::isPolygonOverlapLanelet(obj, lane); + }); const auto path = planner_data_->route_handler->getCenterLinePath( pull_out_lanes, object_check_backward_distance, object_check_forward_distance); From 32359daa181384f6094ab10ab72e228a1a83e925 Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Tue, 7 May 2024 17:54:33 +0900 Subject: [PATCH 24/27] fix(lane_change): return safe is object list is empty (#6931) Signed-off-by: Muhammad Zulfaqar Azmi --- planning/behavior_path_lane_change_module/src/scene.cpp | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/planning/behavior_path_lane_change_module/src/scene.cpp b/planning/behavior_path_lane_change_module/src/scene.cpp index 5a2ba24475eb0..901b795cbe80a 100644 --- a/planning/behavior_path_lane_change_module/src/scene.cpp +++ b/planning/behavior_path_lane_change_module/src/scene.cpp @@ -1939,6 +1939,11 @@ PathSafetyStatus NormalLaneChange::isLaneChangePathSafe( { PathSafetyStatus path_safety_status; + if (collision_check_objects.empty()) { + RCLCPP_DEBUG(logger_, "There is nothing to check."); + return path_safety_status; + } + const auto & path = lane_change_path.path; const auto & common_parameters = planner_data_->parameters; const auto current_pose = getEgoPose(); From a06d4afc16731a80bde7beae051837ed013a0ec9 Mon Sep 17 00:00:00 2001 From: "Takagi, Isamu" <43976882+isamu-takagi@users.noreply.github.com> Date: Tue, 7 May 2024 19:35:53 +0900 Subject: [PATCH 25/27] fix(diagnostic_graph_aggregator): fix a bug where unit links were incorrectly updated (#6932) fix(diagnostic_graph_aggregator): fix unit link filter Signed-off-by: Takagi, Isamu --- system/diagnostic_graph_aggregator/src/common/graph/config.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/system/diagnostic_graph_aggregator/src/common/graph/config.cpp b/system/diagnostic_graph_aggregator/src/common/graph/config.cpp index 9005084f84503..c9d281a5c886e 100644 --- a/system/diagnostic_graph_aggregator/src/common/graph/config.cpp +++ b/system/diagnostic_graph_aggregator/src/common/graph/config.cpp @@ -232,8 +232,8 @@ void apply_edits(FileConfig & config) if (remove_links.count(link) == 0) { filtered_list.push_back(link); } - unit->list = filtered_list; } + unit->list = filtered_list; } // Remove units and links. From fbbb2f315e5b17edd8c72f9a7a60f33de32c12b2 Mon Sep 17 00:00:00 2001 From: danielsanchezaran Date: Tue, 7 May 2024 19:47:43 +0900 Subject: [PATCH 26/27] feat(autonomous_emergency_braking): add obstacle velocity estimation for AEB (#6912) * enable aeb, fix topic problem Signed-off-by: Daniel Sanchez * add clustering method to eliminate small objects/noise Signed-off-by: Daniel Sanchez * remove comments Signed-off-by: Daniel Sanchez * Crop points outside of EGO predicted path Signed-off-by: Daniel Sanchez * remove offset Signed-off-by: Daniel Sanchez * Update library use Signed-off-by: Daniel Sanchez * add check for empty cloud Signed-off-by: Daniel Sanchez * add extra width for pointcloud cropping Signed-off-by: Daniel Sanchez * Use single PC ptr Signed-off-by: Daniel Sanchez * Revert "Use single PC ptr" This reverts commit b5091fc6c284cd3ee76b322db6f96b77efa0e37e. Signed-off-by: Daniel Sanchez * Add back timestamp Signed-off-by: Daniel Sanchez * USe object hull to detect collisions Signed-off-by: Daniel Sanchez * remove unused functions Signed-off-by: Daniel Sanchez * remove debug timer out of code Signed-off-by: Daniel Sanchez * eliminate member var in favor of local pointcloud ptr Signed-off-by: Daniel Sanchez * remove unused chrono dependency Signed-off-by: Daniel Sanchez * Add object history to etimate object speed with pointcloud Signed-off-by: Daniel Sanchez * Add median velocity calc Signed-off-by: Daniel Sanchez * add velocity thresholds Signed-off-by: Daniel Sanchez * refactoring Signed-off-by: Daniel Sanchez * cleaning Signed-off-by: Daniel Sanchez * refactor Signed-off-by: Daniel Sanchez * change voxwl Signed-off-by: Daniel Sanchez * readme Signed-off-by: Daniel Sanchez * remove mutex since they are not necessary Signed-off-by: Daniel Sanchez * add markers for closest object velocity Signed-off-by: Daniel Sanchez * added units to marker Signed-off-by: Daniel Sanchez * delete duplicated param Signed-off-by: Daniel Sanchez * delete duplicated param Signed-off-by: Daniel Sanchez --------- Signed-off-by: Daniel Sanchez --- .../autonomous_emergency_braking/README.md | 27 +++ .../autonomous_emergency_braking.param.yaml | 36 ++-- .../autonomous_emergency_braking/node.hpp | 158 ++++++++++++++++-- .../autonomous_emergency_braking/src/node.cpp | 133 +++++++++------ 4 files changed, 277 insertions(+), 77 deletions(-) diff --git a/control/autonomous_emergency_braking/README.md b/control/autonomous_emergency_braking/README.md index a4e737ca545be..7a7bf212320e0 100644 --- a/control/autonomous_emergency_braking/README.md +++ b/control/autonomous_emergency_braking/README.md @@ -108,6 +108,33 @@ After Noise filtering, it performs a geometric collision check to determine whet Finally, the vertex that is closest to the ego vehicle is chosen as the candidate for collision checking: Since rss distance is used to judge if a collision will happen or not, if the closest vertex to the ego is deemed to be safe, the rest of the vertices (and the points in the clusters) will also be safe. +#### Obstacle velocity estimation + +Once the position of the closest obstacle/point is determined, the AEB modules uses the history of previously detected objects to estimate the closest object speed using the following equations: + +$$ +d_{t} = o_{time stamp} - prev_{time stamp} +$$ + +$$ +d_{pos} = norm(o_{pos} - prev_{pos}) +$$ + +$$ +v_{norm} = d_{pos} / d_{t} +$$ + +Where $o_{time stamp}$ and $prev_{time stamp}$ are the timestamps of the point clouds used to detect the current closest object and the closest object of the previous point cloud frame, and $o_{pos}$ and $prev_{pos}$ are the positions of those objects, respectively. + +Finally, the velocity vector is compared against the ego's predicted path to get the longitudinal velocity $v_{obj}$: + +$$ +v_{obj} = v_{norm} * Cos(yaw_{diff}) + v_{ego} +$$ + +where $yaw_{diff}$ is the difference in yaw between the ego path and the displacement vector $$v_{pos} = o_{pos} - prev_{pos} $$ and $v_{ego}$ is the ego's speed, which accounts for the movement of points caused by the ego moving and not the object. +All these equations are performed disregarding the z axis (in 2D). + ### 4. Collision check with target obstacles In the fourth step, it checks the collision with filtered obstacles using RSS distance. RSS is formulated as: diff --git a/control/autonomous_emergency_braking/config/autonomous_emergency_braking.param.yaml b/control/autonomous_emergency_braking/config/autonomous_emergency_braking.param.yaml index bb429662dabfb..68a42383feb1f 100644 --- a/control/autonomous_emergency_braking/config/autonomous_emergency_braking.param.yaml +++ b/control/autonomous_emergency_braking/config/autonomous_emergency_braking.param.yaml @@ -1,26 +1,38 @@ /**: ros__parameters: - publish_debug_pointcloud: false + # Ego path calculation use_predicted_trajectory: true - use_imu_path: true - path_footprint_extra_margin: 1.0 + use_imu_path: false + min_generated_path_length: 0.5 + imu_prediction_time_horizon: 1.5 + imu_prediction_time_interval: 0.1 + mpc_prediction_time_horizon: 1.5 + mpc_prediction_time_interval: 0.1 + + # Debug + publish_debug_pointcloud: false + + # Point cloud partitioning detection_range_min_height: 0.0 detection_range_max_height_margin: 0.0 voxel_grid_x: 0.05 voxel_grid_y: 0.05 voxel_grid_z: 100000.0 - min_generated_path_length: 0.5 + + # Point cloud cropping expand_width: 0.1 + path_footprint_extra_margin: 4.0 + + # Point cloud clustering + cluster_tolerance: 0.1 #[m] + minimum_cluster_size: 10 + maximum_cluster_size: 10000 + + # RSS distance collision check longitudinal_offset: 2.0 t_response: 1.0 a_ego_min: -3.0 a_obj_min: -1.0 - cluster_tolerance: 0.1 #[m] - minimum_cluster_size: 10 - maximum_cluster_size: 10000 - imu_prediction_time_horizon: 1.5 - imu_prediction_time_interval: 0.1 - mpc_prediction_time_horizon: 1.5 - mpc_prediction_time_interval: 0.1 - collision_keeping_sec: 0.0 + collision_keeping_sec: 2.0 + previous_obstacle_keep_time: 1.0 aeb_hz: 10.0 diff --git a/control/autonomous_emergency_braking/include/autonomous_emergency_braking/node.hpp b/control/autonomous_emergency_braking/include/autonomous_emergency_braking/node.hpp index a30720e16a25e..e2e2d0ae6745a 100644 --- a/control/autonomous_emergency_braking/include/autonomous_emergency_braking/node.hpp +++ b/control/autonomous_emergency_braking/include/autonomous_emergency_braking/node.hpp @@ -16,6 +16,7 @@ #define AUTONOMOUS_EMERGENCY_BRAKING__NODE_HPP_ #include +#include #include #include #include @@ -40,12 +41,13 @@ #include #include +#include +#include #include -#include #include #include +#include #include - namespace autoware::motion::control::autonomous_emergency_braking { @@ -79,30 +81,142 @@ class CollisionDataKeeper public: explicit CollisionDataKeeper(rclcpp::Clock::SharedPtr clock) { clock_ = clock; } - void setTimeout(const double timeout_sec) { timeout_sec_ = timeout_sec; } + void setTimeout(const double collision_keep_time, const double previous_obstacle_keep_time) + { + collision_keep_time_ = collision_keep_time; + previous_obstacle_keep_time_ = previous_obstacle_keep_time; + } - bool checkExpired() + bool checkObjectDataExpired(std::optional & data, const double timeout) { - if (data_ && (clock_->now() - data_->stamp).seconds() > timeout_sec_) { - data_.reset(); + if (!data.has_value()) return true; + const auto now = clock_->now(); + const auto & prev_obj = data.value(); + const auto & data_time_stamp = prev_obj.stamp; + if ((now - data_time_stamp).nanoseconds() * 1e-9 > timeout) { + data = std::nullopt; + return true; } - return (data_ == nullptr); + return false; + } + + bool checkCollisionExpired() + { + return this->checkObjectDataExpired(closest_object_, collision_keep_time_); } - void update(const ObjectData & data) { data_.reset(new ObjectData(data)); } + bool checkPreviousObjectDataExpired() + { + return this->checkObjectDataExpired(prev_closest_object_, previous_obstacle_keep_time_); + } - ObjectData get() + ObjectData get() const { - if (data_) { - return *data_; - } else { - return ObjectData(); + return (closest_object_.has_value()) ? closest_object_.value() : ObjectData(); + } + + ObjectData getPreviousObjectData() const + { + return (prev_closest_object_.has_value()) ? prev_closest_object_.value() : ObjectData(); + } + + void setCollisionData(const ObjectData & data) + { + closest_object_ = std::make_optional(data); + } + + void setPreviousObjectData(const ObjectData & data) + { + prev_closest_object_ = std::make_optional(data); + } + + void resetVelocityHistory() { obstacle_velocity_history_.clear(); } + + void updateVelocityHistory( + const double current_object_velocity, const rclcpp::Time & current_object_velocity_time_stamp) + { + // remove old msg from deque + const auto now = clock_->now(); + std::remove_if( + obstacle_velocity_history_.begin(), obstacle_velocity_history_.end(), + [&](const auto & velocity_time_pair) { + const auto & vel_time = velocity_time_pair.second; + return ((now - vel_time).nanoseconds() * 1e-9 > previous_obstacle_keep_time_); + }); + + obstacle_velocity_history_.emplace_back( + std::make_pair(current_object_velocity, current_object_velocity_time_stamp)); + } + + std::optional getMedianObstacleVelocity() const + { + if (obstacle_velocity_history_.empty()) return std::nullopt; + std::vector raw_velocities; + for (const auto & vel_time_pair : obstacle_velocity_history_) { + raw_velocities.emplace_back(vel_time_pair.first); + } + + const size_t med1 = (raw_velocities.size() % 2 == 0) ? (raw_velocities.size()) / 2 - 1 + : (raw_velocities.size()) / 2.0; + const size_t med2 = (raw_velocities.size()) / 2.0; + std::nth_element(raw_velocities.begin(), raw_velocities.begin() + med1, raw_velocities.end()); + const double vel1 = raw_velocities.at(med1); + std::nth_element(raw_velocities.begin(), raw_velocities.begin() + med2, raw_velocities.end()); + const double vel2 = raw_velocities.at(med2); + return (vel1 + vel2) / 2.0; + } + + std::optional calcObjectSpeedFromHistory( + const ObjectData & closest_object, const Path & path, const double current_ego_speed) + { + if (this->checkPreviousObjectDataExpired()) { + this->setPreviousObjectData(closest_object); + this->resetVelocityHistory(); + return std::nullopt; + } + + const auto estimated_velocity_opt = std::invoke([&]() -> std::optional { + const auto & prev_object = this->getPreviousObjectData(); + const double p_dt = + (closest_object.stamp.nanoseconds() - prev_object.stamp.nanoseconds()) * 1e-9; + if (p_dt < std::numeric_limits::epsilon()) return std::nullopt; + const auto & nearest_collision_point = closest_object.position; + const auto & prev_collision_point = prev_object.position; + + const double p_dx = nearest_collision_point.x - prev_collision_point.x; + const double p_dy = nearest_collision_point.y - prev_collision_point.y; + const double p_dist = std::hypot(p_dx, p_dy); + const double p_yaw = std::atan2(p_dy, p_dx); + const double p_vel = p_dist / p_dt; + + const auto nearest_idx = motion_utils::findNearestIndex(path, nearest_collision_point); + const auto & nearest_path_pose = path.at(nearest_idx); + const auto & traj_yaw = tf2::getYaw(nearest_path_pose.orientation); + const auto estimated_velocity = p_vel * std::cos(p_yaw - traj_yaw) + current_ego_speed; + + // Current RSS distance calculation does not account for negative velocities + return (estimated_velocity > 0.0) ? estimated_velocity : 0.0; + }); + + if (!estimated_velocity_opt.has_value()) { + this->setPreviousObjectData(closest_object); + this->resetVelocityHistory(); + return std::nullopt; } + + const auto & estimated_velocity = estimated_velocity_opt.value(); + this->setPreviousObjectData(closest_object); + this->updateVelocityHistory(estimated_velocity, closest_object.stamp); + return this->getMedianObstacleVelocity(); } private: - std::unique_ptr data_; - double timeout_sec_{0.0}; + std::optional prev_closest_object_{std::nullopt}; + std::optional closest_object_{std::nullopt}; + double collision_keep_time_{0.0}; + double previous_obstacle_keep_time_{0.0}; + + std::deque> obstacle_velocity_history_; rclcpp::Clock::SharedPtr clock_; }; @@ -152,14 +266,22 @@ class AEB : public rclcpp::Node void cropPointCloudWithEgoFootprintPath( const std::vector & ego_polys, pcl::PointCloud::Ptr filtered_objects); + void createObjectDataUsingPointCloudClusters( + const Path & ego_path, const std::vector & ego_polys, const rclcpp::Time & stamp, + std::vector & objects); + void cropPointCloudWithEgoFootprintPath(const std::vector & ego_polys); + void addMarker( const rclcpp::Time & current_time, const Path & path, const std::vector & polygons, - const std::vector & objects, const double color_r, const double color_g, - const double color_b, const double color_a, const std::string & ns, - MarkerArray & debug_markers); + const std::vector & objects, const std::optional & closest_object, + const double color_r, const double color_g, const double color_b, const double color_a, + const std::string & ns, MarkerArray & debug_markers); void addCollisionMarker(const ObjectData & data, MarkerArray & debug_markers); + std::optional calcObjectSpeedFromHistory( + const ObjectData & closest_object, const Path & path, const double current_ego_speed); + PointCloud2::SharedPtr obstacle_ros_pointcloud_ptr_{nullptr}; VelocityReport::ConstSharedPtr current_velocity_ptr_{nullptr}; Vector3::SharedPtr angular_velocity_ptr_{nullptr}; diff --git a/control/autonomous_emergency_braking/src/node.cpp b/control/autonomous_emergency_braking/src/node.cpp index 87a1ffa19bc1d..9847d7aae63b5 100644 --- a/control/autonomous_emergency_braking/src/node.cpp +++ b/control/autonomous_emergency_braking/src/node.cpp @@ -14,7 +14,6 @@ #include "autonomous_emergency_braking/node.hpp" -#include #include #include #include @@ -107,33 +106,37 @@ AEB::AEB(const rclcpp::NodeOptions & node_options) collision_data_keeper_(this->get_clock()) { // Subscribers - sub_point_cloud_ = this->create_subscription( - "~/input/pointcloud", rclcpp::SensorDataQoS(), - std::bind(&AEB::onPointCloud, this, std::placeholders::_1)); + { + sub_point_cloud_ = this->create_subscription( + "~/input/pointcloud", rclcpp::SensorDataQoS(), + std::bind(&AEB::onPointCloud, this, std::placeholders::_1)); - sub_velocity_ = this->create_subscription( - "~/input/velocity", rclcpp::QoS{1}, std::bind(&AEB::onVelocity, this, std::placeholders::_1)); + sub_velocity_ = this->create_subscription( + "~/input/velocity", rclcpp::QoS{1}, std::bind(&AEB::onVelocity, this, std::placeholders::_1)); - sub_imu_ = this->create_subscription( - "~/input/imu", rclcpp::QoS{1}, std::bind(&AEB::onImu, this, std::placeholders::_1)); + sub_imu_ = this->create_subscription( + "~/input/imu", rclcpp::QoS{1}, std::bind(&AEB::onImu, this, std::placeholders::_1)); - sub_predicted_traj_ = this->create_subscription( - "~/input/predicted_trajectory", rclcpp::QoS{1}, - std::bind(&AEB::onPredictedTrajectory, this, std::placeholders::_1)); + sub_predicted_traj_ = this->create_subscription( + "~/input/predicted_trajectory", rclcpp::QoS{1}, + std::bind(&AEB::onPredictedTrajectory, this, std::placeholders::_1)); - sub_autoware_state_ = this->create_subscription( - "/autoware/state", rclcpp::QoS{1}, - std::bind(&AEB::onAutowareState, this, std::placeholders::_1)); + sub_autoware_state_ = this->create_subscription( + "/autoware/state", rclcpp::QoS{1}, + std::bind(&AEB::onAutowareState, this, std::placeholders::_1)); + } // Publisher - pub_obstacle_pointcloud_ = - this->create_publisher("~/debug/obstacle_pointcloud", 1); - debug_ego_path_publisher_ = this->create_publisher("~/debug/markers", 1); - + { + pub_obstacle_pointcloud_ = + this->create_publisher("~/debug/obstacle_pointcloud", 1); + debug_ego_path_publisher_ = this->create_publisher("~/debug/markers", 1); + } // Diagnostics - updater_.setHardwareID("autonomous_emergency_braking"); - updater_.add("aeb_emergency_stop", this, &AEB::onCheckCollision); - + { + updater_.setHardwareID("autonomous_emergency_braking"); + updater_.add("aeb_emergency_stop", this, &AEB::onCheckCollision); + } // parameter publish_debug_pointcloud_ = declare_parameter("publish_debug_pointcloud"); use_predicted_trajectory_ = declare_parameter("use_predicted_trajectory"); @@ -161,8 +164,12 @@ AEB::AEB(const rclcpp::NodeOptions & node_options) mpc_prediction_time_horizon_ = declare_parameter("mpc_prediction_time_horizon"); mpc_prediction_time_interval_ = declare_parameter("mpc_prediction_time_interval"); - const auto collision_keeping_sec = declare_parameter("collision_keeping_sec"); - collision_data_keeper_.setTimeout(collision_keeping_sec); + { // Object history data keeper setup + const auto previous_obstacle_keep_time = + declare_parameter("previous_obstacle_keep_time"); + const auto collision_keeping_sec = declare_parameter("collision_keeping_sec"); + collision_data_keeper_.setTimeout(collision_keeping_sec, previous_obstacle_keep_time); + } // start time const double aeb_hz = declare_parameter("aeb_hz"); @@ -297,13 +304,14 @@ void AEB::onCheckCollision(DiagnosticStatusWrapper & stat) MarkerArray debug_markers; checkCollision(debug_markers); - if (!collision_data_keeper_.checkExpired()) { + if (!collision_data_keeper_.checkCollisionExpired()) { const std::string error_msg = "[AEB]: Emergency Brake"; const auto diag_level = DiagnosticStatus::ERROR; stat.summary(diag_level, error_msg); const auto & data = collision_data_keeper_.get(); stat.addf("RSS", "%.2f", data.rss); stat.addf("Distance", "%.2f", data.distance_to_object); + stat.addf("Object Speed", "%.2f", data.velocity); addCollisionMarker(data, debug_markers); } else { const std::string error_msg = "[AEB]: No Collision"; @@ -337,7 +345,7 @@ bool AEB::checkCollision(MarkerArray & debug_markers) auto check_collision = [&]( const auto & path, const colorTuple & debug_colors, - const std::string & debug_ns, const rclcpp::Time & current_time, + const std::string & debug_ns, pcl::PointCloud::Ptr filtered_objects) { // Crop out Pointcloud using an extra wide ego path const auto expanded_ego_polys = @@ -347,25 +355,40 @@ bool AEB::checkCollision(MarkerArray & debug_markers) // Check which points of the cropped point cloud are on the ego path, and get the closest one std::vector objects_from_point_clusters; const auto ego_polys = generatePathFootprint(path, expand_width_); + const auto current_time = obstacle_ros_pointcloud_ptr_->header.stamp; createObjectDataUsingPointCloudClusters( path, ego_polys, current_time, objects_from_point_clusters, filtered_objects); + // Get only the closest object and calculate its speed + const auto closest_object_point = std::invoke([&]() -> std::optional { + const auto closest_object_point_itr = std::min_element( + objects_from_point_clusters.begin(), objects_from_point_clusters.end(), + [](const auto & o1, const auto & o2) { + return o1.distance_to_object < o2.distance_to_object; + }); + + if (closest_object_point_itr == objects_from_point_clusters.end()) { + return std::nullopt; + } + const auto closest_object_speed = collision_data_keeper_.calcObjectSpeedFromHistory( + *closest_object_point_itr, path, current_v); + if (!closest_object_speed.has_value()) { + return std::nullopt; + } + closest_object_point_itr->velocity = closest_object_speed.value(); + return std::make_optional(*closest_object_point_itr); + }); + // Add debug markers - const auto [color_r, color_g, color_b, color_a] = debug_colors; - addMarker( - current_time, path, ego_polys, objects_from_point_clusters, color_r, color_g, color_b, - color_a, debug_ns, debug_markers); - - // Get only the closest object - const auto closest_object_point = std::min_element( - objects_from_point_clusters.begin(), objects_from_point_clusters.end(), - [](const auto & o1, const auto & o2) { - return o1.distance_to_object < o2.distance_to_object; - }); - - // check for empty vector - return (closest_object_point != objects_from_point_clusters.end()) - ? hasCollision(current_v, *closest_object_point) + { + const auto [color_r, color_g, color_b, color_a] = debug_colors; + addMarker( + this->get_clock()->now(), path, ego_polys, objects_from_point_clusters, + closest_object_point, color_r, color_g, color_b, color_a, debug_ns, debug_markers); + } + // check collision using rss distance + return (closest_object_point.has_value()) + ? hasCollision(current_v, closest_object_point.value()) : false; }; @@ -376,9 +399,8 @@ bool AEB::checkCollision(MarkerArray & debug_markers) constexpr colorTuple debug_color = {0.0 / 256.0, 148.0 / 256.0, 205.0 / 256.0, 0.999}; const std::string ns = "ego"; const auto ego_path = generateEgoPath(current_v, current_w); - const auto current_time = get_clock()->now(); - return check_collision(ego_path, debug_color, ns, current_time, filtered_objects); + return check_collision(ego_path, debug_color, ns, filtered_objects); }; // step4. make function to check collision with predicted trajectory from control module @@ -389,12 +411,11 @@ bool AEB::checkCollision(MarkerArray & debug_markers) const auto predicted_path_opt = generateEgoPath(*predicted_traj_ptr); if (!predicted_path_opt) return false; - const auto current_time = predicted_traj_ptr->header.stamp; constexpr colorTuple debug_color = {0.0 / 256.0, 100.0 / 256.0, 0.0 / 256.0, 0.999}; const std::string ns = "predicted"; const auto & predicted_path = predicted_path_opt.value(); - return check_collision(predicted_path, debug_color, ns, current_time, filtered_objects); + return check_collision(predicted_path, debug_color, ns, filtered_objects); }; // Data of filtered point cloud @@ -423,7 +444,7 @@ bool AEB::hasCollision(const double current_v, const ObjectData & closest_object ObjectData collision_data = closest_object; collision_data.rss = rss_dist; collision_data.distance_to_object = closest_object.distance_to_object; - collision_data_keeper_.update(collision_data); + collision_data_keeper_.setCollisionData(collision_data); return true; } return false; @@ -622,8 +643,9 @@ void AEB::cropPointCloudWithEgoFootprintPath( void AEB::addMarker( const rclcpp::Time & current_time, const Path & path, const std::vector & polygons, - const std::vector & objects, const double color_r, const double color_g, - const double color_b, const double color_a, const std::string & ns, MarkerArray & debug_markers) + const std::vector & objects, const std::optional & closest_object, + const double color_r, const double color_g, const double color_b, const double color_a, + const std::string & ns, MarkerArray & debug_markers) { auto path_marker = tier4_autoware_utils::createDefaultMarker( "base_link", current_time, ns + "_path", 0L, Marker::LINE_STRIP, @@ -659,6 +681,23 @@ void AEB::addMarker( object_data_marker.points.push_back(e.position); } debug_markers.markers.push_back(object_data_marker); + + // Visualize planner type text + if (closest_object.has_value()) { + const auto & obj = closest_object.value(); + const auto color = tier4_autoware_utils::createMarkerColor(0.95, 0.95, 0.95, 0.999); + auto closest_object_velocity_marker_array = tier4_autoware_utils::createDefaultMarker( + "base_link", obj.stamp, ns + "_closest_object_velocity", 0, + visualization_msgs::msg::Marker::TEXT_VIEW_FACING, + tier4_autoware_utils::createMarkerScale(0.0, 0.0, 0.7), color); + closest_object_velocity_marker_array.pose.position = obj.position; + const auto ego_velocity = current_velocity_ptr_->longitudinal_velocity; + closest_object_velocity_marker_array.text = + "Object velocity: " + std::to_string(obj.velocity) + " [m/s]\n"; + closest_object_velocity_marker_array.text += + "Object relative velocity to ego: " + std::to_string(obj.velocity - ego_velocity) + " [m/s]"; + debug_markers.markers.push_back(closest_object_velocity_marker_array); + } } void AEB::addCollisionMarker(const ObjectData & data, MarkerArray & debug_markers) From edc7878132cc3355185c43db47b5f8f606af69d7 Mon Sep 17 00:00:00 2001 From: danielsanchezaran Date: Tue, 7 May 2024 21:04:38 +0900 Subject: [PATCH 27/27] feat(start_planner): add centerline crossing check (#6900) * add centerline check Signed-off-by: Daniel Sanchez * remove unused vector Signed-off-by: Daniel Sanchez * improve naming and refactor Signed-off-by: Daniel Sanchez --------- Signed-off-by: Daniel Sanchez --- .../src/start_planner_module.cpp | 37 +++++++++++++++---- 1 file changed, 29 insertions(+), 8 deletions(-) diff --git a/planning/behavior_path_start_planner_module/src/start_planner_module.cpp b/planning/behavior_path_start_planner_module/src/start_planner_module.cpp index e9105f1fbd25f..bee3fb16595b7 100644 --- a/planning/behavior_path_start_planner_module/src/start_planner_module.cpp +++ b/planning/behavior_path_start_planner_module/src/start_planner_module.cpp @@ -398,11 +398,13 @@ bool StartPlannerModule::isPreventingRearVehicleFromPassingThrough() const auto get_gap_between_ego_and_lane_border = [&]( geometry_msgs::msg::Pose & ego_overhang_point_as_pose, - const bool ego_is_merging_from_the_left) -> std::optional { + const bool ego_is_merging_from_the_left) -> std::optional> { const auto local_vehicle_footprint = vehicle_info_.createFootprint(); const auto vehicle_footprint = transformVector(local_vehicle_footprint, tier4_autoware_utils::pose2transform(current_pose)); double smallest_lateral_gap_between_ego_and_border = std::numeric_limits::max(); + double corresponding_lateral_gap_with_other_lane_bound = std::numeric_limits::max(); + for (const auto & point : vehicle_footprint) { geometry_msgs::msg::Pose point_pose; point_pose.position.x = point.x(); @@ -413,9 +415,12 @@ bool StartPlannerModule::isPreventingRearVehicleFromPassingThrough() const lanelet::utils::query::getClosestLanelet(target_lanes, point_pose, &closest_lanelet); lanelet::ConstLanelet closest_lanelet_const(closest_lanelet.constData()); - const lanelet::ConstLineString2d current_lane_bound = (ego_is_merging_from_the_left) - ? closest_lanelet_const.rightBound2d() - : closest_lanelet_const.leftBound2d(); + const auto [current_lane_bound, other_side_lane_bound] = + (ego_is_merging_from_the_left) + ? std::make_pair( + closest_lanelet_const.rightBound2d(), closest_lanelet_const.leftBound2d()) + : std::make_pair( + closest_lanelet_const.leftBound2d(), closest_lanelet_const.rightBound2d()); const double current_point_lateral_gap = calc_absolute_lateral_offset(current_lane_bound, point_pose); if (current_point_lateral_gap < smallest_lateral_gap_between_ego_and_border) { @@ -423,19 +428,35 @@ bool StartPlannerModule::isPreventingRearVehicleFromPassingThrough() const ego_overhang_point_as_pose.position.x = point.x(); ego_overhang_point_as_pose.position.y = point.y(); ego_overhang_point_as_pose.position.z = 0.0; + corresponding_lateral_gap_with_other_lane_bound = + calc_absolute_lateral_offset(other_side_lane_bound, point_pose); } } + if (smallest_lateral_gap_between_ego_and_border == std::numeric_limits::max()) { return std::nullopt; } - return smallest_lateral_gap_between_ego_and_border; + return std::make_pair( + (smallest_lateral_gap_between_ego_and_border), + (corresponding_lateral_gap_with_other_lane_bound)); }; geometry_msgs::msg::Pose ego_overhang_point_as_pose; - const auto gap_between_ego_and_lane_border = + const auto gaps_with_lane_borders_pair = get_gap_between_ego_and_lane_border(ego_overhang_point_as_pose, ego_is_merging_from_the_left); - if (!gap_between_ego_and_lane_border) return false; + if (!gaps_with_lane_borders_pair.has_value()) { + return false; + } + + const auto & gap_between_ego_and_lane_border = gaps_with_lane_borders_pair.value().first; + const auto & corresponding_lateral_gap_with_other_lane_bound = + gaps_with_lane_borders_pair.value().second; + + // middle of the lane is crossed, no need to check for collisions anymore + if (gap_between_ego_and_lane_border < corresponding_lateral_gap_with_other_lane_bound) { + return true; + } // Get the lanelets that will be queried for target objects const auto relevant_lanelets = std::invoke([&]() -> std::optional { lanelet::Lanelet closest_lanelet; @@ -485,7 +506,7 @@ bool StartPlannerModule::isPreventingRearVehicleFromPassingThrough() const if (!closest_object_width) return false; // Decide if the closest object does not fit in the gap left by the ego vehicle. return closest_object_width.value() + parameters_->extra_width_margin_for_rear_obstacle > - gap_between_ego_and_lane_border.value(); + gap_between_ego_and_lane_border; } bool StartPlannerModule::isCloseToOriginalStartPose() const