From 6e798bf300635db49a15003fb7362af0fbc80d5c Mon Sep 17 00:00:00 2001 From: toru-kuga Date: Mon, 16 Aug 2021 18:50:38 +0900 Subject: [PATCH 01/14] code fix on wrong substitution (#2815) --- moveit_core/kinematic_constraints/src/utils.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/moveit_core/kinematic_constraints/src/utils.cpp b/moveit_core/kinematic_constraints/src/utils.cpp index 417791d596..cc10209ba9 100644 --- a/moveit_core/kinematic_constraints/src/utils.cpp +++ b/moveit_core/kinematic_constraints/src/utils.cpp @@ -145,8 +145,8 @@ moveit_msgs::Constraints constructGoalConstraints(const moveit::core::RobotState { goal.joint_constraints[i].joint_name = jmg->getVariableNames()[i]; goal.joint_constraints[i].position = vals[i]; - goal.joint_constraints[i].tolerance_above = tolerance_below; - goal.joint_constraints[i].tolerance_below = tolerance_above; + goal.joint_constraints[i].tolerance_above = tolerance_above; + goal.joint_constraints[i].tolerance_below = tolerance_below; goal.joint_constraints[i].weight = 1.0; } From 4d6f805b8375104fd5dac4791032a9c11353fffe Mon Sep 17 00:00:00 2001 From: Jochen Sprickerhof Date: Tue, 17 Aug 2021 23:28:45 +0200 Subject: [PATCH 02/14] [moveit_core] Fix export of FCL dependency (#2819) Regression of 93c3f63 Closes: #2804 --- moveit_core/CMakeLists.txt | 12 ++++++++++-- 1 file changed, 10 insertions(+), 2 deletions(-) diff --git a/moveit_core/CMakeLists.txt b/moveit_core/CMakeLists.txt index 0c32b3aa0f..f555734a6d 100644 --- a/moveit_core/CMakeLists.txt +++ b/moveit_core/CMakeLists.txt @@ -44,8 +44,16 @@ endif() find_package(fcl QUIET) if (fcl_FOUND) - set(LIBFCL_LIBRARIES ${FCL_LIBRARIES}) - set(LIBFCL_INCLUDE_DIRS ${FCL_INCLUDE_DIRS}) + # convert cmake target to variables for catkin_package DEPENDS + if(TARGET ${FCL_LIBRARIES}) + get_target_property(LIBFCL_LOCATION ${FCL_LIBRARIES} LOCATION) + get_target_property(LIBFCL_INTERFACE_LINK_LIBRARIES ${FCL_LIBRARIES} INTERFACE_LINK_LIBRARIES) + get_target_property(LIBFCL_INCLUDE_DIRS ${FCL_LIBRARIES} INTERFACE_INCLUDE_DIRECTORIES) + set(LIBFCL_LIBRARIES ${LIBFCL_LOCATION} ${LIBFCL_INTERFACE_LINK_LIBRARIES}) + else() + set(LIBFCL_LIBRARIES ${FCL_LIBRARIES}) + set(LIBFCL_INCLUDE_DIRS ${FCL_INCLUDE_DIRS}) + endif() else() find_package(PkgConfig REQUIRED) pkg_check_modules(LIBFCL_PC REQUIRED fcl) From 6ab6d896bdf6ee5cd2de4df93dbbf17f7041fb45 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Martin=20G=C3=BCnther?= Date: Wed, 18 Aug 2021 16:38:55 +0200 Subject: [PATCH 03/14] Remove python3-osrf-pycommon from Dockerfile (#2822) This was a workaround for https://github.com/catkin/catkin_tools/issues/594, which is no longer needed because python3-catkin-tools 0.7 added the required dependency. --- .docker/ci/Dockerfile | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.docker/ci/Dockerfile b/.docker/ci/Dockerfile index 2ee33f489d..8c6352b11f 100644 --- a/.docker/ci/Dockerfile +++ b/.docker/ci/Dockerfile @@ -21,7 +21,7 @@ RUN \ # Some basic requirements wget git sudo \ # Preferred build tools - python3-catkin-tools python3-osrf-pycommon \ + python3-catkin-tools \ clang clang-format-10 clang-tidy clang-tools \ ccache && \ # From 0e9844d3019d11f2b6562bb2da021201d86991dd Mon Sep 17 00:00:00 2001 From: Robert Haschke Date: Wed, 18 Aug 2021 17:24:18 +0200 Subject: [PATCH 04/14] Fix issue #2809 (broken test with clang) (#2820) Because std::make_pair uses the decayed type (std::string), the strings were actually copied into a temporary, which was subsequently referenced by the elements of std::pair, leading to a stack-use-after-scope error. Explicitly passing const references into std::make_pair via std::cref() resolves the issue mentioned in #2809. --- moveit_core/collision_detection_fcl/CMakeLists.txt | 6 ------ .../collision_detection_fcl/src/collision_common.cpp | 6 +++--- 2 files changed, 3 insertions(+), 9 deletions(-) diff --git a/moveit_core/collision_detection_fcl/CMakeLists.txt b/moveit_core/collision_detection_fcl/CMakeLists.txt index 558d96b279..6cbaabf049 100644 --- a/moveit_core/collision_detection_fcl/CMakeLists.txt +++ b/moveit_core/collision_detection_fcl/CMakeLists.txt @@ -5,12 +5,6 @@ add_library(${MOVEIT_LIB_NAME} src/collision_env_fcl.cpp ) set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") -if(CMAKE_CXX_COMPILER_ID STREQUAL "Clang") - # FIXME(v4hn): clang 10-12 produce broken code for the only std::map::insert call in the method - # however, the method calls in here are hotspots in the whole pipeline and disabling optimizations - # is no sufficient solution - set_source_files_properties(src/collision_common.cpp PROPERTIES COMPILE_FLAGS -O0) -endif() target_link_libraries(${MOVEIT_LIB_NAME} moveit_collision_detection ${catkin_LIBRARIES} ${urdfdom_LIBRARIES} ${urdfdom_headers_LIBRARIES} ${LIBFCL_LIBRARIES} ${Boost_LIBRARIES}) diff --git a/moveit_core/collision_detection_fcl/src/collision_common.cpp b/moveit_core/collision_detection_fcl/src/collision_common.cpp index 773fd8ebba..8268147356 100644 --- a/moveit_core/collision_detection_fcl/src/collision_common.cpp +++ b/moveit_core/collision_detection_fcl/src/collision_common.cpp @@ -495,9 +495,9 @@ bool distanceCallback(fcl::CollisionObjectd* o1, fcl::CollisionObjectd* o2, void double dist_threshold = cdata->req->distance_threshold; - const std::pair pc = cd1->getID() < cd2->getID() ? - std::make_pair(cd1->getID(), cd2->getID()) : - std::make_pair(cd2->getID(), cd1->getID()); + const std::pair pc = + cd1->getID() < cd2->getID() ? std::make_pair(std::cref(cd1->getID()), std::cref(cd2->getID())) : + std::make_pair(std::cref(cd2->getID()), std::cref(cd1->getID())); DistanceMap::iterator it = cdata->res->distances.find(pc); From 7855e1ffb9e1d6a1b549e223bfde01ec22bd2e22 Mon Sep 17 00:00:00 2001 From: aa-tom <86778266+aa-tom@users.noreply.github.com> Date: Wed, 18 Aug 2021 20:28:22 +0100 Subject: [PATCH 05/14] Fix Pilz planner's collision detection (#2803) We need to pass the current PlanningScene down to the actual collision checking methods --- .../doc/diag_class_planning_context.png | Bin 133824 -> 185005 bytes .../doc/diag_class_planning_context.uxf | 282 +++++++++--------- .../plan_components_builder.h | 9 +- .../planning_context_base.h | 2 +- .../trajectory_blender.h | 5 +- .../trajectory_blender_transition_window.h | 5 +- .../trajectory_functions.h | 15 +- .../trajectory_generator.h | 14 +- .../trajectory_generator_circ.h | 9 +- .../trajectory_generator_lin.h | 9 +- .../trajectory_generator_ptp.h | 10 +- .../src/command_list_manager.cpp | 2 +- .../src/plan_components_builder.cpp | 10 +- .../trajectory_blender_transition_window.cpp | 10 +- .../src/trajectory_functions.cpp | 25 +- .../src/trajectory_generator.cpp | 7 +- .../src/trajectory_generator_circ.cpp | 14 +- .../src/trajectory_generator_lin.cpp | 14 +- .../src/trajectory_generator_ptp.cpp | 8 +- ...ntegrationtest_plan_components_builder.cpp | 7 +- .../test/test_utils.cpp | 8 +- .../test/test_utils.h | 2 +- ...t_trajectory_blender_transition_window.cpp | 33 +- .../test/unittest_trajectory_functions.cpp | 23 +- .../unittest_trajectory_generator_circ.cpp | 53 ++-- .../unittest_trajectory_generator_common.cpp | 47 +-- .../unittest_trajectory_generator_lin.cpp | 23 +- .../unittest_trajectory_generator_ptp.cpp | 19 +- 28 files changed, 359 insertions(+), 306 deletions(-) diff --git a/moveit_planners/pilz_industrial_motion_planner/doc/diag_class_planning_context.png b/moveit_planners/pilz_industrial_motion_planner/doc/diag_class_planning_context.png index 724cdf19115eaad006e7ebfa97dcbfb3afbfb950..93f641245dc1dc9ec8be1915dc85c8a839f9050e 100644 GIT binary patch literal 185005 zcmeFac|4bE`!1~2YEscmWoQx+iZVx~l9VAN`l1O9=6Tj6m7E9gv!r}ZNBJt;M zi@DbyTCH@@Ybsh`%i&&;pxPT8E1KS(`vDzMaUVyInQsj|(s&PRP4Zh`!{ z;h)Qsv}o?{G&G_D?R4{h|0sJbdExxuW8I(h{PB^l%b}uw{9Sb8|5rY~?lQykfR;j$ z**kYz7Wo^^qBk3s59h9%eZ+_jhm>iaZ>hK#q~UXM_9NxnB4}yWeOB9D#-+G|eC4^? z@5&2q+&b&*Xsz{N0r`rO^K(ub`Bm57$j6-AOTKX9+G?dmG_)7FH*|RJT1>to&wVSB z=HQ`g=^H+nwwEMu7ChU3y*Am*XW-4HY}se~c3sa-R?5qg46L^st*t3Z9;r;99`1;W zVcB#3<797o;5iiux1OU)ovWkP8jYTbrue8QY8O0{PrULixGUr0>B;$voSwb2GJ9_G z;^&97w6tt`Q!NHt3nZ_H2ijYw1lWyK>1djjD<|1hK5^zr{`KQ}OaV9d*HzoXVUBEUfE=Hb!9F@<7-`CS=7 zl1_Is#O)?7Gi-4GAvgErZnMi3I&%F@)ysv0ZAJACGgFhJy{z4got@IOCoO(e#?CYW|jliVgp~dJ1W&$wfXxLgx0>-t>V+pf4WvyD9C2C$9?CiF*B zS{0Pp&uu)9b+fxQUemci^&+d7WnY66D~sNTH2cw7i+VgKZ%SVVf00<}>vIW;vcha} z4lx?3Y6<#w-;Oez@)sF?U#)-rdu)RQ-QJGFw)u(FGXXsjEM%0sh>ekES$W&>FqCk@tyr+O|JEZ znJag()9#cDVCwnNQ64oY=#KsVz5Dp42Sbq_(XA_F{CZZ2_>I>&m&%Ij)g&4Tx6|$a zrBSj~Vc?RyWdi@H@{`@+jO3&pl%73%WS1Pez1XblyHRVt4{thk;B`Ws+LeuE7iFA>5&AZ z1{F=a^0!)fq48*bS)qb#G71XCtGij?jJEP9LPVUdzjH_0q*-eJHiYH@b@PeJAtcN>1{ZAWy zS+C+}QD;@J>WK@bS7$gb&kW;Md&i+T?H)+ov8#6LOy8J^Y;tBzl8L0Rx2FC0FWmm4 zP5Tia>QZf3ZMxnlXl-x!m>-~^kt|uVG~b7x{hiOa#?7<2_ebby$)pXpFFr#ZG-=IOjXi(J%4)n+ zPJ&rwxTBnFdi?HLp&d-v$k-XgtYYizXb>{@a?8+P}mj%rX?#P1YL$XbjIs9#VSK#glKgA^%G3XPCPLXp@+Yj19zBZ1yR&R< zMjH-)utjg(%1!$sdQF}B8rmdgtg7GZY1$2!x8!-#Zx(nZ?Y^`8l*Ljhv+f_m?sDQ) zu@^EcUZ0c9`FL|-^}DO?pOl3)NZx=ohPZ;t+>c)u+^~$r~a9+ ziMEGr@Xs#{nk&MWcmHY6?^52SeoES6?EPt~u;}cP3hy{!zk;^+KiUST)Gihk9#8B| zo5Vh^iByhyamu&OtWy2dvwc-`?R1+3bjPZS>^BsC4?gPL8IwNkXHvLP+}1Kh?q)lk zjMwh=ir3XWA9`7iU2Vv4RA@<9w1Pz}@ztx{?>0tnqfY+3P2VcGre*5s(cGo4G}EVV zE$6v{9Gd6FohhypU`6i#{6KR~kVKS9Okw@WWCn!`3EQg?_@g((;1V3N{(m zoBOX<kLCexV5k^`)_le^75-&fDU6%M*tSn_t&2K7h}2h$b=>YE z)R?iHmy%*>)WhO&<6l4ie+%uHFX&M1c{Pixw)p&yLZnw;4yW>cA(5OW@~HfJ8jgGM zXCqWz%*FQj*>G32C_*PGZWf;2xIDW6{{!Fj{~XBsKk#P$-^9%Se^}0Sx7Tx>*>|n% zN{$;_()!uWFaMCB-gURPO5UaRIZ1ROqwCLAXY00;T1zw)@f9%C9-#NY^jMR_%w&Dr znc2g3@Ea-8VoN)LwG)k+GMwRau1wMm!RUS&f`t5d9PP(kT$-vE~O{A zb1@xLVmHs+4d{{^==%I#zxD?L7khx^HpSBl3f~Ye+5#QKuk+4+ibJ4;nTE#vqMTU& z5yYMZ{n}^hW7NT-1fZkf;B6mP&3@{^{n^Wv3)b6~;&Olx!U@|R;9{1wW|b{oqza}v z_~tRW>o`PrO1k}&u?*L1jnrh^HsF)_ACJCh_R+(Tv@WJkjra;0Xy|`QpPC*`2hwj6 zG^q1CH(Qa>h)T?T&{seC>et6xlftSyYCnuJThu%`M~ZMP-`ocRA3S)VP8&Db^MP0O z?T%5)+5h{VBW*!L^L>}y)NrLR+lQ{ka;!J1y3<>C($UE8n6F0UMLvICK=a@Zo{aoC z;q+99=HL_Z4ES@febw3}G#qQl;@}Sl^TkFQnxlv3>*z4alT0+vj~~ZX@aMVdz55Gk z)-9W_pgrjJ8qwU?wzYQlNp6(<`=Vr#{=K|p75=@E{(WTr9UMTXk=Q$JaB~&SjqaVJ zdb7M-q}{4|u{Pr*%|*oHYFCxnWYuwJ&)OSLMQJ{cG?g#M2X2UL z&HsH%D;-Vjl;tqVLCIilSkGk~WwE9y+tmRe zyr~Gqr(IMD$OBYL-c>qX-`{{?%GLc%SLZMHc5ol6$%S-6&sF2Jkzg-Qj&$ec<$*6t zH|wmZnKHLrxOfGli0Kuo)n5p`Ob1gidK0;xT$1BeI)QfO$|`y$j33RL|MFO2J)SBW zSIZ*4@j8s>p&%0BQGIjq3!69PEpoG-Ma{D2P*FeYj+gyytbpE0iblh?vMnOI#0+)b?TCeBZ^Vl?tV>on|@~3}gl^#{w)s*rM_p zNAUzolpmC?Xp4s;ANM=`+KFIio@XLv9eN416)2g(4(*Ljo*Jq4-G5!co=Tp5b&%Q9fTMCgZPPpKK4w9iHS-PyXC; zE$p4_G#WxEEa)`FY7Ke#>( zk5HTnQd)v%rqP*q1gqX<>I7O8MeJaUw`SUK#W_$M#~y83&o=Y)=*Y&9X7?9Lj{Rhx z_N0#1C5k0tHvqsjjy(=>5#em%+IOR*;V&DPO%F^}gT&470Bg>K;F88K&XV1rp7_}$ z@2(KWDw7Ae9-XvP(S9I@oiK+!1tZ?tRM9{b z9|Fk6zr;BC4ltytSgR0&`n2U6b}#h>CuH5=$lxN{lQd(y0M4tP0$*N#_l>w!fUH|9Xb|?<7g8W{9x$I&uYF=WTsc6;ah3DvurQrj$v~y1!xUt>{U^gn=)O%a{`GaVL$w1>c+IQd zxX-=U&GpzNCowgY&FbKHPUWdcl7(_)x>wLsTi3Z=w{Go)oj1A}OwtE(xw0Q_bXVs? zih29?Esoa*RPsTa|DMscdR0{*(gk0SNfk(V_w0qNzxBrjOZHu_==!`?PPabI&dSOP zIh$16A2crvIE5`9*i0C}4`!WS>ZfA{MCG3|Q#E>byS+I5?viUC80JkcN(fCHP@YLI zk#ZsP?tYsG*Iwzj8N2yaJu!}>^^qdcpNI$ut4`uhbPh<}NjB@wOWAWiU#FWew^<+f z?pgcM;&Y7?J?k`Xq}i+DII8vNq}FF$ZjcrH{|+cROm;<&Xjrv)A|p%hjMKc?CUvd!vlHK34rCz0ET5u| zR2wuEfR~=>)SUTY?rp8qW+E(I*mXQf)iFP0&z1Cv@|eaVR{ODrtVf#@Uh{r+p(-8R zb=+Y#I^Xzh8UF%Xsr*zhu9vc13bKZ%uYr1#MF0E`RBlkyEMBr>9%8 zTa@Vxl*(T}JU!`ddOY@8dE}lWK3~SV3PNA5>;AZ%I$WvgG-JyGZ8SfiDsq2-!nGyA zcS5cSc!xBbD39wl7rBJ`dZz1$86m6QG)%v{V&j_LdQd;U25G`3mJielKX8nnaL)}< zlUOeu$y6O78|WS?`CL3S-I~xI2XEf-p-J1`8sO2h=f9;%CU!iLV!8U`UHj9$mo#kq zzrmdzd z(dw}Yx?Bzn6-&0Xv^t@R=aqEd5J&&4(N1FwqQ=}2FBEy?HgctpYN!a*X z@X>MRui|DkYQM(E+X7i-*F|#;HNVMbagM@^llGU6iEP1(^YmtATVdc~%cVGh*S5!M zpn15l8$&WftY8BqlaLuJ)?0fy~l^ zTnDbDAUj-c}N%$*?X0B z-xYZzQk_D-aj0eW)}626WB{0Y;Ff;H4pLuG!g2r2J(d{&*&_EL5mpVzsO zeqo86qtZ#q4pW_)K??~2Zj5AV_(Ae9PT2N1tFK#~9x@5@;Wc>(?%uU95ei8u*Quv_ zf)IdbCevqptJuSzKx5P}uhQ}<_>*kQ&!%vVoF-lrJP$vj*lQekNcHvQepdlDw0OqS z%FXSzF{l)xDN{7Y|?0I31yHL{^@fT1zYy$owD7yOT%j zY;-D`7`W9u+ONGQ2dd$OVs1#XCFg*$@O!f{zfjiShPO`5;s6@j9r?e@AI+ai$75Pd zB_PqEsL>Lb8A(WYWZu9-VRU&glO`}iRFMqOKYNV%j5=j5i zz?p&IT&;9$e^#7pCl>1~5RkHQ7##Q=Ms8I>mD5k@&w_gO-k^ROQBuG7`6s;S#z>7+ zYb`;`d7-&oSy;wMxyRku3?Q9OS?<8F(hJUWDLWaCZBgXA{Pi(B3;ch)Bu0{r0L*A_ z_aWU}rn^6|NqD^39qA{a%8y@1_6mQStEZy%W;P31&tloYMa%5ArLHZ+$ zujxruhp$()Gr$XRIPp$Q+5{(Omj=7p&eTY+(c}}#8up%q7z z3B+bP>Zw@-Nbl5DdokY6!f5%p%Cplf<=+&agygr`6Acd0P&qyz23t#R%JXEjKQ zjGGWhb3CYx4C%kB;&eQ0qd5%Do?g6X!XjA`xLOnDhWxEi%O$4!U1tU*X87a4ei+;p zVBpp8+jal6&E_z3p%oc`M3#lZZTk%BQUHzd(1L>JuINGN_bG6oHnBF8U9Wg`pZ3FC zmT5_qb#wUh`A8;-MQJ+|i(7FRIT*=J8`&(jv`1_zYT+2Cj29hCk+g@opdeSy;;XpA zQ@$XTn3RDNO5^Ih;7GpXtkwaiBM8?aTl>`VT@&tY+z^>k5;_pU67b;c^!JMMbw`(} zpOE;yBa_E!4wA_)1VL24+N4*d+*Q?fyu}-V2411dDM@&Rcp4#%S85;3^{@g_RNr<$ zf=O7i3VEc}M)Gz)eT{m>6v1n*I2!ktG1{f1U!f z)6;;Aio^y_zDU85>ep0Z_vgyp?B%iGp+i0q-)Dw3XX0T$ihhX26Ww|qKN=pQ%3`u=ezN`8!+QfFk3&?#@>{{5jN)vLnQR>u3FF_T z9G_m<&gZS!(s%4-0^duCT~47gfKamgGw2Tt$y@FO&5+sQqT^9>(_=ngYh9Lm#9?3_ zTK}r+fQjrn>-Ets7U`4fDH|6LLI?kjIumsXGkb7L1Oh*c*P z**%xC9!3nvB_N~5P1b9MSIZ6l!gzUSW z4>;4crW_eGgnAO28e>Az#~PhQO@GB2x8(MXf0JTenQGVcNHDm}1Yom-rp|V-06}G9 zs8kNB5kY4Bg+kj0mk$X)BKTAHTksd;^u`}Q-DG%{sjPDtw)@oqTT4iD-LV{I4U}1$ z(*xd#E%DbY?+O6TuWd2gVsd`>yNU>fkg+Vstt+L}ZMx%)l<`Jh^0$*WGVaEcp4;%q z%|PpfgB#s40$2>sGx|~gz*C4fD;W1|@o<3VbirhrIxdBRQkva=ow9>iNErz|aq|iK z-hj4LZb5Dpf7_8yIPMN83aC@P4z8RG(+1!h`dG&fEnyy-p6u1>-4OMUOdU}nchu7@ z>pfkdyN9H4D|6ZXp*cLy@pul;yO%Hv=zi~u3!HiddJyiPL|}v>;Wod9Os8yRcz#;I zQGwVwtcEKThHbKvX>VbHK}T%2yQ zizh7dBi>xpaulcxE(i+^^!9zXQ4~0)X;th;;Z$mPbhh4Jq4I2FvIluho(qM*7=i%F zr>#NGMRhwaf$*a&FaQ+c7(&)CQ6Q4~p>H`)BJ59#8zS}u%$hZ7syUJ}@vT(|3x}7Z z0wg|>%&$sHN=K}izcMi{f4!1fWC*r1dL8=kPDDKI?%4UnEs|6zJol>B=xcfW2n?0H zmE+Ft)S#YfZ8oi4qV&N0=jyt5R~1ozSybyK^d0{!SLllHHnxN=Qk0~+ulIpN zkFn=?tNvmCKLe|>L-}@a4>>WLpQVm|+K7rE5akElX@~X9tybF3a|LPBiSKixoH-q~ zZlnApWvL>I?JT9>m3Jwg=_4}0aBsatxFJlIgj$?Ae;{OW>LYqpggpJDxANCC!ARq^ zTh;BHzgBk2AFFcBlLtu_r(3q-*b~?pH*!lvesXT_-2+*4WdEZiVs<0+CrCaN*~2Jx-sx5i z3>HZg)m{x({#|7hykY>#7le_b*JI+%GfyU5LYDRn(-kgt(9HiJVuX{eopyRr$BBYD z>S>G9p0x*8Ug`l_>P2aXG7|=ud&_xK4Er0uB-wQ3KbY)zpAN#CxI~k}MDKF;4uegf z3E>=fI8to$d6PcG1V)~z{2BM1jcJs79 z_v_`uWyS~g`!>Y@nqu!BfRlT)-a#TE+J3is@(`Sfx#M@o;rqFh0S;D+VMDN2$U2Li zPw^Fazurc5#I}@2skEKxeT<+a09z&D3YuIc3STcgpB=k)4oAdpUyInwabLKrzCnBbp=}&~tqUH-_12=QtrJ(G*;|1aY zf$?pPe;T{8IRBrxgh0#2`wcJ0@C_#BH0Pyar!;5v8IBVq{YuW(b{tsB?alH_{U$Y#6JF)g5pV?4r{D1s()m@XSHf09mB{kOIB_w z3zPAVE$VB?lmOS8ufJT+0nHdPFIxj|{z+ ztYCcX-y`2r>gJGI72;v4iiFN`=Q!NPz>DTMU@BetOXERtJs6%)1$>5eRj>_g++SOF1^Csg3c5Pc;4v`|L`v4bZ$ zOYuy#2EhD}Y}FqeIVasud)6A4h<}1H7XIm?``8ySe?R0eTslP#5=A-e@UsHe$EXoQ zkzE^pWYRS}ypRte!2fFV$A$DO3S@ow*jBU?t`D&REZCienTAJmGTlt&6btvGjPKKZ zrI9MqW-f!`eNSz zUK_v3gB`;3rvVm2uP=C>H8B5z7UKmOU+MufrsuqY+aC3{4#Q$X=HUVOoZ~MHK9;20 zC~SOLDarH)-UKpmmNJo#DxaccVA`Y!9WuRo%psD>GX1bv4c~~Jy~eJBQiBIN5oFa_#{dOsRWPV3U;BN2Y-mlXhe-iy)S+MB&|@GR7~&8vdS~^Ox|DIz z-jqQgr{3hw=mt|CQzwsbwp<$;z7P+4r4pLEg{J?Jo7^(+Fw4_W?T}or%n-(jwTqJ+ zW~M=TOgFL4Fsg*DP-pBmT#sPyK$*rJb%C*IZ>QTu4nZqI7Tl~59nFAa3wLM`S!(j( zMy&VgC8who-Pq(lYbKhNFuy)ZDuS)r%CwiiR-a`y7&I({5bELaResmqG5jx8JKZE&7r09g zdrnEe%*~OBFb)K`ySw`AyDJJWI@l$~r6)=ZwiX<#raR8qVCV%8nJtzQ6wM~Q^4_{s z!Yd{U>{~hL zq!%)Zl)|q@cqg%|NZUB*lvXK0TC4MJ&mM7}BQlcY_J&}R04h{32r{(+QSSqlM`_%DLqllQhcCt~p`mo4l;t%0ch1_YW*q>J zH=8&h7)jnd8+YnX6#(v&z z^D~hJ41)=JEo(sfY0yDH(6RZgq)axfL-IaS9j$?skObkY2>xF`VUrEJ&&q3POd}QQ zs2%T+JFP6MaoBV6v-CpZR#);zENhoZcigvGPjrhxO8+sTynmS0jr3$^-RhnsCX^O= zZgcP11BeSiz+(J$D-h+Qw|`qrp)1vaeqYagUFcq>`%W*9)wb_YV#&-z%*+Ep#k)Ld z4?v@5+bl+hhCZq_28!V!NUPk5}| zRLi&UEzZ!MX+k4u7wO`7N&j<=RuS`L4H&Z~UZt<0qM>5k3Uvz~Zwwm>aa$bw7;5{I z`)CS?gnO2_`F?1!h1t8ARNooCgf&R432>pg?@+!>rRIM?@JmQO|*yBPL zzltxAR)ImZX8Zu$5v;S^o_kKDU^gT0x%XYfy@9tJoI6}r+zMQm(FW<}uU>rqC0U2B zqaWjecd$3FCW{LJdQFk}9cKTipo4SQSD{tIsjv)`PTyeQjMz{cfapr*-8opj7D6qqb&M)}pmwX)S+}06xke27;t?Fo<-cmRO>LLQ`Wk@A&c$h;O6)+i;t*?_ zO+Ojz-~Lk8uH8;#^gZ$PBEOy!(5%mYZu+)I84}X{fdE<>T8}vdN3(y+EX8SuOing4 zd?rK=MLZ#FBF_wt95zT9m`~*X01)hxfJsdQp^KV?Oral{j4f!Pj(lGq)!$WW&O#Ds@*z;Yu&>6J3S z)e0BgaR9rQ&n`k8*#nI}`3t7dUn#=ayd{u#xNnVFC1=sB5;$5+sjl3%&=!u-wMCt~^;F@HmUF76mw~g*qstsp56Bm-E znESQtYzaY>MDc!du8SH7~6Pdf`1a*H8&?R&XCcX9PGu#O^Zs(FOJ(X~vwzP2x10KDUDA;Of4) zl4Q=gw1noneab9REYA+qW$y8mY+UwJ&pgg0yPr)qZ9iv_>N(iCeumX%ltt^P8T$jx zXHJ`%ckwEeoj*)@xb)7A-xhD}zOg#1vPfX5^Qy_Yb#x)CYoAj#yw%Jqrvvc$ugKvdEg$*_2b_-i?NDWA9DjP7mCQv&A-lq-H zFKKZ^%hclv6*@G>0ti(>@b%-^JBr&N z4A3{y11JK0H!~ry_%0purn^SiOzn z_-?+gu6@lFFBRKRkRxqg7%Me`fbw~x68qR9k&*O;?Jg}DNBPcu-T&Tae~`7`yc5i? z3)@8Y^HUp0*S&!Dm)n=={wfZ_)no8}#A?$(IFrXP{dTncanEDMXe?m48=K6v%4oYb ze+x7zIy^c7q%8!00-lRSV{ag>Y;#))xOIn#aEAw85|F=P6=Y3IJ*Z^pk(--a2oV{) z+s>qh<1Y2O6ZOS!s2fo-ONp5Ndc6BUVM!p#zoW0>3ORS}x_?HldASms!;%u_JV)ot z?;l^+<-dM-SZKjqWg)Z?uk7;uB%*PlrQmbfOGRj)C3!p_x&+h5PpPU_!L$LQ!5j-g zUR1lMPQkPC4;H;JpwVsQyNrYqw4)4&rMk2;ABHs2e)}#3HY#vE7HC}!4Q&R~`mpmP ztcCkLIcMso5%d$TSN4dupn6$XDXr2k8-4c8MY#V6jNI?Ea`Oheh*4-csOYF!f@!Nq z{14cSAW@5exE33}jnWeo&c0`vGMciUMPabv#3Uw;ktRB&H9uBxqZkuH1~qwg+LJlj za)ieuaUfLm&LJCY_sr+RzrI~U5>%BrEj;0)I!LJIwx@0UHLBIihBM=PaM1P*+`mty zwE1=hQw%>Xg1gi;s>M61KVLC#caAlW>h;zE7!RqL64Xr87Sz`Uc3hPBM6v66o}0tY zmqjS_b9*PsghY!Y%%SP6?wISj9d-f-y4L6i^)We$1jVOQTX_3>8tyN5m4=K5Mb$IS zCg4=RiGR9UK-=D^#43uOwm5@=RYi~t<#V6T4$6z2r=Hzm4oT{xTw0T3trf?@;c28$ zqOw-52f?`(b;OnNBWVZ6XXx^C&27SsS-CnL^F*HFq^vBOO)jtTP+TkWNGgbTe09k; zUi(Yn6`>72^GRhH2qD#rJzu_jK@Kj&q6gaaB#~n->o0=FZdPE%v#GF~c2vf&I((Rf zG%X9_82l_RC9x0MjDE$dD&ho0&v|j{KucbT2$CM{Ye$in121Dh@LvMNL~JH@vF{dD zZ?zQSEya5w%J-Ip$>6jE@?a-KM;t!9NR$+D8@Sc(xRGvGqPO#F=cDd8Y$arkD5is= zinPnY)dCUW!3%eja(Y->*A`v};1&(Ltu%gj;o8c7Wgbb9%m zxO7q3R({$SRB$C`&lOmS%o#gS&E1X5Q*(<7y#EaFFiJV90u~*nc)wjLqV!^Y2Z3dv zGrz|+-gBb=Yq)WsL4Y$cq{QZJMwRg8f=O<%+iPbpCF(#H@Eh+H;0e>U%%>OntaRjUVb&JX>!Y+`y=nHm94ifs{q4U|?Xd=&ayY z;)@DKdhZZM2cK2c1j^=6Js$Pq&vM7HF40*iMbG6^ThB6H|w>bh9-{Mtwm?UIQLW9<1Fqs z(E7>>Q^ZV|7Qcq;vpq0V)}y&yC%6^THM5#MfNF609ZEML^n<9-upZ^2nyiAx6k%gk zC|G&a3T4^3cURDi?MgsyzyfuEY1^8!0a=P0!@W3i%y@kEn=I2|*8e)TS@dF(T67J^ zQQ}r`fH$bQ!2_w1)MZ%od2wuA@KNxP}swEdFXaBi!xJZDpIXv|&q1XQHN1mEJR zLQpWQ8pH&z5WjZhx0Z3y$DJcCXH1y6%*Gt^B%U^Crv=wwcEX0~k?D3hhX=X*GfQ$v zQsXyREW{$4Ge@)EH~}a3*EJ@*JUp_23t%(1p>kifcpc!v>g$Wek;;f+Sb5s!_n>K_JAsRQ#4Ku#WQ%oAg;W?~$MvK~{)y~eagrDz zt4(7~;H?y|ONC79*dbt)u+@fLUAIR*-GV@FV75Q2){{}e@^`5`i zd@ad1WZgJ)EJ?@usU8a>>D{JgaH8~gz&NA?Vi(UA1{YsO?Lg5CwFoP+jQ(5wRBgSZ z2ysKavzgG_P&k3o#MNt1_eA~+o!4G%R{3nmSJ!=CK5W}oRIH`(`AD*4^j^gJK_-rL z!_AdZD!qVfbO{q$-s(h&_+@aoP$rGWXN}=wbdTKv_%(ln>5mtuy zY%;&?XmMh-XRJ(zB;C|roM1^daTtGq+=%4L<(5W^Cwc>T`D#An8}H9T+;#|c;|q&*$Jimot2*$%{2 zi_-~j`4)W%xAcB$rdub44|!V?ntzZZp!CjMlXyzI!U<1@q@xji0J+(0Z;H!dxyg!3 zpPA~FEZFn#WoBR+(3b{Aw~)q1%aeo&0~kFfc)9VU%CP z{2%)bPh>?gkWLV#TaeSdp4wbYV^`Vv3Ach`mneLeirB%8uCDYyNeYI#i*x z{a4dib%FseCui=2@XxY_IQdAxiiYdpjqPF_}EV zAFk3gaev?>j#D4Rns~@z-=v(HFm&URr^rOZiNI8u6)Ms9QVwBHFnQw6XQH3lsqpNRU z`bZ~0&00FzB0@?JNF?C3< zE=8Dnh(y1Tf!I}NTt{`S7X@aUu9vnrF2-PWmuGNWU7%ObW1W+4HLApxQY534I)%x-GNwVx(ys`P$MXf=T|LapzJ}36iYk>61!&_ z=m}pdDMSIS5>oYnGOXCLHmBkFwsDF{?Ym#|z1W1_)yK<)MDcoOCB=H{kfo80~V&Gy}L zK73&j5gY-61!ieUJh>|cYl^YY5xZtidWIi5i57sGd;$$o1g?sI%%jruQuiNuZXJt0r3$c7deuZ)KK=-I5L@W?xaH4t3XlfPW#G2s~%$ zL;)QIP1`MtUW6MFVhpv<5sHHfq|r+z@L z*r?;TdcqLh4R;2xp<7p+xF1rz)y_5^3yPTF!9^22a zGXRu1%pa#sj5YEsoPn?`BZ}#xjmeMMEy^FxFESzsi%Lw5lUWj_k8|zFyM#ea>LKH5 zy49RSHv}|5oZN`MY$w=jo&M(U+KM~j7PJGcmA`at{?H8u)D4B*R6P^D)gi{ zCqhgm&yz9iIF2WR#wKp|o|0nOE6p&1TmO<2x)>;K*C;(Y6y94u-Cci}J~M2ETsCna z8Q#10^ipD4+uS1k`VmJtu@U75ZZu;&Ddy6R~c{G#H)Ec*3n2aLb#UA%UBr^~!`^fY?dPw(H~N~S**fZ+S`U_G((0an+* zLVyIkTXmT%r^LiJSKwgJ-BTI&sc+1RnwAwVx)rI+KUdaA7^AXdH=T8@%xDVu1iDJ7 zfq}(}*x?Z-<74c)MeD~4QSrL(|H;9eULAkJ!^4Bn200~bB`ezce`hV)#MZg!H_q-O z_OoXGpF2S286M8AK{}cA)phB&`PN`*_~8t9)3SAuYscrvI`?~X4W9>x=bHgNXPW_+ z&_syOw0+ng?0+2G>V}&zEI9{9KXyR^9Jk%OlIddARSN{Ta_=XFrjYimnu}=ATgA1($;yx53Z^ zCzZJg1c$dnEBm?Q%$YM4IO(J*kEaTu1TRh#+WI@S*&if-g^We;`%K!V01)6V4r4%L zmop#{i96O?XFs)W4HvAT)>x%2<+fKPar%`0SO)mCLMVO!;B0d*>yHa@7BPr< zczMCQ(2piFS^e1`apTq&a+{Yu+m^E+URMCOUfwmgV6?Lf_U4slUo3tYDjFVy7X>UL z{w$K5y{p}w3}Q8Bcv63#{UYr{GHS#9T;p;UFJ8?$aN1!0!j=F0Dx1B=ZaJZ8naro_ zS?&9KdJ~KJoNi26?=0<${3?=wqq=|(2D+-^ zN;%JjabBf@V@7LG2XW}|P~aKJYHm%B-xCW6E(?(k!ak5MzbfrIk-q>sj#Z!^Un_Qu5~UKu-ryz@!5a zMRb{wtcB1qlvOX)Kag>NdS7U?zT#GYU0 zb@x8MqRvY>WhettrmZYT1yKPG3w7cY2%h_$e`s^)Tug?Rh&6&`O8Igrd?bzKlyda) z?*oBgVB56W8+J3SF*+H($+Q13&0+I4?WqwivJk#=%o?~IL?391S7@B%DKaBn2k|Hy zQ8v}@BGbd<6aPiFyN3Ta>-+hM;Kp~!U}pC4L9n;gUT#&wY;49`DdfbzaytR3S2&QR zRVRHoC8}V2w?#o36i@mXT0TnWMlq1nHILb8k6b)s4}wE;JXhtkQ@E%YET`~qpyA0I zeF~NE#T(cU`Wj6&Ha0>~SivM@h}Mj?J5O?Oa;l|R_OBKU6AXy@fh9)Uv=|gY!fe4h z1(2=0FFPIJ7lTU6J*DhmbX%IhQRwJn@!Wk}0=$O9hZdC#E+|#nD4ICrh zGnwmp4*g${o|=M=d+NwGcjyRJp-dB9F$}^5y!Lp+Dj}=CZ6q>d21PY^lL_2CwM$0= z9khk;87L+>sOE*!Z|WDKxa8X zF%B;OX;VL0cS^8!9XBiF;|Iosnt_#OW++_ZXv_NXz0TBH83xxu5cDkOR`6d>-&{OO;e+D`-3&+aR9)9|hqH6tsg>L=G4_cbh*%IM0GiK-P>x`z zgNp?f-NIzbO;!V@aX(njg{h+HHmcdeD-M6xf(fXfCy4)>d~+{ers1uAjgL8nf7{0u zs^eu18<*kuq;^C`5w8~PG3g-xaC*t$?~qf#$b<__QTfi+W%>Ekeb6D-8V)wN<`Yib zn+$yY#xw)g9Ovo){6v4(e&AK=zFq^~qT;V0aeL+X zL8V$|bJPY!MEpX`a{1@I|Ios#>*qo6Q{T64e9}iq_2=dJ!4#wd#^|L*+d5y_a&m9K z03T(86?EHqI@KaM69!$J+d(j6QjTF^VZ^7nFFTM^ZuinC*!*2bX@kr0uy{|`A(j}S zr7!gu_$6+g183ebZP14W;EEMG2taHnr5)V%SDqE`dyQv!!sFb%u~y06*ZrWXZ8TR+ zG`x@^1D9iP(ARpob~<@%R02}v=Wwv?+5FfJ?jPcDF z1!a$Bq@VQYet`cA`j9G^I-%MI3>GlJBqn7Q^dN>)iyyR5=hK!FOJi)_~J{->vHda|lp`oEjKPc{&=3$)hE>6w|PTS-p z!bA_={0l$g^qbLVj1?wC8qumj*FigPBAy12z)@RkFCcaky(x1wsySLH7nJ`=MdM4N; zWmzHUff%LD)+-5>7IGZR-hGQQbyCZ3x8d74gX+OK;>YP(3nJk;xX-~xx^Ip=di84i zEE(rZUjqL55|lMEdnH(G46VxvwlQKb_~C4B^B zSes})>B4%u_~5C=IVNlVxcnD^(pWF1ozax<92c0SO{B<#G^rK;8_?B4n*WsQA~V+h z7ehR7=XRLxL;8kVjaxxtNU{BuS+~QGcvxa{DTS0pG(RIQ|H(8!CcORczTf{Pq~cEl zRuf(>E*tn0;Z6(G5JDpe4oSE-QwVis9ik<%Jii^{fF12h^VcV&WBd%9fkWgsM`(m` zf{WLKEhVQU(%s=R&5hh~-?`};@{EM7=54j_e4QW*grWNE1UyzULG(Z`7pxob>lsYI zvxMO)e;DVCwdEc-JCknbA-5Ax;ae^WIM7rMzeGIj5AWXXd!73&r%NaK52RW`n^$ky z(YJabP2`FAx$ZRi@3^MRDic;r&wAs~eJB))9bs(VzOz+J1&Rb{gI&#mmEnw4vSf08 z0FzC!B)oMv5oDS}xVImiK%|3O?RAKIRgr1-Q=~^Dnx8^B^X}jE7;s>CXV&zFiF|&$ zxn~;gq6^2qX>&apYK0q~!kLDEx4kYIxH9$<;LeE?CkUsgG|tP5d2Rnho)N92yO;c; z0RT0Gyv^_()f~pmsp(7Tm5jpO!aBf&K?UHen+7lss<%IzHBiLt8pb6M{{fsc^8B75 z>^yi$JO_kA|To*M15nq+`Ak!hH)u%f+q+E&= zQ{CaG@-79`E)W;c`<~Rpm%+Wm3q+JNq0gu{1TgS6x1z|f#&83I)T6AeknX=(PF!2G zS#E_&BsE*8(dgddt({}d=^``-4^Pj9sE92XM6~^LjY*j3!_9)xsC7W#!L-Ui#403` zFN(c@ZzA~R4`@D3wCrz`??w&=zNx}g^*Y>3@sH9LWR~^H0hn&5s^hP$rZ$1m4Er!= z4X9JW3JVo*3FwOL9jkRBe!~K+xygV^h;Ob0O%V}4$RCy`GRfcQwyMn zhPawWgPHEZZF(oD4xDkY?Drq=9~YOQLxpKV7_Bg{D~G-v9>niRSSq;>umywbhcE!n zj%m%K?5OnyVi007c@G8j=a`t$+&DQt-|cj3ZtE63>xsp#g?Ew+O1O6h^A_NIjl1GD z2^cvKU>kD*Uq|(m+g~WTXv&SjFldAV&B-wx)I6fmGyHZ8C6=Q2HiD5jJrWAEaM-Z@`XbcEZqB8;4;|6XgTH;RktB_YyBLh@m zH|5(+ex*x$z3ggLAauq$PcD_aE!Z?bm^_7T_Xrj(Lk)N-Sj@~)0+jTi;adQLEANtF zeBMJbx_BtK-!lHzqj0{vT%J#Q9-G+?P?%}9L{aB08i(dAc{2mNGsYbZ=zj$!TT4pi zsF%Fj{UN=}?%7UO*SqXYQh9ZDwZPQRB@&Ei&qFRnS9~d+2ESZH$a8Nxi;4y$$#)YH z)7dkLvj$ts=mSM>f|IDl$5XC?na2=^dtT1Y&g9)%mac~LLMFq77`Q7=K|dfkwuw}h zq&`y^hXbl{;43OSChIY%nLG*sJ$MBS>ZYV~Kmr4Upn;KzY5gyT?C-8#dJ4H(q;AvV zk$d+St=ARv#9Mx7>h!9~y{&_WM)hxYGT0i%yLoK~ed|+jvYX0rbthUh9@E>9d2IbW zq;T7pGX*`>@f51!G>HPdhtnGeJ3o=RONa=g)C{820Lw!oa5xcG5Z@+T0Tbg|0XR*0 z>V`5|r(@*;#lIPY4Y$_FAdkxB^eo7};#5!|TuIISneCI z%SdF)U7LY1N#f+vWU2;2V-x?0ULDi7B<_zUL(}GTJ1hT$c)xsdk6U~d5x0t_qj{{{ zI#($W6UWEZ7kgAu(II>TW?2C;hLo3-l$f9y>sfPMnw<^id&5a)@|~`QO!R^c?SRG< z_tji8{w0HZOC zg7RVBcGxaa){X#ot!+ty`CtgiAqd(5`tel_E`~7-7$MHOlqMf-h3eVB{3|DF?Z_S z%MhvaHAYL>0)`({UjMgn<2U>a$z#Ovd)|dmO9_;?BWR@|u(ScQw?2j_oZ+|#W~{Cv zzIst1q}p40(W=AG;B!F1#1o5R)YO}I9O~5Um}%Daj8TBatK<8b){glj4#eFPhUEeR zV}4v*9CE;;-ihQskXI)5r(Z#f3o69++$;otJH96nr0i`#)oVg}k7I9*H0eYd?VrC=p`1Jynl_Sk<(Ggu8dykByYj zT;B@3zFdVv6V3j@0@?!HHdwSdybsoP^hn$N1!QZ|GB>8N1(nkKyEGLPC{hZr%?1t? z>w6xk9Ek0w0*DgcW|0juJ?MX(K((ycY_I%mR6k%6_j}+kb8J7D4gBZIJf5M+K2bjv zvRq{8tLWhB2Z>9KN*mct$x>++~igxjh-oOBWy)b(ypsPmeg69(xzn7|YJq?%F~vesiQR72`kaF*Sv{Tc z#WMyx+aq`l1_NE#lq3X7h}|Su()&)`Zv#h1!!KURl`~9E=2L+ob-Vm4f;f%l|5IPv zaN)u{F}GE}<{SUbF}Xa9bShosc#ScEv&-TNJ8N8}u51K!$%KcwFbX=U zOC+$3Y2>}#`i_NDVtlD=|sq3efw;+?B<#=_32;rFwGt+Fi-2pn1!vVyd z!=cDHc3-(U{eCH7dDtbDlHKjb+_f*=DCW;v4YC)w4YCbcwIO^d1Z(oilYzTAO5LP= zmJA|($6v*TFTFuh4C#p&ie@+dp{xwt1{UCA>Y@so`3D>V6e1-Jp}4e{-$cF=M?T7E zD0=Evvo*F(4+C*#MD)#2k;x}H*NU;~ z6;EH!<}ldG41No_fUOWXQw6XAAl!W=4&Y_cq1-~bz0g5c#{NaUOn)9#XgK7f2M!!i zH#LHmqg~`@gNS$)fxQBqYsk9CL|Dl=;Ca5?X!W$1y1K`}p7l2$jlTs~Kr15XG7K)V zX2KT}c%t=i+cf-oVGg4<$2(8>x8}hQ_?M7^G#2A(^yjDt9b(&XJRz(3fHi4&NfB_1 zlMh3?;@k`)gizsQLhygWoY)p3YOo7{GI>_PPXOYb=S>RXEkVFmJS%fh!UaAh9NDws@qc3mm3vOY^` zdV?@dd)I2PhHFL9vCJJy>aaQ#VKqT!7!P%*qQ!f=iXVIx}G_1T$`m;A@NUa@0TZjbPI+w-4~ekvMsb1NOFtl9er>{Evs|lN3*}MWW6*Lz86=S~!1_K*X?XYr zJUbqZ0;xPjRCiRg9-LpuXZ`Jm6lh*Z>k#7xb-ZZ;K!MG`HJpQPulCP_n(=e1!8`hD zQA`LYT3J*BDAt`xWQ_S}p51j1R3g(+lljNa?$m?M(p`~{#zCpF3xAPDR-W2c=a+4z zaB;gaYA1p>iGuF&*d48P(tZ(keA3}XZae&iU$ zSoJZ>7;V)*_F8#F3PjiE zt={^0ycpU)zZfV976P260~8D8;0pybzz$M$9ce$=t=j(-08|!|h#a1TOZ0i5O3)nc zf=e`TU&6&at|oDSOt%YWNV`#l#yP<{^;ns4GQ=?b+~EZNA_xCE>y!)hl$a@?e`h;epj}lkG%%*w_MJ z>Qt6t{K`|Zbq@BJYJs^;U^YV64ap>*jC`(a7kHYnkxD{P={hn)_cpy8GJ;u|V6h>& zaDGPVeypHhPab6JYg|qD=-4C_yPm%Vqdik^cP+Cdn{ujPvT5%hkgyyEU7fjcf6YhPZgP1-%KB}vW z?X&>E3FAFn)I2~W1RQ>t7e{EefpDgXk6>%p#hE~mLXk5LZDz!okll{Z_K2E3YOxDg z77V!Zp-_0tu zf;1T$X7l0JnvFKYZA7<3c=G&u{DhMN>1H%FN94l`%?FqQW6w@+mY&tUE3za!|I|{Px;M4HE}Yp^7<*uk1Pup0etr zOy&)YenSH?z5HJ$=+j*co25ilcC@}pfG0(CrIYG`P4a&g7JNK#X7vUqtN-n@2J%)n zqrYvyX5^y-VZDx_!qRX=UBnO%LM$H_v4=ReKL%9`3DBh9s%v!O8@}Bys(%1#eesAc zV&d^WgV>v?NQ_Eox`iAhBTDj7Qxg|-B8mDm3xD#t%Et^2XM1<0mSe6?1Z4tGLow?m zoTl@t;6U=Z-NX!HGnzrZKc3xzn2)%H*DyIifMQYp?eV(N7#bcUY{g>sv;EUU^Y*%e zcrn~jDDpy7t;YI|u>cw~cE?;rf!d>{xhIWkCiL%W-yNSJ-n4OMM#cm}^(9HGs`eRLuVN`W)&3kCmV-9(7W%l3-AAu7D+{w+hsgsmk7eIN z!yS!KH)>9k4_E>L$ju)vS}gzr2=hoJ`uc$PWer6U0q*`i16`eeAMOAccmaQg`j~(6 z-h=nb^bVh#Vecb+!ca^}{Pa>f^rZ8L^+kN@M_bgHY}t@CKMt??GuOXj)@_2raw%i( z0tY^uJ}QEV-|kx{M2(M++Rym&ztTE)ruUec-r!HX4m?~}ruK3A7X%yr-8o2O_Fg5n zj8+z+o~En%spTrjWc_2!HH_kZQT9onj_Eofb{w@GrrU;7>c{mJl>g*d!7u6;q;1O+ zgZP{O!qmT@L@@Q|sE-1xBCb?+?T^u(qG!bk)AU4LlT)eqcGpc4?}cS1yky{p&h=d1 z5k}GY0n{@DUJ7uF@bx05j3}o!_x=a=`#CUKi6K2PRqC<;NAyg@ZkYh#W5fbsZPeA6 z{s9Lg6O6IdUm6j`WBvu?4PbW9$b#(B!$#pQIt`^q&sw%X1&g`d!>}Gc#Erk`xzj`W z8DenzSwAO_0^~wh`t@;=9TbZ-O!&T<*Qc+_|N80AQ$SZID*Ei+wtZH1Wqcr zT7VtI1xRzqf-84SVJYmphOo&*ARh+JQgmz{-%weJro29VR}%ms!KB}iRr!lZAK$Rl zu$Sh2ayq^kePsX zZfwa7o45RS_0-oQz$8fP(B)f&<|-*;3g*Q+g6P}|O6oR;Yr^MBW>tF6o!K?ek18KU z+qtv}$?Ln45|fmh!U&bV+&KK|WPC3iGj_}gA7;%!4gyjsA;SNVSoQ!7BZ~SfC$&#q zUt{IBiq70`iRFFsD&R-n!+iyRwB!|=Uv_+0?#d6GT|p{db7Qd|kE{f5`~UxB=Vb?D z-#jY&WI%?Pi@=1#9%H78xB0B8XD!g!LYQTSE2EJlxsUp(;)wxi<>Z#iA?u9$FCw0v z8REz7TJ$zZkP**S@;<7Z9K1!N#yR1RmJ>4tt1UwgZHkzw-}?hsfOZo=B9=YiDibxu zmGM#efscJzjz4Gc`sNp~2HuXk>E{p2wBNScs52zo^B;>WXVhd^LA&{|+M_dSXZLx> zlCn~XMt(4NafsZ(rm3`2X}88km&ihA@zn=dq8gtoJvH!FrrNvpdF1}px9(Jr+~CoP z@d>&v!js6Fx-LFB)}IR9~7)^j=Gka%sQ@KZJ7MfM9BhrVnokq-Xsi>nYYMaMIceU@&lUL)v$ameeire;Ki1=i38D#h9NMZ<15~4JsfTX0P zmX?;fdXTlqh0usBTI$3``~m(%@cc^>`R(%Fh!VkB#FiU0o@np;#DemQ>^UERpgclQ_XQclI%7%spV4p<5;OYgEcp$_WHXU84-6wmo6N*5}P-;-d+5uDR z0O*pI#w{O+a48HF9w91?PEW+0k>!GfgoLqioV{r64eiuJNIakUSIVb zLLq_!BQ8!ez*%+vLilg#7c?*W)tqXn>rbnMnx{4Wg4ZQR zEgsw;0ZEDkbb(j#!rL#*+cmL1W2{9kRTEScu_VG`X#5Kq05S5R^IwDf{TZ*k2^iwd z%(`cjZWE;}-b6t`k>NH;QNwWUv9WF{FBjJ+y6%Pswy*=%yV+}$W3Q+yS-sNQ{e&f? z{(!ngrkk~I=I!pQZqmV@R3ckm>kb6@D_42GHoR?2HWOIYT##wImz>Ny>IVl_xg;s9 zG33freG~quR(GrT8B{L7z`u9wyDYW>5Qs@4>#$^feLWt(O^ZJ7>2&6|Y%d=CrYZV! z`3{lr7cZT$;W2Ax6au&?n3x#?{3KA?D_6!4XEMe%#DYYE8)jr=6cZiY2t))#!DuIx zrJyEkQ-7hD{OpC?(&4jD?#0Fe9PTRI*1qL*xP!GNh!W?6bzbhNc|_KN0V<&>mt|`ts#* zdBYlI8nf_6E3H(T;?ky>t7z&XL`Kpo5$nl++om~L#8GTt^!hc>ivuPcueVcBq?xrJ zl~$1Pu9yiSc>H__E?|Q6wXu7wGW295oI5ZLJ0nY+$X1MQ#C1L1?E;x_9>aniIpBs# zbbR8@=4{moMald;Y6l?xt=CPczhnZDMtp*$niYCzZ*Ol1Ng9{mXFyn`p?nRKwY{&S zwmMJl{*B3fiMyy`6)!z(C!Kg)-Suojsw#e3Vz24eniKR^Eg!PJab5-RdGqE?`IF>sBZ85LWcWAeG2YNL6pd-ga8APzDd#^=mltBu?ICBjoZ7#^wB;} z5^XukFq#o&NJ22oy@6onf0F%zrMk@CBS&noaJrA`7^VDOKsz)(U-UAOM=L5S`Wz+< z<(~sd+qu9)s5aBMvkhwFX_cST845p6ti;qDj8c%j{I7=bo7>s_Km|0>1nLj=J{XT( z85G+8iQSG$Q;v@eN;I$HPE^h7**SwrU}CY+(bZ@^1Ox;ak?vQC)8`v9Vw@?Cj&t!2fAHWN9P9$W*9UMIhHx8J z!nz>lU;@)F>$G?4=~UEx-f5^9@>*(-&(afWygutb?q(IFSZytUOB)BI^rYB0A^48!MyZzdwddhK z9(|4auLu9W=+XH$W~$9m0{!~I3C#s}Z66_7$%he1<9&^kd<(0x+%`q=H3{2`q5p9? z2K-gb2a|mTr`Qu29@%!D4j3?Ua1&fa4=NhVsY%6Do4m40FHFg!eYMCZl3UDZ79 zxVm^PrSV)FlLL(#wfq$K6DBpFv-sNc9rFPV)}6I~wm%%>2MqLUeUd-<2esXP0hejATdH;a})KpZf*RHLcFC0TRK$r>ZH=U&P^iL0@>7}ZIupW?o zpnXF4Xe=q1orMLI>&BF1bTy zRBmhQ=_a@w=+ByVe8_u{ooR!(79Cxjf4d+)E^(ZcRWCm7Jnt>$Gi+0HRXX!gDKK~e zhC$3=F=XY__M+tG;kkY5R-@Ao38v*(QPo$uvf$*uCR|iq#F%iVL**bdb3Z($Oibd{ z!ZE0|v&$aMYK5J_18?s~2W0^@F)(yP8jU`3#ylL0W z1qCr!wP-zlPenx)EqfOqL6nXc^|Q1>ElN3L&Bh<;w0_)VN{7L`)*=u`?R;kchPQ85 zu3F`3OG`mXi3oF}>-C!YKo|ktV~#C2y-n--Z0qNDo(!PcIN!O$u2Z1J=JbVukx@dd zP58jqhvVlfh``{3tVl3l0k^$lwn&c375Du2oG$Z=wE@iz$xonGJu5>^^3 z+v(hsHa0f6A^1&DxiL_~@}souY_(_|@JH}DUcGt+AZg3y&D0C<=@J$Bgb;&Zg1O(; zSV2JRH*VYrb3+9d&+@q|RO+xsEd$$UG@4>9I3S*F9#Xa8#{@CYK&rqUce_z-t?FAN zbjq0JcB)scH=m&DozUSd0P9Mu_q(Z+Fo(Z@OsFK9mVWu4=doq{(GrT0^ zxvpAk&2P8AZ5bI=j~coOIM9O!50J85+pC?biPIC+9i_;N-3nld@g1qSWoqtJWuNIb zN!T`sG2(VIEMVT{>S#*b6#Hie#7!ALZFq_$n5as5FAPQUhw1rrtDG08e9Oa;fWzxm zFiro{5K;b%{?uYwx|fen_0vI z08eWc+p`8hI!23^Fw%fm3XGY?nR!^!Z8w|gHuc=TP6U0|qm_TjwUIOW!=Tq8P;xRe zKa1YJZJXN!K2LzZzs8Yv3eGB|thVfIetm23Q}82?s7#*pP(NLWlTKRtsTX+x?V(Zo zS8Ax+F*4;|u(cRxl#hqCni`+dix^H~p&@cI=fY$A&GFi?@gL=lYHw@y40X;YMS>AP zxLVb)4D*$9JnD}F-GV9v+3Iq;9HpPNNKEZ*JH)QGwl+jQbw1+{$hIHjmD#-gtZzSD zimYTmB27e=dpr^&qGRINWmR}%`Uba4eE1L7oGea8cPEP|0eJM#IM}Pe_+NHk+S#amEUu|rp#G&fdBu#Wy=m;xd z=zUQ-DS2XI0yD=TMc}$qIE{pG2h~6N&^~G5Zd9iL$plfJSf3Q3GyuzlKjhZ%5Id0TDu>{N3G_@N7lS!Pf!QCsPB%ZR-38kX!1ss= zM;&G|tXqd_=T|7Do5WK#_w5)EqGdUF=OSwF?junLRY!i+(9g~z3d9Ta3F{TRV1!W$ z-~mb-J8<7UoBngZKj6X|23i(Y)v}T zR(ImFt-M8GlHgFf(}JU=;Q=P5gE|Fs=q8$L!pZ6B>FMZhV2FU?MXk*q{@ITZ%WFQb z`ebUmzsBD+QFrKiZUz7v%)7~U96GKf*EkGyQ}eO8&|GqM`s2z^YPAv`$=J1)Nm{*m zI4lu)X*6jN(sZiGWz*fzXJ?E;EbcGXnO71TOsFE)Jl<&kpR85UR+a_ zt*ENnDdISXL$q-HxH2(G!d#@eG5*7D$SJ9k!F%Dex7+msX? zzr)N`^^ksppRamz*jJ<_24CpCi~D%@?%j*EE2AqyL{lqHpEao@c{(B){4Qlqt zFU!;7dIvZiCe2=`JOM@#1e8si5Rj<`P~fX0k%@DBWKmU9BX(pip(Sp+6ciN1?x7F9 z#)#64@&Hgi50&}6=I)ok{#vZIYNCGGMNK{FRKhBf$8P~TUDSDo&q&&U_ym!)F8^ctpORMF_DFxEa+8+PQ1DqN>2T_;S&4NQH>G;fhwm8^ zs~wyy8RTz*J=9kIYOgvkuRUGKUPK(qHQ+#hfk^Y#?c0xxEF?@$b!Z1mS|*ipbI@HN zd&K@)iEu!eTo)MfMk^V5pZ(=<;BoDzRi{$;Yu%kan@gy5u=?Cc>W&LBYGq_%QhlE{ z=fvtxiS3+n>;&bl`vC~Q=Q^PHc>)NcpK>k8Id|V*MmFx#w;rSvKXnSjwbmc>?-7G| z`#A1}IKI}PYgz(Wly#`FrQQ{6h5@3{vWshj|0f6+a~SFm4D``mO-)UO?&ye0NlQ^t zQAyW~2@VMi4krx9H@OAnoH%TcHy(VMw5Hb#PX*u+l zTK0hWM3M4Z!wnA%d4+`wfD~b{H4R|`9PUI`uUl6aCa6lh>=vpt;$@TXLCKs4LV;10 zSo5=~V?)Qfz}O@xIAUVOQ21WVr?>i4PCh>I+#@R3$bVxJrYhHR`JZ7jRhpm=lsl>r z8&I_skGOX;T1@oITSn#Q3!Tl)A*Z509?W4i9`94ltIF}!h^ev7#rvqHl{|Hrdcs%h zbuFH%+gO}Ap1SxFciwvpcV2mqTR=!i!e2{vt^DC{5HB|8u^c*dh@bzx+D~{9PC9tF zu5d8f%fwX1FSK`W7wXLVN++Ee!bKJ8H3Z&a=txk9BA}Y~K3?d4fY(XmTwGkd!)k|~ z&wM}<2Nl!XN+zai9vTpn?6EQfFKNFszm~z+pP?J|&>2K^J~AQnOKNI?%!6PnU*7*A z_B2482Z4dciEim39ggpFtYXW%zy;ALp`lX0-7k>MUdVnfy{0C+O*%rIe6!i5nU*@o zm_XyY+S+ZiJI4>N74NB%Nox5Z-Ts42Q~Om7Gc#+{`%kXS#o5ZOCeNNPfU3#2r2dLab^xsi4TDQq$);1uC?xnqHgPh}L-Sc$&_;UAaCevr^mkLA#wH z-E)IUhTcO~HQQK5?hF9xU~neJEcb_g6&K9qd|Jn~26MIBm%DpGAnw7pL&D7-z(I503!`rFJWz4PZIr)A4qV^8nK z&jnGnQjPjT1QsNuf^rezmX4Xki3I-J45nL;tqbT4cw+iIhbACzprHu^0MFC`cy1|6 zZO1OJg>ADT3kG>I^*_=SO`qE+@)Z>Mt6K1oy16kQv1cF+PQR2HKXLgiqejWQT?UsK zzHGs6>SEQokd14ZR=mBGX+g2?A8)GWdF+$(-7Cp2biBBpr82Kifr``^Ui2t~P{v@y zY^cviBhG7RnL$TELlgAypSw5+ZM%oAOD-Uyw-0#}HjxH>Ev~bD8d;Jp1 zthAFDymeczOYidg$>sj~^=n)s6qq|h016?%hekvkyaL|cvvB5Z#qq-J*5FcEmLuAF zoFpKdYF!teWnkrfyx+pDjIUxdX_u~uvK<^mVIO;N`!b-E@_fEwl#7dtVDLayz}X{P z9%A)|P*|cvDK+^MOcdaGPvNi&<3U_0t0R0?7$Oe0f1@g6~Q`!#%zBja53e3+sl1*%j!YIHlE8$<J=qiD zXG^iCMr9)t*Oj*q2T3Z1B|jwPaURxWOuN@~>AD6fWBi`ld5AZ~b*QcBAtXTSf*ft0 z-xjkcA%@|;|4D-sLFV9+z4G%*XxT;TohN>-`1F9?sz&8R&5%sL3<@3->Wz>4t8ew6 zi=w0r!KUgJR*dxzccxIf`Ck=LaI5CkWY4FJL9r1TxksLN@-G!{=kOP@*B}mIY7vgd z?vK&UPE;*mQ-b@7S_14W(_Wu#c#I6~fzLhM-M_SEjewO|az#T!0|%bV*%EU_m?%SdgK<2u4RH5vvpL~H{<9Ji_X>m{ zR(ba989Hs?VG`ovc+64@4ekDPVwGs-AlfjS%e-Pag-`#&hDjzANLK^kh)HRQlTUYw zsW_s^zhoxy1Ed6w%5f|)JV_;`wEys7rDNv~JI>jq7S6M^Mb*Hh^Konyt&XM1^}Gt& z4*RMLMn-NtZfhH@4p}W5Y=`@b$fnvN8J z*#8+-rwb{e7wDETtrfHB@$;+HJ!>*{YR&he=$81AyN53JZqJPK{%1Rr=kspYU%;Xx z#&2G}U&wr?od9Zxni}Cs0DoXAlv7fgP{PF{neW}ZmtY9rzyEwr)Y{A}S(1w8qh;By z6DLkEtaHc}wPBDJ5U_;%2pZJX!ngtOx6ytIK`w|}gX+Sa!PN;es=YSEM3mW!>sV+& zz&miUhumA~m7<g0X zX@i=y-deW~WlHd6+3T`f11d1K7N;(LDjq4G@*cr+{Z*t9sPZ+F<`%xV7eVS(b828Y z(IKJ*EVe1?OXy#TJ+87&iuN(`Q!n286FH9M=(D2gA&#$(OL3FquD7*O64q19Rm+*PQKX6_z1N=@@oU@^}m3PCYP#z;sYXu`49M` z4i`qXG9Mv$7Xvv|BS8!A9+%**ir<41+wYL!{?&~XbFpD+bdT^`X3&;^C7Oo`O0NudkbR4zF`^u zs(+Fh{Og+^=O7@eLw(xP(AR)JS19~le_LaHD5(we5#-C|PR=!hqrK#ifoI5AEAww34K> z&Gb0TLePgNJuM)rRu5O#4O_M>fECFNAtuhDTQTNGW#>{CzB`DBQpsKBT(#QH$NA_Z z=QQ3QW1jCQP2!K)FTb+aGdl3NyZ$u@$32nc} z1Xz~&z_k|I>yDv30i}#P7P|$9FjLe9#U8nI&a_x3Nqd4BH`*SoRv@quQBhGmr->}icwLA+@C&$8oB|mR4%rLB+%?MH zvk8!>=68Q=`BgSB0C6YAXq7IplM&fUL($>1Uw8MzS%LmJP9izPIzY2 zSOZj>+rrb`({uawZSZ#qgFyGQBafVS1DJSsL-=@sOMaVGu_{9I1XKI*A(H9NU9!s^0;j8& z*MAL|9Kb|NtVdC1+hxHF*a1qBIkB8_Mb%bf~GME z!M4j?LKAl6hzdJ|m`WXG+zteWf~15R#sO@NQeiZw_!J`u#$sY(dV1X$BVYKcgC(#Q zU83?2k%_;-Q1oye*92Y?;%wSN%hxfn*SPb9f&tkIDCr(n)-zvYV)2Xcbb_KxzY=xi znf*|;T}J(L?AnBjyF305A__i(aU{;=;m^X(PIcD_lYn!5=b1=-9zLW%$z!G&kRk{h z=s8&fgHPB6O;xxd!rPmiNWT2806VkH02)MDis{p4Hn6T0t?x{m@_w?B;kb-V9#B#f zlR?ZVBb~=^2e;?ZXr3d)T7)_9EJ8n4#5^_D-q&tuVHoRQQnI^^ReTEJJ&NXB?coj? zd5echRa2>aDc-Kep%{_4YB25J&#s;(R-A=Ksrw}^0ox*I6Yx20b$OaexZie+evmC< za(3-0AzD9{RnY}K7qtsHwTu>9KmYK^kq#U{@Jnc%1(_0J7`+}lx-cKd6hhpT5IRR) z7I&t)zRa=WzVb$k*WKug(l!AB0gPI<@1>kxqH}e8L_@)Ez0T%g&WpS4BX@##aw!;? z9*nQ5Wk->BN~}^%`s~?sgYL1?1Q%Z)|He;V48zW+)0I0Y7^@x!6qWHTACp^)$7I&R z{>g&FH}udyPv@YkK-4{;K-a{PHbN2P6^43*R@ei+n=s@f=D3p)=7KStU zzd>U&MQ66{Gd6CyXb{WPnVBVhiQTi~IEo%goI1Ar$gs>^Kp${k+95Y3*3eINTn}90 zM5VG`*|r9pXWzJN=A89q0M90*`;IfyYBdX|T|Hat)-Ja5uV5hgnIIT0pY&aTQB-+( zxgBt7*lnO%zQrb(S(ROW>x)nt!H`ld#?dzS|6XVo`(HuIY`@0r{sn@9cbZk3e5X48&_x0Dkx9Bg2tEWEUnn=MCRg|QEG4NUm zXbpezI{CSmSYth6B9MB1T6vXzClOFlFY_?67Mq|r^zrej5j5>x@KFox2g^ufx}{_< zCQZ2oxY}n4Qo`pQ(A#WGZ3W%4rfjg038Xgwl3Al7(HJJ0RI_d3`&pd9ACFrKgM#=1 zR>E)tEX{@h^S10!xg2C3AcH?J9eLYOBhXLGzz8MyPRMou;6R<1iSrDiXNc{aoEz=0 z_OJ@#<$<3@5VPP#3=x`$hx9KPQGDoiQIYuQFJe`HRUZu%kJW9{F~l9y=PZW<^89># zpgb(--BC%D}ZDls#D5bqZ^bXu70(0oh%$}dbKy+oW`>$7)FW#yUEr;#d-Fb$f8 zEMZMohFtyuA7-socX|+3MX{&K1h5nAM$j&f1ONEhwZ#dXzi>g@r^N5&G3!F4DxXDzze#-&;l4{(Shwz+Zf=5T?DwT?{_N@`(cn z48bS_v#z@l3nmLKJ5j;_TM?5d_8af37xo+#Sr`{#h(N-VTe!Q4X7USJE?}KYAM>Zd z=c1q){`f*umhRB`<9d2gsa|nm(?ibaQscq|Cmia@)mG*>si zpGc4RDaBPE9u~$i#TV1C$*r>zxMOz|S#nW1Yuk|}47v9Md63JhNyD&d>vifOGZ=wU*F$fO4 z_^+eNEsw_Sm^o&Jc?^bgd?S4iqk_};HOR=nEA%j(T%DTEpQ)mrUhbknm^?<2gPF?B z&F#TrVud!lvoX{lImbkoZ*f}G*b?j>-(Rg^m?8++iknO`?V9(MK)_bMKdsk|P8c~8>COmovqcW&kGS8sOQa7#QnytIuD=*ZNrYdFO43jq{z_|khhc47dJ z;%xgy&^k(mOJDx{9fLe_4Dzd!_cqm6UXat%*B1d}?CaOBpn&33T>6kv!T+h)m9lhi zA&6c`G=RkZ3PP^y6W~||AvgRJgw$CCA@f^fxd?L;e3 z1n9lbzA9d$@VU=j>)+^RJM$`-<5}DRsf?!j{hz?f?Ee;6c|fYW5wp@vyS0?EdfoQb z?`sn84~=fpmRQ0rZ;t5ydiyU!6prJAdGQp>*}@(>~wZnlNv933jW}y>C*Je$a)?ig6y=~1nSfXIF+YQ zyQV6$EtFhpah))1q4QGFZbWx3qXX&+Mu@&YbxeN7w(INZ!C<3&WI!r~hu@8ekTW!&Dg#JF>U&Go?vK$8Deaa5np zmn`L1XT^J44?K6h)yJ;sz~}t#{sGFGiQL;!(gr_IIB>23?h>*>;nFfBYWH7(M0J#u z48Ah%``>_~pZ~j{D7!BA?ia;Afp)toWeukaD|MZOZU>Mrk-0i&cNE?{b?ETg2)%&^ z#7@cqut`Eq5l5ccI+^&=Ask6kqw6mWM_;d z!1Lw524Mjx2UHt5Wuxg2g!GW3tKLRVZixa7fdMcN#ufLRop%;S9ISmvkp19sbC8|= zD+nE!o8gqOlfVS(QRX9;42F0dkK4IeM%EnR+t)e-W8O^WI>35cma#T8wty>-3N|b&add7Rnmtpj%>@F*|G$s0cK&}rSjiU=R`U%$ z)AeVCyj)|sM=vpkzwr>09_jvem-wZMLhXuo8gz@8gyPTIL`TQe{d09JSJ-J@-AgAij7 z)e7W5Kx?8NKjtXh6BZJ}Mj?KWaGR5pdr*ENLgqo3WO@x-;AcC)IooJxSf;k~9)oTL z1tKQyRCIJi8zaAebOeoNu^F0R@?NeO^YO7U_-&4siOkoB7uEP=TR<(* zf5QdY&~3o+$k$X=S2wDP4~flA3^tvmI<4e{BBk`OhXBGsK;}{gD7Rr_Wu3u(s{^&n zq=bzNm~o7ZjI`H3pw|Jf_2`~G#~a0cn}4(prFF8(T=sIW>QrG_>?NxD_Rtb-M0Iml zrhc7R0=zD%h*4IWmHJ8pb-$X*JQ}o}nB9^+_7Uj14IEpLnwpMYv zNj**46Qe6)`(G~717^eCge|fIB$|UV$3)^8MEB|K9kYi3yoO^NN8#`M0GCDbNYwZ?s86kTdRZ_xK_|F-^KX{X`@*}z?$v%>ac1~xX&4=nr+${x%dD;$9IZf}o> z*N1cYcJc}<5Dnu-oZ=o4rt zDJggFp2rn5z>Y*h(c+2$u~(kn!pN-S9p=anT5H#TW87jby2a4+Tkp;kL1@vsgQSIW zTphlO++Ja>;Jjh+i@w}`X!(Lac^hFIQx;VUT5{oMQXamKVpJqA`2_4Ia-ojk-SDw@ zztrNtAj#Ucd?IxEQ}MrO7d;Np*|YR#zlV$YC!ji#z323(4CTJvW-o2W-wqKuEt95WJqe#Bx&7wtZlx~K5SgTF%zN$;7IuVnPqUKrPW(%t^Z0>%C*f%p92~4+ znMWWB7>-DzPzNH4)o)qgk02d`9QMVrmS4o2mvw!Rh9kK>@t%ONa4?F2=|4lKoE z@(1g{byx>G4Qgsb--cd$a8ULQGP}`|lY0jS{s8JVAlS-gTqj3}gR$1*dw=~tPEKN( zphPae2>`(;b+KB^LSy!sg#Gc@){?xeD*o6kfYQxDxCo-MA6#d3d`VupzvxF<6QS4ZVRv6!VVN zt5>sQ;BiAc9Z((K@Im!71K{0%h^{ln#$bry2xbUQf;zT$oIigalJCC3dUW1o zNIv?8gb@CnqwPe&NkA`2A=t*l@TZsE`OVrHFLJO7SO<=~yPMlvRg~AD5*5IvplYwb z2&*MtQGG22%MxziO1A5`6yv-GQ*OrG*c|r!Y$^GAiNtCP0ReTkgR$m)b3MobR;8XU zUNNwsZcR69tc;7lHF6cN@AzevszP#pAog=)uWqhbg$`do5mVO7cyht$(=nSQz)a#d zo|1$_=@yZ>JrwC_X<|KvaQH1XGn&~+0dQI3jHu}AeO^LQEtNc2Y>n}dl+N?QVGBUR z%TRMvD1c^jXemKQ=QUj8xv8W@oQBv!jVTIF1SrjA#l>wHU6#u0$@awISm}s;6gye8 zFZCbw+PD?!{EH2Y(&{Jn72){0aYIVFD9#-o`};?}j|epS^V3jP#}NfE zFG{lZjarvvKnAQ_WP9}YxFZC7N{v`n@8M7l>QOFqqQ1V-euZJc;NWdQF-|sP@&|$k z4Qd?PP}ApQfjYL&LiylJQT!c1-%PyP)`VIeTl7|o=-mA36u})P)8e0`4<8n~Wx9ie zWW)}g>g>dT{`7S_086@dc6OGQsRHCAB%goC5c~WZjWXwUp1@!PdJ?kWP$7E-#e&V9 zpRAn`Tp=#Ua;F&lpC=}Mg%Sd@>sR1=WQ^Ia2O{Mg931ag==26FjNZS04@B9x*J)hu z7lfo|O$a;3|0?V>S^fflKva4SFcQ$y(-ULF*Vwwm)eFZS%oMjPMg|7`Rr$l`<9fGy z^VPrkwmw-GZAd4;WCUGc9R_GJlk{Pn)2xIgnq7ieZb>2+(llningIJ*X>osIZtQ#s z3=(mJGLP5z&2a+&7O$4Nb0TA4hzff-%(9|KBLdL5iqHS{+iy#dhaA|^^Ne>a0JB3D z?J5nT2emo}fuX48hn*Klk+cVtQfx2&9P~jgY!opzHulrD&Au@`hQ|T%04_i0{YAOu z>t6Xxb&f)peAj#TPFZYTMbfzj*Aj4RR*XO44)CKi&AdbS3zkjLbuNF0QO}pAGT}l& zVPWUw)1MpP+3<|k%LoXeOn(CwWv+t!GJ!RX|`&+_x4{8OGx_0 z&Wi}`VAWX{NfWUP1G|#%n@NuIehVX-!MK_q5+vEK?&YSx!d>_jJf`>W->;^~=H}{J z@5Hx-LZ-!*M|D{w$jOlM=usEBRuKwD`v1;D zi~sJ~iACYpaP5@nf%DThf&Q!fe52IUw-8!0(Hpk#wbMF&8LLqkuPKA^2jL zI=V`uBm<=mgx`U-obkXbfNCjbFSS0G_ALa!v}8%dbKhG1A#5CIGarPhhEBjz`iiepSc#DZ>3?A|Xq+r^H*$=Pl_`Q7`+$5$+Y-~OOr zN>p6G5gT2n3?q+Tr$JFgDps0s4)Jj4xN(TUGHDixMgI_2cvo z*+hxy&w)*3%KBd@Wret4B9hvfwm?gZjOf5Pe0r!h0EuM8o^ zys)iw3+GfpUlte|n)q?QX{v^#1No!1zY@>i0{PdD^~7$qYkX_gu3fus-OdCoj7lw# zy?Qmnp3D&}5$vlAEV%JU&G;930`A2mu`UL`WzL+bEH8(OhCXA=)!uRn<>|Zfve$+x zGmP>imI~vweeYI+kSkUTIr&xmU4Yx*$6#7H41cJk8?QfVQzUhNdhs>iO+yf+?~Nb7 zDqlA%tW;LhQOO_PbN`H#)M1so=m*^^9U-Ic6AKVqQJr!I77mI^Luj#P*!D!#dl2{1 zOK8l+W_)OCK!{!YtMi2}oqPYoOP=Ms^-tTEi2i=#aiyPdcH_}2Uhj~D^%j`K5jC2P z%@lSBflW&20^gRTVh263s{yPWsPG`^WK;m}1IE(lKk4tSI+IR)JmH7NOBfW0zX0_> zoBOn^?7OTFXQPxu^8>jKFy_qS*+Qd%dKu}XL$Skz}7r&mAjxX zxm3FK2U4D+SOfLMvVv$8?kHBbIHpEs-5zea5V4Efz(q~&5@_eQe=^*1{#66~?Nv8+ ztfz9Se%)K_=dUvEMPwtEucBuMTYXe(G+hQ0;P9VDTt5SXx}`Ws;i|e z83N2jTqX!z3MZQWt=17J%?mE#(?yYB%%EqFR3B9dHN3Jp@s4H~L^ntMdj;{dkX&if zdR^DQ$TA3XnC0o!1RAz?399C3$Kj(eGY?lOhAdcs5Svgz5~PbObiz08FmP(``om6y z_vqh8f|ij#Y_Wk!k5Bz{wa@poaaNOE^z=HhQD}2act>+@KhY)zfYue&)rZM2NB#^( zqel}~4!Imd95j#KA+{nMoBSY+2hmLQ@DDgUd1NsxX-xKbW45Vi$!Yb*khp+A1wQm?`$3X7us@{+9*F%qRuZmkrhP}8E9{7%7@ zBq?U-lJ@qki`$i*QJY9FJ}}BurCs;%(CX}q*;2o4TEF2$xzdQE;+9FJ_*xdSr$?=2 z;zmAiQEB?9oS86X;rKMZMt~?1ee8Sgcf#X=aN|0-11w4<85tSSD;UqgE$~+P(d$!* zjP31@gp@QiSjn#Aki^HcTIaqBDwp#Aq6`2;N>cJcfD?v-aQQ;w%d6N7#_?fvej(Rh zX!r&(?>2h1^Y(g9`TB39rNAks_Mrkz6kV)tLp=mq%;b5fXItoDR>5!((_$?v^>Y$SO`%0;ve7Tm4F>tkdi!qK6g zh7#=(5(@4VQE-7=0Gtrqr{G}P8lzIJ-7Qv-RfO|gxPN5Q2oAhmu1w)?_BW3_8+?M_z{Y-p9VmK{vCy3=^?Q=U5I{f|@ckdm}_4~e$Kcy(Mp@fu* z%1(Aj+JlC@Nhm^*nXDwEY0o6tWK_rsMVYCL5JE;|Wn^Uh&WFaUdX3NT^F6+QeUIaP zypQ+01JB3ve%$wUU)On^=Xu@0{fJAfQL*adnSIZmDI~lf>unJ6*!hnS_CewjM7z+P zYlf=xBYi`|T|V|AvO*-P=$Fm{Ht6uf<%2Mv@!)}cUIT5@PXpf^mz(s=sITJJ@wp3{wN7tq2K94XO#ZZ*GIJf?XC&9mDd=OE*|V=OJ5&d|4bFe^lEcyzJ8);Rzci1P@d;*n5{;wFC_NGB%Mw3byLJuPVKhuA4GcUhAqP!H zPzBn6a!hGWf4Mp`MZ{F(wIEuWHIvWjAivdu;|xMB{HqvNtf+=D zJB4TP=zeRv1$r;Aj2ZAx24M~>!XUw?n%W8_tbDUg%kxg0Fl)RL1b#eUIaeW zJVGpKAIq|3>qWi-J49yBx@HXySqDyomy-DokZFJ+gkZ-DgN_dBAoq(v)27GAH6tV` z^@wXl7?`Hey94Q)*&0706=;SfYFseR5y)tzYP}T{R*?jjXjRet!TTJDoRDI=%NVAC4ZAxN&&3+Lv7x3skKZNaYP%rh#vhTjnp9#Z@Ls=+` zmA(w?XYU4KxWmBwvWLfFgZ5oYN=h)Z!Wa#~8SM~e7NFQLLi1M&7Lzjf0f}m9ImB`B z=!21Eh-p;g3Xf~ol9H1HRFH)diJe_TrzNGE*gG(wFzkb1X!lwQS7Jv-0|G=+PWY=? zWQ(aI+?*9_F4XevajMu=%{|Jvq54sLP9;OQP}oO{=dO!aMMk!*yaqI^Z$D58Rkt7l z5D^QWz0nFm>Ic@h-_mUEL`2!k^j%i~7Q6_j zfkr4%!oqT~j$U3=c8p^ZXFpifcJse%!-RM5K&jw?h?Y#8Z_vCHl=rG(tNRDi#z=VN zfo<%s)PUTncx?8=y17?TXFOIMJL+Hm#3ASLBV=_4L_-GHj6XoYFM$hT`|)S3hy2x- z=j{zUg`&uZqp=f5v`IL)yoat=yX{11Z;Hw@-z&b|`dd7Qxc>1n>KR-Nw^qk23`KH8 zJyT{3a&JA`=FR*2tfnW-4FZ8NlnllKHQ;{W^Np$Swsg-(Axa2^(TQX1#SXCg{A<7{+BhF@cAh-20 ziL&x=1h_$#6)PapiA+k+`NAS=vl{q5+&JTs$~ue|Mj8qAFt;x>d>Iy>G>ZeoU=Q}k zVSH7PiU+V32qT=Fd`z10@`oXaW8_GPm75;0$v-dJ+=fwS3J)|z=2yf*%0%I4j6_pv zTgPFAlhf;O6E|jF0y=elJCs@uE$r z#}fY~kQ%%$Vx}i{vfJg$Nt#*m2@Y~Q^h<6zJCkgx>DZgSn{O9@DoLPgy}icq*2LI}to6d`X&5gaZR>?TwN@VH1EF?RIh23m0D=0G?qB zh<3J=bkkGyg!f_}LbU~yB*KgiDDl6;vkne{GTi1IfGc(t$R=TnOfvT#io1UIoxPbS1LNXX2 zN?3!Mn3(A5w!(RZ35Jbp*Yf38IYOug&6IT-mzOQ9!-~wC9^C97(8%JLknS9IA~$(!2K-6aebk;u-;s0&WmkTc4HT=P$KW(PXQg; zL`_jKs%7Vuyn^^L#BxXDK4 z&-9rBXjY}Ner6=;uGAy2?N z7f}W1eEA^P(B+&Jgw*N)KPTt$%?ZIgZxdJXX$IZ86_JGDS~m&HA(e#2BH_;T8Q?-A zBO~bz)+k5eclH%V-}fuyDwl7D`SC&1E0l89yIaf@MqC%K-KO;Vk?&d0DSCQ(07?-e z&*)!?l1QoRetpofoQ)H(nL%?CoX@XtNWp+xK9G7*x-?$bO$Uv49GuMH6~x>-v}9_U zi-c!X^a^&3vFwSXR9Gn|F&PjyheQAk+yPv@jgmU|&XP#F((U}D0|Nwb@V5 z)nQA!XWu?Tq=&9O=0yfsQ&0FJ7st*rQaHO$My7C3YgtdD91HVEpmM&<VscpmiZ7zB|A^Us%5x#|=f39(*cXIQiy8=!|sBwZ4PB)fj`c3JeF^ohP_;YX9 z*X0iA8UABo6T=l^JLU2-o|-k7(=vR#!ZjYFxpO`M$Lsi9n(nzVK^eO2w* zrFYlLDhc&>X!K4ouDh`$z37thiaU4zY2lW#ut=P3ku>eC42AL-2;W_~S|&(9(V2S` zza6E*Q8_s!yo9nGn3rEIa!0A*l8wk&66Bg5BwR5-CV6qPGcY|q z^}r0pvfe_)y`SFops)AUnD8S6(t0R+a#E)2=DAO=Yvu?(IW6-jtcns=IP86oedC<@ zYfWf)asNEjEw-L$)Q7gSS|fat8vIB&4l=P&uiDF@ds)+kwm^jd)=5j zGb!N&Q#EUD84<2yxYXYtX&2leCN=>pURXMKmJq{OWMo|Qi=E@&M;F~B;6>6fguV^WIn+Hs0W^UD$L}*r6dH?L@ zu~S7*7!Sgi8(w&xWFJ_kriiJ+gxMm2>xZ7;51d~Yuiw{Yfol&P0hYt)#n7+|=b4pOeSF>2CavLn3yeWQ~{o? zOl&uSK7^W@TG-x*ii?X2tAkG>w%*vbxfFC>yr})UcP1fxD?X{$dU#znOchS-536=? zCu|TF7KWw)HI~m;u5B;d`|qnT(Qi;KA$IV=5hiaxKlXjM6>SPCLPZB*pR1g)>=_R# zTJ7ZIYD zAqB2#>wa|wg^ejhgQWA_C@j0pr;!7$ldzWMAor_LH$5}OK9H=h~`CLewU`8 zOrh56wX;EPU8iweZv_?$Y}~NHPn-(p5p!54`W{w|+Q(B{*bu#73_?%XbX?J`egZOJ zJ#h&M2@a0v++5B1MbOvRx3Wsl4G9Z_c#EDz(OV{<$dZy@aP6MdTk&3XnZ8|udf3IN z;v=vGm>I$O;m~S~j7Kk}!$80p266%6;ZG2vp$2wycjs0Mmwj!)>@dSkw^nkC@mXB8 zjWju{!w~F-mj4>HM{O1oVxGareDh9as%p)!B*~S7tMLUrVzwb+h(HwH=VqrT(f;p) zQw}axW*GY5vk-B?21&xYLnDYo020A1QRRG7zi!%&uCB7gr^vzXT-AVD ziiGGNMM5zLs6X?0VPSK$=WdQoo65?)fH!!ZnTC?!?!mV!HphhXra64IKJFW7(WK-p z(|=IbW@y_C+oeDReg_H9Di55%L6jEgArjt$6REJwyxY-W>5k$VR;3fT=lrTuG_#hk zTGfRtGKW+BhD9jlqp$VF?t9UqSN#>k`lqtt+cKyZz@$UcqT_&F)?bCec?%0{6$UUy zprZHY`-03!3H%D^o4`=P#T}h3xSViyII{0ZU>=MCv2=cxDRj*%wenHP+$%0B!rXx^ ziM@=siG;(9&lEQ&hUP^+xZa23*v`CH&iKt(ktfD*&yrAGmfIZ6zq+apiDo;LGXE zULki~Le<+tr*{HuxU#)dJNfxBUH4Rl&B9LoQp}gx5e=N-7UeN};5G zi$kEfu$;gF^b;b-`a4QbT{g^qhW^0jDx;Fp(q)vAj?<5QgwZsyLH*}oC?ofNXU69f zuTcW8`s4J9N;KaE{Da5=EwSDt3T`MNm!L@i1mUj)-CJ8;ez<^~J}M^WP=BA!H$P*Vfc{xDudMY8gP3Yd5>vEGeyIK*F%G zGlBynG8*0v%VLD0mV5i@?Zh#H#Bac?*R=%or_U)bf@ZVE8Y=wxXr`C#`d2h7^~IXG zVs@WgDU>>)lCf>Tabe)C<2V@|rmdt@i!NS_M9|%{Z0{ygPlGga_4lBEDfIRLTQ2-o z;Zbc5whuC`7KlS%y?TWJ+ttz01oGjAJX{L|&js7k&MvFo79_gf!L4FWv(v~gmO(QF zsUB_{4bH}AD(FC00DsTD0k;l$~+z?B&Nf`fa8-y~~hy@BZx+yMcHm5A@6pj)%$=(Teyd!MV}*e1NA`RiR<5}t;r!Ju}0TT^p!^!0ue zjAdb07`1KNFjaK|u@ys{VNNRh`NRuLO2JWDeU^2rXi3f|f6Yz0u1j13{?*mh)tjH$ ziYg0r1sp059YWGQ2iM3rk;%Ez&{AItW~!O!CEvjIW6IybcK?8Y1d*&Xz`|YK-Dj55 zCX}#IYqwvQSr{m*^ytZLNz@@|RU)3jfC?xdF{N;>dC)Po!e|ROw><{S?!ADw-}Uk~ z%er-Uf`a0t7XV3&`seqh)4WXIz<|h_{P^aypYitm1={CAQTr|7UYNN+hjs%clKC;S zSg>EgsWM>CQN&)jyPI;-{o*m{F*CN2i>g8-(v7{p0zxSRivc5`iCzMR>={AlE6-J2 zOI+|RI{QaQs-!W7cDtx3*qx56Ma?u-RqN51PiHAS86bMA`|p2^$!4MR!Ec#$`MVwn z&Ty2F-(CE8*Bz^11!`UYs>e)`F0-nKdEVu+jnf9I@uU_kpvHe)3S4z@^^}^f%c50g zE{p7#wv`W#6D%Adwx(sIO#&V!Clex#HcNLuqZs~qj4O1rU75e5`2&kdzN`0S2oTl4 zoskpdlYig%>spqr`JRodtEj6th6tZ|6u4eMfsG6_qMXHO7^rXZI}|uQM|r zsW~N||1jabHu|fo=r4)XZU_(a+5ArR<;X4vF^{n4ihHY%IKFhJ?RXYRMmooXt1+lB zQzCBJx3{g7i4z6reyd8o~*U?dWn@S&|xN;2fi1%3yafg~(6W(jDw z;L-$HQXUzA4f+T>d?8_b0xuh@k+VsT!doHc#F+cj3R35vF^_ck_1dI~?sWHVAWReN5^TQ4nhTy+uM&6u_TtWKm#04W7S@g~ z%2HHNSi!_J3GV5Z#Ba&??&kZlX(uS0pH^5>(x0gaqGdeOC3*eZN&NF={H$t`5us^; zYPPYaQOEdzoLoPIZs<_L_J0Je(x}*2?kqGdS4p5LDh?l0fcrkiPPBKC5CDi+qx1

0=vM!+63YU;KPH&+rJjH z4YV*6m6f?Tsm%3|&J+HlL|+KTqMetcv%C4LNFb^E9^LmD7B>eQw2$hLPfht5cc1d$ zMGeQ7nX>I$#~{+L5`cWnqnz@DS8szZT17S%M`P}tT7vzd$Rm56d2U*o75Ut8W=utV z2GE`4S-DcBqt$m}6~~J-2RO9&=leACMd$e)CTu?gSOLwGW|`~X;oQ%xE;&7PK$D5^ zfT>TYg3thmgNFay419cE13#~+sX@q1YryPb|J%3o;A9IexYs=gwL~~kBuH#L0pg9` z;p26Gr0rF#EG)?S-eI%Cm=J<$F`z{Z>))KUJ%?m<*|KGN4`BvkjAg;a1LZj3)TeqI zzKUQuo;Y#WkY7#)XgUE&undA@@y%gc?80bVZaMxhP)UCNawJ(>_>KjW(vUqLA8B9Q zYpUN~w8sI^`NK%AJ;GN2oWXVLrTm@zT%H?44OUK*GjiKKqba$>?mi?54wfDm8aMvt4qVFT=Yp*6-ZG!%QN**f6`m znF$c>#&4ZZRJpAd+0S6Xf-c`Qu+6eW^sARpQ~T=J6C8e%hGAIaD2PD6*d8Qsl3hi5 zRYb*srS`&STQu!%@+lK&BT)7O*>6W+Fnk|iA~E+qL7!=jrrh~Qa9=MeZx6zXmo0Py zT!dniAjnVU)hxp9m91%kQ&Oi=I_UZkRVv-Km>4>d_8Huej#~7S(0UpkwipxHX08X6 z8J*K%W6VH9V#~w-DORGST)v;<8nbW$DlZ^o^2^60U;8yIw+yeU-&vKh>HuyB}7UD6}p z|9ZZ`&<0jPJM-M?{ME)b9eh|4s$(Vpo+@y zG<5P}h0P?#_;39N`>d14$PYP`Ro)F3|D5xF=4Gd)J7Ehkxom}v(%m})5qydWdwbw2}k!+X{T&jtm

+jmy^vlxT`m}pZPa+TL5Iu=JAPi+_?Zt2j3FB+rg~8Y8 zbD(V{J$f=p>JrU`k7JG0l{ss4`C}yNEB>BW`~*s`4K5~teI&bXlxS9f<}D2j5tk-_ z6aTj@#2A}v*Dy&YKn3Hl9)W$B#wPNqI<^W*3Y24L>PMltM8SnFtJ1M!Yyr|J@UYbZ zi5&{h3lD5slZ!glT?tJ+gZVYVjTgc95fC6T77`$XqD0kh#RHfNlG}hC0zVOI@xxyL zZ9y%xTMdRw%Qv@Ld~rQMk19rIuxh^Y-3 zjC`6)%Zcj&)*uE}$BpLU7E>s~nv~pPjA&vc`~m|pdTG9!a@#^c zzhvoa+9Z@RS%X9b;;U)ambFO@j`xbWJsn2RQu4D>-RgSww_uHMpr+Ps=_3*D`sd&Bc%gp z71!^IcU#;pOkB`*8bYSmr2H1S1nmvOp-Y;1f!Prtn4qQ_M@tY;N$y;LYPR%& zEZF{(0Nj-B0&oM6uA&S$g8RlXltfWmiaasAl4JY!?L0iPip0!sf3;;(J#@tUjjnBD z?~U#n9wYCaB8=Jr5boZ!D+G!H5e3JJc3iQMhI>AE#b9eXr9^dibUaR^lB-@VYqPY) zY0km?*3i&7^J&6RdURcRti4Tn=_}qZLs?-3`?}eqlU^w4VK9S1Lmrw| z+3G(^Ck1RCjxX{pexi$q#RL8PPQSrhMxTO>f9`vq!b;v|#alnoarCb$;Z14y4n&Ae z{QQIO=Vmi^Xob~6$s*k2^EKfyCv*)Jm6cYLd5o(PbdH|S44jl%NFPi<_f?arE`P5< z)Mf@26G<+v_HB%fVsihAElH}>>{F)Vq#)yH#S9rI>p?vbyZhFGy6B%YBFAZ=P%n$Gejr^_QP9HSgu*st2 z@|X}n@@@7;oe?!XHvJ{LSJdMe{XZpmF+U3k(8KB!w6$l`xu23e|{xD%hZ2-Yx~=r+7o~h70~E;{TH&}d~eA35Yb{XT&nP+ zzBb=a3MyiIaQ*N1&rhb~KmN!Xw>i(meZXY?pL(IRjgUdiVbUe~J2_~v;f5@K`LfQ8 zZ1CjYH|kuG(%)X7kQjRL2aX=S12oZmcNwghZXhTI%a>cgxrSz~q!=%6KQ7gfx{H{Hk^Z${Rmc_R zz+)wzO6CrFF8wbv zAI(jr%o#U4AjSheVoF9Sh|GQ-{-KFz`!KmE_tO58B$EA~8<{j+sBtzABHBHs##*Qt zQ8&&_z0H5bl$i~Y{$o4=-e#@gW1ri%VJ&<3bBYN0=~i3EW8&@CDE zA{DedP$|zS+-}3$yY@}VD)P*qV7S(t0^J#Zp@jGgAgB_5!CA_q`S*k0dVcN8lc1)4 zMfQ*$e?tK9J1Sg)XB66Y2n8)xGBF|H5z|iB;t^`wMK_;=>)cxF_j|;e2-`fedU#}n zP)Ea#*GO>9z3l9%EOkAZ&{zc}C1F%N=u?ecF)?X_rZNmzc2m~5ml@Y)Ud4FZkwSFP9z=^3evglXuNbuMYyz2?qx+vPBs5R*sK%(eBf<2+jQopRK7JY zMV>W$8E9r`lbp>lVj&m& z=lky)B_?5FxiV|f<;g~UjCipX1NZ=FV&Z@&F_rJbbe(Q)L)rdjs%U9blR|W zBwHTLZ=GMsNTig6xVQs{4taTal$4dp#|kzVz5`LiTtf>ptzMhyFBn;?D;Ta*Q)o$< z`0b$RW&R!qY>#SdYg<}cqOk>;`=(DKU_f%=BkhN#7ibsG#~)ka=-)%IHetN+E!y2% zRn2N9RblU}@~>f{6MN#rhY$De-6K>BYM`gNpYaU!&TP4Gmv=vY5(qZ(*!J{bB-1yLc&iEA8*!zCa*oymf9uFm66| z$WH~?^CyS$%;)$8wkvnjIClbmz`3@5rwPHu+J!pxf6L*Liesr-m1qP=%3yx}damQH+R-~+l6IZH=_jZ` z=J`oL?K-9uq}>(vL%g#z2_T6nxAB|&nVISG?ocA7=y{NB zjsN|G7o5Z|E}5mdq%y=P^0!TYCU{Pfm^k%B9XNG9gl<0J-?)*rSCqHeoil$ak}EWY z(N#N;=3(w6F@UbF%g#L~He$4ZY6hcMsiz=0CXR=^NlHC5HP$}e;_rt9qe=jgV88SQr2y8r6o2|jD)Hi zv5CI?mNq%3S2!ia#nQppX$U<3!_fcbPC7PA(#J}CXI6&x1{3UP6d#R>{O8}U@^KP< z0Sz=p&GEpwmLP$@LTkF25fiQW9>BL4mPTuS`k0 zoc*yhB$Y=SDM=Nt9m@(1KFTAT|6ioH!Gmi<;>qzPplgzE9{+@oSr$6>8=dmO42T~) zW=5+KNg+ZWAAB#papN=JB)Cj$NgNPKOin)XXPel=w1a0%Jm;MQdV9a>%e<>a&$g@q z^8;`;Xu)?Jrw)pje3z5)odb&yjc3A43{1P?8^apsU743=K*WZ$?W)%72kF_}e%zb0 zc@97b%&=b}WJh6W(i_NAHu|GFX3oW+_|i`5^t1wY5)6m&f`Y*ZTFAZ&&>ai%B`6X zvmTJ`ynd6RU^mSw(yI22#cdx+B%Y%ER5U?YJ(WHXzb-)76P-Qy7LB;SwI<8HK#%k% zP1FBuzetJvx~68sf9U^WAnk_1$Q`F_axi5k1(`Wo@;Y@sbG|zJ_U!}T2V=oqHEoo2hiydhpCF=mB< zonT@d)Q_$h&f0KzfMj zjJc>J5GnF7st%oM@Ob>1<}U2Q6K@%X@_g7B(gPsw{&Nk|&E*W{?AZbamz7M+q_`x>yj3Ar@q9m3>v{@mVolo5S(1pow}_&`<|fgjfI%_3;;395@E>R!H_fG9n&P!R zaiR^i4#1asu-0HxAq0sHT9_8fAazdV4Syqb2D2C%X{UV>mB3KU$Bz&uxq68Cr$3fR zVz8-6)4T#6Gn^O#(FWT1DxTHb^h;2l^3|^0(-&vL*#k~tqDxrV8gtpsateKlMNCAr z`fE+nbYHD$Z`@l)C|G&Y2?3tw@%4wwzW051B~Y2la$m{d%WO3`Z zOPX{Q@O2j)zH&CW&!Wp(L`8%Yhdp8IQMjOB*TpEYHLN6Jv$&9rH18fEr=l9u7y>>) zzi!7gaDmFwQgQ4AM0Oabbtcu7tRxAKG=er_I!Xqklpf#C-FtztQxfbNsxqc(nTLQ!dQMZOd>BKFoXBoGW zt9s8htN||=1U7KdlpoX(q)+RLswx$EI0*X#gP3~cXxR7-a5Ai$0Atd zNE6MNjH3I(-mUMYn)38iS}x&Q@Q}Z;Mtno;)kSH&{XO%8$iB#NT3rK^v^@5TjZ$>St+a@q~YxABw&;eM7pL+6^XwIut5hR320T>xxW zB!;Xj4IqLf=7=E1L`5O?JHg_|=j(&0Y}!+r!NWJz2zeoV20$kKir#srrCfFB2}chy z+QqDEMb7I6o^R!NmMLp3eqJJ!o27vFUdtT{RIt4+g$s5n4<03N=V!paesIBwd8tC{ z`jO^m&D_?Vytc?l@e0viD;@@w{R)~iOP99d3+h4Qr45M}c|izalp7+f;yMYnDpdMPnTLq)Z`I{?;;r)~rH(DW-Yu1g9&eHGdb@#Y8~ zxo2646(!6$$>q!nI9Z`QS4SU)zuX*^6>XVI%B3KB)u&z@;NB{x!#+-T_| z)MJ%1CoaE-K6%3OjiLSiysA2PlTQ}2_sFy!9L-L{fRb-U7^Ho_&lQn0aE^Z41WHa^m79%n(L_9TfP z|L|DpH5uvDn<6@!M>$!MEfvqST4giOjsJ%pjPZrY3tq`0lGMBHxj8ns#+EWNik_+C zvGQ`GRHlGT@_Rhm=N3+$}Qpi8l% z4EFXG0Qv?17LxQtX>DL<8y<9Yf|~6BjQyujC_n6pUa=Qwj5a`;6z_uvb0FK5dvw3X zlZ$p>$igDw>o?M2RCF{l-;>{s2>RL|L^L%ufzg13a_<^_LPo?mJqi&|)avQYwtCL>P6mQ z+$A+W)A+Gi=Azbb$%SWL7!3M1SxN`qJ19S9Y~yz5N?vouQF154AA6a3%eNIH0;pTz z0x{psC*S*;vbXaqek3^y+HLzH)v#|vOuZ>9njWo6KO>)^a$tjLojC3W=#@y8+Gn1kj2#T>lA z=pX~3p=oV`f4wbe4d0ww3&BG~O^;io#bI2_D$96)udcK9U~<_?Pw*!G=8G`dDw@P6 z&b@KtJ+J^lzuf?4_ujChNOd2mK+jZUUYDZ7&v)p^DA&8}u(_eR!%t59TtKUa8Oa73x(4te{`~)g6Pz**3<%xf(frN5SQxT%bxMYa>xH+G~VPwPd z{Hb1UtH`IVdd*t5qqtS>0U!0V1r6|^jSC&Nw3 zJaNn9;g2=N}jDycRj@Fr9E!ZQx5ch1mScsx{vi{`FbhuxNi`zltjf{GO0Cd=z zFNwUcvWAAQuDSMLwuKw+8Z;bX!+I>N`=`Q4xpZiOKe^YNV)5M3H-}LsA!X4_)h&cW z5HZ@=fIltzK_D%0hMvvwH#}xJJYXO3WbX8Zl$?QX3!zd!?f&Frr4DBU`=*43&i@rI zzXh72djb*KM6~>VY-V@4(UE?fDBQQ!->{|DI)nK|fZkAtA>_`T6#XB9omO(=NlUBEdNjt)#07-?{`2$CeI4T&RmgXCO;9{!v(rIFj zgT>}#sRMn@_&T{k;g60}uh|D9M~R@3ZBhH|#UEj#b4OW_wWvx>sNG{~5(RauY>3#W z8$bTROv#c|5G<7TjJ4k^IZkxs9HZEZX7VAfE34NOBh2Qy^6>J~LQ(U`$k(S9c7~`c z%E~EH*!@LA+TWvvwx!4Ct@gQIYI#3@e<|qKpazrgw|@nX0n8m%%5%vzK9@F-eB_P4 z2KZ_rJ@6VBCQNP7*TA@=B{Vda&kpHGx}9Kj!6C)VYl=Q~0_}bM(n7#X86d)eP>7ML zm7Vle69IAc=yjMTtb`UI4N6GU1jNo$AUU;JeKS;Bh_~2JqtfG2d;Y?5NET{J1a>v z(0tFpN2V{uVZ3@ zBQ0-=*9dMs_uM2Wt$x!CEAhG4YUjiXxpYA4$uXb!^|f zXKATJUe5=QChiasQ?3hpWo0WsR5Y_)YT$Y$4kbzvgRRG3K@dVv;0#H*7iXvKK6mTE zh8#ju!l?s!t%0Dcicc9!B_unaH%HeW51R&;JNgqnU(FRv-@GVvRQsGURT-Rof$M?U z{slK}i}?#y0Pkol4F{l5U;2Vk#S&>e#iB)S&~7?ajTgeG-`I9XwYcg;R zVj%R9)2Bbm$^Eb(E_&YqbYkgOFCu;KwBToHGE~8JK-=jwNR3UT`6q$$+@W(IaFz^ zdc0l>uOV|ovSuH|O}MCPb@J>ULZ@6T z9wufUnUHWO^wdToO*pL@*q6)_+ULTTbEojMPcTnS+Rs38&u$0Ixe4ovS_fG)uh*uj z;Sxu#?h9jmNc_0o@vA@jSbbDl?MZ@Lwjtx1-uKhXDl&};S(m=3^U7`l%2zq3IM zA_(~P`(7?5%RzcWF-ME+5!OgJ@1XZeBLVOkNKS%f(j)u^ppkpVx5dxzV>fHb73bqi zhWhZkIajX1@#C+dV?-q7Nb#blJ1&T9>h-$9R;+*Zd6la6Lwm1V4Yp_{Q&pba7TC>M ztKIh!77PPzLJ!7qCjvE?Y$Azb@BqX6$WoDd7{6Fe9Rp_5pXv=>Bu#K^3i|O|`J?neIk> zN`Ye?z-rKXjwS3$aA@xukSs3FFsk0CIEIl1`1B1~XFtu|%(JIYXs;M~v5qd{_|T=R zOIn`O)NKp6aY%8iS7gWIqGcPIi$87Ka@Ww6G0fvM6XU@{qCN|SS1)4X&0NF(nq7f; zucvOCVX!Q%`R#=z5xYvnwvby0ENI`7IqTrqJvkNCe?D9Ml|#tkd>yB#Bht-P{zs*6 z3LTx=`o+ZNmVS?RU)Fek*1m#!0?u@Wm3qESLRXbk&8$8NByK%9b1FdvSQYkoj7-dt zB~k`Cu0o|=Qg0WlI>{^~V^fu5Q@7Z)6}Ts#3cy)RV^A zS#;*le#+O>)WrMdE6HD&o{-SX^jb6~sIm*5N}uQUclfJlFO#10k>IeCHFRhIMv3*r zNXnTT98e&5xVwu9U&^R(w87E`ep_-JGl&pW7m--Bhspl_VJlq{>l~&cR5+t8Y zSS!5CyvgdLl&H+B^CZl{%*ZI%)H@`k5$OzKY!e=U7nxK%}h+9c+l87)svo{ zj<>42`)<>b-aZI_isruFXsQbFem4+tE80Ho+m{D5X8S_Xt8y0AJjy4sYVT{LJgt-S zVc(~kA@Rx`!AXAIA`=^1<~p6$rKAPQOP?jNm3=VGyJ2f@uONZJDVS?l2e~@1*FC2b zZIzow1y~Mw~LEoIGp$GZK0Lzr*@;)o09iMJv5g6 zW@!?Cj^oVsnJ9odwo@sNW87a%;IVS^hy&zF(|)Sv<^s2Qw`^(UL>~bg{Nx?ey5b#I z*I695=IXdE+JZ@faPhJS3j^{E0;H-F9XpdV)wa+_3WaRdMg7onlBIJQfY`D z^jZB`KW8`8Xb&HbUWhTp_&z;A;z-khH zy6WV%&aQ?vrvjoMJ@PxH_W0a-7OGC`L)*Daggkx!Yn#b^R7*@{7icfFrYszGnv(ZT z{joNM#tYg~FO^hQ>>AgU@q1Bufwj$@n5!)%C55Rln;t105Y?;7J6k2ZppGGxio} z#`sls9jf-K9nf|L$!^M;8+XfFC@dysi>M5laePveeoy=Ig~2XLr^B1X-qzL02VA>G z6JGq{g*&aAg+%}KZff^_x=Rjk7Xv+dwf?c1iBG6u8ddpyGbxjm0qpxcG9;!UmWZ{Q z%*>zZ7pxx`S~!2`F4Zo4dSa1xXmHLTRpi$BAT|WjD6TpaSi?oA{^NQ`l1E4wF?_Ln zGfOTOE=2Wix0a!m)wra{ovy`^o7FJN38o`}B`$SR?{{@|y^Su&OwhF*(_NzZOfcnu z4`nQb6$pf)qN1}wedq)skOWECm|-vLPWD!V8wTl(cis~#h+bE0lGSxuE#^2amM$VH z8ff5`c=gyy*aId4)k;Y@YideMPe1GEDFk z-B)d;gG+=`9UUFt?#09(-V)KHC&HdReL6iegM4NG9ke#&Hmz7kM)Bhk z2u;+m(Q&&Usy}mz>$9~xIt<8Tq^c|N)Alj<9=eE~bf_w+ zDc+k?+$D@}?pxW4EIrkCZoTfp#q=cir@RzbE;&=)X4=|8Q*ZE5lWX@8Vmq?bK>`Pp zKI1cIqBmQ8Z@QNWIUv!egFipqXBc;a7WW|NA& zp*hm=JS#nY3^@!YhP$%gHrJG}&!DTKAkG)rW3`%F8myx(N~;r7Gqy{z=*}#nBh!`6 z3YJ@^D)UH7hT(aoV+g|=D@$9Ef{+E)yKG5f3}ymb85T-@tZ-g`s(^2Iw>*^S|GD_bF&UTdr4fxA0YCQg332}x+^JO^bDCek1>iZ+^KS9 z<-*aLwgwXNizPqui={&mg5+1i$a0d9QH?`es~FO_9*7I!L>H6s0@7$gx+GWo$oq@J z&yUAgVFa4`ckjM3B6op92$0BV6;j;DHLCVqd-g7H=4s+-rdB?2ZcR@}<67dMF14|d zvbQC%MQrZb{(Amj7Dz7o@eJ&93}mldgsAMZ&0crH;n*_g>`Dfwl;}fHn|A07*9(Z` z&mDjD%M*}x(kM_l-#+({?uu-3+r~4<5j*s5~QNr3rM7&dIUv>c|Nt5{gRqR0DS6nzk| zPqniw+*s>sYhN1xchhxWj)exQF!uSgn(=XEIty<+uX4igpNIV@&x{U zK$}l`nhvnTbTrCPR9N`n(ZvgB4dvy1Q2Jko9l(B$cdT*LNccmxp4eq;`*@=H77C)f zF~iTm{O%S0Y9ay|c?%)oJ`%jm?TQEer6_L^iAeFzTW5T;(RZgHEq&&h{W)1#O3KP_ z48WE-h%p2e6&P1+f}#UTRof+K7Y_{&gTxe31twl7P!N=TlWJ*LgEwl%rLn85tgJ3Y zli?Lp)6zt)DTO6K4FD@i z2G-+3Hu3`-zTw2-!_;H9>C2JxHZ?b6JZ*eEx@!QBz#CkmEU_dBywhu5_Y)F)!k1nq zs6~*<<2_>4v5t{0?eAFOgBnkjAhmJhNhDC=;oZ<|y0#oeBwM%eZ?D&`$a_J-U z_q!T`LKj5mC2c+X%B=RBFI)e1lT|PoNr>aN0jXeB&uwy2#0|>;vW?#R$VtxI->6Zv zF8L#oEz?r2A7~vMtlE*8k%3;MuGYfsh)|>4yz6zK0ginaseW}sW1{r%H zc?IVkBKxng{7znDfojLdA%ESibae&O!M&E9z*Q&wp_8WiO74W5Rm-~jC2RQcLO8;R znl+W|(8;zet*!O%?>=p8%uLX(9KKHY!vswovjB8oSi9%u=3>3BT%kC4;pEAC?(Q!D z**BapHSLEOr2hG$gd0abOVL`2!C+-#!qz%27kuS+q0hrupBEQjUn`})R9OD*#t;R% zERp!~q+~M^NkEp9Wc{>q0g3skpB|D`(yOI049A>*T!U4lk4Ko@q;6XU5-r@8qez9o z>vSZzBM;707(TR}Bc7bdJLz9sXUPN-Q8?^C3+*v26;-6)U-`U_^6}$sV1{~vo7V0r z($F-30X>!UE4h4x{4MgnG@iNCNk5IS%dZ2SF`7_-5uZQb=XgEcm6CqP-1JD_)y;rG zmoYP!y}=!Fn)KfG!*#3!92LMcrKF^UWvX`S$sE@(c%g9-IGm(gnLZ0+{VLi7zdK&n zu7$y`;cHTE^Lk`=cd-4V)?b(yT7Ncb*M6Z>tQP%||C@mIi7zlP&}pOyX9paEBKl9C zJ~ap%K2*!iU(d$Iwtl_Ky5ansualFNw-grIHeIs3r{(cxHwp|s;B$Uw# zZHQg^o}(^wll#cN7_0)@38^v5HvPq4%@&Kpzk5Dxday)jdOx+MOn&mj5uS%YI(#hC z!1u&(lL<(c@pijXF2%*i3k1tza85(@+u6D8xy^SoGU`f8IX7-}jRh+p^*S{IkYz6t z^l3$1T{b7vXON#8ZJmrqhv#ah#8O8tpe4YoF2#9MvAzzoC`mu~zx-AYoAJPfwY7*P zN~zOJq;dV0mU<5E0&mehFz_u9G?WhTDnwJfy0NkB@GTEd&tSNZAhYbZ~Is7z|$gGd*_4wm`?}66-rwSl7y$ z-lI5tbnz~@hv(l?JhJy>_^G5uTn# z9^i{~^!4$y4D56_kp++#{}9F?4B=)`n)`)f*I1a!2Qra%Dj>L#OuSn#2%`7EDWa6cXPK4e#toy-Dyd$0nGJgRX0D&T)u z*VH5l){}7ogh(5YIH7qCmYtTSChR@;jJdjI+ zTiat_Cj-@P!F2;rAw9UJh9jYs{_fv~GocdMWik1~(RMQv*m z>h{>%;{RZ8+!z@CmbRKadA3u7HSr_BUwkR-6C|jLNKiZR&J(k;)Gj3NR@cxt+w}M| z>`o3GRZTV27_5rWM12inhL2@(T$~5rtr)M;>(-vW+UIW$M8=hJY#4wD zdb`8e?og$Ji?i%b?*?^sbxc8I&}MmhTH=`A4Q{6F95Ax79irkd^wc9Q*~yxt_UQI> z+N`znheKBe=sxjVM&4NDoUwwr&X4Y#X6dWu6LKzm)IZYDZ>g~6+a3!HnX}VK%70KO zv*tBvzh6W1Jl-auXoGeE$e7Xbtmzn82D|Co>j?cIQn-H1{)7?*VZFPzml+sTVxyD_=^QQ-^DLKbBGc+jJT>oMESo~3EXwCE3)sc;WSF9J9@F` z=JQ!FRbMnTOhRxt4gbSZd6Z}m!QqIBiMg}w(SA_F&_9lf??0in>&%(N%*^r4cP?%? z^620@mtO6p7x(jO0(E5>?nr-aK%L(w*t0}y%TZ2J0q1)jRi{N79J({=T1g6d-?sjS~tDH9c6R@7Z%1F$fKFL>XAn?RS)#=?(Yu11(F`Vak$O@AJJh*n;K4 znb>0P{mn|R5&-P*zzhD7PVdaV7OilR29|s;UYv^GtER@p0cUlE{EH3_sPR$tJWoza zNQg89tU8~tAOC>KPPz{-11%60&4fuq+ST|kIK3A!SgXdimnTKb_Cf>$#h&CDi=IoJ zodI7o>)yQa2?`QJ*FdBO=x1#Cgjy(gQ4_e|h#5&pPhti}EJI!SRnjZXSD4T`=IqmU z(LB6x()*Me-5Rl>H;4IOPlQQ3g)g|dAUrwjTWP^BlUi$GK((=I!Ij?VFOaW3*c1Bf zFsQe?Xg|24OYCD|Lb29r1VC?_`vv)Md6Kij6SdUYMjoXukt<@<2m`C5m6FsrUeXphZN zqXajzIY#$+I4jM}e(m+wgS|+#@0P;}9)>`JJw0j)3cGv$DS`j;XPyjVy`FS2u6dM7 zQ%ZMqI5(+y>rQgsSS_Fj`z=^SPomjyW?L|E?eq{f+d@Xm$J!OHW@l%k5PF=GQ(d{6 z5hFK`xd7)#x`mYd*kLF_7M7oZkt=G0`-dYQ{(tQKcRbg9`#+AqDkBXoBtqG89LI4V2TB+8a>nfnW6Nb$!8PN^;wSfkPRl;tktuVN`mlz0Yc0P!AD2?I zK<5WEu*ynH30E(SWZYd&n33-9vFnOR1d9=)-ts;#PRewDR{QZq-s1F$4N>Be><;6( z@@@boB{A<6MIrW;$)!v1_Jf=^ARA-KuuSsv51R$47SMD4v8zHvzk2g1jStEQaDN@f z`|g8qj1hy>snuX(-YU4aFcl=KqgTc|B79s!=txbjh792umFxfwVkR{w9)|1+62BX= zhNLJTF10i|__TDU=XzPo!*d+>{pn~-+PUr(ky+iZ0}+lBYyH3r{zM8^EoZueN-j74=1gpV4$M|6QTu% zfq|#sUznVl`q=mWQBHLiJJSHwB{b+q(H=PaOgB3htInaRs;s&H| z0MHjvaqvS3VYQrZ^x^elANCzP9!=0eaM|u!_&G!&^kDQjT~6^)$iWEvr6Hwpi)*p+ z>!9R4fN|7F8Xyu2JHJ5ECng{u3ok94fF&exfI-fi1 zlICczSL>J57cky3C7qT&XRMR$>9CDb@79_wE=v2q*b6$m#nJu=Bj7gLDypj&<1Kvwqv9A1 z0b7hA*~Zktc1K^|MzlQm)siueUR_b~;0EiDZ&&$z$0)`ukB$@-716nl(}f%*!r-kB zH){{@YWe2eJ&6g+VJ;{))z-IM-rhZDal`VK&%@7c#lIMmhYZR6Ysr~Q!iLZow;hIc zxEwG139`zTM7L61eRw*KIEyNtZ1HlBkyNuAt7{zQO5Q@pa{Dq+Sd%o1Crh8q?yOzI zW_O64m3uptZK1T5iS?I#yY)B|>o>ODb1#3kIn|+}H6D}2F6}hB@`gpcOthf5^R?CC zIV7)eB1&C|oI4Yx&WHxt`zunDDqV%n3WakK$4hPuPN5xtuF}vfFWxlxitY1mSL+d9 z>B@|)Q?KQbH@}kB*gH5RW^b)MG;l)7D@w*yDv=8?nythIU0s*JO{oH9%RbX;EmV%O?R;Vb}%`xU_|E_C5&+$S)`eYsEPbyMI*NsoRobqMB3czyYe_ zmJc7Y?N}5(6x$AM&HE-_>W>W^mvv^@XfzBFhmwMWUuy}}jEmjA%3*#QXdDCy<;sY=3y`vnuA z*oK%w@`Lf{;JHJ|Sxp7Uc@=MaWi{1_4J>F?4%j?!pU3F#YdU2ja*EmQ_z10B3v!N!O%2R1P6hD`Z%lYsn4Ov9?mmF_zo+ z8i6jA`-n|+$d+&Jyn*T&RvWRJISZ0~E{k#Awv>^fm2zKgbM0xw8)<{Sp0y+JB9p%@ z#c9j7KSGaFjX(1SBL-sEE zpB(9D8`_LS-cy|W#IIyz*mOoeeY|+1R~_@K#YaOA_MSYLIna`a0~rI&{BZgXdif0> zw^?q~R*)tv$Csu?cgmyVhBB;#xwQ=qmr;Tl7#QrL0NoNfF_$iw0PWN-?QXpVSzYp`LK8YZQW+!iG?)*ufS%^o z7U?Z}%r~f!|7csx_8l22z>5eyG^l>dA{i}lr`l{^bA-W}nmm#3$}xDy9b8po{&K!s zZP)}+3-grkS|Bp%w}02s1@qQd5gV#k@{EZT;kOdZ6qbpd9Bi#JzBs-TUDNiVi$+EP z=|}ZOa2#cx46U`Q*QZ4my_=W!Hf@CZ_nLLc1fNw%HE`S zg7Q4gacK!~y$;&MaZQ1;S<0dD`$2s;Z6@37gsv&4EjvmyUg&JE zwYFC!qu>4}C+ASzvH# z;y#?rL6bRfn;#umVw7(nhmYS4|G9)g=fTnoC(2LJ@hRjY8}Rh<3i{L?hdxJi^yVRt zMme;97N}gM$eHtQj_DBUzMW%snyzqmh7>=ByhS3sj9LutB}gYq6-0Ce282`$WFK^| zu}o?X^19Y?IJMXri78HEvNZ%Oq48pBPd7va)7i7gKJ&`?Snj{MLt~=C*ZY~h{nwM% z3*G9<*hC~x8Cb+j?%f`6oK&64OlP1K&NUimtg`|qL3E9gwWrpn+=9jYm2~Y}ek(V) z%#{kwoTx^&_t6aSljHJ6Z`-#}ah_yLY`9|kVGILNs_QT-{XA^5b0(=5>E%za@CMKN zXB3nJJE?bbtToHukt=&#!jF_22aE*Y+ zK;-^D!%p2w?pqAR$!L?GJ0Egi?>_AY{*@L0y$$a|2_{{!Fqn=c(yY_L7@pz1*C3{A zzmasQMr+&LB}A!9A^zsHbO)W$3JZ?ezx<0*ce-UofxF{M#s2NuKKC#a>&bgxAKIks zgGmvr7iE($B;*|;8k}zx4G(>y%XhaXvPMGbCzqi=nI6`cf26RHIX6+{mz!MdpuMCB z)ooCiS~k36s+yWk8ybFAA8%O+qMWum2i)?~a~ZnGU#W%Pe$3T-rbopxeLHeddNPiG z6dosaMbYZtNli%BY0@~nWe0`5mD-m|9sMGGMR}9c#;x%c+vY8iU%>fW5AIVtpWXn~ zZfle9^+UaBkcV~9Y?^&1w)v>(Kc~z~5>i(__a(x~^XLq6n7kobw5U$=avkaU%IS;P z!Wy2@wBymSMZiMEQG{Oli=OV!Or3uT*(F7mwaM6t`tMuaRFajla)##f|N9?rCD{iD z#w{XMuTL{3k;?BC37lpt#UO#BlEMX~UF&YslS(`XBj>dzeTP#Qc}o$^tiMMv?0q`% z){yogQ!HIUB6-gtw~}Tc>96qmAXH`270&s!ATcppFR%?A zfJ(n_J?~NlXS6>-%R4L|A3RMe*iN!%oPJkx2xt!rghZgF3&igZHkdbx z0{K9z5wV-#itvjrCi#iXeAhJkTJJ>~B*uDZWK*3x|4A;XS)Bc0{FxMhSweq>y^^c~ zF(MP->U@3eE zFnzJHw)XJJ(Xla<7Z4YFskuFPuwvP=JvYJsaK3$e0#h56geO*?!DtJh<{C~!+r9>1 zVYUB$fR5<*qh;-;j8-m<8x_c|4ou?gk_QgtAAc2zK^H+m(%!<`Aj<>cep~@j1O~&H z(Js-MgWhmKLBR+YO(!rB0$epE%G&#jsei&^2k&yq?QX_IA&7lC(aywh3hmAt!>)=b z3r+pQ!VXzw?e#b7EP}7w#v_lGvap;|Rec)=vgI{f&T*H?E0P;t?)EAK^<}#qjsTeZ z_%|bsnjj14-#rA&#gCgn&xon?S^{e6HXfyG!D+8IE|$~7 zXw9&zKvz)F`bf3FF&qsGb?{TItVZ#SLfcvvQ}_1vA^}m*hikI$?#pN@RfnM&o0OcK z{+ z@4QfaA0$HEt`@{oR+y4{)sS*5PUOoE~#YoWZoR2r-nmL zBgHWzLu~8_`4;1D8w-F%BKigfEEs=9xaXBsFhJX+P=(PG1P)!G?+g+&@KdOxzR9Xj z(sl92`B4GYyZ)4cL*V|c_I!fbxk=r!jecn5L`#ciayMeit|yPt)mgISE>efM?AqE| zjOdDPn1?~gGmV=J3z+yKojseRy9RSkm~9X50sCq1-nkQ9QdWD@&7OLej`&asui0s& zWn;5TL;<)B`Sp|jvrYiVz#7%@9WkT6W*at*+<@8kw_)flge~w5W3$^z=sXe=6AL*$ zV=up)*~?vggq}amceBS4lpEuHkj`mUJu1}cpLE0@-cna1raM5~I^XTHZgsM$-qE8= zgWxm_;H?AOXgqeBA99% zHX)$_JvNXtbzSkfneq;fjy1hkF!n(BD_jfFOw?~o7u~(vM+U>pd}LrWR>t+!aKFnl z?+aCaRDFYRSA_g9rZ~Tj88aA$!!TZ+DH1f91p#1QP8=)#4^Sm(kPX-v%eM1$9X`k#^vieU``wtKBFJpQ58nDk{DLX&e_wXvowOK$-Yuzn8v&`O@v;{_FD|!sP-yC2ij@5y%lB z^V$Q{KP@c{-s!{Inn25WZy!5%j!TxHN!E$FczH>Mz{AY!Cd}SS!lE)JJ!RnB^hK3< z!$}dTm5G+K989g0Y>>)d)iDEm84g1*yOke?iDCQenCV7?d`xrWo&Sj$(tZf+2skqb zh7l_r%MKKk2R;DxDSvE{<^rDD`re~}6R$Ok5=NPvjwuar4pTNUH7X?Btx7VOP3jBxrnm>me9DUJh%8oI2+DVi;~CbowP}$OEp~ z?e12y>E&V)>vb;5mohJurf5S*VMqi=VQ$Hp^2$mgsDZ}nJ@{%x20W*sdakao=MkMl zYO)ySpe86?(`DNCGWKs8Q#;W%S-<+Qz+Q%RTjt7&!Ow^Jlxy??p3X zWy`e$`Wxm!;Qs#o`*EpFuoZxmp!yRO6GvmZ)s+w%AkF4!s0AxH%)8v8gJxk;EhgN` z?8A7GX;3$<2%xUg4^a2T&!Dai0qS0xF0#$2_r$1kb4_)~PMrMv^r62}#ZcnFfy45? z3~Sc#*sc{I*&Fo9(h{UbnWTdA1l{}Y?$J;*|M7!BkJQ-A*!YZ{cJVaJ&~A5z@uxc> zA)jFQUM%GT<(oe@gvU}5X|@x|rz=QFx5A@Z>zG050i0l&kJ(o@kU;UHPWJb|qP`J) ztB+k>QWu8$`uye+a4q%-dbYI)6;LZH@K1b$iDtKgnpy)^J1o6J%@y83jA_f=e-3QX zCy`jahh!CVD{QfpFxe0cO4QM%O*ib0L6SKr?|0&zJpuF9pXR=@8<4|2WeH112Zv#y zh5b{(GjIy_{-@vx_xkLuLmhCdsb8r)kF=v`E3t42?AIan#;C>&_~rMeQ8INZN`R4A zR9qZ|IT=3DrM0zI02VPhdyiFCKxE{d{3MK)|GF>+Ks` zpHNojKJ*DOv39)5dvAvDk^hjivV1`06v9TieFw>e`O&?plc;EcPoma*ASXXY!mod>JXTHNxL;`~0Z07t@l|sCC$g1rph1lH~8-oXT6NUe?5V z$H4wc!Dl{&>yQ62@?>6goF`s&WfjfuwDrH;$d1ia)b^3{wl4n@1@m8BCAhi0kN(W6 zti6Dk2bR(OU}fFvgKy+!ilcw^k&&NFEun@&(o?EX0hbDV(kAI17nHJuX;7&`ibvr` zV9N*Pc?I3Vh19pf+a+lwjfoP#SBx}w34R*fEHf8^myPjG|NhA$?+2QU ztrisK5Dn=SJVjVwXc6Ro$`j}pG|4I|DjkRI?8p$A;U}&DQVZC)ab7~F4=psY$>9xB zNc)u`Xu)k&YpAI)tC>NKYNmVpsmP@kisO=P1n~I^IN)1MtjfAdgRllG37#!*)`9E_ zJvb>|f+Wn{MsvOgthXG3%xVicVD+cLL6gpSaKJIQ3q{WGwi#;Vq|gjCQf7u4SustG z)Hl;YQB*EtD~)SZR%ZH*4@q@3_DccVZPzZTPyabJT=esnY2z!nV7}R_5K}Dg-ng*? z{ZB8$^p2Jm80W8|r#>cEJ-rTK6kHi+~yw5L)A_TwYOes9^b3G}Vqp z!FzX__;}6q3#yyxyqY)w4j%O5Ch}_S3kK#pkVez196!!3x^6xUZb77(K%ok)*x5o) z3Fc3A%&o!#8d+B{Q`6o(+N9%{&$R=NhZR#TwrKl9RGW-(KMvl@w;%K8_m3HlK$(P4NoDAwZFmSLm=tJi@t2o zUhb=%5%S7WSr9DaoebMy+a2HYV)K8jzdH?nN__QepWj?t zSydG`#oV;pCoV3IvP7)a?&-HLU%UXb11!gZj_DNu@-dw*oBvE5^O246U|q{TKXj}C zV|1hnA!KdlfK;Ci}|)_@{)`cYIo_Gi>JcJz-5uO4_-3^FKr_Z)owFr?OPgIaSda zs68b55R_|lwsCmCiQpZWep(OmUVY=sHDwbLs(kY%BstkL`C@y?I-Dy=vxK!aC@Cuo zpDzyuL>?>Oa)5g<$oM}drc17`UPDTzeS2_97-8gIp>OWD1QTZDU~Ge+3r;w6LOmZp zzMeb?5zvRu&V2HyEhy5mvc=yT?R?!?HPRZIf%t*XA?R_0nDL7g?!`T{`N~-i2S%!a ze(2i41&Sm(6+wFGBOh1$3?tP7Bx3pE{n4H|6?1Q}i{xGPzw`1W$abMIK2OSTrA~H>ug_kzakCrCQVhXGO zRf19UPAwgD5R4NqG-nAl$GB@0@Mvaq(3k>q39SZkdfWExQpKhUdU{=WtQclXjcUP* z*`H^cN!YR<1cLR+;+~^|l7kZL|J-{0EzbX}#`zl_A!+dRi_AHGT`&Kjm?9~86I5sZ z*lVRh?zNI%=2E_KJtz3j^u<4a!gfKy$B9ANjmP~huQ;5^7i9W>e9^0-3)CdhZX|3C z!g^v*rbFR*NS;yy1XNJV9tN8&{;zJ~Ybsw9nuZwHG&t`;XhpKx^=1i%O{?&3qC5J!7W_=jEAZwa~XW8`f3VaaH!3zM> zBOu2M+B7jS0n8r4&q6{%cJsy!zgG~f=e&Lm+xNRXX-}V?|8u`~+tXgO<`kG8Vnk=& zasV{~AX|b|b=AoU{QtODApFAjWpsF$Cmtha$HM5AC0*YF78qeCiIKzPfdYQ{D+_K4 zL3DC#1oba=nD`U?5h#R`j&N?0gA~+DbUh)5S@x0O)`Ml@)@Ae!X63Y0uI$t2^!nkuhrf-m8C%<@sJokWv#5)ZW zljmMuD(Dld5n}+*pMl;HUJ_Ik6v%5F-J{{fhgLb-VWX)yBhV8RwH<%t`_QiwoK6NN zCMz%x5;m>hxibleUwHzeEwXTHE33-#@}r}OJ7JvXho&SnrLjD8OlF9mCr?(voSiVl zMGvIAfktRW+Zw1|4nR|W*lO?6_pna_XA9(93@%Y{m4 zP!&sT*msQwPH;w;MSg4pYT$Ld5E-YlOOqiC?S(0Wg4C%~Ed0`T|Mf|9t%r7Ua_!Jdj+%mL>wl|S zLtg%YlM{909C0U96Mx*jd)BFELSW&gY^K$#!}{S5a%Xt1*UbgUe_`Z-P7Pa!0_`?y zq!ZoI(`-5Y4-Q6mkp)40UUoV*8$2Bp4hzu`R47MC|JGCYjV&=6V@l9g`Lb_f`skq| zmAFFDLsAJer=6Dc{IQ>D@igh3)Xw#Dks8-K01b4*7|nyc)|Qs6B_Kdcncc3@XE5YK z()x7x8Z}D&y1278GlM+*6V zmZ2j>Vy%jX+X}bRz`#7Oo6PVS-`@tmTgMPI+~RI8%ojcOz8AK?IkE%=OdY5_K**yW z3Iji9iWW~z;2pHfc`|%oq?&>@6_jB1k&d?gE*sGn!%t}Nz$!sPv@zWR_%}(P&;KCl z!yOSV%)@9bGpOrtjhUwy_dUUTP1(kB=+6lrp*l%#SO>}QvDrRoAJ1qUk<30^l`JwY z2jt6-BQu|N>VEF{{c=B0Vf~fx#Ekl9;mJX4;bH^nV@O`TA3P{S0c?4gkc;H)LCuCr zb%aZA!D95eeDbt}FONPSwjy2za=OBz*_@78Z$wV_0z-S1ZG#K`yleYv7SA&KMAn; zC!mu7iOMD=d%DU5Po%ECe$7-D@^NM5iBk?&1BGL4MvR^YrKUdKy;jWj@nNDj7=nH< zY&{{Pl2cbVj62eHJpxW1;NGAO%6!@2{CQaR+>>%O2A%2r=7&6}At6x29wu6`XzAr` zd~nlH^=P{sB%62d%9@&PGyMcS4ghIO53NZqle)6<;oDf0PgrYv#lZweBYVXC5*-7B zj<$A8vG?BT+a>PPgn9S_0M+(+o3Ov$h1yU7lw9{O(z(sE>0JANoz8I>EndOHudE33 z8sLrFZbo`+H}p{rcub^k6~Cl!m%kx>lj%qLMrVyV7JK$}wzTYxP$TlUmGpb3^0&oL zW&|M?DcPt)Peh%PuAzqPM08qZy)sgakY7H1Thh?H4A7{!tiwZQ;=W01_OxvUD7{!? zx@un2&<5f;G*;C%6<4gLn}mj-(D_6=8fDM415+4WSJXZGAzB{1dQJ5%=Si5CpF0=E z=DmrVJ78g8*m}UE3IntJl0nGL6||wJu%nya+V(?PpYM}M2cG=0BW7WH?ybbN{liNk z6c?73BkNU!$Au^h7t$H)Hj8=z;U+fSt^jCz+Yd#@&Lcj=e#0+s^CziBO{R?JO3sfZ zS=K^G-v0BlpLMM`4y`42b=S+azIc*r6)%xUe;oMbDIzD;o7F>i?!8sM zzh`T+Uum(Q5^A=s$G~NHJ8MAJO6A6fiXj z6M(|}&wz9*%TnU~GkdFrW%_yBg|GF&X1(@8Bm~{!?_q`wXvG*0QP2p1<|8DF2ucP79dS#lY25>Eg zkPpa{PRe>9VPk_G`z{pZ=01XoJS60-wDjU2^)#!8w*qwR&cj`RgSX(%z&E>1apre% zGC$0BTwKKCAx@5w2kp?v)b#Rq*#g%$8A>Beif5`OXcRO#Puqkgz%796U~S)CjQq|w ze%Ew#9gMbvRm=6yH{-Qcb4|e$9Y_B4=>h4aot@nfj1NrVxQNlO-O))&mVi(IXZOpV zRKaXiIW++HXPqz$D~=Z}3j`&=*^OeCN9043!PGx0(H$KYmY1FF2=jJY$bD9=U0Y0B zH!k2zh!cov)J#!DMFa?3g0=mvS;=wEjQF5HVuEmN9_FHi5(F6~jcLm_Q(_~OOQb)w?hrD2$1w_)8n4bX0yRzZ$-ZM zPuWQ9N3gz9HIp`A$5E74IC<%mO9_xRDD*GLcHwwX~Bpim3U9MP>EqfWI znSu-^D&vUvE8(A*VyosaYG9t^#3?}h^jvFXpYwZ!Mt8VRn*j|1zsOg@_k+tC>~L8; zb&V8isN|1qEJNdPsH{S^KE?d53`SooTLp;HJw4G|PUw66hJV-hc5lVFa$Gr)>CfiC z^XzPJ^_NfQ%=wSGSMm7&M()LbQs+++-4yECl8fk{u@Mc5=G|Unke-k1kJ~F+I#zMEcoXf zIj-T#Zkxe(l4(|7u?UUK&0#K+=;gI~?3s;>%$;Y?Hj$0TKbPrG5F)nznqJ&uhDHpX1u92`M`h2>bv5g4UNuWCcT4(Q2m6Kbh#wvZ;b8m*p6C(YZuCM-n zZT(1a{8O?wa3go}q1Yrcb-g0cZd-?Lrgl^Rnv zXX`;wgpI(3`WNWRxy=H!p#GEsaSoqhU3&lcz(67Cf_*!9oj_?Xgiq7 zoz9RBp#_69VJk2nLab2QHQ44?G?!%W9UWVjXC;pRZN>i=Ut&-HMuvIy(${+)Y(B9D zeA2LA3ZL&!yj~(#G@z65>)lY?>{~HAVl!HQWAJ{y$0kj{`mo;0F)}B*9i{I%G%q9@ zwcUz~GuGGd22iP#FGe0I1}YRbE*4O3y#MSR3{6z5F>Sh$LyMJVBBFRncu|H_ZR-tO zoyoFaHp8ra(Nh8QTj+2e+6_~}A4Ep@6x1T2QM5XCY&kh~8Z!P)wsZ-3fTAky$uh1tUXQ7l}CY@x@N~k zdtsJUs}6A?JH%iq)SRx%r+s+_oO9;wMY@Sp_=obhjQwKNFlpd4H?ld^cw9{%ewGEBqHN#JuDQASA6c6vN^rqJu)l=Ju?NIrQbmFnl zSvjgrcSO%<$Hh4uv5P36Ahow(d-R@v4}IWS{d?V?9;6(xSxjnQlDLkbC~&Bakk-gD zUF-4Zjw?cxA-sFQ3@UMgv0)#_9-X+Ff&x9*&H!Zwg8+sffD8NvaR34gAJ7B;JO=GU zEdOyZd$)NU0sgBK@~2+kt(Lo?U?5FGMqcK0J8)8$~C8L^L>Ijg91l zDnoG>E3&~$=H@U~61t6dG(+;_oIqnh&>j;qfz?*RVxxxKX#(X68lRZSWJ4s*?x1-p zp}LVev)gXcMpjmqiTXrr;2}622nqoF>()PW<^#r@xqEuTy+I^T(fxcmZ z_ZEmrC-LyOBq_Nlf8bA9TLJThE~)aim&& z>&~5o$y&Lt(ol8uMw=(@pT2u#s(m_Q4*~IF=qTXsIGbP0u3=UJbS~m}mJpLz_bY!nhBGN7hI54nKaRYqc zg7-4G6%@tXPqkO@&&bzCWSbk_?GRDwdeTkkq?s-I2{YueFEw(O=|2qK^&vi~rOEsd zEm}K_SARLi0IHNE0p57})@lI_jZ&;u9+YT>I>r_j7V`2d#3Z=Tmm1%^b!!>eqX1s+ zODeQD(N4Q}GF|3GpJQ3-r4LkM^x&dRrdI&;!Y`4Vm)N~POCR?5MZRLirDU<8UeSY3 zM~^NQ+nVjy%-;E8tIM|h(!Q&?d1s% zMxjuxfQ9!1!MfsU!Exj;Y z$uLyT;oE{pGTzK9$!!_R7u7S5UHv29GqWiK701eFu5bR@5P9uGK|gv zh-Q&%jUXp&wEX0qxu=gWQ$o`>qND3(2o6y(i>P2XF|9`e=L`~z4qKd9?Rz|n?)au} zb>p6-=l9&wxN0gq6M1;!Pe|t}58(=A3f_+^ovT?_eD0FxeYFV7+f~PSYXfu64P`1@ zolsuGnw1>1oqBP}mGXmHiYyFCyHd52Pk2i3MLgKraZi$Em9R-W4oz6kPU=M_=^&iM zgrc-!-8?j)PX4Oy=rn*p$aX~TT4T_v1zC>OO{WpS_q4z#mW|=-H#_pTet88lgh!p)wc$7!(rudvgA48i3}SC z{!`Do z3ZrPmSD&l#BA#?X=`p>EKyAb6CvBE%to%4w>!jYP5Ah1lLhO2%mY>(*y~99#Bh{dz zaL+sw)@{pIxj9MjEiv?ne5i9zs;hO8^+%7h(Ar|+dl{iTf?jgo9AFf%dOvR-;|`$pD@UNj4(`@bDPy ztmwj!_#v>~Tgb+;^09}4KEjglE7o{DRvo6CO=gh4kteYRZjy`F_Is-HHm5tBT~2oc z1nX=3j*d;*U$~wUDGmceI!+)Ov2AFDrn8R2rsDsF0tk5tsYSKh|1S96Br`txpOGgd5T+xUd404(`6XYvAz4?EA>ujpx9 zQnS&2ot|)mU`C?@9NTuR+fow0{=|lR69dt?ZOy!8@ufUQ=e!?VqQ7Q?lH1V{8nN-N zj7dF4MMO0i=*jRw_R4`UP7F=-suhx;e*}*_Vul!Qwdnu&{Gx_6FlhR@d%LBbQ5mYP($uSo?-rkn zl^YUPqoR9>RLfVmvt7Sz+{}R?sj3P*@nvi`(*7WS^a<8dVYgqTH_5Tcn|q0~D$9ET zwM~WV-7E8ykmt1A5$RDHf0a8T7x`S?glz}~8M?U#h zRaLz?CFHAc-T*C0G^1|%=Lu#gf8n~%DqXUHABZZ3y1@3Hc`)~Zj2xxtFm8$RZkNMC zzWJpTWP&v=9YX$=XEzZ=jz>eq;!&olW<~&v1S-)R{nlNxmGdHK*7aD=-_pOOH4OrW zrM!aS7BmmGv5y_}$D_w=nDorC*VM3?ocKf@_jT-|_(rd_r|%A&tc>*?xW--Z?q!Ev zB3gB%LIlO0g|(f1crk9zL8+<894K4Bvi8?_;K#1~c-Y15{JUT+UYReRO3r2F-8x>+ zcZgpN+)3?yK{>-Dkj zJ+w%acl;$D#V!!-H0wK*;sV#k(q9k@3Of5xA*FYv{ouKpeK=eSRfgP@#d)od^(3pa z);{0ikNfz@dnZOqs+c>>tbt$L?65JdaNToTkpvNOw=ZW8UT@R5SCFj|tQVxzS}N?J z`mUs;53VNUl)kKmtpgd!U6^w7Grjjy_|VX4?U(C5~ne2yXMxy;5YZJk>SNV$u6QITsM*lwh%dFORZ z!<^X1V*3Pmep!O8!p`eaOh0#zVH5W>jx~v>j4L*y&NZ4`lo!2=$H>y6z$8M@Syh<> z1K31)cF%EHrM$*o@RL@Da>QBRzxi^HfVuXZ?*OTY>jduPkg7U=xm_z|p4Lvg>spG= zr+slv_M}7m_bB{w%I29yeCtMu?zi*IA>s@2bRrDROXlx&m!J3G*Sn)4v06VepU1it z&*5BA-u*)5#$J-i&TX52T^m|P-dx30(G??5^$q9Xe`5E z?;3XHKixNzK<>Hor~mXAMXi7SE|Um@JhneV9Ncem$!zU*;H#2ed_?EBHy;9go+NI) zN@_0gl-wUUx}=Ox{Pre^dsVcVJA1FCZLO@We0CYXWhi;3!J#D9!_U!=byJXeE`P^*qXJ%#iBD_l zT7ySo0e2$UO|8O=HKeiVrE^Gon&6OnWpcp`lX1WW-?Zhq=<>*=*3nlGx8WCFb;_ET z&+^Sd;}gv7dnavwTR0E8j>ydschyDTiFIpM4{hVv`)^t9NW(Nh@W5x6m*;`nGl)Ec zj-Gy^l|u|)e2_5~kS=k)c^e)D#l#A8GnenH+t9qAe~HlWV{%W%L?X({Z_lFAZ?U&8 zJy-N}o?31r|DP7V1kpLHEl^y}s*$qK4<;FK6YY50Lkq*>MfcULd*TVHX1l*r`uISB z;;8RL_gO+j1iBR2`?JkinEmjl_U%;(@UiL)t1fW6@4d^?2q0UPs&OF-XGl_WKKWSl z9b9qX_L`joFdQ>zOIhRKtcu~rFoyRK(9TEmD2clRaRzf@bYaX%^i|Gu0FdTOA8t`GNYX|h z1KGP44rRO#)5_3c=R{Y1D7Pj?zj}$;O+vMU`Ah02PME!6Hm7J-hfWuYT})+o);IVO zt^SPu+lHvQ&vujsp-05S#Z{AHZpc_sYMn-&97DSc5(KNS&yf|TBk<$6_1UI(!i9C1 zEt3+Oi`A!EZ*us|-~AR&ah@_{Zpn)+NE$uW*G*$nF`?ZL*0 z6gyZ{niG0QI4-?LewEF10S&`1UX9}$7meff zqlb+3jR`t?`sPgbIf-4Bqrr^kOJIHzD(Rtt`%-)!7 z1lR)c;0N+Ifx``eX!(KT3JR~H`oSb=Xe3X5D`t8a-QaH-i(J6Wd91_fCB|nk8kj4l zm|a-)O{>!k+fH^^I@9}P3pK9M(sc;d~9exh?g*AT|3VsKJy` zfPvl+rEBI*FmZ2Rs|OPg9I%CVAEckOSd*cofkZk}f(5Kx^;aI4kI?<0b3yh^&om z(10u4o>-!;YDTpm8sMtF|j(cr*8lf_?Wo4%>_hh zN=FAZ94EtWv;xtBdeeNV^xJ~Fj*er!Dg3+MW9NYjB&E)}Z1RzWwssq=++fQ=Cg$2U z_n*`~pU|*w2azIMwBD2SEE+m^2HL~HwUgO)7Er>g{N*xxuAKq_-M&kg`hoN~d;kp_ z1bbYC$&i^-Qxk&v8c42*3CnpLzV&wG2{hzyT`Aou_=-UDc!!2N$!^IL^;&z;EQ0K$4N*(KwadqlD zXnR(%i1oi(0TD7zJq*MFnX(%e0FHx&QA>AK>qVuReK|)s`8(Ee@$kTNQd|DnT@&EH zL}A+q0hN&Vd(&mRt|-OnP`=^4%u%5CAe- z6);j5UA-zg-;p*Ki;Y>-%EV>2#YQ6MM%clVN;dz@l4^Z1BQpa%V;dKJlzNbv#6&E? z-9e5y0`+yx_<~Hwo}qY{grCB(MkWf9sK%rmNg~h35zX2OXP4cd9veHP80hNG&r%uv z5i_<*P?F>VK&G*Ot2?GS0vSAL1a@E#zq;{HT8=l3Il0DP8AxcIKy)z=Z? zOC{HQ>WVA#E{n}Ca`7J>m$)E7p$@SV#8KZzoS(IgX`$pdvoa--mTC0U*uO1lA!&Wl96=0Fgw?>Q zQ?@zuC&!zp#i~;+jWrjy|t#(EFb3k(}F- zWbomLl*}aY{j>QbLxHjP8Vb@4s$V{XxdjZ`n|sc79_W>Nt3VyB87(ETG7WYPD4X%!V(X5Z z0zel@J&qZzC1kyz#v(qVzsC0Zo``auCLYX4k;|Jh{&0ZWWIESUB7-EGq7+4Xt%IQiyPc?oQaCD z#&WOl!6a5M?N5r!{pPVBktGa$u{0q-vWAOxDMjm=o%2ac7h9QXF*`0M9lSkrAnZS- zZ}l`ieG+NFT8JWX8rHiSX3Lfqy^m2w-99Ki>P(vi>y^Tq~0YR~EsI=*1$`VRxI)?CuR+*skK| zXAW%EftHXE42;;)^1O-l++3r3vyuMyEhy;gLwwNpnCXt#Dlr{f)lL-@Ni0KnA=&G@ zd827S>uO>}SPNm$9*|Bb2@$II&4lWEri+9~tlMgmhRg8>Mn^R>hV+oRrJ=%fzI6*0 z()Sr9dv)2JaWJmK!N{w(QewFyT$)OVK9Q4d*oqXZuboI+5n~cu?N!&!h65##fQ7x> zm|3l2jnPE7;%TnAnu!VIDezX{rcWFNGne~48avA>o7uPL6){jFbed?o^Qs74YIvhr?Nco%4IUNl>yH#yUW9RLc zHA~n*V&-gr1uXeT@a$;&IJlayWQJ#0Ry`I?r=CWR)~~_!IAwi+k$0nCjc? zGn{EIjG^Ov^8cRvmgAfC~5v*#aP+Qy$={Pf8!ZN|5I`c_od{PLwpL}cVv z5nFn?ulMtNB+6YAp{aL_1cCLzk8c!?y+gc;jUp?3r*DOqR{ZBL{dKkFF8cXB{<_tE zUO9iUwSNB6PhaTSRSyO!gm% z-d|q9A(0rsf1qA~&Wvl9@w8vFe)h9}+GygtyQoV1m+N^%^#JgJ*pQ!_yEax^N^?!p zlZQNL8#}dE{PZ~P#;_qdJ8IB-##8cj3W%>_jBhuFpLLhOyc)6 zb~bNs-O5W_a%K5bS8&iUf20oyXH-;_tf&3s4YODKV>$i7ekIrWI2XV-umJ>Eq#7J1t0ls4Kx0cw9eL7 z;=9XQ5NwL_{vr^)QCu$W{a`lk%|syvUjl-mwHN025oUjWelCYPAJ2wvC~UtUbbqkV zDc?C8v}d;7?86EDzYF_bDg56PW8L<@y~c_N=aQ=~fxJa0)h|C}bX5W~=E0BEsCG(9 zSfZkBHeC@`g^3i1FR4H+UftMw0Zw6P_R=ipIH2XiK%L9>SNqYWi^z;obPv0HJd=m* z3z;GZh0dd2e}5)63aZ=WQz7M1HAnG_Iu(rq#e;jDclvw`(kz?a88+YG{0kL2K!Mtd+u0!l2;bjYF{u z&t0-Va_mo0KesRQsQ&~yHTSVB0=I3Mf@d|kpW?tGq#U1;4)0wwEHv87i>^Z|gm*?dL znEyFiBO5F~7siI5-|xuHL@uxZNyyIgq)eUwG3g~HKy*uDA7^KNm$(887r zHL>hlIMulr@z*8S78QJf9F^o!280H*{N?*(pG8H1HKCGbWvaRV^|_iWx<|e4xjGPB zakbp&$KhuZ=96mMLD@mUr5vLvF)U!a;R7Zyp#ah3PjPW$zCjfa=I@VBH#8^Nt0rD- z&RVwNz+(`pxFWTQR}1kFw#uqQDL4N7C&UGHfpbJy$YC|T-U}%>77-3f2KT3%{^pvr zb8gY&nuN`|6<^$o2@clDcjdZyGx^S+Kc2WEU4V&CBO(?n4?&NQoq+wo5!@~e$`Dhn ziWgwno{2Ibd~twY6o&y_5E$Q!tIT2h_-wJ>2wpg0feZ4dd3W_aMsH^2QJ2g!1dW|Z z+l_czQCI}n!vMR8LI?wb zZ@yDITtK^jpS4~bI6G#a-%kKIfSrlq#an}-sO<)W14Ero0NEAH*t==1fJOHd{Hhhh zvjehw2OdWBvC+G&v+z#PGt9(QlZ0I~EYo#$bzfknQ}JlVaS-XO^4Q%eZm!rMkgLCp z6zKQM62?N&HN3!((K`vdbaZg-N&^o`dt=C;G(KNOPVSwo?ZAWTQzNJ6TS6`eqEgG- zt35}LAOHGt-V(O!36fd#%48QnF`926BupPHm2#B2#_v^R_RICKSa!#}K@;`EK2N)p zeE=>%wOlcG>swsTg{sBMF4z*KW$$mX+eU~Ug~cPt$|mr10j@`t7YR1B+>-;MgC+Y2 zBVe8hjG~Amur2UP$VKMqTM_9nhryp$PFD1*LbtY59w>1;VR1pQ8{zuE4-^!Q`;~z- zPY&E!V+rL{;=os`Oo_;p-egdL!OGHxt9wkJ+j~7s`hq_E1qyw;i?yIFF;GmxHy-1y zm;hE_xDN!z%)#MNQ5k4=PeoP?^*r6D^&Y&dk0*5}_9Z-TSl5@k;V#TEUY$y?{q+g# zyx1fT0Xo4*Wz$H>Mmh@5iOT9~#fL zx^MGNYG?+|YuOnVf(e4@y6*x2UD}}me>*5DG?aMLhFDV2(}|6=KEU({0$Ejh(!&4# zSS*m+q3H?rQf@q}#B6PplxmpG>z7?6NJAh+W{g%uWtDk7i-?$by*+&kc;~Q=0_qtP z7^nr_j)sEN=dTz~4b!UBr%yX8%4k`34P$W+V)7jJ*&c_c2NWwY^zwqmJq{m>^~0M% zT{|y4@oY`zO<E~ zWP^*n)W%+Hym^U+f&;+q#~7y-^Lg%~Q>Tpb*nxO1QQvqus&B_+2&Y3FUvhf@VH@9E z@bWI8UXbaX-oPy?b@DlY+^^tfBslR;E{L$p4c4h+M$mIC9(PtB*TinZ4jp#48*$&< z8UAZ*aYwSTm`RXxh|<3wAS#YQbg!!m{_5s2g80q$jFCbq{xlOTYNP|WT3umd$t<*} zSuPL0yM#$bcr%zi#RJl4tkxmM<4{7Wd{|QdXDFCz`v5^U%OU`FJOvEua||UYAOK9U z74~!k(>k*b72fs+6M2irgK1eGh6@*Dc4SKQCU-?*Jr#jFfp`UA;G~-A@$OfE^YG7< z#Tw07*J54{Z+bqt&dc+H`3vv?9M2kMFWyeDBwJqHL^-(RNs-kr`{F%Jb(@huWRcBQ z)b&O~Rsp#iI`~`fn=OlzAU*d!;TTA_$S*rSQS;C+`!xa}&MeV~mtp2beHiT`{DNy~ z3sy`v!D9BE91MwxbC7pfF^haR-F8@AlW;+W#|9VBY~}#==%%!2B3>3uP*}m1H9BaW|+aE>g!QFJx;_t>B0n&S9jpT_yLOvp47W+ zEGxU7|Gch?a27x-vW#q}{mVheQldyVI6W^uLS>rO*Tia3 zQ&YzbTYG}Mh%{!~B7J@R@yf(>dINJ^;j|c53rj5LYNacEZ8$Cf{4?+>(=A+!gypW? z_=mn71UVry6R&+G%jbra#OUbgpw9~P?cN5&#ty*N{WDkySTtFE!zE;FG6CyZ8kj$(QfC$r9250)f{j6I zcm2#jYaW<5HA%*2FCr}SQ~R0$w{O15n|6}b!WqXxPi=e`XvZ)KUGUlmV=@UR=QEDm ztpL+!e?UMA2oKi>n2Bl`dyN^581EGk>LER~Dw`3H>}jEcYh2U)w(GVIjnCLN{ldt*Cb9^aHX`8CQ;dXeZ>K*9vyJ%>fugmeD6&&TAAJ60~T zr$D?fO2+X4PZBudZ(zLlwYOmm7;P`o9I6Bnifuj9z%>7hCI?9t%U1Xv*@E|^nTPtr zVFe7}K&Gk(u-6m^&cmiZYSXOEFG}uFfb*o)Q1`0m+A(p;R#7jJ%|aN)9Jqv~2}X{H z>ANn}J_nLb{h6iSu-d0shQ95!;1gn6o9dY7B0z`$ zh1R^Sv+37h7WNl8Q9g0LyW2k7f+7LmLJWk4EN*e68TP9a*>Ia}PH1++f8?&wP4ZWl zgYhoP72f|!>c!qK62V8a_A2zfJ=1vYy@^%Qruj5+tjtqS(OV&=8$*?v{=(0(~MKSvMg*X?-9|XdFPnJA3=^@P)5|c@Xu~U_3qCzW5=C0-%n-WnOO%h15|o?-6@|t@cDX9%bi_AH_*k^uY|8EigQ{aN%7}u41y%?n^tI^?&5e^ijSeCU zB1=FqcF9rTA&v)t$186&Mc1p&<2tHOGEx|&A4XjO_X-G3^U<^&hqjO)S3~pRsXV#G zd31ENNgAwo#`N&eP)7K_b~`f|ylB2Ye0dSC1iQYuu1`0(Mj(fdfL6AG$`;u$eo%Gq>gVi9{fbA|!3?gu(CK}MlS&_-o zJb|fiOVu!lNxe`gkKs*DQThwMY@XVpB6F6|J27}U%xEZyvKwMx z{&3+d{!9H9`B_y&ob9A3@|a<~q^<^I^t4{%Ae;x@7}T^85iKBJT^7q#!$_JFO$g%J ztBLfAXe_?a^;A;y6i-|uG&{PJL>R>nE}V>t$`Ih}{As1tV4980U3>by0rpl(#vgMR z6~cdja+Q4{gSW5#su`c(CgbCZLaA#AdF??a6p!rlXlYLS_`{11dT_uej@T}b?&sy@ z8QZt3Vbk0$rJsA+2L}pnVU{M8k9PtC4-sKd4>+DgyGZkiZO2dt?}XRAV4vWeQX84( z(v!a)LK@?p-UQ@#+Pc6yJ-CXoqd4=!p|>JE2**wFMg8alGAs(S{yTE{+<-6S@;iS`E-#_BMW(dzPC5}qwX!otOusar za>LVMhC@Xs%_)?!sd!3=X^2%0Bdy`K18rWXI%yC`Mj+f=e(%i;x`U)}t+V@3L@U@Y zvtAWv-U%(xA=BUAQiE*DE)`+yoGii_O&8mRHqgsJh&>Z0))9k+A+9bcN2y!S?8!hG z0!pwnW-p*Vdyq-}k$!9xMgi1MmEsPn9z4iUJF>uR3#eiaAdqb%>yqiuURPaQVBw5z zG0KE+-%c74CAkDr_~DVOvz>m_N8_gt6F)tqaUgR)1VL`5PZlJBkDh)UV!23TS-2rh zVCdBum!QrBtKKG<_L6D?C?Lp`@U*+N^|;(nBbPkVhmVhyWaKL3s+KAWjhem%|wS+l#AcTRWEsP9SYuE0r+qPlO^v1FCE>>U~g5XyVE#0jJ zOhcGlc_sq2%Hs=z+kpg}xCVk9HS?-XT$x8>4pD|hb9c(kAw{lP&@7rl{u6PlCmiv9 zzIFzgA^?{q&uVPBx0Jv89_*s~Jp#sX&1()nfn2}{)q78Eti1epD2vUVO=P4v-i^h~ zCKd7}Wv6myI_d)KmFwR$$z3P|~fI<#4^a9|^ zY!6Pi~Fe+6rO_$=#kGU z=JA$2AnMY%LD*`b1iue^-U;hm>wl03u(f!E{dn7bt?6iQ+}|hufU?8y zyF&mQ_!06T+y6v*{LGI-{~Iw87;3o-Rb3CQWjr9vBFU&?KzXuu>2{8;mgO`eh*4_G`J9m08o7t66`>+1_fta6Jw$^*8Q-6fYUOX67%v?(z z9JZ!@&Xb({n5p&}8D#OQ6Dj$U^VHN23ZFN0oq*dJia&z79X2wm_k7M-ZZZm0M&=HHO_d?^D1c)yJ5OCA4Gj>3>>ev*xxh6y*q_=pq`eGi6An5n zL^udN7oX4942o=~rYEuj!_aB0>;ymkF4=52WjcSuhJ<{JwSSLK5Z*3`_GC0JeAgOL z`&U^wgT?QU`RXv{0~uDdrw@rKv^L~+9tAjDN8St51Bq?xuUM z)nK(QUII+$sld^U;nukiw6gZi(dU4nL7o&`0fX73CsoPx!# zzbj}2KA6sjyPYQB3FK^x)@%;`50~nEY#(s`(FFbMdEcTno&Pr!^$UYfoVBJe*jFDo z!{z9VRf6B`74lh9+9O+n*XB~?gT3%7ID|0e!hS5=4kgRApKh@)^^Ew>Zud+5<~hf2 z3e1fB_T5QOpD7nuMS08i(|}-f)%~&iZz5bWr#uK2zWuvok+z6kzC|ED9kh;%2tfiy!Eu?K`D4 z{c6akBhbtpMK~z&uMUCWjpqoujte{a+RZFK{_S~`(HJH`I-{=(fxp8^!S4p7w3Jn* zzi(e?VBtGerha;?BF^yc`B}RgwqX!oxV+kRr`qtFhe=^H0wj(=z8#i7c7(+KsiodD zed@~B{CG7npIQRP&=Yl8C@BefOe6+g&YOYnZ?RkGH)~s_4^twqb;t4IWy;P zDQRj#!j}r_>0_c(b&^{4z~xXoSvByKLwu}LDYPK{S}1f$R)ugcKus}-L}#iCSj0=mH`GG?aO0;%YXY@l zFZo?cEvD4=+87lr>q(&s{CMEbp$BMrG(b(&SBoA2(HOp2Pbpr*F5Cl#!g=7@m@8iY z`J*b|eAK6{qXWJ+&(Oe=-PhXE0*Ge_vaKi+DiOEPvHOpJUgTe)r~7o-gWq0u89uTJ z{ZQCMw><_7G9UfCkdTla3n@0iU9BDVte!bRuFQyr2hA3x>%R6R z;UY7|X~WXdQ_diWL&-ZhIM`Qn{8mEIEcw z(G~%g!BfJTULfDH2;YJ%2HM0eHYd@R-n|-LYf31CxOsOFPvJwpy%*B%qDT7@>NpVl za%m})tOpQe?>Jr(YSoqp!K)*@dveJ=C_21)jT{35Cl##a>oL~`@CT_`YrDubZFTRY z$>qVPh^Y{0?RH}n%7S~uAp!zlY2k6RvHN)h(?ctH=oB?2)w_>Y;2!$1=w;ZB_2z5u zF|;IKv+}8h^J(-HI47@=ky$TpY+-d+PMM|AK^swNUcerH5WrTi0;S~?+ek-ZA(!k0 z7v?+lNmW9}UF1g%_oX+cHnxfDUV+OCa`6JtX3{7?r* zZy~o~Fc)9-giIE|blHlEWx_o{xYf%LD&z6u^%S|UCEP=1uVQ!Z<|bu3TfYx8|M2mX zl+<9M*^bXhlnlHUBeUem&-R|vop1NvhoqWbVG~Uq=a%HZn zS}ZNF>By4>!aaC^62sI?gye#_A&6dNLI|Y9cgz7y;y-8a&k;NIc;b$w`ZodXG@aNm z)Z;93ntP{{zfJkm-^QYsX@?y_3`LkJl+$$QhR`~P85ZXcf1f~N4j?qlnm31NJDd=!y2szGet-)$0+?rZ%$7#c!JjSIc-DJ(0o%?bZg6mrs7+xprA zj3NW|eGADuJ++Qf_1JE8VLN6}TFkX*19t4#;cezp;@IaAu#3BG;^AV70TtDv+%HF zJE)nE?(*VHXvvLDYp5wJQ*dBtVvVN?tnBTX?Uc9Rg_!0SUg?64uIL3Pk?gYzC0 zkUb>hc=4SYo;+futQ37r_T|n)=Yj(ZgnN3>i2!Y=1Fcv$#uU8dHfv}DD97ea-Q=uO zOD{HMpmA;q+K0RpAB)3%EL4lXfZepfO}pS$Nm=!q65B<6C`bWOBWNf$QR7W@YIyqn z4;8z6M@;?iZ0w2C?^m!i;ggircXrAi+b5xbr!HdbxulxvQ2U~f85>7!{STpg3K%9{Np0`@*+>r#CS+Y`@I{Rf)1LZus5n#gr?n z|Mk<}@b-}2W%2ET6t9Q1#H|Y*l&$BdwgTC)L8`D_5m;DF_05{>OoC;+_3w$(iDzUL`kR%RQ?zI)<*myTns2Y{CJP7U$>M8_-#)ml5(<>7tiSXBbAkV? z;6Hm1LGPcJ1flo;?Jy(qWQ1~+L&#_vCF@49#<6!6Un8W*lYSYeB{TO?o~#JUDt^}a zHIARU+8RV*pXW}wx@D(r(2d%E1@qOVqEvFr*HW$0Jv+E_OWO3W5q;-v=V_rE_f8Xe zKCAPbjuG|Ouzq$w?To#Lum0xbx3FezQ60_K*goq9)10dhSIwsItx2Z4na=n%z%SS= znCvt1>J05I@g6YW9-D^WgjfHDw7NyoMKz#%IKbMa&Za#UY@;dTm7&AOmYi8jd3*VX zyDQcpmeOa0lItyM#R9aOJ4rvqs!Jgp-a2A*>Pw_MZ+&>qPmGm&%b09oW;6&wO3ML& z=%#QzF@{|Y>;@YNgTpF2uVy!$#H+tp6Vq3^!lTuDg!-;o>4~C3GVbcSD2amb4}h5% z!I6kG-lPDCr!9KX^=QY@>l!2*o=iCV;^()&mAcKya_9lA!$yq8MOS&^&LbLMI2t0A zd?E1RnJ5k4S{r^43sJBnxqkqu3d}Ey=FT&;LYT5{cb|%yw5CzXdi9gmaiQi!A5!nh zTyBSxFbI+r?{6fOGEkt$Y<$2(OYz&n(TP4G1MKjTl>2b0ACS77@;=C!X$SZMoagp9 z^j^}mn;dO))7W+8vQ)f~0%znk*$rT`)Pj;t0}d|;9`{Bv#AoZ~u3Q#YmZj`#o?w0{ z%xCk@w?omXj9Nz59c>ZPc1?>}{mn`M#0~?-B*ss;oBmFT`lEo2WVKL1m{p*B0om#r67G|5H0kW@OzBk3wzI~=A|SCz7HR1N93dPF#b_n5 z#;53$dX=_|>m7-V_6Bpgy-Z%3l+T1&0U9oMfro=q%wbvadfOCLI<+(v8}`50j|_Wj zy6&LgXJ%oMSF)yg1K~Wd=YU450?agDXfOdruyO9hy6D~UaDQT!ibd|kOAr&P{CFZ; zRN)~A&NirV6&oDdsX_!xHN%(SjYdrp|P3fM>?+1X{ zD=i*tz~XaoGioH_=!A!b9%(mr!9gK~>aIIz*tU%Jz&l~|BAyaq_+@q^0t6@Sv_NNM zZJOzpMCDpg)~jc1Em+|tzwZY2_H0%^nW*E^u()Bu*aDeh-9@fKBQ1oJ@bXfGcf?uo zT5;yCLsjOL>LD58Pp`xri8GQ`c%uxWbAOT^y|-C>hGRmQO>T+Ail0ZPcOoSg&V2!X zZ1g}{kfjS_QU)LkbkQxab3nW>9+o+p`G~Yu?3qE?91P(=i+*gp+mShpTRkIL?tqv9 z^?gD`WqS|EkAt09ucAH{=jn98;{>sD>^!~Eg+4O%4x~O&&$~eFK!ngVE#fKXTcbHz zQ(1t1(Mr|l%c5B_;#%5DUPKwHlw`F{B0R77kAyQ>Q3f&;%~6!qYH){r>@W&jQ8f4Dt7jdQKNKfQS9Cgg@3gr zwxv&%>sUe3UF;u0xFm22epnyFk=FqO1FBHa7)yE@@NZ+z+72U2uqIxj?#?0;v=Pz@ zS8##;_=twTgHV3ZIWMiQUJ>SJQF9#i7v`WJ?H>Ut=L&}n7^V`l-6oY|4=hcwb7r)- z3uh}17uhf%7;jGIGgj8r9B3O^c!4|^>~9WZOE&Cw1$ha0A+ZmCy&tvpSw4R(qL}PH z#=X^)|7!`c>WIxT8UvF|(MZl07PW@FFbyKqBs@LHSfVoP591`!^*678sssO=#wOk0 zi1~jBWdjm3QHG1-jtRfS%k<%FR?iRI;In}!!ryU6v|sE1c-x+RB;;OLsmi!C|ZsptdyaR#@S5fbVwDKM@-eJ09-D)+q1GTXC+8 zY(wI!dwc?C*1%BW!I>9_u6lJLw%iu9{|~K6VE=O~Fsr=4y}$wE>)ljEtDz zg^jmFgLgW`{AZzRvqC);j3YMQmgo;Qnn}_6S;nys;3^!2T+scF-p1pX|Q zx*C+hcmjlah_#`Y#-+AR7l|5LK8Mn;gT(GAPueBvjReJLxiz$-&>7Gj7P}hYD#2WP zwJB!%R)|qKHS9gcogDMdLbZG@Wq94gX{1;`!WKE5>ytAf*ih016cKjoB|u=N1n<=6lL#dHowSLUvB!EPP!N(1%FdbksN zPhsL7Vz#iNP?IERjSgl&FCWYE%BQyh+E-%D2IWY$38YRL|0+hr`+KkldlN|?J?=`* z_espu_(0Mp97?KC*9`<2hK`)if&F9eBQ*|=LGY+9u~cXnTN+fWhOIZ!iKLE|Gy$D% zkMct4`u(>zeafG)%!N@Jlqb9kml3RDm8ciZUG(R-Jm0R3SBp4G*U!5K+WEYZVnh}? z#;AMnddyKXFS+dx3rIS3Gg*NYTUfT;1Cc6U-nIkGrYaDhLiDi|&#*T4a0Yi{J0Q31 zZW>-0?M!D2qCEUcQ~L&=ZF#}4@z8zJZAYfNhgs9C1&-5k1saXAdl(0@y6w4d-Hb}D zmMurD@jJ28ya~V=BMX!1vrXkL^{|MvTeE}rRz`w{)Q;oG!MxH)&W+5X7k!7`q=0dQ z{-+>Ooq%uy(~A{#4Q3?Fjj!wRx2R#yC_(Cxaqo4=;Dmv9MAaJC?Z129J!&5{64RBY z*WU1~t1|Ow<@F}?R%(frv_aJZ;X8c$wJB4DMWLRNk75?(s`2mZ36djnzJQU8RL2%Z zTcs0Vvu{uZ5sbOny^507MaG~d@qTtYc%zZ;umrQL(L>sawU1X1=xJOwjmuv%awCD4^Dul=tqEt1*1$CsuRu!}%BUaiHkf8R?7z@ZfcGbxLyUwRZER-! zYii-42hgmLsExDI01_k^HKH2WLd*B|YD*_XpAD!i#Gk`_72<$uuQcKvi=n_&)C{0R zo^A6M80&e2z3fAtAvbb*Z1?r%<4e!{?=J>Yaxp)`5uO#~C}9!p*ffj-i5Q?4)P`!g zp%P$wPsA1Ek;*VM)ZIl!e<;M5!dPD>Sf4A+LQ2m*pK67|O-x$%*C8Ksg6|+|Q z{mB~ugV5oY$Dnj%@TS{jik9_7#CZlVN2nPWux26?h1s|u#|P7Z(K=OKf5nNS^EGqb z>U+@Yf{9}CHnqriNzs0C%JrQz<@Ql^eG$nK)-M@H%i|rEsuTWoFn1LQL^vELGX`U7 zl*+U6N^TqJ)bp!~XWvK}sOX$~G^J8S?T~7H{H}Um2E~LK^hQxE^W7;T+$_m-2b4@R zW7=jo*)2Xig?esI#)CU(UarWV(|oH;v>kk&wulg+UKeRUvyy#aqr4ZT6*TLFZ#^6r z-H`nPg62ifmfP<2TraqEtMpzOc9hm?034vWhfw$b670oYZX6BdQ7K#n{ce z%XQQZ3=<%m=|#q=A*8U(cK<~DEK`jS@X^$d5VAm}-w6M;6 zM1&HEV)1reB>nf-$f^%AI^HabK;s6&em)v8LLh^_bdj|Mn(c06(#$`IX%QsVh9&cH zKF8Ql8xNss92(ps??{P4SZN`nc0k*+kaL9D1Sof$4=}G#B_k{pd}9wPcW_<{?y_)h z6I$w(iX3`(HIvn=Q#b}rz-1Z7GhZE7wvvX^8*i&}_lBzszd5KGJy|%r+7C z+9r~^`@B!HNO*fTDlw^H;>?6L^C&5Dl%EnZ|A*vKDMC#(%Ivg2S3s$RQ%l&M+3OC< zL=EgCue5-XvT&r6iE>$ken`8#^56bV3CNs1@o$uXJh@CDYhwYVhRv%XPvt`f-_lPA zeuONAD=Bbn)AGpOtxKF?o6|~fOOE1v^>;8oS+69tvcKHPX#{D;x`V=H0d0RcyF&RVQ6@shK`Ztr0 zxdbxWrqgUcg#HVN4MSurA&)!=_tBJUah?G6j4s%FzP&115FfJnBe0u-JRcaB?hfRhtmEBQf8}E6$q>(jhYFN~yChxbxJ4a<%wDQ){XXQ6#S%#F zyvysjqHU;FHSSU&{ftvrSq6$jJ87^(jG8-%PbqX0NRN$(kugpe5Qj%0CiJ0IWKzSB z*6mSEWK;*(MJGWr*M!Cwxe!(yf?ML?JfqtMWMkvgUN#^Ctel_zq_t&fft7$9C(?- zjFzZn88#u3UAdVCEXp%UkNJ=f3N-HL;2zKAy1Oc4wdOEZCC#gohCPhDGcSX1({Uzj z86M5}pLo;z7&#rYvBc8N{d(*J>+BQ3q@H}HE3^e|W*Ao&1qkQZ(H82Z@f!da3K)9K z8vKl$hM1KYY^tB+r6-hWR$tvEqwdfz$u_xNT(zGu6Op7a-XoQNt-5wW(f)Lgu$$`? zkwd*RT03w~u8qe?HRlpBV7$~vykiskyV^Z~FH*8R0rROAbtXp9QTim$&LC}~S*mih zk~Lj2;|k_bd7#rd2KoeA(9k_rgNX)FMOL$@SH3qf%vQ*Sb*qEIQ6OPCFclB!hcH@6 zJorxwt|n*17*|df=1|Ih_G0;37!?8x;Yl{ zR4Tl`Y}cu;$%*nz?+Bk-jCV^$aI}Q*zbZBMK?%)~k{nFCQf~0x=CFSPc+R{Po8Kb0 z6qcxG8$`Am!7ze5r9Vm}ukz2M?EN$Wqd=Gv(I9Q#CQoFQk$U7MY8FMDj%OGtP|n5_ z)T<^QoQ(-MH&{pP2o$9x74I!)T*9i>#_=JK-dF%~Sj(E@;Vtxvd|4KmqMg}iMtPAN z(lMNgX(IuxK2g{>Jc;XD6Z8vI6XfN(6hCsOD#&->Yb|kfDK&WOF?nb@jt`K)MI4MJ zm(fQuz}mk8ne;(%!~HSUVNsnl*9ZZm0a#x_j;Ty_*HyV1VinD30~m_K8O{Q#Q>&~^ z+b2ByR5}|mzI;W2v3#54$dTwQB-8{Bf|_5+fj+Y*V|0-?52BKJShSi!fs&Jvk!6IT zB8~`;f32rdrEdvc0iQ?Q$+;uy)%e+p9LLEP{$&!~*?*Z1K5@5cS(nCdW@a`IMpnR> z*vtjvK7%anLaAUGH9`2m>6k`xcYk3=hyEtSUgk|&yAXCF+rtOwxDKj3C*ni~i>kvw zSQ^RNBNt|C#_2*2(3d={N)%E03WQm#DsGjLj$=Qf8Sup;N#1&eeU~}vfv=F&2Yw(| z=_VooV3?ZGOvV};CjDC2%>z*ZZ`S!QLpX2*6@@c{$rG|wvW(#K1#JrX zt>Jabj`_jTrg+Fgphbj)gvG^|61*6>p?BKBwdKD3Psz{#=+h?Evl9T4y_|mo-tK(T z9S_^PB-qN2aF&-Tw%N>MW~s2B$Gnsu{1+C*30S?~Hki=@bBZ=4Bv2Alr-nz@k;vQo z%IiZj8pz;s#H5d@{GRSPi&A*``Tz?GkLcwt;*}^twcjuIsha+-%saAA(9ENjQC!_R z71|9Dd`-YYAvtmXB0r ze3Jki^IRD-kv{G+RQqcL zQZ*_vY$QRyL^Wl;M22#GPL-Tw0%3;e+2P&cU{8^5GzRwFVgp--YZ@KcS5We`w4AxH z8HZn7-#nq#m>L~rW6KDotoqfF$xlehfv&@@fI`62D^tSz^4E($|XxrP1h`Qb6wy}|Q7e%rsNfJenxJLiN|PG(HRESB*L@XU^+VeX5&D`IHXJAMr|=gUJ3_vb>9=^5-1~iC50K*9%RN78%Z6~hEBb;@$meRmX?-J zYrq1r;N^j9c@jB!p}y(qmWdTQ1LxM(4~ydja;!r12=?op?i=Ea>}A2qAAy$ziLni$ z{J+HGtdpT5cwygVilfDid6kvVL6fJTS2aZ%C{7Y%8(?o%Z8|k=_?4?0{^D0Kt*Q|& zQ(C|XkQcZy*ACJM^xTKb&fpjot4OsHGmZ;`pXFEIVsL-PNsicjgY5lq;!oJL!03a7 zH5dyBI8df-!Tdf9#t0i6*p_0>nE@vMBqn{a-nz*>Ouv>Y@YPQ$?I$*3w1P0iA-Wc6 z$rGPYlWn)eqlz*f8Ehb}DaZy3<5BIDUE<0(_U4V+ADyh3_;O@f015(-Yd)rZyEmSk zhFyzm=5B~iS63RCCX(%PXNvl=x_zl&a(eo3X5+Y#K+3Iu;SasjL)#`8bvUCMy6#*t zXqVpBb`nZ4)@}ewL#G&8my&$c{%0{IMUcSu*FoI^@G}O)Yr$T+LxLQ5U@XCv`g(oGE#w8O5V07m90*LBHD@SqIJQQSb z{s4u}`TH^+nVaV{huN4bijx5mBh@b)wsEYr*buIxLU5eV`V=H|~cd=4ULjd*glvRC>x2x_-E zBzj%UXq=F1E4pk{xGA4O-rs#o3V8t0Kijb7gTtWP(t^qk|~Y13)jII6+tD3`EL*~dgYqefqv z<2^z3FzanQ=yBLZL^m2Uv7Jx=Nw=|J3}2c3R643_ex$9lhgnXuc{_*C0`=USiS`^J z6fiGUUs7*Ev)be}pyrpYfMqVw_@f|&&Bt+2G6Up3POvIoD~VdWPpo`g%3Cb91_6-t zvZ+yc15zU(CA^r>qw;GpRCo@PJ2Edp{L|A48Zj>!@RrNejm-!!2n+5?6CT$gIlZj- z08@xxBqPa1C4Vfp&#tc!CCW*HRnp}Qi46l3)JKy>&f!)DBr$IG9om?LqR#SxfXL{; z#Ey;NDFH4yvxA?%(3rqa=tLOzd7_F4HxYk^pctIGK{YW{;lr6R_ODeki#=xO$gYO> ze?;gmGTa0UtPT!exl34?R=bA!2z#qmi#Q96((&8UTD^^fBcrNdshF|wK%_Jo5!5W-)-V~$A$P!QZDfRAdE-+# zrNu24$GHX#i^l zGUAZ07ND}?xWWJ`@o{)7WIUA*Ht>@F{jb}_QPxL%F=Kxb3-)#w40XP^% z8YXAvpaag9kdnf)BWtj6Bz%e5$F>sbeRP?Fp(eq!zl%F!vvcr;^h+99?&XN}JRvI1 zW4T?7S4~4aj*}zEMxp?({Yv{{WHuX&w_lhO!*KI+qgg1dYg{_&_b|nM?ia;Jq`dVG zEVcj0A-s5zOP?n8U329=AHT%Ovy zmoBF~q5Ij9s6xBJc!m|3EXfYL8m(dLHquvSya@%JThuc@z9hd+Y_%u{B{H^_fa^(8 zETvBODTVV^}&dyN&{GsIZzStWR4SHctrV27-=+IZ_) zbrZ|MdXzaNme(?7luk%CJnOsdM@|szu~zMs(<#Hh{|JljT-F|h(`yAn0HU3` zLncVi#GVej?O$E)s1M3z_9B_8;V}o(H|srvr;Vlqeb$8rZ{`hq#Oz7O`|W=AL9{LT zk;uJ?R3`uv!IS|{*>8N0nFT09KUcFLQox>UFQVMCNa1-Y^^$rxI%6w*1HS3bqtrN=8alyW^ z;&SX9%_KclEU`Ex*T-TEu<_IDS6|mj<9qK045C%QHwo$18xzsEo=2JDP5l5r;j|%e z5IFuruslh_NLYY1hXAB|y^ln4i19;K%`ZgA;2Zenapy?ch}4eDqXj#YhQSIBU7i_C zA28b_8@7qfdkST@pv8WNfF8sH5coNJdKK*Q^a0q6f^AjMN~VZ7PJVRsX-rK^+f&H{ zE^^BN+S5!~M$kBrRsrlEy+5!n^))kR5672J-@}SBih=Wv=fUS_d5{nUdyX|W^{`O{ zE?khm39mJ>K++(i^(Y;;mQ$CVEh}FbV9?Kase~IABz@`O zC|+>5!&zWO7BO=P;l59b(ob(}uxDLVs6@1yLV;zXLTOZJ=d`f55)D|yWy8j5 z@?YQjst!)oXBU+k-br_o`b_UHaw)<*N^=}dL#MwRRT=@V;mIL@tL_WJ@$Lu67~X*w zXo#QNNH@l8sR()YJEe|>??S60zz{2kvhIpr&byoX!DG#=kCEilzq9o zHY3|?#*qwo%{7=(C|oS4LmmL8nA@&Os4isNMpmC9?<1ZO4oer;TPGgQZXVm0yG~ub zfF0%FW9F3fgWCH$Q&_#G5~dUPsZh(+5l}EGYVvw6F--(~BNo0ZtzBPp^uRz+Xod*M)3iZT+)Em|XNAbBw=N6i`E2Smi%UtV?WL zZ~~F3&3!pW@hae==t>(r>5lU%QX6Dj2fOQZmgO`43n>Sb@!#HTNAj^5#Zfy64zI^hg z@Q!47%>i0amWwLi5bJ3t%8{y6C^66$C2-Uc(-wpCCN(Q)y`&@SuU!pIy?C)kDNOS~ zeekw+e$~o#+}4F1q&QZQfhSn*^8GWV*V#YL=Id3(wm5 zm0&nwrpCfdSy{?F|89E^T`dCGrco;m@U?XfsU} zpr*Py0nkCnWDGDN+P=^U{~RUfDO%o#weIECMOhKPR8Gs0yH9aJ|9q`7hSa20PS{6v zb#;(ff`YO13;Xp4(!!sJ6H)l)&42#p4bNuPVm?2o!z%p#KX&X4yVp>y0tM?^t}6ySD)Oh;QT)nI*;P%zDJf4=(FgXGV zQUnhhIL|A$xR2+7z9ob&(9MNoML7Pvd}$lk7+jB?7RY+J^J1KvRUycN38 z>qX%cQC}D*Umwrm-BlaaW{5~HuU-8!UIL};hgJXf9)9S{Q#ob)?L|dQcV!lKKtP&O z4z>q>LmK}2Sik)NAePSXYtoxiW-*uiY=eD!2S9MN1deO}3^>5EqSuM0w9MA#|BjOU zHRb(gvA?4~f7zSgEG`(zOIH0rVOgegc7Bo~rT=UK<9BT6pWWDZ%C2i4vNjgDw^+z*gt!kKSfXeSp+nV{#k_Y7vTu;(z?QG_$^WY zXKzIeAlhAwJs4YRkJGIwUnulfZ!d@}zmECeyjOqElKa^%7cFNz0X?a9284n-lvR13 zsdqnnWB!&j_wx_bQdP#PRU(-!D?{NJnz4eyw&gRY{fC!&mZ?Ga^m7X*2OT4zJ%{TP z{GcYm9a|(kQ^dzpb_u2B%D0Kqm#B4?FV(r4qpHn4yA2_6C2`E_edDp2A|uWO>fLuN zf-mu9*L7{%>#?U};|8M}e#xu*^M|+w6;WaS+sDF}%j3`-02AIHlso_`AJJVUj6?4~ zllcDpV{v1O@Hvx`moJ5{50Gf`A+DbsqEms{Wn=yzjv_VnenlJ+V{kO2g9EN`g_tJg ztA6B%ZMpDW6_ZZ%q3GJf&Wv#xZBbK*tli#!=OY9=d$W(el#cRM(DK6$`*i!q1njB) zI^2JL9C`nI(f_bD64-qg(q|{izFmJPh)Dm>-wOAHD4`eKe4!#<_YFw%CFl74S%M&v z6Oe^#T~nMuTHM4o#gzGyts(x=BKx6G?x$*R2rN!KFt31+UcW~7hYYnOm!(kdbgIl{ zOO9D~W{Sb_dIdUn*i8%9k3h%87qo#b8SnwoHEun^HPO#^Ct#JNQzt%1sTVlgQ8%k?n)i z#5Yvv$i$dX1y+^#9VTCzb?sf%EnFjBz!M!aJP*Va1*$Yp6G;f;dvqILYO|&&K@iu7 ze}7#ymn}ub_m6~v8BSUfrspN`rTx2aYTN#E@9(}`BzzvtlJiGki0gDQpOKB$ zg-T}cc}skylhg_Zws}v9#q&}(ei^1k(*v*0>oybDqWEv#F0J!$V5$35teDeWR=t#!y?ehii zSU)BFxEh{;j1j*Rr`M4SPQEye%ZZ_;^{XY60t}f>;s`9CZ|u*AEIK?S822| zE41q}4e$jc?afP#QOJ?{F#v=o(+64)W}B8EFy`v{L5L)@!Yh@{(Y(C;=ntY-jsC+i zG)4+en?tgT4p`#oDvJ^CyceBUms6IA=D*GwRSkLF)OBMdO~%-0n{Phh5$A;%3)~v_ z%k2frFWO)I?uo+|p`|NwqO`Rr3e#w5)&-6Y^yv_dJGoJ)qUtlv7hO{8emKZ`Xf&n>XpO@*LrTO8uc*$I)pi?8+KsHWcil82H!Cq+To|WMi5{ z2+0=mV4WygaF?$kd;(U;Dca&`^sb-R6GqRISRSdSm-~3}j{2Q2kA}VNz&A z5BD{fpP4@}j9v_(@njFaz5%+wFKP28GAD}b7{?2j%PM<46Hf;b2f7dP9iyaYoD(lj z*R2{^I87-RbR8caP+TU*5e%(ng-^1UjVIaLc> z=Z{A?MD4)dpGnJf(6)N~{aFvSsTfc&=dM7PPElj4cPV;Gq|HNX-y#Z)P9YH!q0ci0 zyE9*5#|docZQxjby!T!(g)>S2wv_*Y@nI|^J@_aP@)Nc?b{c7(WiP6QIDd=nfBnpZ=OTHZN)Sh1F2!KXfy=NWqIBB?K-rXZ9${Z7#}8T z@s9zErHrP6B|GP>9Mgi{edxilmrHVIv=w!#|kQka1gRU0Ts!4}QoLIaUx zy@_1`mN0uLm%GBXa=+D^?y6@(hp~Qy%c{>!L@)i|*uxX;aJ4izuM4)hjek zEqSetNm&AT5zrOpQn~XAV3!FvO=P52TV#~$A9kf_3g#ZmDamnN&L3Tqc85JGlYddB zIT`1=G`jL}q~ly>%O`NB$QditcICTGwxNDA*@lY(oT7NW>i2eL&0l#t2y7T#=25SB zyQ3KOgl6oMmEksRlESQhbyG)(oYMW~lf3#9ajAYpj#pC%*+Lg=BOZb^MX2RW=$GPg zz`ZN>R+J$h=sRmUo1t9n0KtS@Dbf6ZzCvh7O}Uqn-lRp+8!8k}G7=invT0qOz9j=US;oyaZy*NUxeAATQT zEYQFEUwbUNHAbtgTP7i{=JVRy_TPO3dP@yh^LSXbZ)ilqZTR%JUYpI$#j_GhIob+4wi>3sC_q+*0JIAqn$Czxp(igK?)231!&!s1<>xynpN~ZaN zpl~B=97YoH+0PuFXjs&l96*;lK*)Z_1hp%ImJq)KW*BT`h&OQPCPQEz8?l634RrgO~ zaHSDFf|M`M$%_S2d{{`#jbWSJJ^uQDzLZ1K)&m^fh5TLc5M>I|r)A zoOcp|Le{Ix5Jck)CPpUkafuvB+xeM#nwTN!SSrbTbVj}7} zE9H!8&}RpTH0V7G-c4Tk03H=H0$2Hla1zDL*uqkq6Gmx2nS5#&v8 zb&qjdB0SnQY3vS#7ij*5IQ$T-Cd6C7l_92{$UB6h8z37t+a{fj0 zawRo~Brh7~(c3S$zFEGExa`EJG{~=C`W_W7qp=XaXX(eo!Fc;t-0h@`kvXEd8G6wh za;n9h-HP7z8a70X91+EO2q1kUPi`BNrPHFhTc?88`0R+p;oFI4s&hf3G=!^0(hIy( zHUkRy`y*gec%?ido)z}hMc*eQ<2NVI(P>~r;!|wDsuRSwWfGaIvf~l>b`Wv~)Raje zmW{k2N+~9AW{px`={w*A)(I$XXlSqsK7;W#4#>{+1u|4q9)ii!-cP4vq4>1R@O36G zUkdU2eDNsu%GnLW1yK!ThkP0W6f`oa>bv=#C6E7&5&pKQ*c}L2wPuq0=B@gJ{n<*% zvhqN^X>AeFscmJ5L`Oep&V0%>LDXP*iv`PKUR3XlWFZyAE?FF87kC^&BLI_^9~5ii zJ9Xv#LtBV=bza=62ce3LzUyUBTfa*SyaK`Tf+!sXbI7wiMz@jF^WvEuch`doS6@C;-J8mM^T15~&J^`Xr!)0c~$t(1}e zrl=$zH8@8YtmvP?Gg}=}mpAFpVPhO%`kW86n)KJ_={XWzx%OUWdU-H;LDEcxeI%ui zu&O)NcXj#I>5Nxm$wP)+)BF{ik6=OuGD0H(bzRuhl9CaQvQH5_6y0D`^63f=;0msh zWAF~C3Tj2@R+`Q@wvF*h11L)aWGEMedPq0XR@&+ZQ|NN?4Iunk;tL1z>GN%@)a`E- z3l@oSZq^sEHzMURAC3rvB54%UZ$|bJg1z2P0k}YR}-Q$tdcYI zCz)0EgsE~L z^ad9lVMGNk7@U60TxY)c-ajqm)|a3==O8B}x+64gJBQQ?^uK(9jgmC;=$dZ|eGwY7 ztv8KO6kKs`*jw?E-R0$)o0lGL)R$rURH=*E*HP^#zs@O=)Oze~{K**SN}hLf)JqR~ z?s>D9DmG?Q4#5oUP!^=V3zuIs-6SyNn(&u9D-cbU|E}Q2%B*orbd}mi9;2tTLHOsY zU!Y6Gdhfg^r(AbWe7#WGYN^9}|MZZ@o_>CQvP_Bo53l}d&4xY90W@GfzG$v-0)?-AvX>gx505VMR`2aH#vuTC#bIs1C< zmRTGX&zPbQnrQc*-?`Z)Tx1FUbQK%F@3|D5g2Bgo6+Xc_^@+YC z{pXuDefh*ze1Zp%2iysCgxA9i2Zrd#O!V$e3#_&~JoEMAo7LK061Ofl$O!E2UUGqS zVb1F4CSAv@`i-EqLF5rT(&uOToVcISb5k7?(!Bo1s!w;Z1$S}z%U$r@Nm3OdIW))t zC>Hegz^BI z_Q)AbyPyYQ7((3fKb+q6om+8sfxeELBG>R18_{dav*cGz4UePc_Z9nqGW^OXr|v7P z99~G_{1Jbz?4i1uPp4CCHg%1Q&b_3c^Qgstnk;_IsjjMe{Y@-{6j+?SEjm~RGF=-X zf2A~Ks|)wDz*eoIj)Vf1Ik>U&Uv4ZtAxV{ui0%*&kqg#XHJOv}NGxp-#Pb$Yim>#@ z;#9WS#+bO|w#?5x^yS`e;ob@W5|HW2z`3>}-GtRoaxa_6mZ699ZgNgNEv-#9qMN?n z7c0MSZZAYGWOgXAH=>um_mUj681Xgf_1mlmxUpTIZtNOv?EaS<^TQVMOxmU|FtQt` zZxeJRxp^VKxG*T7U>xB&UW*$dt^{!Z*MK18S2rZdJLz=rx)FHqBXlX|@KMO>m84`f;f}&fZwOLjJO1!ZM@UTxtdDr3 zRJanWhaWK_05F#I{1ls9ym$)vHw2mSMZCDAwO=mjbYha~5l-c}Ivrm_Oe>J(Cq{`d z?K}c8Lb(s|V?$=4uS;d~^zXjm#C+dMoX7lNKsJgU?ar`MoHtv&O!>7Oo7S+G^yZ*rDlPvROW*hVUF?E8zRxzjZyRvkZ zbRNU34NBaXa9S*A)OqRd!g<(9+^TT)qOUv2AckVS`JKqujkfKQ_x^*krz<>Ele#)} z9&J~upP{QgYbO$3$?r?gdV4!niBOv^$Rjk5^9PPSn2kz3CM}?o6B49U&F$wIGld*U`k584?=M^=nX(sm-vbix;Y#$$*h!t zaEFo7fC^1voY5G;rs()Ubl@~W#|P*X1mWwL1CJ*DiGxHec+@y%Vwwvv=O9K{sysrY z)h}FE@ISptN{4xr4@qyCWfmlvYKwMQF@2_2tq z>le0h=x4Rno5#F>0q-`*Wow*spx$>JP?$wmbXyy1LwKH=!ZFVmf0Wt(QiA_Om=a(CJ&h=(@_9C zboJ;kP~<5KL-ee=@PBuaRS-dOjj@pmV1J?q$2!zQN~r2WngpKe^0AYUd?#H>ax3B@ z2PZGweaNv>%~Q>YP2B?gs6APTw2nGpcx_|P3GI~QD6o*UL6f-yTSaEb{Ni=Dsd0Dw zXz5s4QQ@7{4t-Czl^(1cjkga0p4pOlcVyl!iwC3wdVVg4ucPWifb>z03qvN}-;B3w z<^%u`DeO*~C=Ec4&ugxe?M83YSHRlj=!Z3Qm_rlK1QEUPFr8yBU3ufk)pT;dNM+kz zVB(f_K7WJkWFgaL(mzpa=<}Xx_}cZHVfNd2cxPubapPfzafH|NHq)14bfg7V9zX!u z4pY?da{QU+Y*q$NWBWz;6f}HFq~>sTssdOEkzdsmbTER;QgvKw3bSh1Bm|F`T0GF4 z9MH_^9b3i+b0gxca{f&99{X3*nInYzP^=eS-}DAuhgXn$o55M51J8D<5jIAQ?DoJ; zqu`zJ#h1{TfbmK}Z{6V#Rg zZ{;_EuDcTnFz$B?wmF*2*qO#P$;aWKl#+AqPfOZw5qnQQ?T9NgxE&P%Dux zJ87Kja})n>{AVO5|73-#E_}pOOM-;FiX0h3NLvsgio7#;G$A9ETWzBDP;s39RhSF$ zJ_tWii*d}S8=6g#>ZDphjYRs4xYdK5r-_$C%G}gqL^LdSHUQX4 z=7X6QhDsw?a5etTXa>TTs$!z;F&F?LF?W#?u8+=xXPGc0^abynmlDUA8qLIrkB^uq z?w~CR1@(bPy=jo<;=PT^8grW*a>K~v3UM+k25ny(bl1&dq{|_koM;W0IF5{*xQWn9 z83r-Uh*8OX-1{`DIO5PV(l2VkF&ZHTR=Q^P81Zt*8L!P@wCj0* zcGD=Dhm#czzUn9N)VOWyfkIznBy%58WIN)O+B$ad0|{BSZ-{o&apS08%sRkmk&O8A z=WtMt@NSU9xP7bE!6vd_E0Ew0sxQ9&yXG8gc_ZTU5t_LI#ZrS`W zz~nWoDLbJzcYsYK_m{D%%zd(lc9PWUBWuXW0ATNfI6yi0Q;KvD+KXHnkOd&8kDkzQ zj;fi#L!7EC#t>Eu9B#pf>Cp=w=<+Jb%%71pH*nbMpwApFOojo#fUzHTIGp3?|2^aI z&U)tBh~omlf2{f-3A>qx2y*~HBU*($pot_~w5c_YRJi(fBH&f?l!tG^4({#%!vMWa z^t){a5ef_on?tG&(o>+LQV>RpGnJ|1c> z$(fk_c9^%pu;TT|8g!b~FjJivS2Z+fI0_I&s!o1V5}b05ZC5mg!2({}z2lD<)K`GQ zPmELZLIh<)DTYD6c*EpgdD}ssIf2v87Dv=1XffqhTx140-cxOyX0PD~F#uOK-dkNR z)2Jgjf068l-QQphQ7JQ`IH&}Fe9VbjeHI9?G2TxBwBDGojq^+e6<$%y!+w$M9eeuN zYoo|7e(papx2`__mM1T!n2%=pDV{kJNS ze{Zq=t2fsFl||csOqGRiJ&X&K?5)weBJQPEe2Q28?Qcb<0e1d07Bk!eF2nX184e6OI`d*h zpyg-O{bwMAMAqkVj5t~csNn|B3x^Xl%l<$1-aD@6{SP0`4AGDV8bYP5h|(e|($u7Z zNK2*Co`gz~QPMIp+J*KsS~R6X6HzJ+O=;fOi*pXnagOtS+`q?t-;euo{L>lveBSTZ zc#i9NJ+J4O_f6G*e9SOF>XslD;Au@I)nmy+0$w+hRBZU?=M2U7LB3*HpjA3}olxo{ zw7&k?^J{XxV&Xr=8*X(Wi6(_tG~NSC?u9U;7{XR$Oi!JTYyJSTeT7D98|PlLUr)V1 z=-JPJ>)2<1{j%6-(Rm!&hUm$7tPIq?dDhzIddzenGir)IUA$=-&@%rUlK0z})GRwe z%a@EUk9TJ9#)}k&CbhYbe+T&e`PT|>^<`|LQ~Fvm__q1cSDvppq3g^LufIaj{eGR_ zzOP{Gcks+`>RgV((s(pw*mRC3s?7e&Qhj@R-<_|l?N?s@S}FJjsi;ULZkcy?fLA+f zv;LSzJpIGJ+>9=>MY6uZI_T_ZefCK&a^CH)rJ8StMnlyCwU1o1rO<}tzv|ky_G{he z8)_Bdvd5d&s7))u_E_eBOYz@Qe8n>VI~9Mxy8kW3e@pRCW|PD73n}InL#k;SmHeLy z2j9%^JJs}>SVrXl#zcpQUn||;;+sFL_{oVU4x8$t{Hmks1eyPYuYYp}=Vasza2rrq9lUKxcDH$iiXZ-|%nwgLY^ zdJmKspowKeYOG7TLo|^EWJ~BAZRu#`D%Q66=Lgx_boeUJOyDRW?IP2cFcyUf;Q>%h z>z%4EEd@{lME8}`dWHHt7LX~^LUatBjnS}iA7DUjrFP#@aK3wLqN@l8aib@64S_sK zxLYsycVC@69X5@!K|Od%=l~f##h0$T3q*CmZXRU-OaVt;t4T@DAL~NI zkk~%7OC;gzx*m>|uzCO*ylPv@gC2vOw>|_m0G~kr0Fl1OBnzSxbss=G!Q`ZZv;Nwm zF#%!KGU+40fLQlF?`;E`N(2KSFu2!MXRhU#;UCVdmnau+u=Y;{ zuy2-^@-L zcal`AnrqV=92GJ^pi1m*07gd$-W$og;6qel9n;7dUx!`t#MUIiiu$Pmes?!F>jW zl=u{zBISU@=l^{1?q}9Zqu&T>VgmY^L{@`T(8kem06bh&KLxRI!Ugam%RCIfj-(jD zM9I5v!b(4Yn#nE-zBG7)3H?Kd(gH~Vh79f?EiH9#(ITWclGOE<8rr}F)FPVm4LN9D zP<6+qCr<&EqfrgtKvcipmUSBfGQC#?sI1YVFR^pz*eNpp1T)yWx(@5x&>x6T`)5NW zWR;Gt1ZVJQ3A_mE#aRH!fE~4`*A^1d<g`@xv#b9*mAgF_6QILq$+p%Nw`!w9X+ zksQV@>_;!qa-w)1?^zIayC!fCMgok80}b2Oa}Q@LX)Lqg0_Vn2^>+s>j{$^M zG3-GGb*<@X)oxh_AtIs*-QV7BLr?&!`wy2;E+e#g(2I`RZ%F!g7ba&c%oAEk?4u7T z+c6Xi%nb#0_f*g6DKdi~XU{Thc2ScsTc{~NVbEqPTZ#f)RV|zBH&m7JxydwCyu5o?&QCJN{PuZPfQQr zok-?}bd`1cbQ=%b_@G>o59E5${rlJB#!C2mfqX;R&kT5dowtE|Eqa8Sz-ZO8&P#J~ z1L?(cfZKDId((al>D*06nit}u)Af4{<5VRVVzMGc2z#B<+lh)RD8VM>m#aJL|D{3g z8?u-}@(50IRhVe}z0cLhz(CDNOVdL43FePpC3!7UxRk3X#@>ff>gvZ*1y|g^LK3*DphN|vCB9N^ec+i9f3XG^(%0RrHRN~P4a=#mfo=htxLkha;$<(KK4c7zw z|L&-hmWFoBlOX!J$mS`jSw_>6-7R5OW2AcTfG_`p-o+A4)-0;*cmBKf2NF@jQ9&-n>kQ^mcSyCc0}bY25ZNY|z1!$*)B29X+4c ztOr+n>LbiUGI}2Sx0z&5$Dr_a=q}b++jIUlP`fP{g$yS!FO^F|&og)R1?7O=U)YD_ z)cPrODh&`k9k-b1I8N5>ovedw^IlxyVt>U1IrZFzMj%3c5GW0*j%05=U}#Y% z$?ZRFYw>?5-niIvH15|=q8HKwl9JmsDg+v)x!HPu^vT{fLH>^#vXc;VPd|m_@X? zv*G7R^$Qhx=f=jC=cr4%l{RluHoKI#Goa%afx(OM!}kYD`CbiN$^hY^2tbU>*wLcr z_28uwg>Mx1y2?=EAcE&^Z#n0iDW(ib3rGDTq}$tZ5g~~u zhD_w+rskmUDP>jteNt%x9OL-x5a}U}(>Zi?1eI_{a1Ag)Y7gp#!~3?nd%(kyCaGk1 zr*<;dHza@P*4Qdh6#OgpKo8Z*T(UnqsVf)b1TfW$l$(jT`7ovzpgdavrFIwI_^OJH zuOjN+;}%p^PL+VDf|4s*JkE<&L#=%974{^Jrn9Rc{^~jR*TmyM!#eKyDFe}+s>AK*pl1EviA z+Y+TGR}^Yf-u^Z0k;cG~6mKFE&*8&DlqvN#>ZKe~b~u7DJoPzv8ylD%B7N#jNn?mU zs**8D$jTG`1RBob+mbK@3&r%y=r0;JRv=Vit0-!FB4)3 zL?O!byCheS=)K1k8N1QisQAi_zNECpIs> zcYm;A;&Rp6oaF`OS0Y2#CBJ8vcBm?kuxrojvujskb}U=A;qWL-}NwMS4% zuDmR~)$>aM)!2AW!LSLsipB~kJu&|7;)M%w&LXct4pLE8W@sjZ%CPq#LVJ^f6}nQK zY#>^Sl!cUQ_k2eDv23H&VYjC13W0157S-`2*g$c(q4D(T1vdF4Bf34XPiql+S8A%Z z4=H+@pI}e%N*N`|CHfJ4a;%E_eHbY27DgP{wtj`ThI5-{&gSm=s*&x166p7p_jJX@ zM2|KN^V(}@5@FqRbl&Wls4iD;=nRy2*Vg7&DT$gP2#}E?#){h7+Ac0*uz;BdN~qP7 zJmZg@?|e1&d|_MG^ziWm-#AOkJT%Ud$$^%u_`JWH<@bRr*sYojHc)#t7TDu9Y zs7EwV;=yh=lE_j}JT5TEXdNwB;H7I+DZFyoxred2adSrfoGJ99@N&%4lT$>if4%8b zjJZeG$X(Y@y@iE^NKeeehe}w}57)2Uv<^aa?-wFp%Jtk_$z4~Aq#HDr zA@m6L2!B*X=*N+HyeDYTOmUqURWdOeR$4i)_T&bwaKxU zzck0O&#FN)4;`ugr%wC(uNvMh=00{*R`yZ2b$)DKVoXdX*dT(PHa_OOG^c9!xivjp z!f4UWJ=e|u-Ir(G%+{ODP{OWFQMlOdEM2wN!gmZS!Y9>7yaOeIf`V3aaiM{EbFQ>~ zm!^x0%L>|g?oC?|7;eMT4Zli!ndkZm$pp6{%-5{g*jTuOCCO!FWzf+}=vfQyIbIZ! zb-9_DnfLDP3TpD4p2X^Ha_GM7Gzt2V-zjX|;)Tv)n=f9yD&%6AY)IZCe8bX6d=R|a z1VTr}ojZ#fL6xyb4*_OjH9X($&Im_9S8ZwY8Z3rwIyjo1I|3zU$0z27m9WYd7#*7| z^s+uL`DG*ie5{V;&ODeRQ|j^2#%EuhbehErEAV=D?RrM$+`{>C-q;AP{II8%o(QVipV?CwPV=seRkp znv~hPKwa8(F;e|v5!<_+exrf3*%w;VtWuY;IDar^d{8P->w^@7}>Mna&C!GQsIm5XFR3w-^_ zlPB9Fn@S%RdcF9EEwnolQLc?!_FFrEkG~{Cr)j zkg7ls4Xg)r4S3GZS^v9xCU*2d5C{L_S(nH)y|MkpNsza3|2pe*_QG2CAX^_EKy)Bv zkX?Ic)nVbHy(cCK2W_ZY;mk>Vp5CM6q-z1&@v7&JiI@1AZk{`^;M^JYQ+Kv6)RiBg zpa^(m$kc)y0_e_0bo@f+g;l~qNlA%i(@|4n<6AG+V@5J8S{RM*1(+;J35iDixYVbk zOiWCUeJxUad}W%{*nvlG_C7|kOh+hI(EQ=t^aNJSv`eB8-AcYiHkk@&)D}0l3BUpB zd-lWyv!Is@nks9AglH5!nmAUiIsjfk`>tCji}yaRs6sUxA=U0LO&(&7AC&r^FmAijCMZQ`ve(642RJdFJa62 zX`8_X1{`@Gv}n~@H%Kdx7H_7>t5UA%9Yp!+m$YU5zVu1)59OUjnJnDTUF}ru~#`ux=+xi*cxgpOrK6o&9_pO+i?MvF< zy{k>sb3{}P!_F${bOipGYQcg41v7{d6HFX20U78{FiBZi*+Ylgp-oVvS8W7@TQx$A zF5v0@yi=D1^hoD0h=f<*?Gb&UNgx%=5e7OR#a`LjAhey8H5z>wIsSg8$*rd!GICf>7?=0ajEh{4m zQqUymuqJbY5)$~`DGm1Q*%QbnmHHw$I9O+|yFFr-)C>j&2E;1*ca4gsdkp0I?u=;H zK26lyI4L23X(zgqW=Q?g(Pu!khqOJARwAVZ)aC23!R%S#sKyc*^b}xppvPpQdg8LR z>}b_)I^&5$|{R02Fe#vaOuaz(zdK)&NndSL7+xONEr^&+@!&(I6W`h4rQaD}7|=|IS#d^36;9F=FuRoEy1vl2tAN2hb8<{?(#8jI zk>3H_>-b=Qrq;x%A+Otr!C{yIz=$wvYY6gUh;PJHdQ8k3+Ibj(peRHnG;mdhGqS@Z zd)3^1R!Q~JcE%vd=U%;z{CSK-&JF+iJSXbKXHgZ3EOI^n@3|_Hs$|w?x zvn=8(T@3LYJvNm4!HvRplT$sSy=?#|b$mKLf7^9-S_+CI;({%w54g|$E;{_p$ae?! z0+i`(%&5}65EAkU6-XUz?bFJ7@oo^%RyfNd+$WJ&ys z?*Pt-Ats%nM&`IjkXBq=9AZBrmnJYZebIQ$+)MQ|H{NU7l|oFb3BDd+ zA^YH5??;aw<>uzX0fv^|pBl5UIo#pRf4($6nw4S9>BOA#oAmS8CF7!^qEP&62-)0m z`t<2-8R!Y;PhVChv_tgEj&lFqjvhYSi{Ez{?t+(A&6UP66UbNJf-jr6;9oplT{yXZz`gyo+dUpH>4impQy)#(}5?zDxve{cEC@0LqUg} zv}BvYcv?Ken-t zZjl=fj1x7JbJ+Y{5Pr>R-3gpD13qfPwU&a?<*tqaOZ(OGkeC!HXa;fJw}iW zM#RHutcw>fM)rRO>9Ysj4fF;;p>9JSwKnTw1bJgaW<5RVx8O5xOf|bW;s9)!cuTl8 zIld=PorKY8MeX6GWVyWubQ1~nb6Q6>X{sq( ze4H_Z;zG%}K}u8O9&az5`In2|Z>@EUG zl(x5UZ9bm#8EQQ^N<^3hRt!BvokW#u)97)8$A|)V<)SUS0L5)>L&GHNFo*;I`GZd8 z&Ym7DPuNE5B`5iMp*7E*0WwRLDN)ncmjsG|cFh!og1`>9tEdo9yzMha z%Du{Sbv(csRSgPgm$fI#2E&~-C3l(^VDX~ZCEJL!9FF_O5X0=hqyZJ-2V`$*cg&I! z{N(-R_AURr+t(e?TUuKB?%g}m)qsV>rAGs^I}rMM_G_aE6(gSpz+{gD*|0^I$va>4P_g|EH&?2V!nMQ4zFEWVmOSAHNH( zZpE!$#xWciijcRhiDJ)9D2)966!4W+cC;Wo7jwf6e;D^FVEgv%AQqpusR7V&txsQF z9o1D|4DjiK%I6q0Y6Q<5N4H$J?;_&`Z{A!z8P10O9oD7Ex(8C==o-wS9 zN(AZI0cof3c6oXE)BHKB99R67i1m#8k%-Zs1TDOFoITc{x`XgOw!dHQDqX$ojFX|g=H_vC-@Wl+w|aT!4en&&?LAtsd2%~|b3$k;&OO;%{?(QjC{C;A1EcPD zL5_0!MFYp}_M@2fi;k`xN=i#Cn{CSkqL#NNrgsMG7@9#|X$39wxmU%)?!&)#5qrZnIBY`_jmgvoVU(MHjdCXxrtV{rJz3IM2Fl z3{Sp~&xgdv<&A|WMD{0SJ=LI|6!u35(fO)k?UC1;d;E^U^7gFG@-1y?M@CMo z4C<1^?SVT3gM&qtuw&INr*AjHMo;XSci>fAr`L!#4|49hjb;HTCoF9|b2MLN{-hTK zTFPwx#^)AwoL#_vN_Z$}E4$;`d{)$t!BU}57)zUH(~Ul_4XE|OZyf|05gkqDl#g8r z!}|F*qp$3KXsJDzVwcf{jGjK=-7jG{H?IKgV43Ab(>>!NG?90$>yBQ_&7A-{J`?3t zyw(ur;wldwLMwZKH%kj%PT{)M|;s5c9Zp0W~1;3_$eHZtmDp zfZ#oKd8b?C;(s=~U-Rq(9Xw>ZC!iq6f(gN_BqSuXU!5ic?odC%E?HRP|4m}SJ6*f* zwc!yFlBQ2r+}(PoD})Q=j90gIGWAEn3=0d}fbA7E0iTYv^4R8UC^0CJ0}pn?H0tAG z2=MN7#roFP)^>MylVrxcA+g*4T^JKMjyNgL6}b@V1k}yQ3CAv! z`|)^8^zRRfttDxLInIJJh-I(Qn8QKMkP`7~D)}kqwJ1=Jz|KNUR zcc;>pNB$km&I6 z@Swt)M$6g0CSK(kj|{|llJ8GtXDta)c}6b%yEi|^70%Aa6W*&R@MrM!=i~T;fyu}i z*~N}L$Xyf?6DAhV%NsobfE&|mm+u4?cE!1U>4EtPex>BojQoCFw0CX6xnVOXKCVl; zu=TEdSZWQRkhZ6n-a z@B)MuKoj&8oH5?4Nv93v%lU>*-~0K1;MW&^YIL?38a|1K^19611yoK!W*@I=WsdKTm+SZ>&R6i`vEt-~zi3#ARD59C; zLvdVKr5D0TMc=xWX4O0fB1uCdU?1Gz-d2Mt_VcG(Um`!5y=vmJ9LzIn?P(cMq-K$D zNU))-Rr{$|_+d-UydCTB8RLwhFwf7!Ge2k6;ep@Qz!DYYu|^=U$m7V2MG)IBY*g3y^;>ezwMK~;(YKwQT}5Nu+AruDz#kwSAQpbGmYMjt^==h# z3vR<#KleSQ2jZX}#SDxeV@Se&S@;IALvLn& z#h$N6M`+7=<^aik_wHbSD?ZNXJ(76yHdNi?rFz$*d_b5*KC_*hI9z^e0#^tnzpGnF z;dRyKT45Zx&A2i3qKM8m;Hy z=>#`0X7Bxcporh<(&~-Kb5j+anmBlW`Hq@@#5=>>42a|%Kfc~l^ZX0iA~`u@-s7L= zJI>CW$2V9Inr{7+g z@p~oYdkgpF_CLZMp$OMi<2~y-_je5P|ECWXleK5_>~{Sv2Tzod;`5))7_B^3;$`9S zT{cbYYFX~e>aH&4+QY_;1CGTe0o&MH2*0nD>Pj_JTrg*p2Xx_K${uVE;W+FC)!2Tq0l;z!1W`uDy2i@I=O zv9J>eZ1s;G$quGd!RT#a1~j#go=UOErb^AOZ~@o=At#P31wH5cJ(pBm*aF-GG_Qz= zh} zHy?;n*N9kl#zNQh->|`Hy4_#LSZEZ4w1%M;|lSOzJhJ`>T2w7jXHh>TOANAe4%_K*v71--u zOSPXFL4-KLzfCw^l~&pLHVaThc4A!zRq9KXq56Vhs8;=pnLQm^3aC*w zjC%PB?lD<%X|nJm!(R_!%pLCxRH(VRxshG2Teq&8I#ct9^KK%eP1u3KXwm0JE^1aC zRfMb;(4TP=I3esyKQVnOMy=@C)TCh}A;5|DUaLp04%|d`uf@if(;0i$ilHE=61gc- z#?#PMZ_l1hNSRRu{M21h;a&pHuZyr)>jJ|elA7BH#Y)4~89~5v8x?R48 zot2QtL6cBaB}j`pAHu~Z0CkN+sYgD5`Fun~6Uq7=K=*hUS0V%yAer4zR~O0!G`%P} zOQew^3g0xs|Ds0JC_bcpWz&Ks;Q=M`mBS{efs?KR&PttbV5C(Rlx)&&y77fh^82eA zsK@=@@O^J;)V2yxcvW3ao()K32?!iq($a)C+-{k zG{0p5atakOKHXnE!%_pqzx|)cXcoB}pFe+Ypax?Rs9`bdajofBn^8L?Wj_~zT(HDj zKZ0DX;+g|4#pV?#MX;M%lSZ(DMH|tG#){kEff@-~R&Ke|7l89LbP5!aa7=9J1**S0 z!z!|4Gmr>mNU^Mjnwqs(aY2LZT--*Z56NIa6AoX)o7Qa$sHoB^-@kk3Tbgz?NonU! zOj0UIEjWoNo9Ns>jMMP<_m^-VOVuW%kkhl|r1n_0+T+OL8%NNk=!sKsehe61pFVij zXkR>M+KWb;nrxf)@}-H3Cj(YSrm>FD7wCL%F|W;S-=Vv;oq~|=X-J8DFtQc_aS zs54jp`Rx5(yfOL5;tl&O1lDyPbOob(K=xts`B1eHL?KIsQ7PXqO|61mi_(xV( zxj+vHa)Lr~TNw%S#!K_)xsZ<^7_^y6u4#`dq8Rx4Jey70`%Wk=e?x$NY4irB{mpl zNnDZU9LJ4Tdr*Owl|7#MIXNMryCyntgo+7g1z5sj(Y+`gAo;DZy~-40ZT6jCqQ?*cZcTh;HG{tCJq%zw6zpw#)60e z3qV9b`I2*q0wDt<v}5nVYNE4y0_?uT$u*}A)x~MSn$&sLY|(+^-gMjD`w^+CA}5~o zXT+_jfk}hVw0f=~cr!RDSgC-Lxk4;cRi0BCxmIA&Ax&12INICvnF!W_S%p_ONnAbD zWMABHylw>ad}ZdbK7D4I^;gJIe{#rZbkR?bdg{X*z)gr@p!c|Jy343(#)cmpenf?C z9(wZN7RD84alk(b3#+@1Z8^L+_j&A`Ou{|FSE zx>ya9{??+_VNig;F?$}X!QE5FFa>^|eD&UyO|^HK{c?MC+Nqz>~!=eMy#KYk+!v013e2 zbJk-3Hu6J!hsBxf(z&mwtSov-63xb_xJn**?e$VKUeV1hcTHzq{0mae?z4Z|A<+TZ z`W2;MQF9rhAGBp?4*`Y!9>D`IrxFGAmC2F>R$oypq9rMZi$DcdRD9nc+Aw`t(fOhe zYe9O+5U-5gCe)rqar)?`iel^Or?PPZls$AHe4{nnyxAa%++ZI@TqQ0js4}D|G=GtQ zrEWOaE>A#VavRb0ADbu2X1eLd9TQ6p0aw2_8-H-Evj$fuaM)1<#_1%tpe+WGQu%Vh zeSeOpW0~Ub-Mfb_5luJcyR zZ5dI`iz)f5yEsp2{`3o<<-fnT44}sMDOrrTkugYV^(aY)B60-2d68Q+Y@;j7pMwA2 zT^Ruk{v7z1K@ivzE+PTFLVMl%PdbNx`g1`4n*sQO!ThkrKS^G^mR;uFzbJIp7aZdU zQ}~ml&G)S{F? zyX9sf?e5jKI}Qdtj^92$N_&0nw?ynW@Aw6F`hJI=nq7bSr^3PI6UqzE%dGU@Cg>Ni zK>lUP)p;ksrD=b=B9+XizZDX$t>c{gL_Y;A2(zZF@x&SC}~h|8J>eIL`G7g%XhZnlIYXTnd7`CG>K^8?bG zYm)gf@bTS4y(K8n%mIPhFECIBCct^Qo9e-{j~AWiSgBgxD7ZE{OyaWZQhJrN4=O)y zaMUJG4ho80Vmr2N(frGqije4A%F?NIQy!2oOl8=WD{N+zqY>K!KtA$YNawurUQuq= zX{w7Qv4Y}tNfQ6!X^-60xqjwSP>@oDm@p@&F(TvrjugjF71H9f3S)tJW!%h$!WLLV(DaPN)9We%~~y@_)bf7T&(DSSzu5p!qMOc zzNd4+oU=mzKj6e)f4`*S@?5|* z<&PgD7bIBJOV)k#|I6Pm6?1|plamHR|H^LaI{|;d&%eH+q?8Oq@qAcV*!lB!K_?`o z*PN8n@jRqeLtl&VlEXG6;O{49Xj-q^+@bD{0w#}GeyTsF=CnV zU+?f4jZh6LFUxitd-UaQK}ZUY1r3YXzLrxvHI*ZPs(OX(10MgY&v>hu<0Z0kQB+e? z6Zo;WqoWlXW`vyheighWT<63T#;Ujf^%{x=i>stjtyy)HHuy(J=QZb#XpMN*rh2~3 zoGNET{%X03W6N#g3^p&ly(JY96`F^^1eKJLk-=7+`rjU6EBiK}OF#y!>*DI*C&8+a z`1ecsWf@Ypr2dhi!E*zW{VqepQ9fdlOc5+5TKW^85-m~^>oCLEcT3QfD=kRSnws%s88Qs&4%dM21t^2;a%JKjHS_nuwsS03QYZyWjL z>@CU~q+#jpX1KOET0Zozk?~v2cCk9N`Qp#r!sg`Grq7hrzp{$tm%Vgbdv$DjCuaHl z%A1kj-pp_FDPGKR>R3T!-b~Hb+BJ564Ot^fS)v<=)Fj1#KG;il z;9axO#vWhcUDW7|#t#+e0cj)D;=iCFh%WxvL-L_nW(oo4ZPBQ`1wTqJexfS_kL?Ri z@%=hTI)5rtmM{tk@<#JNerR0D4b%mT=1WrZ{novElC#&Uf$qRf7PO1g9=I7X@Xo!E zaP+<;XkVS_*Vk8VnY67r%e<-${qElQ5yaiM>JkW5Um%LF@dx?E&HT;-y&>Tah0HvZ zP(Z+sXh~=GyWkFf$*8}E8RQo!jGkO{yni>#tO~VWXf#?1E}AQYiQdo(daiH27JO_V z*kL;@iW}|{HMi%y00t#c?RB<0GuelcDJZCt$rDHxm%8p6Gz8vx+6vTCT_JJLsoduo zYWoX5sNCHlzUIl+C-jM-+nk^ugT?}TJF|s;cAp2zgwAl{E1pzTFxUm9YsqK`)0v&j zetICUXe$q;#Xqb;arFVq2nXGA4kBV||Tt~ANAib=P7SdJ^QI|m#nS*#KKR-W2p3qrGiR8pxZc&*VpxXIU zr&_#F5fXcE^BV3%lpJ?>x?eis$KB8z|FhPk4r$HC)DJMa7ghvu@H1x ze6Zf@(#a`&KMxvUW7<7Rq`wKRf+$y$GQpVL;oAqKO8&(Qf>{-H9X%vVsZf`-&h3{! zup=f+hD9w86zpZvwEHGX2>Fv#pit*x>QSFXnrP7YQgKVm+(RBD#~e(H0&Se|_XgAB zJZ*9@Exr7fA#He&_XWuyN%hbj>yuoX-eBAFE<2;gG4YNb>AgVYNzJ-R-?7;q-DHtw z@l4KZ+V-9K`=k5na&syv`4m%9L(#MO+7@q+MmsnGDuavK(UdiaauaZ*G})Sh86c68 z8CKvJuSdaxNd2@ug5({r(*&BE=!j|g9Br8CU!zjuYu=-)Oe)4d9tj4QCM z*miAobqN94`)#J>uua{(5F_MMj2*uCq?6zdG6NJg) z*|gCu@CMql%O{VV>F4l%%AUfE&hjZ$uivD~P)7zoKQ$@YvB-AplSbjUKPokKy|}nDD(P5kbXNyR zt$%`Q`PE@UHq9`4kGiA9v?(tnKx1K8rZX~>gm;R^l)!YGaS4l@E!{q-`|;6R>Zmx> zAgfR-1O#kYhmyT>^R<`!*5X&1_&~A5)Yxfb2ny|T7 znM)pY-{z@Ub8y2A?H3oacAse8R^luk+VC#Xu%5NX&D7=Edbc&RtAjqy=xUvH`FQ)R z(y7F)FyTt-VaU{ypXo&$*XFxaQ`%rkjMC*V(mpvh5Lu78|W7=E3(qaF|6K{RLL0meFFmnPoLhko@x$us8HHSb@(vY+n`_5 zEl2vja_4y6ybJxdq$)X^lCq4G8uhh4^dNE7U~wAI+69n7e%rQ%tee*J@$K}89DjU% z6*(DfR%&cTer?oqLlT-|Xl)Dz+R#>F`JSpr(DCUdwb;o`V=yx%MMZ@44r+c>B@yoG zO_)3r0Ds}vgvRh4%Ka?swo+FFoIGBluG-p>bhI{*C(ZE#+M1x8waT+V*7%bq`Xd*= z7q@-qo85@RDHI~X>?kp}Fb#TTePEF+eqq~MIKNT9k(w76H3$}GZ3PNtIVfK^CHYA? z9-=U1>)?J9cKdY1ZI``YVu|vDPpXqcy+=@uoIQ8$l}+~MSR`1$EL0Gbs^H{{wyUb{ zjpFdkFf>?mE+m9|ghxDUwlIBJpLM%!hb-E!O%Ak`fj+kvV@A;= za0N~LqIsaezj`%|=dbG?pN^%PgL*068iPS&4gmtv_mFu=N}F%8@4IRrW?TwU$Q-Nu z0m5HHNtsMR2SXvO!_-zKS}c17`ei_d3boBWFle#;Zu;su-9I@#>a=?;Ia>BXlNWTGE%uB zxm!z1OG9H7J#3X-jq*lxY`B2`AR=cYDQ+^}Jb!LmtYemU>*xh|Jt1^4Fj+aX|a z+P+ol>0je0&^Tdr9Dj45<3tLX{Fe6cblZ`uJoV zuD8Vy&Fll9f)$0IzEPON4)TK(QJuYh{d#M2-IAP(L8mK>W)|I%tmJn*a`Z{mM>wHC zmxR^RN5?TfbeBe#LGQKN-c{x|01R_*a1c!!C#D`-AFwd6(5khUGf%(<*oW2B{JxS3 zQhpD=tYlY9gR`?UIm)W48^y4vbr8UnIKRdvn2az4EiMAQNy#Slj8z!Tsjb-uwa&wP zyOP>KUTI*US(zc1=;cMBZd)CC(8NSXN2e^ZPG1YmB^Tbl7mqgm%ADyeY5@NgvIgi& z^Z-rGy=4*DdPY|fGj*+7aw|924ek2_9~dLh^SBW*r0(WhnS)A}R_foA00C4-O>JLJ z(3Z%}QV5=GZ0-uaxRJ~IZl6HKDkqla;9cHh!f!Qr(qs-*qfP%aCoQk4qeR7y!Fl4$ zANA>7d&?=FN zuG6Xf7WeRchkc@Bj9*XWMSgKw1>ZIeK-q07RlO+iic5rv~9Y{b?t(E4DHSv zpTE2%SIWE1LH+BL2E#C{shOO!fEd%9{J43K`xp)=BT;z_Ko&=-_SLo;&a6{+|thX$fR zhWrzKmXLKY-`Oe~i-26v|6rL_qRYA(*(B#{*h zUC}UeZKU*q8SgJMO2Rk7peG9ob8{;!+1J;Smwhx5{7ETjZ;WZaN6Fg;)GAw7NH`&w zwjb=Fms_-OVK>quQ`49=El{n|)7HNIDpnfD9K{QS6^|<`5&5R3uNKs=MlbJiYg1^4 ztO*_i2lr}iUr)0VRaX14E_2)UGhVl4?oi&$`9Y22lKddxD+&swLr;#ad24bx;GB1v z64e!q&Q{9RF*Llg0d;pyUS7p;qq37lGaSyaNi{qPo`FZtLo;}r!~XqmpqX;v@?~8U z8g72Q^aM1^jn(e4GOUJXfdkBEr$%By>NyLxm?SO*dJ4m{;kC0h?@==tnXP9hU;E(T zB^F;1k5f>aI+xI0D?I;y}kb|%&L|` zCfL!@fu8Io3=FZIk3c>o!!lxGVqAN(OrS!!(ikDDk>_0wLkIi=PA0wiB($U1A@YwF zz*L`Uc>m8BAWL(r*Orn4?Sil|MhC#(A`+vM!!O_sz_vJ;)I4zT(4o^tCr+O9`*a~B z;nKEPS2+iv`peC2)YjuiNB#BFG;a&9dlxn%F8)dN zY_E{FT%t3A6SkhzT~_f$NpWo`CuLN?)%_x})Pn2QIYGXisNUfAl!lP39qos3K&$p* zSox;at5>7(6qz0}LS#2}KnsGi{bzyCw9N&QXUMG(b1r9NGelyPg7Oc;k|jgs>#Cqy zMtE!x7P&G)8VoUMl}u6StBnJH6K#TUvlSJ=KK{F!-3BWFcAT!T^#R;~u>SNJ@b2NH zwIb{Q2w=sow`NKrQ$&63bU?t8KF)hV**e#)B(e`4a0rp;C>;UiizKZG2GFz?aOMo_ zhQpT~s$j~d+c(~)n?r9cz-x)F=CF0n5uqF}7G|m$;B6W;_#nT4Hqo)}Q@R*bkBm4` zRrGx3CBR79;kJM$pchwHTl-jlSP^1w9Q0c0CE3L%x#0RutafdZe=?%WEw1rI`c^gH z3EJSpfx{={t)|3*4$GC})n%#kpOnAm5fB*ugdxn6pW4bm;wMx&+nns|Y-|CxMZ?kK-FXF&2XC4( zQu?~XS)((LbNCz*Ujc~c#u_9%g{MRxrHYjPGeMC%P&L5Ds)TP)wt^VRv?HWJAR@3U zr-=~z5PFa?b`YecWoFJi@<#TS!}SNOj!oC4FNv-R+%=w%1uCYk-rbC*hp#W35#Q5$ zO(6U^T-7!{;!E?FxS|0XT?YpF@Nz^I#j~YxuzX?Gp$8|s7SG^6o(_nO_}Y)iEkW2< zx_{AbTk7NBt;%v4BimF5)S8CosNl-N-bUX?)8rC+nLez`clkgDCX+bSAb>? zx@_5UY|RtsZRex86L#UWG`F<0Gz?PpQBm;!jo9x-yQG5;3duO%Ge9!V8zXr_B0!{u zSy=c(#C+KXpvZr*GinfJNn^BCu3EVglcK|dgS89{5^JTUuLvJF<&wF@c?tI=3136`D9wz+6r3BbKjq0b4iaY5{_1Rdxh#@8VU=y4fDN107)qO**Pz-hnJJJ#i9HF zF12(TV;O6%kImy5bCsyC{B1hLxr3xrcR^~EtEnS0;qK6hs7nFP!3X-~;qI0^y@Mc# z$L=O6D9ZAWA3yHyK5U~RBXb|k0HsG2RQK2i1}-YSA$IrMp=?Aq1C+$l5C(!&h4_2! zoH?<3<2Xi?l$EtUK@3?)PWaubLw1*0Y_;FZ+IP+r`_164g7Z5FuJ;-)E_t^lpD|vb z&iw?y3Nk@PU0t2TgUfsxG8bo9+S=aBJjqZJo$WE{f<_snq}ax6G%rt&B~S0kvb|Nl z7`^1HtqO4aPOGkhqNGL*ype#)8YYHL!?+g%wHm5(C@G=osVt=!9*lS zZ)NF`!LQrM!+Il}^~Sp3ZjEJmvh&n8ZcW{?EbnV@u@?R@rhn8K1{5sBG0iiuEq?0~ z^fFYg+ITnnP=gZN2cAE)Ubt$i(++0|>r10bku$US1 zo&!9ayO8-B*Cv-|aeBM<{SFlzPH1VPMt&5vo5-f^J-w(OrfJK$#z(&=ck7Qm;V`im z)C>{yx_I#-0w10YhR$saHXi^QD9^S$e7GB`R<-Vb@jJT?>^Kt-Q=X2L4%zd7i5d%L zkVVM>J*D502E5gCJj0Xz>ZaOP{&ehY$c3R_L!?X`Eb8Kd$L#rGwHZR3(GJoW(z>Vc z2^qOz5HW&zIYAOJ-7Rsg^!}N#tZms3zBz=A67nXz_0j8HPSQqMoig=a@A5Ua*+;^? zxBYf`WvnN9n{yyc*nt+OUDHFm+d8fnz~7C1>Jw6#Qb`0Bra+?{)ZnuMNERy?Ensm= z!}`Nt+OVm|0gnk_mDnIDnHv=)+ntUFL<|VdjE(I1TQ9@!UTi$8ILD6Jhh^V`iPxc` z7MCVYvf4`@)?6)QI9!|l@r-=5lbUc8(}d?)PIHVTAPI!!ZwbVAM2D+h`~ zX;?R{PRD_6_|2VV1lq1jDvT|p^hR~3E5#xjH`9zd}Avk?Nyd-O%3@=UaXALiJ11LkyZ=Ts?XCR8W0dfQpgfKa(zC<q2XEsv(OquqgY6masNNdEEhZ+$!9fI5M4Cshd-nwH z7IQHbf%ua|Z{}8&Q9rv=Cr?5GZl}o3+-~&yp$p;NPLo630Xyf=|F%z`Nv0eAU8c+L z5(gC0KS^~W$Eaw*EvpQ>uG&~g&o#b!bst{~-N@%7x6na?DOaBc2dQXitn2T!T^2rY zw1g3D02>(;VpUJy!c+#IQ>RWl>S(Y?nWY)@;& z|BDtO5>OXR1l>C-YTFYyoyw~+$!w-G2e(!}(~l9Pdk{5@;A^H@47{v(oO}V>&u{kJVQg&*1gHG?P7}pHW!L z>zoUCVF@XDh3kfIA3W83sn(DBar(`~Wt^F$65FU&Fk zd{N0$nZO2Rk(DM37~X%~t(T`*Uaz*Mx&nLw{sn8_=#gR;KSZXX)k`^d0W_nM%l`;EH#6(w--P) zSIoRN1{-_YNdj1kn%X)2*{h@v`#P$7mMHGr=07??i%3FR)|7yHDtXZ5P-?bBPH0=Y zdgDf&gHV1Ds#fzfZt}`yq$`I0QD;kDj@9$R-e9iPtC0qamD(SpQl@yIRM~X%?55c{ zd7-i;rUk#9@UvmXR{A_AVqAalGd-hOXpahC4)b&A(xuz^32|}HdJgkJfM(5_nC$EZ za@1`p6=^h?WS3O2WBqk7GTzUJi*E+Z!@ersalQ7&r&&<$`M3|}z~D@q3& zF-tBt;K_B8^r2kcfQk={bYU5?6JQ!NOGUP|FOxh9 zcIOZNq}hk-LT|Dww{qALR#t)c&rr&F|NebQcsO55#O~f}%$F8$t)>3I+Pm^_tkbrw zWi*vgk}{T8MIw>L7G;POAxp^?BiYJMs4T@qvXn$wE6G+0k*yGqrNt6bmguo7B5P&& z&ikR7nRkxf_mA)U@AJV}^ynxQv2F|VXEy8D!LCMI#uu|8=lg2WdzC=Gapm1r9KqK8%9?@6>F zV-3A!&8u1P?X^XPQ6aFb3b!V6+!Vz9Oso1QIN(vfQjdYujQ#8#LC?gA!uasv!<{@( zJRC-<71DGE?2rPNmf(uxxba+ZCdJVq$6GGRcz*kZ1q{qG;FB8u6{v3r!d8% zVL9Bh`eA;^^M)van{GZRzY=EO>Vs##Gac((jYZ{C<^BscC}8#vx&8w#?a9O%zI7dK zqGuN2KkOy7_0E4~>M9{>W2%6)d-4J*C(yCJd-4r%Ii#-^b3tWV7Sc6$bg5c-NbqA_ zJJEiukLL z!LeY+UgJbUFSV4ocosm)^z?MD`P$>XT+!KsgA_#KLMN?8fd&f#P}?1MFY2?y%QG1; z--asiotWqycMR^|x~_q1Yj8-!`z z&hQOHW3nvLni@mtpVvz24YXzc>8Ve^N&!sY17Tj?cyJ>y{D4fX|DXpMsH!yB)kuR0ErSW4=OAP)3sjKhacXKtF?|M`!*+I9Uw5VNciuKv=91hh( zPR_lnxNpYCBO+Ay80b8|+qh*YB_)0yZP<;W(wi`y5m1ww8oTcuaxwPVJgdEJkn<5G zA3N?LsDJe=jV~U?S%EX{JB_=N#2s)%+YwvQf?m+oJ-kGufBtddpLP_62Th=r-)SV? zCAX4H7bf9${5!!G?rjF_T)-s5%*yJFp|gIE%N6>&Ini>jb*-fWn%nE09>dIkgk+kP92B_mLe}(3~X{5GN3FlALQ) zWyP>8afbAjWxNmE-*s_Tk#(jMHl@LJU53YSL5(J{W4o^~KZx$_9qsga>)e`@HUx1! z;vXxW1gpY@0as2=Bk)8(jqk9z5e43XY&#zZ6U{GliW2S?545u~*zvX%6%{p>ttFY> zbv)#8Jw#h*MoBeBh;uni_&7 z5?;AtzFZ0CeSl}wG{7AgO|f_29(f_AzMOCBj@ARVQ0|v`4(4{7J+*{fj}$hek@4|X zWTc%?<7{H04;kYVlf0gtw3CLJ6`r8o9u4nk^q!8bqRxx4nNMfqFw7^G^UEe-VPKS# zn8h@@Mxtk1F?<95p&*7%VaUbWBPg(-8<44%c%qcwc1NN4(+sPXnw?VLW{sIkn*UENiE+0EBB5k!-NF-&))ffD#x_h_CgeYqs zH^a)vHSBpCZl|UWyh>|_HKQ&LXQepOuSd@kN(o{MBX$&BdPYE$ie zmW;DF(TLrbW!pN9)V(imAAaf3hPtZ_6tp*T%%6$nS6P+TVGsBr+dX#a~~_sf`1j^=%E>_OY=t2P(5L!8V2$3qP?)c;+ zrmMbj@-8UwG&a8W`6G!r>E8rh157LN8wON;#lj;^YTS+P6F2HOhuK(J&pG;UO<8p7 z=1nr|(MEc!yTv|%ybN{}(GcE4{5Hkwejz2xgY z4%)`cinJ54}c3p2P?QSvt_PnOcGvNaBbfkeAO3L=RV8&X2V&pQo0-j4QVP zt}$cN1@Cz{##{8&o#s>BzcHoJ3Cmq-p=5>J@#4ik7kgyN+u@$+i-~FL<)drkld#ns&Xe2XZ;5yjShf_H zZq-dcdx^h#Ab(ix)58Pw(bq-3bE;fd5YSRvA16~sd+U3UITaWb6m^#z=aWx%GHEb^$ieSDqTxwZMuVIg3|2yQNXLF@1B>KKR z97ooKHfM1~7|qqZ1Ob$`cb`Zg^SVPqLy_WKN%VqnXhgW~xI|6;o{6pgy5_y5le2{I zW=IlE@Vvq|@)XLfZslHXfgly$Cn6Y$hWur;<#}S%3<69}Sy=SI*Hb6^+f|4|plDGL zDxTJX^2^NJW&xAi*5#-T8`Gt7bLqG1d~`q&vRZ_ZE4B|ix&4B7P(sSnnmgkd$(adF z48Pl~wZ;JkqiyP11_m6z{L+M4Q-i378^tA(hR9>lufv#_YpW}(E!17%bwXuXSXfAy zQq6OoXyCj)(7X6skQ@SK&U8iL(74U;oZtV{hu#ym_6vT$*2 z_D`6O2|p3)yKN6jZE2hvstiJKd5>Bi0MkQXjx1dU2x_o(z06RQc&n zqiIFea>x0r6l*#2MI(zxO`Kkrf z`qtOiBk2l)`sLNdPrLs`gZ;xd=xGnO6{MAw1o5a-}Lw>3(w}* zqW1wA>o=$j?48v{s{P=vu?`&?MloBm`VnCk)~(o}^l_Ocl71@PhNz0}XKM`viTaTJ z0!be3XSW}ZJttW_l`?D=xWZvjHE@N@qgtaPcYN~5`@6ZM`n{kog9w)BMqC_52WyE9 zVS4v_#LMXEMf5MKG&AB+Eg!Sx(x%s4Cjajal%Kg^L^;ZQ{(ug$REoz|PYNY9q+77i zJt~&AebH67OyG@PMc_cR%bRn4ei(%Dm~fTc+^ukbqXO)8N$%`jGL$^AB}e2d-}h3q z+=^LUg627)+xFdaGRHEcSvVW!yAE-Wy_!CKdpzTB|5A({zz_ue%`!5R@!^L=C+3T& z>-gzVf^}GLX}IRj5;WCm-zk%Sa~~Bp2z)|G_W5S+sXOu!Ya(cqNR357LamW4Hud2! z*fm&a>SN%&&rmgpk1n4>B584=DW^cm3k#Z|!K-5KApt?}KxYbJU@={W%n~`a0eti^ z^*hKdg4)-Y5zXhn<(oMP&CrDGxOMbFAnFZ26TEl^;R8L#8bi(>W%Hdm6;LMWDRn53 z@J2}*XA;~-bW~pq^H*NJBV`$SVVLtj`m&roC&^GN1jIGNLXwu2MqDQ2<5lJ5)gMd` zgNAQxK};4qyn}GYqHNN*Ip;&j$kT$K3c2R1HXXbW9Zl*!6jzlnMVbK>4In)$F)z=Z zR8>D^qlR_vZQN?{pgzPG9-O0OC?iC9__RicF9yo#7&fY8aL^0{Q*D;wQ~NKC$oNyF zx!JP09d`WjeMA16+li>T=&~RR<&I3)Y)*gzA>m6zB!j$e+c#iR28IU8*q+f&Y+QKz zZE_3`9&|;AhM!|{j+!3knPZ;PNK$6h)g7S-Lzjdl$;-t6 z;5PsG(c$VVey92)mfz3g9yc0l{}Iatx&XSMlbPAA9sAoMF;f|EMbw%%--Ef_J_Onv zv}Ldp>U^+y5@i4I#ApN!+E=T!EGE~Qv`bhMfIJDOgvF1Gg#|;**J}RVLRHbCAVo5@ zA3rWx+&S5de~1zzszU?6k4gI3d80`a7!8m+i0Pt<5vh_7n&qIOFJ)x(z)%;;7;ru! zo;(vlkLW^g2yM!0xQr{eQXG>OE{eJg7-+1{Nw9Xd6jrt0$D`b@pO1zfDkrI9z~QI( zLXz4WBl8I?0tYP8(E68pUKzk;wSZyuqG0t=ozm^WFIGnf_x~a2{4_~2dz;esVAeIh z98N!C5>e>9i{7!4G&0}@y$iMg2YK#o1Xua`_?ViSf-O7@1?-MqW+P_z>?RF6uw_yz zT9fwc>Lx|z&O!EOE-4377)Qzie|hkG@mY|7BCy>@DTP{LJwR(OV`93Sn8=)mYeEn< zepryB_L*)BV&j(-xI74Xu@xg-sPd#!iV#Bit{S)ART}3v%i-XXhpmmW3*-YbD{rdC zid#oCzcdWr?FNn@3~$w6NdilK!^ZiN$;_Wt5u-6)ep#edqEV!#wbjS~C1p5f<#b_y z^FW%!~J*VSJwLz=Uu944?SF}d@vSo+9I zsD2-^+k;T^#g9dSVCmzCaeWQh4Glr%;b`&d#SpvZ0~~v~*~6_0z2;%-D)$?mhS}yg zyeWM)$E$8hUU7<&_4EJ-8v5CcqyAmGGwcBx@%TJM*ttIbA&2*p<+eNm3hqm5wowyd zFtzW3J^K(}MAbKz?6Q4T+^?G5ad~!>oXRqrD#!MPs}6%Vvz#Y<&6bt!je=*{UE{3p4|DCGY>3{mnnfYl`|IqId;`>UC8@{A;6qn1FFGq3p{K=E# z)YLFtY81xJTxfDgJ`|<9T?9c#uuVhK>fPzBS#cYtCbx1Nc$pdJW|sg~uMc%emo!@g z;!YU80C*;S1#D~$(1cN3csW)2DJY4G{82R#q!%4^*sQy3XRIKvk9`3?$(s z-Gq3#WlNUe@2W)a#s>ATW}}?Q{*mkbbxj%Sn zdc1(?=b!x^z6~#!j0Y6}_-<||PLZoXZw<^wnAlr@y;JG!aM3?&#nmheh5gj&;Ka zFItxu(f!Cd+&+}C)rj$KhE=@)%p1wc$uRLi>LxrxffBLsK9AY1?{4YRr}m;UiZr)g zLhF^rbE5OX)h_TL`sxlR?PPF2q?44Fx6>BV{&LUHwXq$Hc*3s)Kg}X7(}(A7lh{0~ zm+(4qJeLf+eED1!QgQE{+9+P4;+*51np-!2wa)H`mx69wwSm4dGU8-?BLSzPaiOH^ zse}T}_m}0GhWP{QKJ{!ixK-Emsjg}Gpr3uYobQjX#hf?2#W=#(W7Zn_Fv*p31g|To zXUu3=>zJ_j>WVdM;7j!Q^l{eG65a&NzGcf6l)+G{A@iq2=W6wuRl*|)T@ksy-Qug~#ULWLnG^@}SA#R$QwC0+WX^uPK`4ol z9ze?L1BYq49qyM8BRb0Nv%6s6@#S1nupd9kH5#7@lgNK@!+`zc60_0pk|K=r+%S&1!@Qq#Dv7{Aoj7)*gQk7@`1;O@pXaSE=FDM_53F#L0D8!dRPPKj zf;jlQ0h->wUHOQHXCT@dLDgQf6B!yJx=vr)IqR<{^*Q%z0`;pFQbHrP*~MQ^3d z!wt$ubO0<8qh^7{tZsTwKd_WtkH=vKZ$v%|qZF-|VmXn(Y3_FNty4a{ z8x%dJLlg=(edb>n6&Jj|aCk(63>~0-RCDM$X!_)E&{_^?%SDq<$@g|V4!N}UStlUT z95UjV{SnMsS{@d)^7qX|@SW3rzkcUG{UTSMLKv6IrU5>wuRqkbZj;o;#|Dhwdq!vs zIr%pC?-hG4uJY=|Z!D?Ay~nE?BKX%IyC!9#iLm}}9|swpa(?>+YeKo#{O$jPumAtI eX^Z1UnUoFJNpvv2RO&;%ut!l%AywY^%>Mvn9fYR< literal 133824 zcmeFaXINBQwl!QHTRA2$f{K6{6$KHM3@Ro>K}3lH0t%9moG~FP2#88hf*8m-QzRvd zL?wp;$vNlzjZN8oLZ80(zR&F+@B2N?kMkTtRqeg@T62y$#+cJ5m&MPmS-Ev3i9}i> zdj9kk5^3c$iA0n8>o53;l#osWiFB7Fdivy5^V(jDuIsfn8 zMdI6g>T}M?Ray$CeM0WVdGS0vY&-aX%fH3rbk0pr^*p{UC+|PqyD$CTFFV!ONRaknTd@yQfDQiQ%PaVaonAv?A&$3GWhI z3GwABQ~Yfi^?ykxY$f}D{x7L@OB?Oqf9(7J@{f0~+IqLF&}KPtGuwGZuaUOPmHv=B z=&8DRcf2B3Hj&QLA2p|66|kB3$%$gutIJ4k%hvej+~2?WB3G{6*OuJ9dGdiq^o^&B z%htO3fBrUseR92;HecV&xVXxM$x2E~yYu&rmMWGkB|fZm8TE|}zLuz#OvNgtS*~F` z-s@}C&uiRS`lO!S?0nKx@V1X3A>Gfo8+b6d!}*Y3Ncs0474I`UpT=X@dR|0CL|3=Zo7YIZbzG`}>vDf-ymnPfo{L}jh}JQB zR>OdLmC3=Tv9U3)Ropt&hgGwG{rSlM@lI@J=WEieCYCW=FV&i|8b~uMyTtwK<;&HZ z5C6zz)UQu5({FDV^I&Jjj-(sWnL?%w9?{Ors{sXEgFDG9-2Cf((QXT`mav~>mg3FWlsnCX|_ za*e9du%SMrjhlY1?bfeMxH5%9EXTCUr^kBenD|C(H2f$Q9X@9Dch0r9?>gsf-4|bl ziyZH*F`DU1Y&5OY6&2DlqYIS|4+#niij1Ty$ZGT#aX9;me>d-iuK}0dWF|k%C@Ly? z_Uu`el2u=-#mE(H@z+PYvgm}Jy4^jQWz#IjTz80^(iT~oDWp;Cy~XHl7=MYSl9$?Z z10KHP^qiM;D-JdFMXTjy+9v4Mxy#3x^i(=>r1KmUz>OFaHE^)1)> zU0e65YqrY~KO55Yma5 zxBjtqg*$tOYinzhjXG>cznweh!YpV#X%MRQAZX17+l}$^!-fv6YdR?@6L~Cl-XAu| zA9~Vt&&|y(p^a9OrhD-A-YwMq_deae89T^_OQYDucJ%#dmAtp=zg!cZU2U{;(_`9N zS{Kr6=f0r0%}+_c zImZ-~_1^0yb;~?EV8&xRJGn_&%qBi7n42TO>OK2|)*_)Esnx_ocpLQd{BvFDKdfHp zNhXuq+uIWxZLP8&uhYO;uL!yJ>eVYoZao3>!5fo|N`5-YBG;}})W&Ob*_}|KkWKdN z*(2tDuqIJoxmwrUieggbbN+Jw+OnmL$90khGgm3wPPGLD1mx!CdU0vwZrj&WtY+E! z;n90FwRL6XL8hkvdS4K0ux8B~wLIs(nph1BizyL0L1Xo=O!pBLXqoup@F0#IJ4Poo zdE@pcQQi5>RUB8PrA>P(4;lGPPfv@!*gMu!6^ZBHltVV@5#PPf>~Yt<@_T1pn3;sa zgM!TQDAj0Rnsl%#^slY(TnrKX(*33P{$)tGe6&QBTfad74}X_ZYw_%@KZnr!w)FgJ zxlU#c7J z&X!kHF!7rfK4$Qbwc4`JjCeXEp8eEa_&HYgF!j_JKBAtQ!GrV{If*~H>%Aj*B?9vO5X=8_Z$t7{@8?=v(0oxqppEwtqVy=_K1zy=%;JwPuYSo- z!q2yGsjuF0q?Ki1h{c48d2>!AFD0F5n3)@}TVSvoVptdvUXYTMjMk&@F%ejubmFrV zPP^*_LNWvU_039QN@?VG@0tgjvZnt={Qhoc0N~g5jBv%2gn)o{0?8yMHdyvh%o@WL zh(93h)A`CoA`Mpq2qDhRH9K+yc=S?I%u3&$%vhKkFrlLCWfzGHVOBsKQJ$+%j#o6F zYV!!p7@)%Rl`e)fq`TH8fNL=^F?MrRcDgf?z;?p8-kzO{AG7k+;-8F-_$^r1#%an4 zYw750J9@j+ZehZ%XAkvH+=xF(HU9DG-pL2cj~zdLHhhry^RF-W^AV*A>F)gx#LaLZ z^ee_{lsL;Z;eLSM=8N=g-$yRK$3B6@yD4c%vnml)$33Xr5?n;dC+-nNf~!X@J*T&k zbLrw;-BsPeN=v%D@174nnD~17$eV|B!vAlk#GBx2-&VtB63Kpj^?quQe0%%Llcl7M z7j6VnG40)V|9OM|tN}LWfA+zD)&TM1Kl|YSziaTxk9qAcB!k??!bHyFG5LOxG%tLV zbhmUB@!$n^75!~{2Q6v)D3O-8mz?KX@&y_5*ED=b`oe`jHbnY4#X)>K>~wU)U2p#X z`lUH05=Lc9A1VN#FpxIU@O;;~@$L%kPj{D~WLApTx|ZHpRy-AJ za3$-}nv@P-E7UBl0W{Rl-nV-3voH5LZ{t0pSDyqRF~e`#ds|bJ*Wkye*T=L2#C={5 zOvH^k8r(+>6dxaN)LwY!AD_H@@sszN(g_THiqkApm6lC1P%$wvL1~)Vc*c?bqdpUz z@T|eDTenJl1v%12zZbpX7M^N-fh*}L3oLoKVuNXay_dxc(WLgjGD2L~IQ75J3&$!5nv?o_2@!&}{zoGO_Q z%^GbIgM+*Bgy)CAy>Q=Y&K|8})JxhiviF5Sk>vZc;mR5FrT!v*HsduusJ!x+%sxyU zHf;T3FdCH)Qb8|cZoEz}<D&1EmDcjxMuG7!#WM!eYj)~Vwu$gesV5p4g}|N&d+){f2zaJ&r%RK zbam>?g~io$cXtn0NK~>Js~~Vxa@Q?ptSKkUC0~Il&?pz|;!yd6a4O$hm!NADy@a}N z`5b?)^B4YlNP4eSnY$hF=W-yWfu5`a?JeDH@+I_Q+dQ9goC zv1~c8e?Kp=lLJm(~QyYSqD)KtGR)uwfwA+`!9%UC~Uro~0rG;kU9JbCN=JQMBMt-7^wK@xe-7$*qi+ZZ7m zy>m{Dp3}_D`4#^t%KG5o{bSQ(Rmu`qlw4c$4yx)|N}dz=_RY|tly?>VL4$vKOIjA8 z**<-{85-fq&(2Kz>9fNHOKE6RhrhB(1&Uv?AzM!k;|nzE(PPK#Gn!07Qhyk~gmMW*cWo<}!)@+wG9 z6fEVntHk1~WIdvQ$8&TjJ;xwcuqv-qgMZj<`p%%S3-TZ378w8d>P1Cu3TMHcZ>7yNP@Zn8E%*-Z7Ukan_2cMej?)~#DnJ$4j&8SPADS^6-*nUTAH zrg32&yH{Rbo^~5glzP$YV5vagfcb%HabLufjJdjuBA?LC!s|EG@6-jqY!MVd(#Tkt z$yjh%m~<)aMF@2%5f~}FCZqT&!-%)(jP270n=1XlX@O@22W6YJhTGHZvN`o^@7`VX zx6&a)hjYvpAKtxtM`hbqF|Ze2ANlB^v{lg3800;ucrfwlsP=qE7H(0duzfj_e%zNX zXhdFlqel+@@Zlzwkh{UW1+^bnT>^-DPPN>JOJBLW7khH5;j|2~-0J65AMuQ}!uo+E zr!P}eX~Ri~QkhJ-{q3D;U0H%ct?3U2W$Seba}|-cuaugi^O#d`g3FX2ebZu1tTz;^ zTNq~=x2U=0VQ=H^;lZJl$`cSjM36qMuU4VLrvC7vv3Xd*;ba`6Sv_sV*h z>agc+W9y0kW@?&UKT#VYCnF;xEnNxXd31ViW@2HqOkzVroy4t%oW`W#I}JJ9!AnPI z#ibVG0BMCN*AnBXMN)OsrcKaLkVl&akiN>a^-zA72TA@Z|7?hE?01bp*#G|hyL3TT zL}jG1U1zC(iO@`MG5dsV}>$-1moL! zV5N;`cL@S1B31?j2VDi`W0g#sJH@y3gvI#UR`x&hTP4}|q;_}DiM*?{9|Nv9PZ%U! zZZvOsmf&L@GglMM-dBCynOC|}dzX57GY#9A>Guz!D*YPlsSEQn#HWBx_7Lsw3p_H= ztp8z(XF&D!M&W@Us~r|0nXBv34JT*{nD$=ube-BY!6p-NF_PC}xE0(A+uS#7P7vzi z+3x(vVLBA@Sa)b7AcAS(N#TXr5l|$BMT}dwe%B|E(nyK0@cesem*#iJU3gQlcLy3X zghNuWM2V_7Pe<$83Orm`gwrVj3ALhEX@KB{z(3c=X-a_`$1`B!x`=(Fsi#+b-LUPI zjL<~A(Fz5|#vceX+()}^M!p+;-@JX>(YZIvM03eYms0kt`CO|kE2&KzGTIR$DEa1Q zUj+1naO(1`U%qCmalxU)*@BGO0t7W;U7g1?^2l*&M!fB^a*@wGCAH0>GV65f5^k|$ zH+-2$pGd=wRI-~J^HR<-;A>Z$eRh}~NZyCi7VY%TB8My%@l{!vVpSt*+(2>Ys{qQa=7_>$mZ;qFNz;JY&f&{UY5) zORUb!vPsGCXZi-414=Vl<_8@l1ctJqp=>ju4^Pmo@Pn|R%k8wahjz7bpp%KToP@CU zL~ev7&xPd1teNq?Rf2>j=ZsVx6JrR{ovE|L*+et1-LNn^Mv0L%W)tV` zEn($#z*dEO%)n7`*i97-HWzU>t`q-g={D4R@?G%?~tSu9xInZ47@`#9jm5T8=bt(E-axc z_sO_z;m-E=3EGc*S7douQc6qLs#|um?W5;V640&;EA}y4q5r|+C{9Uvv;|Gz{>3`z z?n9&-zK*woqJDi}e~(Er5?5 zyCd$j-cfs>ad33F**j1Vcxma}sCe$j8v+dm2A&g~-h|C3Ud&G{&1cis& z%ujV}NEkoeT>H|8-^{j!vGI!~@tDUxPH$ipzbI50IHqDi{h2Ona+`+B}q*c?^EMl2P*F zGtufUL!iKyesz>TFzf7^NGTUaHRp;1g&5NxG%VJa<>g;bmvlA_K=&m|vW5>8i@AKU z!ZGmYWKc41D&WZ2wzaalng`k3voe?49L#IRT%W#3R;Dznyg_`T@7O_kU4E$l5WYt5 zoeJE;(o;5lSV%oA_N(RMda`H7v1+{tV_jcH$9n8du{52sNyRk+3oOhJEIbMxou3&X z^y`H|x`onve@=6&rBk%o6%u-%vPD$K+!E_P$DRPNfPiG&R~z3a!|y$v%72HifT{Rv zs-xz2(IS2x${*MJ24Jd)18pCQflHT)9?%I@qrMqEhx~`?svDclPsk?I5g6Luo+EYe z6w1~_JxZ<3**D3l{{AYx)zK;)ZEbCIf}^Eg`^_E;r{KNjT3Lm+2w9uUn*SFdT5Cd9 zH|3))4FUI|#a*!DwjIpgAmPL;NKQ`X?Geu$2BVG2-OB6S>Yj&}PQ5{a$c&c@mFzUC8@-pQ)%Bir+v57#hSgzxB`J)@7@F%|m|%SkW7=qw zE3+cg#%l@h1!{SN02JLbfp*h@g<^abcBV;U{D(c%oHrTi-Yj>-3xZnG~QmnMe$B=?-}F;#3H32 z#g{G`6Q7pS-JBn2{Us^aDZb{Rg<1Qh*GDy>C$qCYHMJyQwQB(p0(_19u&IF~%IfP= zZxy(soG$Vc&Tu7vj4EMQj^I?&J+9JluZuwSBsl`Q2y~?1%y$!GPyPVA297{bXsFmi zgSE=O-q->U?cRgVW4tw+FU01jat*xw5y(osZtB#3S7{9ICjh(U>v8Ml)22C3H{tPH z%>CFs@Msfhc7z}cKFP5b{mp>hu%Agt)gQ$lL55FpBDT*CJor;5#L+38lj@D>X- z5sx1EvmfSi;6O5&JWbFC0J%mMwf$Ib93Vh76p>S7k#>FU%c=Cx+q<~MeP&+?(v3@`-sj{+PvH>0V7CoRs`<-!z;tt1g%|AKgMp5r`EnNVbr`3MMob;2w zX%JOZR0JCIU{{pat4|{_*m3rH zk9jd%v0fVEyNcw)xLAsQ$|pdIn~^fr8Y3MpUr}COPK|}-!$fR-^$KTATiJT(49p3U z*OQOLJK*s=+M_ZD)L(B4V-CesLF)yo==o-bjOq+KJ2A0>0o#d`uChSC+Z+WfLQH(d zw{2`}s_P!DVf!X>7^w*4@_tKBdr8A^T_R3zdD9^gYQ{rn?S->bVr2qzuBs!aKU~lR+AN{gXj@|A-?*;a%?0c3Iszzp3f!XtgHeKe~7>M$((adq1Az zbes&YWlGtg?7{!i-Fr}#tgE+ zUazrm_76eJPy1l~HZQK<2^vtIH}jK~E!tj{2u@tDI|feW_Xt)fevyzG{<{e%jex44 zwkZAU6l`AGW->k8rG!*5#Au5Ij+5zS^;k=y{9L$i+c{k!&~r$oAB9);2?QHDcuL>W zJN9?5ecbp4Y8%TUWBZdSK3+A4B-OSWg>8s#qiq^M8TS3v5<>3eDiL^*EMHz>xD$ZL zHgqytTT`&q9FJ#qEMRQ%GIUsikICLU%g22zFkTjw$}QY(XJO`Y(q4(+X&ClXx$*+LEfQ` zg&sc>KcHGB2%dCylUc03=FK3aocUBkbqRx!#Y@7*!$?Go>CrBnWpNunJ7lIK6KgAc zgIsEDO-@!8Wlbe$)rr31&yG7_WYHO|r`&@-$5F`)Y&v6E1k~x->+EZ0u?>&3}35&-?hU*5OS^cct zKJ;X6dNaoN1lg}fAyd@2O3`d?*dt>#M}zf95kk05W4d6xz(|$g5tq8|Q%|){lqZu) zpHP#q@mqhTwYO%N@Cbk7a8tM2{AoiSBZnmJkr zKhMKG0HzaX7!*exglGLJtM-R1u`T@N$7(9KR=Nb7r<`H`Uzw!>+&NIOr=|*6Z*_M7 zC)v$=yKrd>g6-^hVum2xSk5vW62|D34LXYO#Pk^3`bIM zXsEWH9uW)AIc>fJK#w?jO-?QuYiV#6_?NmKH~)Zvc`h%Sx#Ck^OzJ(^TIQ*i6DKTc zf3lod5UvUO*oyt`{HMnXMHLTmH(HNm+OMkXBU8E2n@U;1iWHzpxX5NuUuRB(umwqR zb9ybOl^D+x_d^P%Ih$mVw)Tv%ZK_Mu&uDX3Ak2H?p-eHp^27oDNMT!YxAk{BVBC9V z6-Vk}%h684D0ua%z;x&Pt~OA;K@k!C*qe(~QIOyVk5nv&jH1c4frc~`vPV&7qTC2D zRg#md0qq^;K)b5!+=|d!%z{R9Ke<(UFh&Ho3bWe|$S6%5fKfAjlEG8z@^~NA+q3A& zlE!mL1%?hUxc~kK#?Ji8BwmaPjy<{6E!}3uc{ArbEH^S& z@bSd9?>m(vy59*hkhoz~hkWMo-^pjK7m5|T8#jH~KmNTuSjuiZ)~~I6t#^Q+U%$3G z74{_?-D;pZ>T}UEp~VQR*Kr)(jR|!E^GX_qaP~b{h~;dZz#)wj-VOg#O0SxnRIQ2-E{kRVgz^+yM@CU1GQq_NORizZUIY39Ch@jXkX`zzL%Cio%`XqX z0RS*Xmi*vwB#$OYs(-0Z^@jwj$K47p-us8Cf}%B$sH-FIg!MtQ&8R*A8`?8Lb~$b4 zYz}+L@9h;U1okEAPD?sGIs?_w?>~NQ1Gj=o9K~R_*S3DxNG(R%aTNx5w%qjw4=lD$ z6VQi!a*G*RB1F3?0s%-^VGS);sK5V?>vh;D`EyIU!)8vfDm{}cV2T+JKUe(Nh*+O5 z+IT=Ueyas%2eZH}AYrDCeis9oJKOp~f|l`k81$YEdoNZe8)>wE1#cUMM~4Dz@uUz; zaEG6rZTkX;zMdYfSmtnf-A{WpfEI$uPwlQYWXp;S_w5$D7#SG@FTFVq{V1v(&)?&a zg1h|umt8J^Ko8xk%F7?do@Zgxnwu1|?hX!=7i@ZScZ zx$)^Pqkifg#DXppcXmZS_*)I?!KA{`)mxXyk$=wX+!Ogj>O#4V@$bgBm@wwonuITp z?t3I@vz{x4Q|;xTbSkLVRqRRICusJ~3$5k4<3@MAu6XrCVN_qF?O15xlp)wihc>wh z*LeN+l^1#5`x}WYipibOhVS;a(c%G^Pf*O>ynbyv+rr`pfs$Z5GKyw}NB>ImY-^k? zYCNb&KAKjnZ#(iPYWJ8Wus%xHm3D95yum{t3QKIDc-^y^`XLh4U;Yx-I@teaLGN+M zK(%~{-gG(nN; z+O72_VL@|{E{;=1sIsX9H&46u`{ixF1D*+1pR>)>trJiCh*j#w%2Tm=<~4?5zHK(` zg95+GUW*eBB4uR9UnOEn@6YdmkuOe->}6R>+v&zFBPzFhsbJ$q_r}-xn@F z9Zt{1(lQ{wf{v-tM2_Qb;hOi;yR~k%sx-=|&@#$9_C3XxKxzvdrz7 z!0<(yj>#30XPwWa``@?M8J)u6(CQ;&i{mhQb3Dcs^2*69bKnRJm5k=ud*KpH+Xd zc0}^tG=t&Re8{-g(_;$yX|LvQPxMnD7W{y{lc zUo-z^nz*8XY5j3Sh{#Pz!m~|ue&)?jT!iO&D8rC#Zzc$&iB^ui7;VD#hlyXmZ&u#? zxt4@wqTEb(c2!9)e_~2=24zRuNYEb1KAjYG>tvB~Ta>}?EQQ*wV`;xCno-6Il;@A6 znvWE5=Q(YOrSibaOU^qE6awz>d4$!eR|HD?ag%HDk zYUx+~FY;Wr^f9p4Nc-L_{Pp_gc=;)=x6(*Q8qbc2mVe20kt`JbINDni zixY5t1RWsB!Y4Q%m!dh}O$9rCjsvkABq$);C+o8hE zPuS+AKC^s%3`G$Qv-$Q^PlWl!CW4jdvvEGKo!}*g6Msi2zlJJh_AV_iRJTf^+Ec^N z#=yLZ zl-uo5PBk9_r6I5D8^smN{=`n}%}sav0HWe`u<8P{9T^hxl&@%a8!h2c=_p>q1n~3? znK|z&opr?v`r=F{=V)4A-X%lyC> z%ps@<*DzA@BUS|RQ@LtdSM^_bJ{mgw0r%U;Ouf-hpYpJq@@UEdw%(`|DD$fyyKK~3 zin=l0CNwggFIb(`x-|orq;K8A$XaX7ZDsCb@?vy)1)~vA7F)Xee8`hRme?<~GB}Bg z;J!FPyZ8;aKB{=hyr;Dig(XL`z4a?kPPGHhf2Lvi;DL<3>tHf^k3_iV!86~Ezm{2C zNZzg9yIv?JBs~1m!r6SyzK@VFW-Ar+pYat*&#XSDX+{5sMvlU=(T5{LA80A#$JbYw z^eK^$Y>vgOh-@`|^L*_6b;h@zGoM5+c?S_E4S0Gr8XbTHF3y67&YfMgz9KQd>R}nv zZ^ga$mEW!O3ey9?2^!J2M+U4~jELGz)L-Sz!^Iff2Inizqfp>cjZ(Qfbo3)tEgFxCQ~K8dh|cB{!b?4JNg$m!`qX#!~- zo+Cwk`ykY$G(Tla(5Z2o9-iu}OKdbOI0OK!J5xcM&(GE4<{2$E`Q?C)Ns~PTQR1l3 zf%k&;D1gL&9kLe8M9;_Rm?;_b-?gluZNJHenS6TtM**~;>Afyo~a0Oy>P7qWvvER0_3 zFsWxa$+Fxr!p{4Xsu`8t}y?eK_Vnk)*k%?_4 zKvFTNsz78;pyW8n!mW3`dIZ%6K_(Wxeid?$r>59Re!U5MK8u{a3L)rs1{w4dx>i@` z$A#IF1;XsG`DIY(QJXM>&o>ix7{&iAnN0s)GPP@3BH;N+bIuf666lG#ow;Hp)r^~8 z7BCqa+*R#gn$Id;_$j`x5T+s!%(v#hmu`>{Sa){E!4k4VQ2M3xz25!5$!#Z!=Om6( zn{4JzD5XG!u|=V<>C;7SmNjds-nqAm0KPeI{*t?H%(?5OC!~7!r>{i`!Q;!Aw^gA8 zm-jogDP1?r--B4s1S<~?M|(-4NQ7du%QlFu`yGP&U@{jVoau9k7TesbB0_IKMo9LePOH=_5wzrH4YBg4&& z?e;1UYc%>ABNGz?XAA;5mIcg=OsRE`b{YAOcn^$tm(ewjl+Km;t)w5EkWR&vxF=SMl++CsJ(q^hQ-COQv27k}^CcoDY$&KiV{ zE2!$fe|IytfN=#UK`?W%$~|GrMOi|6O9L`-i?Ho166>4mMo{URo0~y8iWyKpMQ!m@ zZovLC5BjRywC#iF3%ACJ#b1)9@`!8n4FRG4;lpC*M_oG6kGL@2IR9qtVt0jW~i*M7qrwk1XmLCu-@YyK+bQovBL3_&q)yWF{K%bQppA<3YNqF19(6I+LmQu`~UL|HqHF z3OzXi?AB9TKZe~FKm1xYgMh$zwHoxO^*gCo^=k1Kvbh}QJZOizb7u(jK=xv{#$D@M zWb~xaxeu*k)=TM20C+z4hb7n1R302eA25IhwY)VGQmy^$>8*ORZv zE`HJ%ed=z==P;i{e&W~szI(~y+HD{3!YL?i*^~aG3F)V406Bkp;n_$rzdkr})Loko z-}v-+-7fk=^2V)S)?egF`kinL;wt(mj|JaI+i&s1KnYaz>E!93|O0@;B z7M{^r{5eU`<0UugMEdI9+KXn78>m0CWZ$p9_{YSJ;OoR^*Wu-)FCO=Nh{eU%#?}Ao z4{E5ZwsAG@oj<+92AV&Jxb|Bup-pl1Psh-HoG%0elJU_iy|5$5ykYcW9PhpCmTJ&$o9Kt}@I7nT{?F8z@(3 z_)PE}DPuz40kip!dxRTZOBwVJYBBI+Ej8g+( zp}4U{wdvDRWggVsn*Ra}SS2Wn#)PjrdFhQszT;D}#G+kfctoCP zR>)yc_D+}wp*xc=VS5DrCWt_T)8=S+g~2UlTd;|*$bh#R zRnE*<4^h9u+uy2$5d~h{`bycN_RnDQ$#iZSc)E$L*gR}xUiry0g5d+~ayW!4n#FqX zGf)_sfujZp4)*3f!j=edm^q!W=XCw<*lQd+i{T*Nsw?t5+Bg42ctiyI{{3AQp&quh z)aT*~$_7nGQx=B^izLPJL zhjJN-cHxe2F83(#9bl?a7(0wL4FpNPce7GNO%7M)SJSglbvX9#U$Kmt-}K<@ngW88 zObOZ8Tc6D3Z8BL`T6$SQ!D_5RM&{Zz`!O_ONbWNrEONZ%{ty#izKDLP!=3-Q`PWS$lM^Gx7P1yjA%pgM#y=Dj|LcM%bjO- zV7}qd3{C<2zgw9Z9*XKHl{*c5YAXPHC`otJ4Cf%&`qgWrZy4V3BGa?zifV{b5gBen zaU6Kj>wCn3W!Oa4@TItM&@l_h%E@`jHei3jT}}pVgMJJsi(GYzoC>5}As&Z{!Gw#6 zKlwGYKR+t7Vv(>4uD`R>GiP@4YQdkQ={~+{|BGbni^F0~;=phiH z6Wq8ie_H_mO-G~ALKmGeV~^!jZuPbp^=4<~#TD&fu-PVTD-b;kwb!`B*ddN3_Sb^^ zLoi6e5a!Y61W9bRH@0N2vR-x6jGm~@)X9p_0-$H$grv7h%Aw`Xy4Ti6~7jPN_Gatfl3h)5R5IKq8zf(rmU z?EdOiAG9yfJ=mQ2hai4LBsD+vo9op8XCi1Zd{a@8!m==#2WFYIK{3O24%;tLw~i1$ z2e}WjcC0*oH5dbYKoRBpk*h&pf%3ppuxb7B{PMlQ;n&&`D|&>%k$~peovyHRHm%i7 z3=8OrjeYM~kWvBpC zrmv7`q3a!Ox$X|p^oB}z=f)iegZ1OXf4l1Ai&uRj5zdk-6!h6k4pX^NXV4pHo*~zR zhH5}X0(u66g>(^@T?B?7d;ZK5rR%6K_fUW^1E&xL=W-#YfE|}1WYYcePk;7*kX;s7 z(OP*Tk#n9f>Ah`1tXOQ+q3%-4%|E+_{%`;GZXxeP`72GvFW;7ujDIpwwK!snG)1fc zb*0A_k2DR5y6|rue)dcKo4%bC=0$}`em1n|m}L4pc|_f_rCC3zsDJ&f_j}$6@yKh& zn3#|RO@`N~eYbM4uiy;qA^pj^9V)9ylMe~<<%c&;Z>bIMgbvO0n~bS9OO`Hwn4u^i zTK-ENeZx>zMO7680|U|MkgSfz9E41Luu9~BuJiFJaR#JMtOto4uZURtmOp)bJ2?nB zQy3y_<4nT@xijgG*7u>TaJks_TJ6Y73cS!N0{v{sj;{ma9RtDWP=u*V>4|+}=+{5k zqr5;yABJ*p%RqgqEVWl0$qdk`=!jPz_C>oNktSXd!5fugAbH#?e5BXd+bEixuw()kLc+WGEW1fMy9qNp272460_8_-PPorXBulgmD8WXB zK}hx)DpP11m2f`{2M3tiAl-XgGAM*Y+W(=!g#;bZTotHF zz*SB>!L0?J_JQ`Hy4f)~tnW-ncgJZLb=2*9A$4yHx87W4bPkcf#^tu)-m~V~V)j4UL(*y=29Uj-+fuNl8h}tCNq0m0V?R%L86u#-t{$1&y?&Y+VY%fJW;D=*p2Fn@0e&FGf}NMW(Ki!I0^3GX$$`(1S} zo#qYZDERsn8?v!t)*W{W_A(PtvT>ojNXu*QyGHwd z6ITEBIn&6ue=TvZR@82--yafb=>+U=n5+l{kXZkRq(7)fso?AH<%V-a5xdL5PCM_fAW0Z*Sk#o9m0Kv&Hd>5*~|&10HxY~pGXze@!>N+VHgmoukiZ6})?R)zEX#NuwJ zjxI)P!p2f>)DNE265J}4<{thnO}N|cOvfnLqZs~t1*p@I+8dYr>%Dq zJ}q$6i2NmbH>|!IJ1`GjZBJcjM4~xx;6Oj>%hIokmTF=k6tI?F41r&!K8eg&@qN|6ZsT}u3Gg)j%c*d50L$$PK9 zMSnPeD0<#x3a1^Op(H?m_(X3F7rNIH7#~gx!?RCm6c&8&H|r>Z9WRvv(7?_n%)qG3 zk^TV%7GOoG3Rm!uU4X#y43iSk&5L75Ox?py)Bd{fi^Tb`sg#VFlsMKH+=1nESD=(j z5>PaDG>)V_v7^sZCZDkS{_60nKH9Dx695KQ{%i8?`sgMJh2t*X*qSC!#R( z|AYt-aXoq1$$wQ2#z}g-d^w6J{_a9wcP=q;0d&GPCa+fKrts36P2mPfFt48(c*VJ$ zskfxBk5{uJ17b+KT%cs~zc<{pkHua`fgI`gV>*&~o&)kG zl)1_dr7EI0;kE&Mb836&5h(7n6_NxV>;~-yDB6VmQRS9l0qPRm6k+s3MZd}}YnZ69 z&9za7pkD}O2+-3c>iM(I+q~-86qv5CU6z&}hp8g4LIY zHEic+rub^-DW+Jxbrmz*3+;`B)hoG%=xB@DYfCvIeNdqd!x)S)r%(res;e9u3D1ll zr?E;SY8wJIe7p8kNUyGo7KeaO?dE!Z=dH&M#5XBf59M^G9kDGrS&Sp)`$F0wd$*^P z59@Tch<(;qgZi}*aOQFHrfqMjU>fS9U4fYi+n~xO9Fls&W8UfSphxZs0ANs08R>1z z$bhQdzU+Ggy%X(UtnF%M2g^yyl z`%ezS&;tu8;dNwBv;YQ8w6^4L*Kz;3UYPArTIwq82gtU^9f$q(xFO&ZwqWI#z~npK z^pa_WABnISYjMrZH7?l9lH;|>Sw#PUK~h59xrgk%Z@l-cr8vr~T{JsC?|G(qhmH69 zz+?632;7n;lR&eOJl3(z5?=V_wA(gYp2{uWVABj68GsTK-%*|FsK=rFs$`MJQ$#0s z3(92l6%{7j(%Rt1bEnx|K~E0B8^I7m3cRD+0ehPGo>|g*Qy}Aco(@f#wN9r8{uZ0o+kM~+_hoPLnX3Z`6aKUW z%h6NiQkZ3kAu3pxp5TiBXt^x=AOEVjPgu^cQ)wg9$E)aK9fH+Cm02*n>6FyjfmeN> z?evIEQnuBKEHe7UVWmdurkkncU3wddF0G)TU#<4AhdL<)93O&%cP>sV*Rh#CH!|Mxl1Nl!MwXsq-%y&>|qtC~t=Q3*cMvDD8_*dS%Ex2qGc6(IC3!KUcXm z%DPUsEnr%Jj-dwtboNx+V;z(8g3p(&qQ^)=zUHHNhU5b|`u87utg9d>!-a~BX&IHK zy2g1^*~MGa)Me1ce#lq;dVZ5+VjS1g&ND;rN8yHAjgiwxkawJYD-Hbjzn{=zbafsj zHg@e4j72DzI9k+)vV6lu_D1$Uj&)A2uG5M5)#G@8QHm-{I@_s;A{#R(Tu}s|xfq@4b|I0GM1Z5BwT;p^+$Mn1*u`*NpEqYq zO@$R^eI3zm3leLpZE79OrS#u$;h}9i2|mi<_3uC)bw^uf!)aCM!_WP5LE>}gGlti3 z>tPE~ixF+ALByPFbZ=Ydl0R{+4FDLU+gVc4+xA2`iRhO_uL{nr&#aci4S4y$eN)eU-6s0Gdd$B;dR}oe zu=5NNm~8{oB|QTJYPkg@(I;a_4@A2s#&Tc2dUYdxf*$3y>;gtJzkKy-tgDPw@`iU_ z)@SS^K%(jKKF0Y74Bat_#gqup;p2;ZnBmlLTd>uwFp=)%0H*%61TIY|b26_vb4`mt ztKTZD5V}uMG8^NDOJoz{68P1QWfGMyfP~%ST=Z7i=91$Dhjh|{;swi?h#UbBlgn#4 z9B%MBcvEqLOx<1MDB;A!jyOS83}J%3P#B)=wc}`(AR3n8OwiJ=exZFti855eSL}{r zzzcgHDVT+p6P;&k?-8~sc=5;U^x_q(Tdiv1W}V-SLL$2mlNB%r^Z}9f&|mxN&9W z41iNqVF{G&-nC%6DRZpNUE42j|6R_?>mq!lu&^+qy8`1V@Xkp%=GoJjpQZ}#vcPXaJ!dv%8E86h;Ke!yb=62haBy?O)c!q{gcBMF&V|RPRFEFZ&q#w?wDOsWdptHvx4ZnY zNZu>%Jqgz|;WNZMD&#RgVLMydzvhy14ONBwe9>`&l9HHij&n+w8VORwBY(k+d9G*a zmL54OGSm?0|0{~A#QZHG^{qK|3wD?n1Xi0OCG8ScUpMmdeFn<9TDY;tcmmz8_up_en&EVe=n;RCzoAC;O&_s7nYYINSq(EC z%kNxelM44B#im zhb>GiFZ6I^%pNHY-s8c)xz#(6-&oRYE04jAeLEC%VtsUq75AM^`S9U`qRo-%%=$Dd zv*B>iZS`=w67nUNhWIf5?(Y~U=D@a3eU@uH^l?;nFC)p~C+|#UsRW9_QbEze*FaK> zGde#}tmT>Wm+H*zfrdZ5nO!I7Q3Z|s|i zEUoqt=1%lpZ4vAIVeG&YxXq?=i^P=E82SUn1bcwVd^r;qdhF&RiE?90p!8`!Lz)NP zBgPJRd{C=md~{OCr9=Qh@q(d;tn66^PvS!*&MJGt)1I$L*w~ckx`7|iz)L8z=+#@_ zBfU4}{f4JCst2g<;@OLTfxrVq6^Nyyb-H8eW=R#T948b3v8&s9w^Q z^^NgShHYPgyal6)VK^vsITBl>eRzkfihRa<2d-{#hY4&VY} zrVuo`7+v?p)5DGdTga)b?nG1fxVYKlq{C(7)0Oz=3;@e^D-&cu7?^acbj%0=y0Q}w zyB@Dq0f*$;*l&Ni!3@3o597EB17e||Km(dG{yhys@%{?-3RQ{mSa$^&^cDK{9#z+k zE~(BynmweDuscI1!_ikFkZF&CU{#nLK`S_Y#5hJVlSJlz&W!o?Eq_FtM9zeqx($aItkLY$ z2+<5KoAJ+b-jlK4m_4_QbFKk>O@`(|KBg~q#&mAq{*{C1PIR*8P)G=a`yI0DqUqp> z-iD#u$+}GM-q#Lw(Q2M6tUUT{Ow`w8UpIE9u$my(apeR>aX%rVIxF90y8DanE^F+8 z(tl`>0cc?d2a(<#5_%M>h`9 z=axn=Uw6e(XBe=Ho88vZvP4&6E{5!(caY#%(Y}U%`=YmfgA==ddU|?N5`ju6EJ1qv zrs{)LG=)PIUZW3O-h5?BI0onMG2R4N#hm%^bpZd$EtgU6~6WxVeoMjc3C( zP?=90l}a)p27QDRmR#_KqCmxb8f2pV1fCk82!_R)A$s^<7 z4S>D@^$Mi@oMZg;8(U>Pf0HXkC5eD)Kyw4ped-oz*k*@Q;gzH!PZS zoc2I{*ght#_h`&twdwS!oKs%FXv@%u+H% zqLLvAjYO*fr6LifB}L}UM5r_o6@^Nf=OHsql8DSn=6Rmq{Y1lBclY}~??2x^-+OP* zc5mCg9*gU`&htFZ-2*DuJ}Qs@%WK%_-6dh= zDhuhFJxOr~-ey(SEKhlOSHT*oWceAeu<@V!ih%r?o=88}$w&v49o(8Nc*WtBw@3#r z(iT(!Brm3@wFoK$TmNyG2k!1f6?kigeT3}MdZq)ohxv{L^Y-$kx3(`pS9km73Wpz?VFkwg0+LXEGM z;^C@ja1N!V$#s}N(gz;9@gm2<~->vQQN-<#|5y{+Tx5(ImTZK8Q2 z7;Jc|s}_r0^{Pl<(t@ERuhW(WZXQeh_(=wv=WZ8v+O%PXh;h&GDMp(GSRtNHmD6p> zZgi$+j&C@3w~Wc*w>*=Mle1#qhOY|#GnsRi2#hO;F&9iJZ&}|R<^0+(6m{TFz0!=1 z!KIw?#Zg`w7X5Lz`i}B6NqVf6jCfic6j{-^f2mZB+bs{K!sc78$2Y{uOmrGPnd!X7 z-kTcdw%|^lr`^tTPed709 zzUHkgR{xuawOXCs_(^Td-_Af0? zOvWiDit^E=a^ElSFlJV`Dg22QKA)$?MLLbiN5tm!v^G=i{O3mmbu6HRVX4dpEjzdL zYdr4-AL4??zeYTvw3XRY_dI&}fKF1a-^?|}^k}TUWtqQNBx}N+wnfBPgvih%yJ2Lx z52L$KaJvr_>g2ec`(PZ(`uD^8vNl^Tj>X<)Z`ZA_%D#rdW%-~Pj=*m~pH?AkY}5)SC??pu{|2O0VXw+;AP%N$^-5 z2A*>ckr*?oDpyy|b98%ot!U)Lp4L&|PW(Z3u>+qmas)|}4KSfcjyUuOwY2<`w*^pl zES*z$aOzIe@~9(LoUyL=(9GKYwm_L$PXAl**coNbhey|ZERA4@DId0xe&o{}csD{$ zQAe3QDd^kzyE&;2rbZ8%Ib${ne%{e`*Y@qBqgpQfbjACGhzo(g*4K<-m_YRs0La9V z|8q|22cBc!%kmwdt(HU2lBlN*2<0zc*|2M%{6$vq%ebm7CzQXe1r6_9P$c>;t)w*a zZCBZyE3kF4sMGA^h7NQf;KNc1Z3q6d#U0d+rtv#OhvRRZgl<%h)N$g0j>K8@xiy-y z>gMjlE~JwKrT(d{2J!Ralw<=y66*rh!%v&@(vf)MBYC}KloSeRV7?|cZCa$S{X$ic z`!Jj`TT7p5c>7)2Qa``)pb!t&QK@R~4*!H~Q?sjJ6Hau&vaf+!&h{Ix1E(CKU>tA6 zhsUJ0B4MyLA((SuNB>*n3GT0l*;C0Ei@ju#yj^kLjw;{xWfzO%ecU?D@`Sh7gI=@k z7ZTe9#CH(UziCj?z;y3h8sV>}&f(}`CDVJnOk$TP^m`vMi|j^qt7w*WEq1?Rl%b#d zuoJtaaXHGy>n0OLQzLS`@S?oj&~cnk`tf6)#YH$0)c%H;9|oU`?ayX3EoO|!{q~_B z{~z7@twGqp|D+Q>?u^D4oVkbAnD0!l{Pf8T#xdjVr{yY<(I5}P^uNjBd^vEPq`%5X z_|mVz4U+&#>G;Xkf0Qoa7{(|1GU@xh$Vs>lf)k|pHREsBjN8xy;uXbjF+icJ53zZ8 zKHJ7K2U=U4wj@LxR+LXZmz)j9S3pZ}c3iqo67X@cFh{E$Jnqwh>(pzbH2@j%_vVAw zI7f^#O%7rI>S6!x4wa5gSbmauWsFHeV9Qct#iF-moL@NwN42*!iW_!xqfDXlNaVdA z(e~&p_tNSXPc5*DI*B(qe0*;WpPT}WiEQQpO8an~l?>(AF~z!tLY-W72KcR`?!l{@6m-an|`xZeB|z8hSS2xV*%?OKV!_Hf!@o zu!EygEx*(}galh*zORxTr{AF1-GhmdNaW}f;;`*p{riw3gLM8k+z+Irq`JVo9?2Ll z8lK~;&D5uG)s{6wZjJMYqo~ip%b;x%2VRo1$~Rujdzj)8rXDa&gsEP1;T*zlU$W3(@AO=y(nSd@^KG5`OdkWNDTTtcksDT zR1BA%uj7XrF1&*~0Wh@SHAV|0)b@bQO(sI+)@ye<^;CwHj9t1y&;4b2(RzIga6NLD zAe>FtK3q+KQ)1e&2F1h+^23L2F!;dZ?etaVC|;~NXNlq!vn-L0$_1O8nr~XLP4^l; z2uwrbeR3`+Qzv0SX9a&a;?M%4V0TVYIZ>vF2g?^9%%gJH+U#`nO9D;ztx|y=vu7lP zJ|IMce^Eb1UcxGeHbDVINc(eRhYUO)eumJFUyVdu#Xcwcf(tru6A6shk0H{f= z-P8n<@{iLxM#USe<}a?>2ZjZZZ7?`UrX9Z|y2A=p7UBYMaZw?3i5sC(-5Zc*`r@={ z652Ocs5w}WSAjetlG>dGo*RrtqBM4O1~R^XBci_u5DF+e7!A?o64N$$z34vMrLxW6 zamcQ%N=r>051MQVO3v8L=cJVn?qL_q(;+puka6XGob)lHC(1Fb^H%nqCza_i3!8+2 z+AyCbXeGV97vkI49`B|R4UqI;4GVCrsL_8NZv&GKoHlrknTTk{7AP{4kM&+<@uIc% z($$|^dI8H4#s)Fa=5C;3O+&Uv%z3jFK$$}oYlOaLd#SHwysb?BN#LNwkq@0YXy_4E zi3S@$!L{4g2X_^mtwn!K8_b{T3zuZlOoFNzdsCKgF+B!U27?CrE1sTD^nxwp9^6hZ zF!msSW%H`khB$pY34iADJFYa95F&tE3IoW~h_MSS9-B?Ms#rDJtc(lnXrcQ%-fpns zG_uw0TB!qNS`q09q;Rok3GuO?n^^KV7QQrxlg?e_e&HJ|OUW5&HPQ7on0mvH!IOePU~~BW$Jwy`xja@P69fGFK@_j@!5| z!EP+UuvjGq=GUL5bXG22w1#8u@_k!BUB;!z`o?>qg`%}MF8$3XW9mLj;u{K2(f(6qR z>G#VEfP$yOpIN#_zIcD@@p(IHdy=P;3l6I&9?TjDG?7D|?eYjeef!b_yYYOxaVV{qSvG)b_?5PZY*wyqGn;kFU&I8^OM6tl$JMLE z3&a*%BI0gu3(*U)+Fj$m`0`K87tS(oL@795o-;NcM-^#1*%w4?j0=wvarjT(t;tM# zqHrz~eVBOQ?)Z7DTQ}fBj}%`v3{GYhZb&lLfaS{nuz+RVtx^iVSMZ_WBXbc{nk4ww zeYL)mY-OEr z(g!yenaIv^L1WIZc3{^iOPw3P^{y2!(-!oM9e#@Cg$D#oU^##RsVMfj>?ZuE)G z<#_^IM>XG!i1=Puxnr6C!O~{cZsVaax0NP}yK~+3%ywUly!$24HXhWqLMCoDY|ecv z>51eTCcdmYx#ui6ANuB|2+Ypmh}T1G2}rY{qPKg@qAf1CPu>%rMh`X* zu>t5uO@oNJ)ppzwY*eVw#Xrg2><*eNvD-C~?)6}%a*p$fJx{Lo;>OSgTeYlD<_VvS z!5|J|H#KrF>~ufVJyJD;55)PEEToqKIlwt)uBnD3=g7E}bqmSsHKx4SJ9_`EYPOiS zBjG6Z%C%pwna97l>c$niK(gVMp-er%R5I>jcs_2OefPchiuX)6RJ4Az!@O>jv$Bp+(#6@#{V%V{`9+t?{*6nZL4&apG3VKr zuUIh!p8|lP9#bc#r#0GSzc6eYy;oH;86wkNx- zxNd8( zRqT_jC(};|XS@n^FPg-sQ@IsQB2g+&jR#F#0Q-OKh9vR%+^9M<6BQ_xw>Xz}8~3=g zCb+#*VA3;s?Fl}jxa}#+_&l%L=wh#xF{gt4#Z5H1^`m-T-Y4=cQiF>XmT^9MS+c=) z60#t$&Q3zQ<=z(NID5L9Tj)+VCL6r#e=emv17rNT<#i*&ZE5v`nU!fIjPP?ogVByQ zLIGCgJ--pLJh!wm!Ac{))SS0rVp;I@JX!Z5O#EWXUrkRRmutGlwszg<93H5ssE8V4N}GU*_C-uofkPM@M|QKBD>_3N9#e(xSMD}7xaX)c2Q6!0?u`~qE9O`=;iw%AQ zhIMA4@Tlk{sCJ`0-gefH7qDsFc)lvzd(CA1tJcGHIEJ`Vw2-B%G2Y> zQBy{Ba1phJQhf|OE^KtebqX?;G|JDN?K@4H~|+RKc|E%CAzZ_w2kt(t_* z#WL$wB%QTmX|>YeIT+hyF+YORwRSvosy`?lGgd^7M1M1x8Z@Eq)@3H6X2^&N<9fNN zrl|n@6X@8`hV`mdQAl*44A$7HyecsdhUMd1$Hwjpbx6bPV2KiPEHV7Hu}b~1{e>

?>}Y?Dips^-A-~MLDeT|XgWUk% zGVg&%GL^|Wo;fvw2iQd;5zl{Q^Ap+X6UQ$K9YX?)p|hW*7uL(^ixqg$1L;s%y=o7u zv$16TaRu>V&?JbvW?tYZl8<~J&KS4*7SybT+ydb~UPIF0@He-#T*jGjY>R^VGtc3& z*%e7t&l6Qq%@vo(Tlm5UR3`{s3E^tOen-$ov>#(YJ#@1@I+8JwFf|B93{6El>fyfL zUI*cXgam3k$HwLfN3}YM(gx#zS{@rmE{({+<`@o&Pw}ueM!Jfpdjq>O>(pgEKtId*5|*DbgmIkVFB9<3MNKK<+2G2FRz1KZqTc8x+R)to_r zQG1yCadgidRr7`6PL2Y>KJWNbSMxd6VowlkRGHIenK55t4czjMjVoQhZ?XN_IzJVc z+n>0uwwRuQ`qn|C7TeXaV|?^;#?Pha`LXnF&wb9GJqtT@RX)be5S(Xhyo8n|ne!ns z)hV|E)THu?3f5yqXm0G+)(-IVTRvV5vsJTGy1Kehdvp)tA)$cVQZI}+vTp5Kf^XrP zLhv1r$?OEZX) z#|#3$^p-8(i-I^OcD06~$NvIMhAs8ML(G<#@->8ua%!@63PU_1Ync?f?}Y|hK8=gp z81l(s;`_I60YHP}ean$BeuL*y$AvKj&RVZQc{S^ik&)s@w6dD#DfJh{-A*%9)}7k6 zz->y%hPiXOpK(`~4MgiNWA(Oore3?JuJU(GclNqi}IzjM9)+~lpe z9qSh?GtEm`*YRjbNnxK&cxo?b^VqKGU@mZ)nn650JrPx?6gI`t2@TQTuW*ZUi22*?jM@c1R{N#XJQ1w+pzIwz)^RlGw5Cx!h{CUKvmV7t?l`Be&j@C&KlwonNI|ayV?7;U8v};Z33Q0Y?v85 z9d_L*OO~Mum7f2lvJ#yBWvTq%zAl-5(7Narx{zn&2I2#pudX|XA|4j=;menGYNKZO zo0NJ_9iKptQwFpffic`Z=0PTcaGjm~hn{<$MNufUD?bO#{IKKc*(VIcKThmd-$QQb7N1aAtGs8J|qT!GIKw;i3@#Fu$QDgBSf*^ExHVj ziw~43Z2MiDH5Yzx+2*x?a=yj+BzQgj3*~uVN2<}x`LdpzJdrdtgd%&6IR=WX%xAde zS5hIGy?VTYM6(aPEMFq^4)Xb>9M{(ibEceS`Tgm*zBSOBCU0*w>1u7Y1aMCD;9%*& z0s;^LNNML-c4?@p@xCsY{#(|tfIIPRR3iv3Zuq@MoN~GE$kam6ij%=8fc;2mb#--F z*&v)>B95hL8b008&p!P;_WK_sC0z#1IU*uLVUE2l+yfsdum8p=SO1I+Y`J5|3ebAN zSj`qlT#>saK{G)-?;%?QN8c%-f5e0WCMNndNl8hWN-&}TEU@A^)U-yC;@`UA@Bw&@ z(440e72`2bh>oJ)2>uKtcX7Cna0{)e>_U5&03!rr@R#gB!RqFW6AxnZh#3g&_25N~TJO%HLbr`fGX*4PW^NA6VqWPl*yv=|9v=Zux7e!)Vw1y6t6m}BGeb5_(!at%Y4lvcgo=oX=|iIyoD!lYsBJ3d zudIVx39B*paAk3Eaa9%3Po9HZWbg%u;AFB!shim|SJCMWM!DMwTy_8nKN$(>;NUPi zYB^_){OrPh@eW$Q@&Ts0C0k>@nUgEtq^nPO(aHcMbl_z(9@IzvqNQ@lnDEI#LT|4} zkpKqjs%i^lh{hAh4K0DLg{t2p9^HJ5Eqw+z&YlNB4A zRyMu2D0;~ldW2T@d>ZsaMAoitZf#{`qV%_rli|QUKD;Pq4*E#`KCU+Dt4}zB&$W5; zW};<j4lh}eb9A~4K zP~~r(G=G7=H{bm<0 zKDLOB+DOoVLe?|al*|TZ|5lQN>`p_&78EwRMw(h$7fekFor{K!LedU96U6 z)Cb=PnSKqbLu{pEEoQEe#^XSim6Zj`*~xAiuB$(rQ2pe)f#MV|Fu|>zk;A28E2~EYL zHfd>T&Y9W-jMBeRnvyY&XiVx>Rz&G4!xjn9b~mYL3q6G5pA6YzDglnHgBM2h$$%Vq zXiGKsd4RGwP3W1P0_vQpU}KYZFL>$ExY;cnMw+)3hbl2jk-9nr(k2ha+0Tm59K2!n z=wWE2@R~KDn59)g!vWw5VqLgw&V2sge~!#;Cx*xh$3B#lXlQDVn!`imagM}%WuDF_6yz(8{(rHSuy*`a3hJ$#4-y0*|%l?xTWUV zkJC_07gHz_X%ggq^?`*_kU`-J#aXnR|6u8`08r+szY za{l&mZ-ksbUV_8)0((t3tu2`1&jU6M2nYZKugEF6abx56@0TuJqO*j!1&N~m zFsvxR)jr+`Fv8KVa4^tVqj(<13|&*?0XOcdtmg`wcVGr%awprW6Z`iU!))VYNePoF zUr&%kh3$6Pi|hIn92!C5UBS#uHI{|}e30Oz1MY(g`2>yw>=w}IYngaa6J!Jdquf|U z(O2^*T*Xic3Fbz>z=a|pa2Hqs!;Lzxo+8|}D^^geF0eyQSJ9<0dOf-HU&|uDPR79} zWf)9aqTsBotdv9d27P7eOZhf{i!d@o^YrN^bkpMz#mBlb~MGSlzs zQNj*m`H!%jPo2OG0*GN0q!e9x=mBoDAMIHwBqU@F=d6a$pqD&JOx%>K{-&r%4pN-R ze8fFOKSEY74h7oI>8|MDJqU&Ve86X*;W^7a77f?3Sw0hpxu)jY2Oy;j`N+F4>F*j0 z_O==Zutx?Qr|Ar$pNR~lxfgh0(S7OL-45;T?Z_WOOapqz+n}eUKzH%S#d;#L4e~1= z-kpOx8-`Z)hHJon9M6B0PWEC}Hd3E8R)@x^)~E(n6&Ekf_zu-g=IdpM<_K z%yP-DVcPQHFAPQ|K09FyRpbi``x=xwwbLU9nAE?cqU z^r=$|Dy`AFZwT^|nL$G{{`dx#^I6ZJjSyw>bRjbcJz`?TZh5=@aWDK{=l$Q_mcLbl zKR4h9UKOMHRPhzv<}f&H1U=MSMjNs@U2hplr~J)Z)@66E2vd@`^cd~Qg1m=bT4hbK;szH=@aP;n3G_vn=kOkKS2nW zl1e~U6-H;<{gB0f!BZ_6Yh(yq!A#ubmrth%*=4*eS(6G~du{%EZMdaj%f{@!iv*`1 z!N8F_-S@b(iDF*4fSNUC`nT@jov-&{=PHVi-5io+*gq@hU3hsgRBpm>+qO)nMNF9d zfwJ$b&d5yVw(p(<=?;O|)zZ>3@;+gQPCUd?XpPEB+5YKjY@iRv%o;{_Pt2nmjU2jV z#VK!Q19OMSd~{3^SBcdlSW@*HT)K!35dzzVlG51Z=vM_GPvzUSsP6xup>t>3|W|kGnJceD^)=OZlwgk#o;9Svop8GHb`j$IAsF z4||7GNo|Le`kuc(A(epA*Pj&L>@_8uz-e3$%(Sh&ofu`pu#H$f=5v1hc?TBgQ8TO+ z6tn_~QdB$fLv=N3Qj_snz@7;6-@tLWm;oy2HvTXYI- z()lM(s9bT$xwLFq*tvo3`!AjB>s6g7i0IRIqTWewu8J6>6_9aWmDy_6tkw?E{tIgu zHl0)jr{x8ND@A(&rt84czLs|!G)7)um2vL-oBrnc#&v^T{y38S%_oZXC6h+Z`#pHn=<+Oh+Lo z-D+i&5DePAC!4(;4Ejgz4Z8|38z>knD__}igSKR3*Fu&_#f2nKCi$=Ylm3P2H?-R~ z;?goOGP)|`nbF{Xo1y{yIMP8Wrzz$ zpbbP@fiRT7h^WM&%IqO4=xk(%{9jl1fS$|$?L@|#;`0OO_l4YKdToTENHgnaBVrO5_I+MyDw_yBrQ1908stg(zn7NWW(5tC?uk-jIVVl8FNfvP- zFfb5Xu3M`&Ep$QuWy*fi7lH*31m%w2YDbUW?;gC;A?26Sz)c5Ow-N`x*Wc zxXPFYqmg)`at~F1y+}?!3RJM}G&^7`s9u3D>`N1IUS^+Hm7ne0PHNkO7Vz>?+T-=e{!m@`Z$sl&SJ}J8r6F)aQ7WD_*QS3GgcCi&5 zQh3$9MuCESMSdUJEaFkh486u^)!Euk&P35b@GueZ@&dPD2q|L26I8dboH!0upzPrh zoGGOHNc3fG{qNtuPdHatVTS~OeFHG34uh>$7S&6Gj2`oRCT$K6k~usJ4(8p|4ty#9SU2h;)KgSq?Fp$41K0#> zMMU1ee!Vz;1i@=CWk^=;Kt|B&BP3e%FJEi8RcA@BUVbU$p?U_iKLh2`QeM(t#1qcn zPz@gtwy~3r@{!{x{91-u4thUS6Abk{w`ReD1rVCMOVa*0t*=TumcpQ@9(rbWc6Jg) z(Rzb%FaMoUo2=cI+am(RlkdYUn~7Llz?9Hs4ykEL`j_Y-_;uMQbSsCw5#@rKq_uzSm zn#sTvDjPi~^BiZ*&0g0oeXOY={YZ$;cCMtNe5RVI<+H1JS)SS|dQ`HOzqy`f)Xlls zPZ&6l81i={+)*2`OOOU()w63gO1erSI95O82sCB0c7Mt=kr#s9iqwk)CVa>jODNOZ z>tiwSX4ZKvo!%kvF0i1pLTX5CrI-%BIF>frge(3pZ`$P2yKJowg+sf>pP`DaKA*jW zxZ1JazowU*-5pDWJP7O|Po60K_N?1$co*L7jKp1x40q2x2}67?s9z!2x9$(e2C9Wi zFv{`($+KVB&8v#Pd|^9UTUDhEc+B5l8rU+tL2+9TBuzk;0y-8vROe3@o@48;cZ^Ec zUfLX&#Fp8M^q7W*#xWQkUH`SXm2T||{&}arzynR+>4!zOtwl=Wpa$e@fe9`B{$Y(# zo8;19zE9h=_C;-kF)O;~4G6ANUqvSs-04nBqaW#^$dfUgD;j%(a{er3Iu@>vMaj!L z?++#K3c$Yq(~`HsY78`OZ$+L={S5Fk!E>;NozR;!{3>d(l7MbCD6@GQ%We$ka~mC{xDw zU+LPTT6G3F!F7`Zh5D|BYp&=_jegF&JLDx*gIen6er6b4sGv_P@%vTXb=wB~dtVj4 zIB^9@I5N$zU$uLOlRsMZ9^aH$bYQNj%^UPHg4=MR0-PgL z2GBIbLVb|U&Hy>W6jU3lv*$k8b6km zF>`t#qjGUtJ1#IGTiv>!v6Wk{V#f-ANkp98qB{9a)wcIWkoLaI$=MK0phbSN4c=xq zjgz;pi^&zD@#iVfxqfpM%4v&J(<`H zu>~k#x2XYpR=l9b2lyt8(zv-Vc=>c)ye73BTLa!D0=KTV&?T4hxmX&!5x8{Q2EPFt zCiAY~7G;6l4f{U4V$?K57ryX`ftW(pBgLOLk&=%0aY_k0t{X%rj-#@mfd^?B7#b#F zG@8iJfG#r#-<~oA)DD6dtMO+rPhdecu$+DT)e~vH_OK#v1b9*~JDnyOI&@dd-mI?A z7s5PTHpWNYq5WfK&y;tDxyA=joxhfd1c35HI!uf=m0Mux&-}Pc1WHXP&{z2kkz!_@iJ7mX-SgJP-TmMr0czvJD>Yx8oC~MkaZ4b1$~r zm7$todDDq}HoprwKNwvclb{aiM#Js?)?V|14=y49@x|DtacS7*+_`;w2)?`dW#o{< z58(|e;=;mk)Xs*6XqA{i;dMLm{;vvlI^bEEbEnwiNFmNa*T;GEM!R`EwOlp#3FS07 z&B$n6$QBkzh|5!m*AHqT{LTXooLiUE?1+3xW_4{J9w<4YsTE{Hzi!=N}4*i@S)=6uc=Ogp{<7 z_{x*?j*a;oR(t$P+*mBg%BkP&Br^^;Cz_RU6G5R2H5O>JCgU+M76iEmbT#-NT!xUu z;d6hDLkk^m#&64u#?dEIgAz4tSCAFO%Pr&~M`0tGg#}D!ZO9&D6;Y>$0+8{^=S^Q}Zi4AC>Pnos$u$zdkHs@oixVt>7J`$u3;t<=-WM}Zqh<_C_NSMidOKZ}16P>e_6?!WR&1E-5a zN^54(&CaK&t&j&4D&cKaCMd&~s7dO=@||N_7yIMrwq^99xnA_P$=f}&5|Qif+eaFt zkLWSo0Jt%lCa&vU90d~RC~x$;z1r$CnnNLzgD4EZf3|>|>J9$A_i*XLpcmqrk8Fa~ zt@YA6r*aCfc?xn}oQEEP{o9ktjdgx@(|E@EuDLM|;mvq5{nSVGf$2}NCQrsle5IiI@- zyxI#B!mRp9PT!mw=hR?wr#BZ zc_^hvHX(kd)<>dT19xVeoLVI2u%20uR2gkwAb$O}hq~C&`GNEJH{`J^1q21*ccIho z2RsN+xGi%AVStk!uD~r71`n>M+txZzs7&@;8n@vnrJO4oVjY=7E$3%qt|B(f?W@W> zjwFLhaJ#Hk^qE_hrCT6Jf=CGa_AR>e)qm%+qm`aqnr)sgJ}#yoQ*2PZk*qDPy~*^3 zA>D_P zFlWvNw#r|i`2@$#PqkAMwJ$Z}p4RfJuI`;jXA3l5eUa^OQ^$tk;zFjv)(a{dcc-0M zP&)P>_(t17`r47#-T8OkDFt8rOyL@sw;pkSx+F(8L9Yl5;1HPY40fZz9)(fXNxk^0 z?lKpl-vW64X5yX7VW~GEU*Dviv%q|tU+6(}!=6*g+W~@@jiB6HL=WzN zAZZDpJ$|Npj#ZZddLbwydW?YcvOM3jIzDr>+{sa%;TAIV0V}>M5MWFcb50baVOi7V z8_GzQJr{K9`EuiZgRJ8y#*fqdc*R^Gr|ydA+jm)?8rFTQA6%SlMDZD&y~iV!yYGKH z`SLE>-db8(?I-%LT{PRgX3gpGF6|5NHlnFRQ$|g5d(7XL!Fc_o$iWk6{}s?Q~N`!5C?EMVIe*pWIa6P{!1RY|}BPeC{LP zs8@{xB@ba72flAZB?mBddR1(GwFH!w9=JFi4_GHzG%5^)+Sy1*qk5I_+k&|4F)w)k z{#r&4XLR@+7|X^xU)gKE@Ujh-eC}_E!#qTsYcJ4sF+O+hnq39KmpnYwg?veKd;U1l zm5mQEg&b=RS0(2MiHgeV;fYBL<*qu{sXIH?l|HY18VB!YXxDKYM23cj;%J=UXK0bp z!L!9w7{qqYKAYKea0IOH^VR#v{5MgDX3_ez+Uqm;{hG>Q@I7Jv&theP#)&MDi;8+@ zlhh(Vl7U(&ivjop%6HW4GMZoj3wnxv;`u7Gc>cFA^rx@FYzpRi^v^%s*kSuBQx#@4 zJ_Y&Ib~ud)Q-#NF?b_IuaAxnXM!r}HyUV~Iw!z0w1jfPG*Apk|VZdyQG?y@&txm!5 z2B!>aNH}G3Ze6)G6<4go08%!1Ub#;d+7EkShs%kIzI^!bA;<#5D}|IzMnWy}Wvm-) zUaTUhID3RJGzWluC8v4bRZ}k%|~+z z9XN9~HxGbyyC&=gV4^f4vC9~JR7+m{jIlAS;AkWRXA(RA&h^im1hYAHC0BZt9i3-&opk0or00s8SH8L>{8zQ}2#mB}D3 z=O8bhX2x`BDq*zns< zUu!!JU;J}r@4m77`Z|MR>OrzU@jeyjmo@WYvfl>csOv}|P|Sxfovy+Mh8{vcczk~XfMnp+_7W0MxM zEQ$NytSHxo5moI!e-NLfs(aV}{1t!g_h5M|t1%cP5XA&>BffbPb8PnQk$6 zTDUCjvK%(?;MIPk5 zM=+BFjfXD$r3chQIZUdb%E~x4n|=cvGYlcyIOkM@-6{>=5tFHo4A4sK(9#M|9R|M< zchxxq1GQil8_!v$zx|2&UwiMB!2rBxC%>(cTV%IaRh0;0kkGTx?gOljoOzw-3mB|C zGV83`?B}sRZ#XxBrG_n<=miM*i5wpLE4%*Y$QH%0Y%(g&*u?-@7ZJBl)+lELVwTd( zlKgeGI0ygoozC@o%in-aWt#9~^Hb*eeckGUuSdL!ja|Y*Ly27+a9-7(0pOd70E`X@ zD>2RL=;j?iocL>tu3z_9-1}j8xFOa>z&0&23}dG+&cM6^ek&l@f+L)4-`fpmRs_5B zTs09(-8l2tXDeRHyzBVWu)~-v)tM+|@%{_D5y&~|2OKzNjo*odgS){qT~E3^(ezw1 zSMFzrUGgYCDL)S)i_d}YVzF?wMt>MPH<38%g2qaCYTPeL9~L`n0LtTOnH%~ylkG*5 z&(TE@vJ;~UcAQnH%vmq=+gV{br5=#4rlApoDOU9uw85E&1M>Ay-jhwwk&4ug``dvD zmy8k!QbA$_93C2&46MU(6Y;6Q3O$FZTCZaB%Si3zHL_%G> zTxP9o=%(1XxE(r!pg)kk>ozzB`0{kkJl1#rWvvd0_+6$2)SrjXl(Q}qgiS}fqg?`Y zJ!n#uVYtGFt_@vRXn*KfD6}*QPq0m9f|k;aWldr*tDC%gI&kTW8uF_>gK^h9+y<(q@XVTlMsj00; zbts#WZ2z!z=V2vNZ(LtplylK6{SEX|<|ewsPFgUc3CCVmV1T-!HF zNPr`X?}E&+#Z%8LqbQa7h2~yn2Md=3rSAfaKM}wE!N~o=QDSsowb@khwBE3lb&t!X z2E1U^z>$St?{==K0nhDL_GFJRHDnb%Txvq$)eH0|_H{&vQO z$?!uJzG!TDB+h!(J{CNZ9{6qyrqNt7%Xf3k{bxwHKG5HfYHkM)j?FbUs-Cx2$GiV@ zB=X`>{3AHQ|0Fg(-h-;}&d@7+R_sJ%+s~nwn)llmV9CbRIlmh>5K4*`E)Wp!x+3^r z_V~T{_;?JV0zC&D2z3b-N*@Q5X#W{{UX{a)hrwMDW-L{urK{O!uV1Ej+F(2T0dViw zR|)^P_SWC(pMIs~%a(z-s zeb)(EalDaB!p!&l(J^FsY-wqUGIa6c#SlI2aP-Yfb&bmYbHI6J@CiMvW5F~F45lpLx|M|DMBJfIBN(lPYbaX`7JY~Pj=t+=Y zYGG8c?$$%GpQn!&AN+u(rsj|LIfozQ`Qu+7Z#%L;MX-sLYcE(nP%pBNFJGLutdB!H z{3Z8%7Pfi6F)%ttfTzf-04c7l|kpNq+>s7Uca1GCL-lu}VwNq}KX$AJcZ9+viO6V`s7)U=nYnYL zW{7G&Ma#)RqfHjN({S{>wTU&ESP9yiF}cb7DYuSBVq5^RhU36?t4T8|B~dEv#xtip zD-KGo(kY;-yE&JQrtYT0V#=n+4=ia*nF+-N&+jw<>60D&!na6E%fSQ%>0S*or5=+Y z*ffIn`K6|2a+csl=Bcey9Y}G;V&XNS(57m0%s`i=5aWNMZ-)`a^svysfaBsrka2%a z$e1`A9qFW42Www4G}R$^2_0AYclgc(`>+or^~lN{vOW@WcvXww)$Xr}GtKqD=MM0n zlw)+CUr8*E95OO{;c@dKtnT`P4QpQ>HzFGS$W^Q4LA{N<&n6fMm>Dvq_ycOURbnX3qz#&z{A{Q+k zrk|>p8-F=9kfC0+KWJsw1U4v7?pGC^BiN;vE)4?Ky6$ZBulDrIusQ{Y5h!#$G}BCl+6jR2 zBCW|fM|!APkdFkv#Bglu@k&^6d}`u$mMiUIh9g2TI>lO-q1h6&vviXvHb5X@j+QEV2aboZlza1XAzUk2mMXv$J&0N_KwB(lK#zP0r z*JoBi78BWPH(4}w_esf<4eL!8hndQX>&E}#tNR+$^t2(7{D<6WbrqNDVBWHzU4zk| z5KU|;6%`d^lGeIyDudx4D9qVR-PyF?tllc&8elwR>AIKsdzPaZtxQN?>bWh zIw0Q4fb?&;WqSGT*ER8O(0>NgmscMG+^OCQEcm7)KM73W+cLd?D`&Z;gcy4x0I_WIR4ESix{H3VtGoe5?k>WdVz?)fYf(n%j*kukg@3&d}OSC8-R`a9$z zKO=&** z>B?enJYKNh(Voh`%HtC*BXbSQ@VF39`zsm|U*`^AQ7kk8?rEJ)l^jAuSapAf6_`DVT zDF>hER;}~TlrnRD{XE#qgJ&N%*X}!a-S|3h?pVe1?Ae`Ddh%!46cvN|_Lx*xnGMO9 z^?j+fma{Xfwi-(hxX{@Za3N{vymTBcuZ#>GYY#)6pb!3go_zVDIUvf9lCs4t83|Qj zAV-vzSPG^GuQ^6*?sHQfxq+!^FBY-=l9jSD^ixsaOpiCX=&j75Hm#(r`|zW}9KL*CQtGJR_! za%$|arAwDmITF8MjSW@XKyKZ=bLS#@dMW>Ri0aIXx()kac@X;K33BSEpJBBww05l< z8etwDj7*3Es;MlUTmo~Nu842gkei?s+=KB_*XLcXN_v^i9?Q5Pyh*`yi_?`WS4a;H zr|e{XRni4)dJv2a8?~O5-n(^+nVFei7C}1y{MRa)lKS&{dU}V2m{0Wq=)W4nb<60! zrAVv2JLCQy;P!o%8vDvGp7gsW~5}9ApoxOX#ddFmA6=I|2_%^yPZZIr*K9#zP=RD07{6+r9ofnK~Nd_<>+N=R3C1nHm zR!AcVw-sg{XAm=)ub$G=bK3B}<$=eXZ4BKa)QEJT4ARikADa5+HP)yGbPDcCD7_h( zn8?_tl9GnM6~m>biiDrQz69-Rwxvs>(6B@Gf!c?d=Hm}c)748(F?mzBHaBAu>0Si| zhw`0>)d20+FsH+y;^afVE{+XtV&+bPg5@2g(GJQv!3_!z+r3rT)Aap&d_uz2w6oR88~OS9MMYKb9!;~1llrWS&5yx~ zmrP8$K79B9A)@wy1ANR|IB%ahr7akvnbc=d<>~1Ou_g8|&H|Ldr;rrZthoK5s!C{( zOO~Auhd3YnPh?Vl5vWdJ`?hVRbaspoz3$HW$vNIu`f*uBx@Xn9wzWM-KNz(0%o2x9 z-&i^+$JJY96Y?l8B7bfqc?-$`F)sOe$7~)zu7P6v6i&M^ZmNbx^bP#QE32#7SF9M) zTa^uS=gRvfX=!O9F=Aq3HQL_qz#l^aB|^i?%bUv)EB?aoNJN#Fr8+ckp`Y8*L`5Eg zlna*0>q9&=`Y}f;TEVD`jnX^9k#~KenLFpu+cVDO`~Rig>Ub?;bdQA*Lk@TTd1}fH z^`WGVR7jeC1Pw~oJnXYMY~8K%a`W<@az6JkjLKLubFbEsUUF{~}YI_28 z7&kZf$)r1KWvpy$kGxjD>0N(I@xku##M1`_$G4X84{*fNwHgiF4JqSt+fI(;e;$xs z7L+>&VmH+7(pRVdHgTTXTbi}+Jar*|ja*$SI+@5K;TyEvSO02muU@Rq93NWq54$49 z4k2HIsZ#>DuN)j4t5)@k$GyH@P@po<@U3NH!>xL{$(tf5D$tlVM&>W4;i~?H|6y6hy;`JI?v{ot&L9_qD)Z+p}*@=-8D{NHLLG8H()( zLWh1-L}{$J;N@d&wpGo|1}W8@0bu4iAd==RjX3x$DAt13yj!(*{UHC`xJQQ=Z9C(3 zrm03a%HGA-=q=+aAc1O5t;l)iwXf_&l+Jn0k-sx{(p#>TGQp(ZU6LewoH|>++cR>X&eHk4TLLJaaZ3!w65#~=$+WPjw;T2Q> zMWI!zR$0SB84MOP=;%NV9~>AUAUpm?@7rC0pOZPI1O?xmjM}v78YId)t}>5ose1V0 z#lFyzzmUfD_q*j>t$=`c@1d*MW>b9hx+Xkof|j!J!~WN2~Pdqq078O|~Hr zH;{jZ;mIhmetmaNm&pxx<`a-r11{yMz=;$T5_0pvCHS;JSbs_ocR0?y|FL z&|J$^IF7Gs=T4&UiCx*c`rxy_v{_x8o!yIidrd_}T?2N5-yMkf$;S57c3n$Pu4aSv zs}|b_;L}3*AS5m>E-RZ3i^!Omk|gc%(mqhjM6?sv^YENRzZCGHoXu$L)|l%}ah>^R zjf}uTW0sa;p+$Myb1~5o<9!Z;NQwM)`SR8LU?x6!mWxkPd)+BYYH8T=G|l?Zzx_F9~vkK3X{y;kfiS1vnM3B$ElvqzSb3iioZv%3YP-F+rN+4g0F;{ z4S5k<+(DH*Xm+>t9ejRcqNAY?;2nhtqZBSMFa&k;xXVR zfiL4MubW@V$B#KKoxIF49B&#JLXeW{>+5@L+{<5r4AsTem70nwCmtI^bJ}NF&`z`i_UO#d*_tEDzzxn{pCQWr|rE0!Nh5NOa7bI4Nta!3w z@W!$71_iOPl-dcAjT=iFg{UokN^sjdb2xG6ZIy8gsrsh75!K#JxmqP*y#Mj7`>Bt= zH8}lBM~tZ%=r&psI%$?0AA7B#HK&ZrBHFJ{N+=8np8E7=gSa^0D?B5}4Jl}j!#L!b z6dEXUc9W^q=U^xD1vXHaoRcY|rQ2VRG&C4I5%v~@x)Nha=}=@d z*Kgc_dV4RwhLO>;g9e7nAMjn)Yz(-4JG5#SQ_lC-?^m}hYXfpp;eSDRXJ45A{39vZ zNHN~*B>|$a(|I+`{TMJZAeJQjUdP~0lIBe>d;nQ^r3taCsBugd2gy3~FX-QdY=oMXlH}h!0v zaW(uxDqN;ytdu5%3K@$sCZ&PMtW+{(Ccb@LD0O$=&-1?Dvu*FUZQsiu_r3kPTx+d! zo#!#^$A0X`H#V3$$u*z<`TWn4L{7d3=1WsZo;>6n(Du@UGf75KSD3@Pl)UxwcweKO z5Z2y)@ZUX)!6Dh#CE%xMZ`uUH@G3<`MLD^pIZ`o4nm+sV9gy|AqjfN_s4h<|XY)tf zeTX~IBOian8+-@|1%9hZH`q$GPTPEAds(-_S<}xvy`f^FHh}{BUD6Owq-#m(NGS$q z-4m`NDW5q%s&kZfr7@5(ZtFTbcXrvc{3#qo1L%7bTV0cVB4Z8g@%lhmWXduoj!uE* zLRslx#3x?2-kQU> zU0iF|u3cqgR}Rk!H;y;-8%_k~silSHlyFSXJa8aBxyF{A8XB`t1V=^M!)}GcZ-mGlc1UMO*7$Cv%Kj{2yuxG2P z9|Lj^F&0@mJ8+4Jimn}7uHh~!B68&D zQMa1YhL1N<q-Vzc94#oRRsl>!41*eiEm5MT<^}O?5s4iz|nd&B9B?{?=)E z+ag$dyHN}PBZJoV{LL*o;9yj(&{eQhVLOm zh0}>YEkJ%8pW4=g*VtU-T-qZv!^ura57)O%hC*Q$+!%6FY$kG+QZzl zEzgxpbp33o89Npm*1(oi7jb7PaaflKokAHR+2Nu(7h**xI6ZSg)!YE;LlaL?~oGZ^@6|MOII&l3HmwV?2Y{evli^Ee6wi ziHr=^?E?C{$`aSET}!qN`1=bu1w=;v0Q)(e{|7{#Fr&#J?sm>4HbM#%X*|_kmMzcL(YQ;czWDU7#IXz!rUa8FddK)l|?p4h%H^pF&w~O zm~Q9hHiSN9_4oPu7_5UCIc}ef{*tdYceU0HJX?drKe!4+VhcvHOxTxThZY_qWC5)z6>+b+5Fk-6*L$}3g&96pM5jSQt~{2~iF;PHWK_(J zsTFHC%oO91`7zLCU3AyE5n&fdp3|pKFMAGPApdvEWRr}nL!D8MaGUVKzi^jVd~ z*Tav{8EX4hJ|)Pv|+k1F;fUXISI~nRSGw(Dcg{O^;D^a&7@Yf6#p)wSuX8p`_gONob z(ha7NLZBGOJ!kIq>(|Lj!)pt54GlM*WinC5b9@$#IeH;1i9V~a$2Pxi-@-gz!to`s z#e`fg=oDR^M?+m`FWSjVL2cv4>TgFs^#HYheFu%C=s5%*T@_P4~4Xm$ISda{r%P7`X+K)>RI&b81k%le)ZzN6~U@{*3x|?N6sEeD}(g$ClDd_rJGaEhD~QnT1#r*IS?)kj?|6EP%v~ zpkUVP=rw+zqLjW;iTLvaJC-l%0J>7od5>}{r-tz-V) zQ@Pm+E)}MZ&(n=`_c1X7u$s%3ZPEc!t+cStk$D$%Ml`PJ^SrcQ9U2^b>)n0Rc*qhV zT53$m%rrBpg_agVbJ*D8bwMaETz`}n6tAWQ(eYesdPO^O+c^AN(b#xqH5uwQApeg|2i9CN`UX& zMNSpcHM^eZ8Rx32g6KkO^6f34)YG z{o2PDB^F;=FIjn3ft8KzU|lv|FWHp)3r2W0)RyfvIyyQqFhDA)aPOEq<`5@(t-0X> zv|!Gh0hmqawnbooTWiQ-{I`r7q3gsiN7{3G+Mzw|zqmx8Si(IlTL`vu|R3Z(2I*;E$H=f~`HBMu_V;^OlFpXNo5uOo|g3CfQ&FBN)gUaI_r3Z>$LpjcJm z&;4mNwlAn}&S1t;!Jd_mI3Fy~SAL-~mRTA6*s?OmGbgk2#Ij@kPtc;8ttTSow>^G+ z`Lbh4Merr4{o^DokTS1%^$Jss13=eySG)53W#M=#=iCLp>WS~X&YW?b zTW$J4Z;q>#8$^MyA?nSu%O_Ux6`9jb{7$P`$$Zm_pkwE7S{Gq^`IOJH8D|yF_rJaL z+-|OCb2JijbT2j<=tLtEm3UED2wfk3F0M4BtzfT#y>Zum>y91!SE9Rc(YK?=H*7fl z*mBF!*31nJT`{IuNpzs^l$fW`M$7C^J6Yt4%mkfNXjdbu9ET4dzH6KW=EXLNoI_1# zD|eBRz=G-0VLDbSrvLa~zC45}e1Y{ z!^JNKpuQ7GrRE!2ozPcC4{7(4{_N%lGwR}~p#`@MH{IW4ZchczzP46!brqQIIyyS$ z=25a40PXejG}dqJwz?VzS|b6mv_?>Jv)r$YU7z?x*gyH3#y@K! zF1*ogPWMSf)%R2bTT|AmkibApCci$q*b{0Sl3x)B>Ww@|EdAKhBIY?b)5_TvP9^}L zH6QyjdH>4H`1s9(w=*&npjTkM;J--ZV>v($K|bv^Ewl~TnvOX|a@y5k52^1WCd<(} z_Cq{fD6)ISDC*(aW23{hoZ0;%Qey5M+U9(BOvPSe18E&Up5bh&7FlAiqjP@Eu50Re z>_&j#wFM6izXdXydwS-0Z(X}YU;yc}=j1PGHztl6ku`nhMDjT@W`1%_V)^$0Cgr02 zoDVLxjB2Qcx_rLSAmY0or2tZOV$K{jNf>UD&mZsPpYvwx*Ec?3Ik$-i$bB$_}2$AwQ7r5^xbkbKcQ9C1UhXl)I5 z#ajOrO2|u0ml$U$Dl04Z%mht$!FF|banT?LfWyWZexrYEwvXDQ8gA#Ji-j@652^Go zH|2y5QtyhM)4X$2Y0j*-XrF37(Qw?N8`~tgxh3Fk@En|)3XHiiOze>TYFoMIpF4&{ zzCHjJI;?lRa@{+PFZCHkHM1u6Z+n5h|Azd8t(zGnp?y}t_4^E^_%)qc=A)l}%$n7k z(etd6sxGLYfS#AS1)jTnRB9k@X5IBE){tI!_?_F4t8bm6i%q(VOQ(Cf#3Yw-)w;k(~$ynytit?77Zl=uCOaVt=yGUz# z9^{+#CH8(%i*Hd5PH7Gfn>*UBY8xq&+3UD$e^n2rjG!g*wMeT(|2W8R=GyRNTCXTI z#dsXJ@MC_n)_;W2i&iSoG?84LWE#)cZvg{Ar3!s{2AvHOz-y5_&XL_4?*L5wre6z{ zH(*`=8Lb&M@HFX}9tJukFI*v40yCW{MV^JN1GS-9&|fIwJA;DfQYrgmjh|-;3O#S19yqVC`2#mh ztM2B_NL%KF&5yP+^?0T}6c`xzB0|2Yn{7e-PvhDzE4njePjF^`>a+V#G^oN_MHz`w zKHo^$TTC0o(BQT>99)?H?tR=Mo!O(kiO`60dPy+0&tLsRYVvn7XlOOab*86T7(#H( z&i)y~DU%DD=*e`^Oun37!XL1|g%c9{L$%7E=L8gXV<160oL>zLC)&)_UN?AP7F=nm&L_Y0 zM;+@V{QUfK+#SdJb}(s}2sOXvf=20_WCH6w!!_6+FC-u!ymu?~j|$5_Ml17o*$^W6zHwD0fffx6rhVPWs* z>P6@*yIs*C(@9RO@$OYuYP?FvGE}m8GBTs#)p5YA@k>koXs$l+P@?L7!|wJC@u6eK znn?@3_#zCrSD1ZSyesh7PuEZv%3A9pCRq(zZv$ z7HVbW2s`gbLm;Pt7tr?pfv>>=9+8gdlN$r+x0o#5KrYK|1{R{&pBDd2yB~sl7)!Fg z%ppawtbvWME_aFNx2qf59T*SGH*%RLF9mbJ4pndX?yjybB*;`j&hAvxeOYVu_owUa zUPqd4cb6D#?)$ZFt?UoZH?ZBO$|7ZgzH|+`3LorwDfF^fj#=w@_Zb8EX(IeRCpQYv zZCg<6KN>n3`h}pU$j0hj!7p9B$dsTt^FxFqvnufVQr)?{8%O|&RWmq`z{P9|zT+T20NTK=!eMD?VfM#IPJU+gItHYo6QXkpqj^`A8 zQikI>#l4|Bh*HemZKb(jqf|at#2z^;6A5T8#Fs3+7Wo)(Mgo@GXfM)tthHP)K3;h6 z@-x$C$f&0*2HrE}4iad<6wB5m=luBQFxKg%5^GF276Gsl-EAUUBM6pDR@R4usSdxh zLYyD`h4N8G*3!zq_Cnps>e2PRa5O^QYI+_up};L~Ne8%UgS?wz}_YP^aU zX#tfzQnDUVFCZn7#0O=iX4#@W5bIfeE)xEZiu(vs>%lkUQ9X3OpBgsa zf%Z~TBuo6YYWvmt=Y{qI$mWc;8iKwpb&i231lM05N6T--up!lbv%_+0fOV4Gv*N8OW zq}a}2EIEG%$Ex?_UBmsFnuRZ~Z7c{WL|AKU=p-PcAS>H=$N`iO7&TC4htLX$0@iXZ zif$Z+YZ=%@E>?`FuwuVrf!4f-g%^z_MI$V5ZBkXKNoAwyM!yRe=2v`avGR${51JmD zOLY)}cC_q&mP;SVs6$my3F>z0Cc-noLr(czpi1!ZM( z_pO`8jRXVD3;e37P3zqUva!qQCC0}GFOijyXv1n!7jI%)`DM%WIB4Bqc7drl z9hE=D7=_t4`+C#1k4K)*JTD5X*j*VFkxeoil<@^o8x_a#Skt3)eOq0Y4bE=uU(Rms z*ypcbef|78T3gFa8tI=Xr)pitJ*ZaFUn)C)``7I@{M$Kw&ajO`$76*zA2 z$ocmtc#uKDc{Z|d-oCx<8Th2d+mzW&h__uJ!BKgf&XVzgG=|todqiSx+;}#AC|51w z=4NF&og4_A(@0$-aMLR)79SO{Gm1BD8QF92LZ4WWUby3EkK=^$P z>H-0Gr409(IZ5 zkDE^3PmYlwxs5=?g%&SvYHIR5cdmJZFee76zvWK3Y9!@-tnB09$RT2$s1sZtkwm}P(Nh|wCQix0q z-5*t=&M|TrT8Il$f~UnnT$7+5_g_H2`mr>2tC&*^mmJb$P3_)6v+Je?}yecX@%@qACI3&e%WQ>R*gFWd<8%!E}M%k1xR6BK#khS^kCJn+G@FVW?1&&0G0HfJT9=ojJq! z=_6S|U@(b)>+kOms)<`5=_-4vm6esXwdS^lI=&)UKxoUM@Kp!0ZxQEdBL9A}vkdRh zKS;rS@B8fZ@#!i!JMKQ?46DKoHJbBy&H6<9I-)eS%;_Kf#U@OiK5Ng6(`!=xpkN+0 z0hi*5x48JApNVU!rkR`qOJt|PdsOX?J&QikXA-cw>z27O7$g;+!QMt+;n48#(>4sr z%=DWTe+2b-km;>McDeKfsF*2vq0f|t3*f5WIX(r zAac_Fh`OY0fKmYjYSq-v0JTrq?dP1H*HBnkcn`dTA-JQm($aY)CpMjZvu`t)=rd=| zB`fO1-9LK>ic^5sm34MH_D8=$HTw5%g4%+!HjyYtFS?*{NG+wx%+T_IU!azHRI-TUO7OS8}YU7}DSGo>Tr8ze+5VBTR)S@;uP9h~JA#lMi&$mgOF} zDh!0%mMN9uNy8*RR@^P2H?q$w@V?&qGOy>i8vgy)-2D$<^Y}<LPP z#V8j#=^tKX5~8^Ie~_l}AN|MPZ{^lc=Ajke9g#Eiajj`Nos@|jlTZo>iNZ)|d?jwq z{VcPQ@5QNPH68Ex`~*}oQqfn|o#vzIZfAExGt+qYIAi1Fj{k%Hqc&PC{>*f!mg#QV zbUPto!LiS+tq@y&Ybtlv=}vt7DsBW(7pzo3r)E06&ZHua=hk@W=i&+(jL^-{nOFB9 zeGP|?1&xrgxBhP#&i{-9;jPv>tW}9>2&o#EakuGE16T2K(qZHacuOqZKNPgM*O57t zS8~V0Qrkd8br@E#ECuQQ%JAn{<7Wy8ghV-vbf49a^|+ZF)7nTVh3G}vi#$+n(NuyH^J?Uf4F5@h zyqf#e$V$j@|H3SAZB+eTq0%7+8V5nlz3AnO0FbO352i|%Joqhv0#UIw`8_n(@nlD_ z_-EBFI>RaKS{qq*!sc|rKh^?sUPND`CsxFpS>nM#!@Zg@kGe%ZGW00Ycq18;A?+mK|D{c=jVGMNu6>J zxPj3SMxwCGaW=wN#EueUZ%Z23erFA8ns}gl9bgL@sAQHaqci~c5@z=|TL0dbTRBBG z5ZL5hxG~8(DI`&{s1=h!GeodYJRy0d)v)g7k`o%5>N&I3yXm=H9P7P zAhV%_+1WWA!~GbDORS1!j0msSUz8}x>2>;l>oqndf0WtvMajFz+u?#n z6EYLwnFU*JL$R6jI18;;4V_M3Ry}Zf{gbM2QSucOg>Uh-$JmQF#S52;(EXX{NRoT& z$@yo?mqBW&3U^Pa{@Pi&DjP1kM!s}iip@t5^$uFt6n;uHBf7YR;(3;*3#wck!mb01 z1eni+4in#T+7a0p5+^Rx4v%5*(0RSCv-2iL(WV9SA%fLLevd#wq#M!(lEqpdEx0kW zY>(nR^1?)CsxYozz&Ek4X;+7s6w4e%cX|RuLqe3{=hcHY#PFCVr+Y@3omH@GOH;?^ zloZG>DSVxCcM*0kp{2HNTURB+`0i1xaLRY|q7+Ged#&?q!))?{gr_z=(d?SWf}8?b z7F!Jney5|OmEnExtYb|LbHUbNCZres{78tWcnFj}F#uu}dKe&=2aW+G@l4R2xoz7v z5WIHpj&pu+$0#vjM=BaUKy7!x_C!y>?3p0ELrEMm;c;!>&>0FWdv=LP5yAzxEM;L~ zH51I(Li^bQK0ZmZ3ov-q8)1{V%&SlbcTTC2IC|ZDaGbn{lw-CynpDvjVEp3^hSf-A z%W|<|2k`F*(`Nf7W5B0(=64_R>is5aB5~WcXT}QdRP;K>>}DpPU7k;po-}3~Lt5(2 zwE*~p$UIg6JAgbX1Zo)te`R<2a`R3xFsd zrJktsr%ur)1t;g*rT8de(8({(K=E*(@gzS${nP}uu-(}?Mf2gnVL2Z3cZeI_UAlbv z5f5?{8K8nMU-l&h58O^mb7fUuB7a{mY%9Bqrk0j|M<==_+jnSn&o{<7+ojQT1td+p z=o}F`!fDDmn_p5rwK?p6G4U7`Cd>7Ur!yvr+uoUQ3>IkXqp|DBS?~RIo}LlY#3ycS zoNQN=z^c7z*4&s)lz~2@5x4>`|?- z)1Ez=S;DJVqgT%;Y(7Ah{w4Zx6^K!9tucCd&d-ni#}f$qsCVZ($ux{0(EWlvz`y$> z-o3$%*T^?%~^r!3JClY~{_(a{!Lw>sgCgB11n z@w(7A@E7BSyc9J5s~15Uyu*j@ ze>mu(i$N>vvP_Zrp(F}L-tp?~iOn`>%|RJBs0zJ)EiU|6ZayV9;kql$oFb$@xKj|{ z4S7gjh1F&Bp<|c+F}wj37~18*iIO`X2@lH5JjBxP6!@Q3p2sA_^J|Nv7m|A4r;Uzs z(0RbDvRH{6s6<&=S!rwgURn?h{ySzBD2wEgt;N4M<=usKH0bQ&`SY4bA-rKtqqqb= z58g1Pw>b(;VPtdjvQI`<&zqZ@K|Aw~2eAxZrC`fp>IQAu2mcNcb8($O#3uLiR12A> zK5ikCM|MbgDS%!G9DSpj8W-zX2&Kt|D)8X0SW$Yo>p5O@Osa{qK_>Q#CY~Un;xXb1 zr-mJ-xE~f`4flm#L|-T5LgZlf!-vs@c|b=5o_82y%!? zO6qEAa(FG6j!`pYzVUF*LZi51ky%vtX`kd~-b4uUB}iGGb0d(Qm#d_47nP^1pilyKP{puTJp39(noqZ=QPVHFpIh zPswm@zGrBCc?sOgaYxR1?9p%rUZgt+juf46fVn+qQCbtd&aKy$At$=ep($N`mDc8J zq=8_>l9L*N39m)hh`jvZ3n-YCMXTs3un}f8y= zh0qYK=WB=VXV0gs%^e#8@XkokhGfN|A#JSUV5*AyKqr{G9gt23s=23tj^ew>t&j4x z4eqERhV^;@bz ziaR&!=|`(2Rz}w16+j-^YO@s3M(}Qh@ajRRQH!qT&l_BjGRZNM3&qf|-?(+#JKow> zqbcp&24DKw$LeStxqHbYm`KQ3GK(n>T(ao2AKL!TtMs>kUU{{ghNl(?WB4)DX2-yM zFHSw0p(H5S0L#V+F^UD8wsO|M$6+OQ1U$gb_YKB+#wUGl8KUaMw zAD;Xra%~P@ejF5uUi*rsYCp4Q-}lCADAKmqDdm#fd5etlnYMg$gO)qH=fH;EGh4r+ zdIa*?BzKMMZ5UpD8!ehZ`+bj~%k3xg96CWDh-RfHH`GCAIzuOI5g(s2WdA_nx3;n} zKhe8AiP@rh9YDV=_L4`PzPuJ|2{{*xsIJ%JQ0vdPZQ*n z?!vAeiR^G+vSdktd>1%nw|!O9RfHf9CSPay*~u5N^yaW{?d=zReVuhNG9izH!HQ`x4 zRe<^SfBQ~j%hxuM-BXwey)B^(#n-(kn3;HB{MbgN1i9H)V}eY=pNnp7m(fBPiyjkq zfOyV^5tl766{PGlIxOJFw8G@(-YQ-8`{NHP(;@gYs7cA_r}VTT3~fC$u!D-@{LF7^ zxG8Db*h@C&A@(7=DDwdyfphnW1@V7S6;QxP-TwS<3*L|v_)~MmGwc)GMJ|GIyXn&* zBhPgv->}EWuBi-NBgYOPu9~0I98S*~7~RZ?r)@pddWf*J`WX+i4(u*`9@D^PI*k)o zNLLrRD3Y$;t2fr8M;3}tC~fGr5E=v#a;%Gg?B(!|ZIa^6pFV{K1(B1}U0q#K&%47h z5gLrPuhKu2ze$C^rDVe=20Sb-N{aC5N!Dy3Z&LZg)vL4U z3AdxN2CORi{(Q3U-;<2Y5tMiVNU-?cY%4v z$2LP}*z})!kR87B=F8|7VRQ;3o^CIgHFM_ip4I?aaa~aHm%RSxh6mlP;dID=3_g|e z5PYj2+K@B)HD?rKQ*H_Sm8rQI#9lktXke0VV@S0ybw^y?e<$k0iLu{zmsBCQWdB9h z$pTD_Ag5**NhRVR?ezLG{W{AZrU$Lha}yo((Nn;6L8JF$u~FmFGX5FcMQdiUvq#Gv zvclkAfC=QY=kvKMZLpe~vr!Vod41`jKMQ>Z9_isDz$uyI^78!+< z`?rj&Z%(Ad3?B2HQchiCLE>*}YHDn3yl>wZB(*iZ8cqfqNGkNpJt*2kf(2ejsdfacKafxKPvQ` z#0y>VG$dBiXFWO9d z?>M=qmo3`f(Elj&@Ip==8mj(p}bj;hA4v<>$bOq+-b zPVzbBf7N;U>J>FIQfawYI|fceJQr;CA`=2a8pr!?9UD+XoZlk{-i|bS0|bqI$@~tu z$$3?FTDTSWaWeU3v1X&HUZReFLF#fxvE zB)YP4)OfD_^D|Di?6fN(3#YKVvPxUOkct#goyiKUgxnYt*U4T)OTx+P$mI|>uh2jP z_P<<$AnxZ*`Nt`U!oax#-17Jrk8(_Y@kEYBesOCdQBF^`Do|9;@N^XiEB#z320jMH zq0i2ry8DAJ_1dkPxP){T?fPbsBuYjM?3hEiKeZ;x1c)zEBnN6>L*eX1{KL9aUI`eK$O()eezF^7h}|4SFDI?kD~Js;j>6%eCf)*N1q)?p zCb=+wy??pW#Lb*3&;I+`=PqPa{V@%RKAk5EZ6o|jn{$n*$CCqx&QJ>2gM=sUetkRp z>NrNgF{c<1^I}60(yQ!lVI072aHLd*UivXHF+~mhaP)#m6PguaRD5k-(3FGjJ$mHk z7TBE3e56W4L*uf}4Vt~g9Kav(!gM;;Gj#+hG%guBC`IG~r!Ih#@_83sNCU-yp*b$x zFgkb4W4!?NGPFZ69&cy5lP%Ji#KgoKH|!we&?IrLi}S|Yw)%QYNDo_#wpbu<)g4$U zeEwwafsAM825%Nz?)8cgk5)VeEhvM#du79p zwpGd?3y_u;c=#dJAv!q^AvR4y#HH@^@Q-%%evCkjnEQbyz(}=rQ0LJY{C~j%qhm7uSSv0MN>z|z1!=>%fBfr^!rCed5n%6%lJ_H<_$TR z2ISo1-{0Ikj`8iQ$MO2~0UdxV520{&2}8`&+U1ySvk z!Uw;>HSP&z&fQjb=E-CxLG!b+eK0Mw(3 zJD;dTS#IqAs*g|usK|EkmO)%lJYo^32t1Gt9&f=Y zeNStL910Si)ct7#8u#2T#rY9N5zEU1@T#(reem$%?G=sY5BFWI8U5rry8E>dIUH6l zqGYY_*fiR`T^=l#6BH6a@*CU!`UM{l%K9@*GCBq?}x z5&KDjuzqQ9tCIB`vbm42!(T%*wD<|4My9V}JGyFp2Lu(Ar{TdPnQ5LLua!P%STcjZ?a8!>k$6^w52m&&)`VO0s(2^@s9w2po5`y`rF76IiZ06U??fUd+bAcP zJXK_~47)l(OzPF2{gVrI8=|5}IT!4<%l~q8=c}@pj1$2N#b(y5Ac5JcBfRR;fn8f@ z)vDY&Dp4=4;%S`ymtOzIplNRx;$xK5cSp!VfU4uq@ZxN=ibUego37-f0LaTjM#)4X z1n{G-iDl$ET*USG&W*E6ZGQ83#$~iGvoL$7|Hsj7+$9f3OAsE1@K^X>MrJ$^ODkbDws0-gE!QgvC8y9=FC(fBWE6T~l*2#Jl*@rEjX7AE-Fr3_~E*H)OG+&ZJjKu3_gjXc^?P4S45 z5ig#M@gMK!-?6=lpWrz#C{oO^|N48?y@^_anlt(?upTnZ`&xc@k&wyj-ktk|ePu=( z_(k^%nT*h#U089XoqbE#W5$%Sz3bi!YM)bYp7#C8xtW6bE6*_{S=*Xje`u5`d(^7G z_VABGVy5qpmkqj)rll+ON98HK_+ImASh4QA<3X?+P^CoN-Dy*}hNEv82EX<+tySmP zElIjlOUdcds$=^bz)sN?o`WMswupDnI+Jydj$r9Z)5Y4Vo%Youyyb{%R=E#4w=H{v zEEhk3enH{uXL_Qmz)W~QDc?CeKWyH7!W(6wTw;UyOg+&+oH9(fG=@BaFIuy#2;#|_ z1OvuHA>o|r63Y=L6PE6?LetkCYE%PL4`#0J0N*_nYl#xxTpI?$L(BynwR}3R`FYpl zNZ|#WA}X-u!8ORPB5Kq1t+*=af1n?xFZG=N zlziME+T(_hwIGfQ>B6~7x&5Oc3Wn!JeWz@M^3TZj{M%dv<=(}w^XNnu5gfB5mFWZ; ziSy@l+?IvuK=W$>C&?~n9b|f9{*)lj95;(&X)OJ~OQ_md2lYCQmzcH;4m78Pu_NT18fs&L@O?Ar2!R>6LrM|Tl%*~X z5+esd#8u>Fts7m|_F8~YReN^ioIqL42RcFx!KNhz43yoTr$@F|-daacyw87~w=Tj2 z9C|`^|9&vAZ3g7s9$YrZ*?z5`?@A`GV}y$!PfHC2jii zB7@?qSTNQX-~QXm%=-1;*F~gfFpR(V7HZDc(*)6+kA0IL)dI{V>=rmkc=ybYEQkzU$4!0%C}o4(-AN08|M;2Y`K;GQ?Ht#Ku`*C zWi!dCxA=b-ChWgjm}^TTb${PaQ{VWA6Bt$)wYg`{p2FnTf43zei;X5=p#V*^1hDlp zU7y#t%n%MlpX-lA29Dtnvd8ccp0oRnh57^sBV7dc9ZOD>baC(lRO@&W? zF7kQ}qLJqiq2a=@W9QB+=-MEg;cn4*aBe<5p*oLdZOq`r19pr#;{@TdZ#TQnS?>_+V-+Kk8It~&i_$)CwK-erf zsxf89_T_2)gHs$|IwCZL9yD+B=yW9%1BK`KKy2`u*>?ttrQxf?$RvBZyQw#z<4pd!wzR zaCHCl)@D~EMS?dWw!`=o=$flX&!t^-JS^I}ZQQJ=o%UuhOP9P3+$KQtE(S4vXIL=A zqt8H4B52lo;&e)fGIAwoYl#M;fChO6kVb}hXiI!>a)}+grW3Q7E$3wfp}7`;GQ=?- zW@PM`xafH3IrXCF4~B02X@0&qtIe8tUyY^X7BtsvjwMCR;0B1k%8|NXol8k0_W7q} znD7*bMg|U@(7pdF6w=bCn^;UCwwM>|5DVp#w>afnRim#l!EUx-L8pWh6lG>|>s_O5 zJ+Wo5NZ1Nj*X7go$lpYqRe6EtdB$HpBBWMlGHxOb*!YV!bEiklTK*{pUv0ILjHX1v zXA;UFZL+uA#FvwHjkd1|_z-6;;>1O6#_=$9Y7jWYLq>h)X?8gF=J*-#W}3}B@#VBw z`r}m=GH5~+AM=8=uVC%w$Z1){_!vW zswr0prAb+(W)copUp2K7_J|?R>0-qg!k6g6(_wXKau zvJtkx7NajbO6k4lk8i;xKlcOqj_awA>ctm(xkGX)B_^gGl0HIg9OC2aN?IAjVB;sj zY^!V-8EK%Cj`@WMDT-%gwB+YK?E38<;t;0+UslZrXFv->b+&EFr)$)p9mYbR$&*2| z_*_1R*G6gzqc=cy2e?9zz#Dd$eTXtJzB`<($bB$jB`nXN?hh8k3g;qp&Lx#s3Hpmaplc?6=yH~ue6_XHd%KjCC{kMKga+!u(o zLNtZ9-g=FhFtx`%@j7b>Je>L$WQw;QiJf?WrdjvcYjDFRUsfA2+W>*Hu`!q8Wo`OH zt50@ToTnqMO3NBCHrF547euo)I{LsdOc)D!Jagfl+qWUWtag;5|M_|D8(HK}h4JSv zz*Zm?rgW|aKLLINyjU;aHYB(v$u>UxDMWerg-2*|S;jaE$rJI+(<%Y0;>1j_JOJSV zYbR)dAqr?qkaKGGE@X>Yvmp;3qwLWwolhtKZmF#=VQGUs1`5%~oXS3n!ZcC<|Iyk2 zUR8&)XOX%R0g;!)5uLf<8#4fjVo%ToWL>{55}+BoRqW4?kxTJJGI*2793O~l5o!(G0ZmMto;m)9kUZl@NP$wzN_!F^Wf>zz zT3X043qAOt39Pe0WuYF!B&kKQg>3%eSyl7D%|DXSSly1k5OMM)1@)8JA z92@x##t6G|A0#74sfwB!#cck)owJkO3r8K=Ev8`)dH#6k`Qw92-G!l|8P2%A^hKSL zrmK^C!0p!_C|p37`{JI}({q4Hv33!Q4xVdMT`Bq^G^gfDM-eE9b-_@`bs;p`ptnrb(TR%7$UHO zU|#g~F%4%!aWIS_8zTm>0Uq}~-dH#)=w;Sk{t1oXC$>vJ30!q@8un?;Zd1O+Xt{{M zfb-qEciWXvTG)Q=eF2>f3-zx>Pi+6ffQz=BPF`4Ox@v%`1Ed;WU!Mnv_Am)MG5BHZ z1A5wXpxTOUi5UyzSQ$UX?m|uTN6oX*(*SkgzV;7`?AiIy+!0vy^gFJpcir2k3sF?Gy`UNO1bj6pT$Gh z%WdEj9QG>Bu4zC8jJM&C8o6Ovrd4#if^Um<3*PSQXgh`w2_m`kp5&`ieXW{DtglV# z858*j1e|8bfSzddS(422soEiDxuj%!4oW1)KfZvbY@K7?ti{JZQ#Yo4O~}AQtf&S{ zIjm|w5F|V(Z~OTWFf1_{q%<1PIh4vi*`A2aMLB?-cWuz%clZMzwW}S2pt&7PZwW!G z5(b7sjK(#M`eIZt1$rSM&S<#u%qDl&`p5Sb%_nVzM_*1x9x6l-sByZgU%Y@$U|-BG zLa@VFHYZ1V@2gmFq%9v}rtFG(Ig)FOuQ`Z$lG!fca{+;!F2Uhwxja$&JvT^39WS;p#qM5~5%;cEYQzgjZu=Z=6n8H^xP= z_vT63q|=o$%GmFJ0_a8iPJ}fn9nYg+GNQYIkiq%6kw6 zVsp`emcR#$VEXt11={{G8Q%uwt?0q;>=BeTI>m6PMJ=oC1qu7tsJ(rd2nXe6m^Aczc61!a zG$C>1is^tIaVI4U&wBD2d1>9(;cv-Fgx#Dk`q-n5U+JW}4yl46Mm>F#YYT@K_LvS#bcL zGKgc+14H?^n;R5$j4dpptA1eEJgaE@<32$@|CSAQQYT5C)65y}XO@UJV#}zuuUPJP ziw6G$Y`VTc!WgWVOFJ%XeaJ$QInO=U!=bymC>8ypD_$s8R97FD`Gk|Qj-+Bj)z70d z33Ve((CZ#`5#>*$@)XfAn|Tjm@^0`Td&V`nInohCsewi-Mj3$~^Tmi30Bk`3u+Ban zntkZ+fy4jAecgUGVa>Hlb|cwn1>!xTktp}>A|Ahuk2mgwh$#ljqX3=+&$uM8XlKUJ zALoZ1EUr*XJ#yiaMjNF@g`6$A^m(Rp=@K8sOkgv4l-%xP12y@nn5Q{5fWZ~(v5FPX z%F>drcq)!j#kZXhh&|+a*v}CU7k=>3-rPPYRQ6o);=7Cu4d2V}-uW0g|7b=IhV+nS zK*eKDXrkS``8h}o8r`onFLuHQfMJNaAnB-iNi#nTR}m78-` z+32{#4`H*MazS$jSvJJzhSbzGmHjx@FL*l9iwj;f>qBj~*rKajF3y*XI%5 zjs?lk!bSLiF>0%Dl{-*PbPVMkx8l#qM-hG}ZH2S4V6yI3-?zJ9onI*d_D#}Uz@EJ@CuR_-obOf%to4jz;g6T?1oxToYAv0}Hb zU1Bwc0OP&oMe0K{5;6sjx!7*g{2qVD{h7brIHL{o^W?tPCxN|j?OGFv#MSq9ZMgRX z0u!ukX`uW2s(cvBgmji%ng2$v1}CrjE=-{7fO<>U%UQ)j3YNtbT9EfL`qIYEpl0rJ zd*X0?sOK5HWO9IZKOE0oJ;i{QLYUkGxct}$Y>XA2QOYNV&MrF0RiquN_++Qchc`7f z5mh9EtJEAb#pPki9e3Y9{P`8E*6vY^YsQT|bYVH#Hny)*vC_$eUkn8;|NcPCLL9n%Ct-&9tSB4v4;T?~uM0|lWm`EHTeNcw zKu0bEqov5DyV}A=5o4f*v(is|jxp+KCD1)*Qe__X^(+6~uNd5V?a$f9?69ywJ1=W_ ziIZ2Gie12o^gI@oZy1J6#y}0DJ{a&VsiNYE{&ka0-N_*ejC{x2l1Q#;+MaX<|Ge4E zXPc|ZNW3W|$){edXjM!V(VFYoHG9Y*di4QQ(D&-Tv#X3a+J`8x4#@b{ANv@IvEjz) zPA%gvfmh+E%_v3>93SIP;c8#p^669m2eT`B_ewCg{jB0BNT@Ks6}7cwpagL)g_IMy zSf2DeGQ=f^G2tMh3Uh;X4;Sts*IV@CY(~)n z=`*|Z4bINr5i8;C_9I3nw`-{amV(!%rVDQtY{ND*pKFQ+Vp{YlV%xg@eFg>BWtf}@sjolVp5OgULwj#zOO2FSTIU^$AH`10xj}Ta zY>4Y6X=qlurJvO~>hZ6>0Ko=iroayxd|W^tP6T+vbu*5eDZi@c|IU|SDYZ9OQohoj zVA)&q;t)vOOQocYnz)%_tk;p}iWqgU;(Khs{icQOgdVBZ0A*klG?qlWcUv8dTXD({ z*8f!jb|vVwh@es11(~F{=7U@2xx)y!1!wkgwo?~BXQKE&`@ypfsRC*>QBhF{Qy>NT zk5pCWe z{!yXsbc(GaI9{bipT-QOM<|T!Pe`|e7!-Q9NR5SmS+_^j|8E(5$BapXpJ17ixm!4+ zSu=$Wo|bsITAK}0>*2X z_QCns^<9>=Erwi%m%=rqtfcbv_uV+fk;pM%QSTud+2F-yJBl>ZMkt{5cs88Tj)Up8 zIPi!7A*{fcu$5fzUb&y^?RS=LVnb4-HdM+$7h^Aa zJd>1vWlwN5rLk}5{zm959KS{*?HZMmE|>oI%=s8>YS_2Ol3+q{cMsrb;*98mPKlr+ z6AbUtKDv!0v4U6b*MavKHzyBEcyYG2VJK%sg)`dEFtOmmb0;snW26j7VLKo$Gn4Q1 zr!bcrTW=|}r!{pI@T(vQguC(A5k;W?1M+7%9dB;jxPcW!#k4}h2-0k_M5t2HHEJHO@0rHj7~`ySe}cBZtl5$n18=hJgDS>EtT7segs%UI8y`dp5-=yPmtX#vSc46JJ~ zh`{WacsNSHZ4g42Ed#S)JBofp?m%)49T}zI#)!qF$~vl1m=}a}0q%Dh$sV)hneyke zZ{5EAKJ%D!XDsYfY^-qbCb7BXXEKd{T|&DW&C`f0*G9GveJCz>0vz zvVJ!04_=I4AqitjATeU!`3%me^ameNAG)ZUiT%X>HVD-vxZ|rSNxR3NcKfnm$mxwD zv17^s{@M#XP+W-6DDhw8is`c#EVj^A-FJM|4Kb0x457Ne6f{_&_eBo)5~GtgWvZ!f zKyxQ*tVK3ki^ykf61rT%Tfe)Um*9{rvPlNj<=Qptv^7v-ed%|LLHZp2VizhpxW~`O zA&MLYEx=30v`5eq70Slyb$558A~0_napon&Ye(FIfQF)*H!B|=2v4TByl-=` zlOsQre84^!{*3te=cpr)Z>2~r-w5y_czPhvUIo|gb6Z=%eBp zl$WzeJxtJCPg~&J;;LNQva@A?(UJS0UJGM@(cJwp)rgLAkE@g6%V{vaMdwV{=cDMe ztAdzBmb6BI@!$_>m%R4Z9l;VQvBs5!{si_p81h@`Enm+{z5DprL+Xw%2M{+qZ4BjJ zx9%}^?mRZ)%x~MmQ3NIdKh5-E-jx_b@D7Np~{VcTR0Gr`lLt8@m&=7Fq9NHaAHSP6&eESNVBrjoV)ERNPtfCIr2 ziN7+&uqI4;7>eqE14ZdiQh`qTk=g?M8E$V&e&JuY1;w$bre4sy33+zdHvoSw{||d_ z9*-upzkK@>nwXe1IZEb5?nBRMPJLQbTS>W@O zeCFjd>|Rw=9049?*p;#v$-y@I_7~bcVBJvy(t$kb;;Z#6UcZR4AvmAdem&#tQ?q7w zJg!#JgXKT-;|=Df99vd0lbajua+80ub3SOX~PsM$ai+t#E0^yXTGB&gGMr$P0Y?cIVcuwxAU>Fj0gB%HfxC zQa2Fb-ZN1|WvZM?b?qKFcHmXXj~F~{|M-rWaW82~+tI4%)0)#ql-5tk;XXyMYKn>G ziMjrNvu)K37?c;XI?j~=y%8Uq!n=INvf#Ab$MC`EXp#Cr`o$kSSQRG*BrRvl1XeH( z@UgurC+1%NbB3L9fH9)I7VS4D&4nG9DSP^nu_jWD% z(oin@w^C5O#=mW%DpT9Pgc8ERkIx>Xf0j-k7`ybbKyqm#IvIde_wjnB;0-%{-$eKy zKd!r$eqB17gJE>B)~cPDTm4p&a5Ln_9-ggW>yz|>Yd7euUivez3Dci}&YKv!DPg?( ze{SlZm7+}f$EHx{`e*l{72$uHOHfYEx=b+@-cC`zYOZ`r8NLyuD!9Fxt&~e5lqpHI zciGN-1+Rm6)ea8k5_Lw3FnimnoO1Z;|Ia>{%+SFMmJClN_t8Z7e|qT1x_rj9ieumN z_c`2_N;X4P9O;JS0ct5<+S*2NGJ`VvX;8;;4Gd^GU>@9+@t_UHjeH!b z0*HgffG82hb4fT)j>Ig}LmiEAckj08OTB7Dg^bjB2P1W~w1(Q8vWx7K9=qpfQOyYE zoXzX@@+YA}ttXSkEkWFDW!E|Wu7oBL2G0n#-|fpjO~88zA+Ic}zer{Z;JU)S2B=_S zxY}}RBsy--s!c#YCKs)PVE7xl+CgGC3~}6WC5**x%lP&(H)Pqs<@c%s$SY|#w{a$A}8dtSlp>&BU5y}bg9KE!>Z z`oBSMa@T#!w|MIEUj4~9FQ~NX|6U}T6uEn7|HQR5lACvT)no#AggIR7mjZQR_RtYV zpo)XAoSE|dn6Et26fm;zo;xTRz@3>!f=85umsR?-x;A2Ui%#=P0>aU=0PR7JDG^9052=!D7i7lq1Ac5YM} zE>&8h|3KWii|DY^uz^sTgLMFnmnq6#S?TlKkP}yQ4*gj8#XeNdB7_*%Oz%I8i$Ndt zp?4_V_YUDm&1aqV7|?DSpt0P%_?tIfFw~yKrntD621szwMi&(V5SErx={T?n4^z+P z*is<*{ivGpW(Ye+R*XQ^BZbQSjXS%@?qlFym->rM*uMT0Yy+`iS-0 zjAm44pdjy42!ZU*jT>zKTeolT3ZV4`g!_$>30kOuAiChh1@xFT0Kke~NC?zF(+I|* z1dC_2qQS=j479=SA=L>C9nIZ$_s*T+UMj73lSh7Q!_s;~Z>QOJZ*TBO%F-pT*lFA= zWw zjG|mgzll0(MfzaVjY1}BZI{4=sVdI5WHUs2gx1e7v|J)|EJV9RZR+J)JZ0TY58gd) zvvYEN7xA{V=f;h%+J*16cb)Q@u~=_CbF$^xTFcy<%uDjFU6`b|ZsX+*Z0b2v`>IwC z`;~@2Uz#z&zTHicYCB*0P)%e?`=R#T^C?1zte=!mt~LgAsjFLYa_T&_)<+*0FjoyEj)!RcF5N7BiBVbm$^^<>2j8n~ zyM?3950j&~?TqDBHb9Lw!I^@K$xFMyO3{0{#Ez0v$GPr{9qVx}$}}E|FB4xpXDUcZ zDC5Utg6il^$xk9TwQtKrN)SIqg!5Q369&O(@7xKpCMM__jeclo+=mjGv~_gwcw4Xu zI$6ap#QA*bTks4uUCD<{SJbrM?Fm?1^S=DmC7aZZ&8dQ4A>acOcZ``$>2Sis?G|n< z_Fx!YDT~87*h6@J1P?;_Xuce4>iB52hZM&g6gc~uHL0sXkwjF_1o49CMCfF71>?W- zGv<+T&gk;T9AUriFD-!CFou{zx^hZJtgOGVd$4iAk;Y4*BQK5jNV#u`>Ny@{HHU%ECgXXH{kWmpsEWX*M7Gc+A@d724dX z*zEwK0(4H{MR%mw>P)yB_-$YIm^DmTT?_pz*Y96enmjuLi>`FFIBz}S>E1*HALrLs z)iHKz_f|GSg3-6hybtaH@X8ZT$95-MY_r|4+4>-2JJ7?7S}%4okxe>p*^2(u$JnrC z7$BYjPR{^Bk0L{WTLCdVIgk3~AfAU3t$tovzQIE--#^4?xmX?9a zaryI+%8$oZKBzMcTi`Tj3SU3!^EPvsC~kZR;oSBkturYiauhW_Hdof$H*U<5ckTcH z=AZ1ds{d>csJXza_3vA95A_YS#2Z044+#w-cUpbWCit)L{Z*(U11P(V(jXJdrWJ-LT83L}kR$^P;xCJ)t1r?2mW-S3?DD%8?eJ)G2h z@zSb;?~6Tp?uqXNp7H=G+~=f@eaiqQA_tc z!XiW!#WA;`-`ltyADlO_IwV8;`r0iSAHfp62wqZ1;fpsO%imfd#3bZK4=3Byc$6pX z0e|mc*OMKS+#t@m=IFk~QRnB|T}=z`Qs5v+8eX9HW4XqNL+?Psuy}O^#&ipiG-A;R zO4_Am8OCsm}(ZshJTL>wGUIP6;Va(+`cNpBX8Nj_giH!|^w^0`P zVenwVb(;rN+6cApv0##xu5B{v$}i3Cfvrl|y0%`V+B(pEJ{)lKkTnNNy=5MP%CWFj~CH_oqzuP`LJgcil9&WT-(!yci@F_II$C&0V_NF zMj^Q%z-qdnd2BiAM!;*&wV+xsaxK(w<4`I%WrQ63v{A7)&1mS;%(PY~Y*O%%)js86 zq5bBpTs-WIF~(A$AcNcZjLHY3olH!mf)SbrpCsN8*eq1%s+;ZM{z(VFYeGj^&;6ts zS{rp6JYeV?TW*5ES#V|3(6ZA{_LWyiU+gPcJtbpFr?g_ydAD=-AAr>HWZ&yh1IG#` zF8RQr&*FJY&7X&zH&MGCd@XP~JNu+bpnqj*Fh@3sFMr#*KlTz&Yg2-sR9cSrvz~qk z#DV9c@H*?9Nxa698A7k_dr#NwPXrkiZ@1d``l09B!z%Q*U4Qg^dA{jvX@8yU58$7EA?c! zmB54gi?{DbM=L_P(q=@hW9~?kI7HqIPj)@#@U;+}*C zUX4SihM&~7H;BxVixy3Mcd9IZ&)~~#-G%2>8Kwn%U(sK;$7r8yp7`E6sOS{D1fg9TF{T3yGdafPQ z!8HsRw(~jfRE>H(ip!jaZi63c{HgbqD+7g944pq77auGAu!c4QzP`6~F{(QSi}T;ObAE90zoKJ)#8$W{K=)lCebe+lJF@Uw9jB~6 zZ{D>U{(+_d-O00-=KOG9?6pG`lB1bTV2VO_f?$Q?mp3?dN{kFt?2CHQy{+NKwiqzf z&SecFx%3fmS?GQQsfyB2$K!fY6qek&U#U)4A{@%_k*jOPd0IeQh^G#>)NO@Gy7`a<*>TdQ$QMa)1 zhHFEjQd^*h*5*i)kVnrm?dD6WSJ?R1J+o_eI!c(NjumD|*mCknPDA;b(`0@&R7 z85Btfk$_Z3?QaMrVtE>ZJ0VhYGa&)zxZ^n6zsFYUr~{R0mUujxQ{j*aEfFaM=mq4! zF*3ry#3J8cf3Bd$BpZERV1!L*=c=AP#GBzyT~S@1%j%=GeS1)!ws$I_{D+3J4svMM zz(K!~R`WY=ku|R1nm?RyXulf# zvG0P&Cb~c7+a@f%Y8Aq56!F`nD}rfzKMf_;MEJry5P)(*-X+3=Sdoo0SOG5> zD_c-{gvohR8(&-uZK&;SttbUQh6vg&Dk4NR5DPd26^BqVKZr&X+vhmA5$#PbS8Te= z1@~X;V6bail+}Pa#_=KVG{hKT@tr;RIP;)FtNHZoNu2YyP1Sw3QK^-Wcl&h{w&zhw zN){|@-a@ev+>~B5_O#2FKVsHq8v>yBTE(x)rCEJXNykl>+6T?O1t3@}qV5KF5Pb}t z3P~uK&exPL)ot8P#?iZdx;6DR*Sx2f>pD|a3b&c9&TBm$Zc?XV7?f1Qm*-day4`~| zSObEhf((D@EJ|%1vQ!Drzp_+M0hg=D(a?^h`EEAo;&VIKPd)4O;b4kr)^RV}*%%~= zCXis2dy`!9K$f*erZ{Bqy9ZO|QrM2Lu-PppXCg_tAPkHll{;TB;=L(Pryp6KFB(ni z85EM$QD_$cjRvW!>-Lw|a6&DhKBCaQMLO>6v*YLUqv^A!z$D|q34j!lmsY-vm^K

msolXK)FgQ;O3!gnx^=0z?RMTA!fdr^B46c-nju!`#Dw8HMw6SUJ9D9iyuWy0~> zVW#Qwk`AHXwkmxst!@PQg|^Fs-K2J|888oM_lMVbgWTxE36`C4#f+4^8RKq1zjlp; zUa|!e_(>7djk*>@n=jZB;SA;5TN~YZC^FZ7dkW=au1y4^=|)Eh&M8PkfdFjwCa+f*a7;`?~K?yt*XK5=Pp_%^-NcF0P_|4z)H?E*~W-_@Kz9ey5#Uq7txip)?qeF#L!EP*h??w4hy5=nwP=Wn)NyyI(Lz!&rl)qoaks|A{+3fxEDnc3(15Z#jKgJ4~JC{ zaJPTb(ND2PyZ&aYeK_m+8htHKjKNQQ3>rYAeR0?r0GWh@#LL5h;j2glATr6LkB{4# zPRmznJF6;CK(d_$&hPifGAjvu4-6YTyRSm0aJC;*{YPAoyXFS?8UcBa8iB(h_-GXBkp(!@>a42hng|3duyX+r7ib_|ms`2^^9iX+53>Clr00_dZDxO@7A> z*4_7sw0kxioFQMqx~P}Wj6fFnnG%X~8HzkORGV|Od&xc{!Z0nkm4S{Cv?4U)q(3Cd zIN^X9d9zCvE>xpdA{h*S2c5j6<2aB*gt% z#5P-hUp-C_jgg%RBAXP<->>h9DZE;++3e)~*!U`{eW@z`#Ozez-a{U% z)jS1+(i`(aYp_{0xFIhF!LzhqpeB#so-A=coEb^JZkUmq+d)U34s9IEG;b=bXpkH7 zF7xd@GiRkGG8|d!1zGhcwVRRR;S@OZ9X|P@v&xU;%gOwGD?mOpIEA@mMPGE~i319F zfS~#$-UAuv=k4ShuSIa;D8}n>WT+kVkOcBe5%?HmOKL$}$|Mt#Lm0q$QUDPO5nE zG~l1GqRiZEB!8}Oi92`gLKn^>*c@{1J(a58c13b#1h<0qV6Vo2_%Ca`SsJ#_ z2RFqTkL-Osmxb8U)Oj0L9FYiTDX0vPFU|5=(hZ;0f5xM~$mm%ONzH2WaD>(AjGd6= zHdIqD;h%i!o)sK};Oa-jrn=55wgq0Bw_?$z7oR{!2k!G_Js!Br3763^JYt4G>1~4UdwpOpdjdo{ zz(+>W zroFr<-JbBhyj~)SZ)eDk1NJ+@EomiFu?EfO1G?>e5G)K_#1u}!3u|?feGtvO3UjCb z&STW8bK#|v-YJ#C8&awq^}DDiZ9YCOOSP-hjyL2l_?V)r`SnRumwG$fnp;_@L2>Ak zn3H(ox0o}xQiZhEAzy??MECL@1R9)qdb$1UiXZQIH0I=0~A4Z@v${s&6iP5i`B}agGY!SG&>C~LHf2^rN8 zkFCRR81vY2#Qt24B6rG}uT!pYrefK_!F>_7ECv&Y$5!KKN;&#%35RoVS4e;3F;r^w zGj3derJbXn*}8Dy!c@dAlf*FOw{X%Y9S_OTJ+!?b#YFDdV-)4Ow^B%=ZZqySqJ0== zA(IUp_pIK3l=gEi(P*%Tbj1x$ytjEz6X@bvL7? zv7`paPH#?9ViM<4z@x)62C9y;h$$hQGJ75!gRemQ&)CjrAOD#voV$=YXlt+9`{ZQp z@llKJ=l$!zG-V8-_nYH!XUI9mK^unHCef`K1>`Af+nDQ}Mxp$_J}6xO&j+#D|5+Z?cm6SofA-A({;e=IW2WsS)9A-c z`R?_KLMxSDqhmsOU0ct(E|w6N^^Yk_Gtf0Ti?1XMKNl*TnSZyxAoRgq{HPl3i{4BY z&&gg6XE!Yys^6qvwv;lt-C~w!F2f3Q{QTr|=A;82UDxg$m_<3^v|@5jEoF`re!lKA zW5r6P{@3pydh%EfO^vn`zuEZt+(SoOFGRWRZ$ZQ4M}7{br81t+Nc-j4G-byZHPaqw z+~8%QY~!ys^EtsVi;r)?oQe2lawU7cTk2;e(R(J9UB0@~rZDv)xolr9TEeNrw!|du*PQ(yp2a1n$n=z@0k$0L9JKR(|@h) zFl6lVA&+y3#q9d8QkL8H(-XUL7#T;+0%+uKXCk35B1X z&|!iURc#&`w1;1Bk^~Ic`ubXtXz1=F;O-hNM0pK$ApX^dXDv0(S&~vY?ex=WMWkC@ zyd4M$rk!$K8=e{Ugy-|iOZw<##Io1cpx$y#uowq3#ZF&MkZmLrHzMgpPD$$u&7KfX z*bQ64my5dY2fS=7iGjhuo-8_U2`IQ|L@BxhL#Zg+xafw4nZr6#jXuA&8oUIMN$=_G zmAJ)cFU2Nwb4U0*YUP^ll=>!{qz>;gtRJdV)R6aQ2XpMy{miREDVEz94x=aoJv-UZ zFPq~00eOoW*_+pFSwXkOE zk8)@(Zu)*rsjURHxhDY?DbxMv+iFQj9{O-l(=eEUcz{>@I#=^-5OeeQ5005^uR^U@SI2Rz| zg*BK;5t<9p>mRa2oeT}zMOoS*UK__AslaIZoQUQ|u!&%_t6cYte=_znBjU`nsKa1% za>DTN=c>{TOfqj61)QcRFInJ;nUjQvvHPavaDc7|wQPOQ*L5-UjdvP=e6~bIHkJA* zk5I@#FeYp>s-QX2^$WXG(C76+RS!={OkOAVw2ELA%PH!I#y!2R&t~rvshK|U-_s_H z>cYV?X_rT1`#IIH{dc;VipGkW(_>3e{zV-KhaR9~s45mM_NkoA$QJuVXOEyk+v$<5 z>u7t#Bs$T3Kk^+l6GaqRRRo+U7Z$9%@V!ur{^G9W@dtfxtvG~rleKO%ts-r`p7I~< zeBOwHkcJ~1W;JaQ=Q&_y^}L%S1P#oZ$@{N6+{xrc$}UuZx28YNLMjy^+RH1 zMFArk+@1H~U{o<7OE^G|^5Wc_7cORtJ@vFG{7)gz<~R&vW)Z6fv48vxUs~+|70}b! z9*|v=s#1rnN;}pMft}NaDi*+A`8LW5Rm&AE!EwYzkRm8L85*~{FA~e@|9la) z_5r0Si4U^6DT-KmAx&WI4h3LD?t`y1G9p@rL|ZMq&F=PplYj6r?RWlxVV2vG>vde5 zacHscrv~y3G_{|=5X}Dt0)h{oMLDQG;PwNXn#f%Orm8=9w5qE!PLBj`poSEOgD3Kh z5UGik&HKyBEUm1DTK6frLb)RwUCUrpt|^Hi5Ij2OI}?`82pi=y9IAL(@bEk7r9ASe zjx%o4yLcldtMUX?8BzLcyqn%uXdhsL8UQ$TEx-+7vfeXqY2P^|N$vaSLnLRGph(aj z>Ds0)4nZp__F$0oaxg`(MSw1_5O7<(@ZCvI$>$rdrJ}q*9Q1N)S1Y`PcrHl9jx&*aN-JrQisoL_=g9RTJC5 zuF^3yy!&>K%=X=C9C1f4^Wu-Xx_|wnv#5;g?cOa9LJ1%3u{E@W;iR^0dxg~C{_4r9 zr`Y3!S1vtF(xMUa5DSdnKRm&(dd`xaCMI>8rK=!0e;5Q!miT)a_khL&uLlpsH-2u} zm!*7*B(9!#lT!i(bjlHzqkIJiJS>7ZxfU2t&}QSikHV_PrPcSLU_?9zjfgfPQ30p0 zux3W6b-sIy^mY|Xp=SK8kW#-RYu9z8qtP)_Szw@ZK+;7sy7a;K=Xd=MRNs1Rdo@+r zay0+M{!$jW@4&%yc*WYeJg0~I@|1wI5jP`kRlarGwq*!^AT929nB_lXrWyx5SFWx5 zD<@V~ou`F51!)Awe~7BC-_yN%{3qr;W!}z2Pn7%8fBo>W*V#V1f4_k%1F1|a)O~!W zFJ%;)P_JlT)5NizNrWgyMVw4mIGb_wn&GRZ%Bm{2R30na9ew9dkMG;EkTz>(CDU&_ zdG(6PGiK_^jZfHr{L$t6-am8gfBtCf(D6TdA^huCD*bDtI3@JR($W&TYWEH`ZduO| z5xv!}jQdJhtNDx#Hp-UKMB5;m*?yl?A?PyI$o>ioH_|`Vd35%=WfdNM3JmE6r%SnP=7GHz3X$G6^+_g_x&8MW9O2;g9VcO1gA0MVHIVX4V>`p^N zMTqUzJ}nFu8wAy?y!?iSr#Tn5VAz`apsF*EnmE)r-jFVfWQ{hf4W$^Rt&2?a^wUpD zhT#9z47^L3!CumO`4f}WN$sSI+h%1R4ZQvg1xvqbOA>_U7GHY7cIxR~Z1Vuc0gJr_ zI1Pb42B#Hm>-m|3T;|y5W!BAKiDcfaTboGHOi{qaO2BJ`BITtlTNL|zX}XLh;`Hlm z{c)WQP$_z)Pk(Sl+kH}&5K#rz9ED13w^49tD6N)NY3n*=sS~HTo(nB5u->qzo8{5P zIdI6EXm8<5e%#`-OD}Gu)%nXoCAzXc9&Z8#F1X+;=RH49A~&ctdV|MStc0S{`}%k< zyAMrw=zW4B*PfMAm z9m9)hixro8cPvPsef$;gNn6X?yVG8e-QIF?d-!rvbEOtTq^>=+j?;{J#ikp5Ig{s} z{ms4_4(*fLPM-brY1AI2GWWc_xf4V#-D--h27T4n(N~=z?x-G~!7~K!^+rLLk^0`m za=dMV?~hxqA7*2VH@P{4wsAS3+fSdraBlQ$6=I9QzuRJj+{LMH>Zzg?X@~Y965$|v zo~z`{FYo)WD?f)tS$1Uy5hYW){c)CL{EN?7Z0wI0AK?EFv!*3BNfrvZTA$sjl0pF zbv)$lPrumus#K>5Sdhqn;qO#d`ge&PiKbD}@JnDgJd~OzW^83aUvnYXD;tA&wzO}cyUD9})4A6?5i9rO&Ix0}y88|645~L{-hXb?S$m9M z-T0sJJvjZ%3NKcdZ}X(TvOm}OmPltR6a9jJuJV6(mF48iPYAlA}B|0_Xut!_zUQ-6;F7r zA2wf)k;#WLvn@Efi`Y}FDz<~>3%Tt3kj?58C5YHix**PkhtV8mgNy)@Ik>MyVv5}* zDiG_nhLj`-xOX8+j{@`4P(kF^3zYf`&}{)ySqbP-=<9y4zjS`5`?Q!1ey6et3yCyC z1Ft2$J0R<#OP6Y6VWFlJX?y_R!Le~sB7qV81eFYbtYX*jL;b1iGQ6sGF`SW&hL5;W z!=oDnbPbXNgSc7p2BL=Q7c^&YJVGO_S7=XnempNg-oE^?n$lIG-b=8)9Xw#pMFX>f zk`(UK*sTD~mZVz%2PUX9x`O5h@a!eJ2D;)j-4`FZ1D1T-BX&tQKqw%`)!;}(9f+kq zLxi^O-Mr+I##^zgYsQLPtu6e_Oga-s>)m8C~FE?+Ed{d%HmD)jSDgkdQK%u7`W*oL_){qQH-cRb- zj^eC^mQ!X)0q5GI(DZt?H?iIiQjZG2%XNZ63Govzwhe&t^i6;l47If0)OSL>&Am6h z#xFYyxyklb*W%>N=o{#W%lN%+QzTY^b1rE~#F*!u7`44UD^|E~C!n|2Is}YDk5{qi zJB3s8DpPEX64D91wt;jd;IK4J33PYk>Wm}AvcTIOD%M2TB7qwQK1*kZI~NnnMe9=v zTF1Yu>Y=$Z)iAc@{=7bY{aE6FXLSIdhnrvha z_3 z@HEM+zP*4V+N#oV&QZXu0z!uGd#g0`SZOziuz+be9wY$o?~~q6UKiv-3S7f6d}Zh$ zvLW^dyA2IJo^tCh@&w}afeovpF&zIFeFMVW$)OBnwdrtmZ<6u2RK_cj8t6|frX zrmT+Rl9di+1|Z`Vv_y9G4)lDz=rOrD?+^y^SXU&8n(awwBRtP~QLt`_x05^EWQ$HU zbjVQQ;{k4bfe-5{Ta3{@9*uG}6RWkiZY{yY95fe^i8Ld(;9U(I-tNpj8-=OUSjN-w z-|GZvsW=?v3RhuvN@vR3GExlso-53(-vJ#V_@W!KX8gh^DTv$_c(f24H@4@3ifY@UEl&$&Qtt zey(dDA5)A(ee?L~x%`yO(bUw@gn8*_Po$199>F34PNRq8?mxn>WJ{@+Vf{+pT6zs=S99RK5Muruh#qW_sw^{xvRSrRdpEUW#IEF+Qo`tP&D5ljvj z*uC?JgufA6=o8~f!a~VsC!FLIGFJY=ylyQ!W8@pgz1+O2tL?9E@o|wajWpTf;Q!#1 zkKT*R793^?SL&F9Pus__sU_$|2Txm~vZ!Ik4NnUd-zjTzmUI}@MYh$9G$c**TISmD zt>0U>qU?TT?~%ywSw&`yAN8Hs*W|O7ALmvsX4rZC;j*l`z90CP63N{uSq>>vj=6an z>|*HV+iG@`w@xf5wTdAIzoPu}Xa5UJvYA``g6vzrZCEeQt#{Io3)M5VKAIHW=(%`D z)hweeHSmi&wr@vI{js$UCPc_MI{fY*pE80JD+(;Kl$a^LVTt2q21$OaKv>m0D*R}@*=-1dhy~; zT-?;@W4CFZ(#GQz$d$k@<{8O!Q^Uc;O_m=D7)=;Ig*mGu&QKQ_?(k8X!SgRazdsq1 z45Ok*Jtg0-ddZ6S?BGT&TwOv1*rCh#%lX@54KML)pvv{(zX^;6Ol z7@K6T9L)$S&WS@wU`5yGFsNeGKArpd_EEZJNP7Hyo2n}Ub-HF-9D69e?1uY3j?pW( z{Jb*XD`mrieac^X*U*1;%x3(bZXMh(<&OLFTm;H49bf>oFLFwG-DvG?s7qj*Mj3oXRLhlX(<`=| z)|lLHMMAPr{dhMn^kM&5U*RY}5*3cQjd#GNa!ZyktG`G0?1Aw=L(EB*u8oQ+MMaKg zVv(Fd|__V!t5 zMkXvSw47T!P{{krIU08S$KP+DNQJ;)51>3U(+;zJK{qiB3OP8$i5f^3kTZxM?yTAe z%3crQ9zjf#;O5Z7@nTYHc4V#6*CDZZPTJ4BV07`-gTCI+az|!Dnz9oTfr+%lXDdoc zNzI#Q^61z^!VQyj1$jy$v->sSRW!XaLC2zlk|p?nKo9^+tODaWPlc6&zX#J|{A5|4zuVyNu~ogZZG=m z-#oQpucHqN2rRt7=y!v90We4rb3n&*`FbuudIvC$I}ZOq5Ksrq#u?Dk{mrMRr=ec& zouW#$YKrmF%zyC$2g`#Uvbou^va*Sq&Zy~oIWf~9ZpLavI?2K8%e?IFKRl}{4AV)V zV1fqTk}w%`ep%;uGAyWSi*{{UjC)j`_c!lbVMJ3N2SPcb*kuicKfQQaAa{`RZCZQwrd3r zw|g(=qx#yf1(cWQ_{a-bt@yl)Xit#2FBpYlWg6k_4MEdGn*a3;xvJC{Lg#At?hKr| zF_(GAj_I_d=g*&?uy$G~Ce{MoCV*JH-?mM(c2e8C*&W^eN*@w4pnXap9zs`q#@B2E zhRr5G+E+jDAGR@|XJ+-|y@81O1LTZYNoGXG}taJUbGAh~hl zMi9v$tx*n)w-2ha!R`%WM!H~5VFD4hjSWV%>IvS5sRH6Q27k?0$r1(&bYJr&?PpTv>IN`R6esb*^pE3u2_1mhY zl?>n=MFI}qRg?K-Ixu}Qh^ruS*29#)_txH4HplP>-ytOi{1{bb8;A#jP1-;%)OPSc zA04_()9ugALjN+Jl;USFE-IZUR{Bu9f7iKS{d2((yi+9}5Ix4!<#Kel+Oxogv=?;#k@g<;IJF-|!F-Pk2FmZDl~@?|X6UN;%Of1E6W);o-Aq&qgmiIH(p)nebX0VHY?=LGI82TT*rI+44G~RMO#$ zQVQ7Au1PQBLr=OtLeDx16Qmulwg$WBO;r@2Z^G46bm_KeU4p#`ztf+mH1ev1;rg{} z=s#Z7ZKX2E*ViCP4ZnDiw^hT?&@jOyad`47fl;%5aG;F%T(})q^yN!J1EBWw2`<4b z)I@f8ICo4W0!xII91EdLJ(vUb%7i`pg%57+{TF6q@!l#PQ3R1=1oF10N1#@dgGvOS ztbIKMs4ozGn7AD+?(L{taAz#0aK6kpIa2?`u@Kn=uQINaMY zY8z)*0z{(F%}itY0G@bUx)SsgU%Ae|;_>~KQI+F|gA+Lu;Pi;NP>cJ`%kG>LugG2Z;a-He!T~-Q0mX=$;Y@vk9!T+{__w1JTWnZ&5Ti@KA}& z%A#IbqTq&=c^0XcWU4;&l@syO&ziuo?~sc)%HtVqDxj9q8V97FlzO6C!d4%kTXyZ~ z@fq6*n5T=4lZ<2QuGTz+YiM&P0(E_roe&rlw7uOGNB`}LZvmh}4}n>enRkKGu>Q2~ zBiDQ%)_efOjs)R}$K(gzs$bePYtbt}NZ($5pfbl3>9a)vcEH@x;r|927%Uuf-T(uJ z3lXVqYS1eTwp{*)kf%T0A_=%|D0Nv~6t(hOX1lP8|bot05xzi;Zflmp2H1 zWB?^M-`@WEIK)0%p+v#yZq8m|QFoRdOzb}+D+~v+qULue$go-8EHEVsp>oALb$(Ur&l*Q*zUw#P$?a*bZVRk^JpDy%W5cJ^|(|$tR z>;uW6@8~0NcJC-eEOdoR7ze+3!Y1sy5!8e13z_(q?R|oE1OHZ#jABE^X#^6J8xhZ} zZaf!NT~mS=S~K)nI=2pDBL6QQ0}I8%B~Xc!2@M`(>e1y7{EQH4;+M5I#Rx+*8zdyc zB{$U}<#~>rR#8}5x)*wBCl$(ZMaW6^aV=W1g|(+H>aQNr(;yO8=#@oB!8eCEEbCJS|+a>-K`jPRI{1qpbfOi%U|2Y z7nuV^KKA}ESXlCk;JKq(Qf6>-AFR$ugWp5>2;0c5>9UUq3q4kMRQ&E^m_<~A?;})0 zXdAjl&t}@cLBa(D^46fU!M?8bke6x!ksZB62(&dIQbSXJ)8xY>yRW_X`$1~bRx`E9 zB4mi#cmT|EvC3YdBlv}o+c?Y9nmvuFfC<0(6}iS~kK1VF@D4=10FkspQC{94x#nP#(V+kFqhu z?l9Xb`S$1`Y5a0U`nX+tbF%Nzdh8|7j$aUDWbFUZMHqX|3wcM5O1?u#X%MCyv-A+1 z0O*wtUNVj@pXax=O?6QSLpC*vmvKiCHOF%%%uz1>WvL=&t`($VTwW?(Ga~pE28yt3 zHv7?uD?B5ASp*r$3kOq-*sm`6c zjKTA&(%*hlU>{Npd$mmm8jBLwX4_pUHsgT{nZD*>B$t4&Og7fmR(j7W6x2gRB8qo zjhHXBeE9~yIrp)l=F0>m=bY23QmF<3z|gQ7@`<7gC?YNR7QNaZt5vc!cul4j>&q&N zn?U1nBIU`yx*Nsqm(VCcBnPjpzr~2=QkiPE*;c?VUF8j43Qnac{0b>C2rVjZUt7Ys zz;^8JDUH^(8aH{RXG8{ndjvU88IPg9XBi%#z@gmfZf;O|ILEUhVlZr{X&ZTB#bniQqBlH-Q;9;*Qr|7wYnure+_ z8Cx`EsQU8}Vkf-sDo8sv)j=}XqyDTaj@`B>6hk}F2_r=`hMc`F>7q>U=-2~bg3KZx ziw@u0-a>>LWqS-{L_OMxbU$FWy#Fw2{b9~NF{7E2nAb0vll>>BB?b>yNJ~Ru`hKpy z7sdYP3gz8zqHSfzr)s7#}JnCUy(*>3bNJgI>fR%elZX{)rIj z6_89epJ=Mh^{%L>c=Z)_X#=O~U{qRCH&M|IHw>u^|KU`qMMJmg?cg(H#~V_-FU5aH zI?F%3-L`u=^3NHAouGZR!pJ^3L7CDGhr`6!5OLjUA84qL5L!@TtXIs-qM`#$fy2+H zQrJEWZDhMWn=-mRC@-r#zwkV}u2lc5rY!-X3&nKD=GUSFMh&P;T?qgVu+PklP-EO7 z%}i8h%UgI|G#{pL0Gh{!?Jrk!-!<06{Ia^_SEkLQ_pxS!`@9 zI3w#*Y9I>l5|e_}lyq<29 zEHwKdnS6`J%(w2t<1?W09k>kx%*gxr*azN+oM%w$7x9q44j2ptxRbP)X_&rF&V86Y z-Vrip%dzsOPIy>Z_-M}0sJeWa7-=#&Gyoa&nm1{L#kOnJkH|zpny^`?iZu4hIa(ba#Lxnw4U46v;hef`K&zE& zHY^tz9awDXIJAI@cP3N1$Lkr@pmhm|Ed)D*&TvHE5|S)^dm&vXcmydE<}Gt>el1Kr z3Z@W*^!VyKAb;gGgTwwcg@LlA`mZ*)Y%9OAuhS3BC z7JPL6tu`D}H8F3Z&k3D-4pFdNoja_^sL!80JJmH8tL9Xgd8)=gvjGS)?<%WVD=bQI zj@Rq`3J@I*S0$kn`hRXM`ZcGhU&<3rkX!p@bJZbSB+4y?RakjaJSAJZmrVG)?-v8y z|HA-vfutkvzf)5>MgA>XlONht;B*zNV>sKj9j~HQa)+s@sTV)3=)9fy&4P*f*suK*CbFzj&;`}3@eRj8;y*KR~Tr;6) z0m?sssE_mlu(y}#fdK~lbS6s4j944tgl@*sWRAXNc2toj@c@tRn5G^wFW~IiM7-Pb z9pH%GH>BajZE*P2dTftZGb`cmV+S1^l%#Ir2?(|H$_D}%;0U}D6gFcyDXDL`Z`UC) zDw;(I53n=94ahRBqS)iQdSt(F)b|hk{sIbwo(qbw9GtH#Pysw3Q3{9ioh{@unetKI zo&9M4?4M5C;=&gRaq-=l3DKGt8|ktbS0OT;ir+~KFfXj*#_ij?;XW{YLISW7Lh-X| zGRI*@+x8*Hju60Gan&i^trg!eoTNW?525R;M9AZe!yx&-V43%JVP3|g7p{;qzSmRWn{2DVBK7Y z>`yq#^1*sk}o;K^w1A&9v4WY+G;1ub?>M{&8NF zr;ZHiv3@A&ov&!Pz?xF~=5O8>99Ru}_|QBww~!eX@Rwe(S7`gwfUV@tBY-mL8pZ$^ zTD2Z+>S`QA+a#Xalnp-&!+<4dFW&&;6;nULISE9QOxVgzZT}0mvhR)~E$xhq$GC*52X;kb(VzI}Pr@0hB5 z(U`104mmT2%JVz@Xw?()#1=4kZn%_n{BIJ%yRPYvafoSgUjsGh!q^|Z{GG-zZ8{=Z zReO+HBeFumVpDgD_k<`O+InPxn-Xj$I!33a$~gBB(QqO|2^%SMN8#jRtuw-W$qhKk z-@|-W_nwUQ9l4I|6&BCGa&lw}K}p$h!5T(iTG)Ef-RQ(xmLBIJGB{Z_t*4USwm#nwyF!JrF>mz#6$O1 zILc)1i#u^!*ltLoO7ZXYYcD@=vdRXRz$DYKmN;FO0yZKkKio4wkkg9y$FiybQYpnS z5MLXo8~5>cjiDqxZ^Ie9ju(Z6=%4t6MY41^R;g)mWTn(U~pO%P;6%`kgHAuMpaOG$S{OmmL+qT+tlF09$c+%u?%?2+7-L3k{^=yPaj^%wM#~NSh#F>N~lmh(%s5m zl7*l|O6_F!h$QEtqM~@rsqyk+e0xXTwP$3r0Jyg*BXcaA72%b(QTCe_EfPRLoWDNSZoDa z0Mi()KX^=>zknfn{Vz`*e1@5_Z&&nX`pV<|tk}Q3m21}x>&;zO{PrDcTeiGJR)Zsg zmqrWHZ(yW6?v`+ksL7!yL6=&_#=|b1-xv79m-_sy0VGX0caBmr_m|b%_>9q0N_=aI zGtMU<8KSzAX;rbDtcQRPpFA0{R33nXD4EqzC5^6&rTLF12qwW;%L4>G`t~%wyd)YH zF~O6^?iZU_&O?dVb5!rC96}A^JlyARN)90-ak6=n_4($;?FK~zSN^&EEn#jmw% zUxideUm!vLwvk-F^Osc1RGcF7n6dMz{;pl+5G_U%?k%jzA%*%0DRMLLZ{|$MEi9Pk zi%tKeTEE@rIELDzP|ppLHYy8qk!87!Z}7aT6V`lB|7;0c`Y3so66Kg z056HXM1%zW7M;}0M_)O~QMm1w9apf6VtayFD`n}bVSFVfLi8Y;#o7@n{U_fAdo}T5 z_XDy420>muIeE1kpbFbj2q?L9;2TfAI)$zAUwmPaC>Av0)qnc8t4(DWu~7m||JX4I zo=t%bSB0SCLE_!mwjMQZ9LQr-Le6EFQ{E~C;Ho}>^=TuiUc7`(s%XVxo1xz%wi3^=xZRPtv31NH1Kli-d+e& zvU3+!WB$zi)aEttlc)on{=3g*IV0)27#b=~9dU#2VWgC}#gcdP`z^xr>T7FY};7tlFB+cW>T2hin;0+YrP;T-{N1L4-niVMe#Vh&#KWpKl6G z_|;dW&O}3xKJWuav!)%u2Tm(;`>q4`1pc)Z^zeA(d_C3W>~r>Gzyu50d{{9JW_j&axN8J%R^~R7khKo}DMWrecL948 zViju9-FWP1cyuZg;pRR8&fEU2HHO}7J0+cm!6EJwk?!IX{Z<*&H1CONqa(GZWebJb z*}KpfJ3wHkb7lmX)H6H%d2aUex3amJ!XjFW3RZ3TJsI9)It8KLl`e`hR(U7_^PGEn zP%iV1Q3>egb1eb2e06?-bM7P1<88;)vU5Ndg7$;m8sBUxfc-|-rVh+e~OvQgv()Fg+xh{4hx@~SQ$x#uQQ1dqsYHN_JnyZsj5 zer@?mBH?m?A#FdoXC;R;$stTNZt=)y|9)|lYY+uNiinC0kMOwIpO283mD<#P%mH?w zph3Y@u5rfVDR}*X7z<0FL4}19lNSjLVVeu)RlS447H#BKC8Mv$E1}GpMPLRcvJ&nu za})7%K9=?fK4b123pWK<0rndmsn?`xAtY{Sm>no3X1_x|u)*UBgrIl`pY2Rmxg0<9 z3X8@KI59nw^T&Fk?|=N8Xs!&Q>L8}O*o&QF{+H+Ea=G)GjJq3d5vW86w36n}x32l~ zjX#I)e*g&f#UJr5-8d`rUMyGN?prptPW#+UI}Vn0?l8&U?R2w+6{D9tMRDb~&3_i`M0FPqx+ z0+|?tvm@Xf?xvu%1Jo}!uKS9Ut}nET2~`d|Djd=8e|EVmW`>?@EhK2Ie>b$@nZ*W4YNi8RY(|nx(h)uM+yMvV z2*ee8^8W3sqi)d*a6IixoZ#A=yr-BoNP_@KxMIdnp+?3foiu`7?|3 zbB=Fl!vikc&(9Br7Y>9o3FQhxtc_3&-NJS>7)D30C%^p0v%h93!oFo$Wn?G$8!TywCfKk zpxWi8E`L1SVE&hr0?G2FK{OjpDr(7r-L6nTlRdAMq(?GFy&bL!#TSu2zFX;Tuy=30#lQa(eUUHXWy(P2 zqOl+7*PYVNZ7Jr8ijQEl7#0esl^rM=dkgk3zpUc~(VyUch;zdVwWk(l-A4%X_m zer&ky!9OhaL%fbv@%Gd800oa#L^bv=`wce`i6<+}M3gv8T_5dNYXr&zV~K4J>K9*~ z($34mE4!cna_herhj?(OTMHW|eQS6RVteRDNzknbk^Z|?nyvp@-*b!5+fN%Ei7NA_ zB``r=0w2Ri8Q!Tb&zDqU`Slv*c9Nru^D$S&aXLs&L#Td@3qhL1elIuPZ$evIai++l z`?uZMP2OVv`}Y5bZ~m7kgcR~w8no~q?{K_2ChTezL%FGTrrzV{3gGXa#|fQZ0ecG4 z$*F@c8aC8G0Z)>(3ad^vwtk3hq5;m^QG2p_8kdGh@|qKF;uQQ|wu z@Je;CNQ3P=ph6r#N(YM3-2w<5vaw36tbZ0W1g0Y)+;Q_C&1jcPq#0%~@gb!Z@eG<*IMUwt}g zhWVO3TmSl)UOtqA{6$!k!}aeM(dl<9J3AYF3h*4)pZ`Vszx_qizk*akwFp08n$h{l!Enp9VKdaH z#KC5IoTdV9J9^|h#8LjYzi>~s;oZ4xdYI!j5p#icMWIn$J#EpF-&R&9 zN2?|GQ$;r}vCXwe-nwEx!)E?fAD23YDy5_y8M6vSO_(o1q`c)E3?Hz)qe z$cHUwZ=c`5|2MycpOX44-l{XKExr)-iB$WozqMQ9r$0jce67|0_dm~gDn}_FaFk-0 zp-O)(+kQp+J&Q@gTfLb!5pHgz^Sjo~4cw_+-n^^oLI(x4c=Xi{3R2tAUEQm4h#!+Q zS?oXjKmB8NtJ=2sO)I*3nk+=`z7b%MHKzOI@Bbx;vizZ*M|FzN5*AX2I->#&E#ZAi z`qF2eFStzlq{kSDK8T=SnI#!)0~=S)uhY)8?(G-%>6sa5gbIKyp(<~SlaP=oM3xxO zX>AU@a>Aj`m#3o+I$Bhfk1Ow!Dc`nn|1r-4d3!0)^s{NxCSc^BZIie{d4+{-Ak##O zTjDlTC^RWK;hQe^1qR`Ce_ck{pO^9A0mKGtBr;rJM-Q}ftBB%2gDq91oRN_c+``eL zi>k=US;ET7s-M2}LPA z_(hhdt*qwYx{C@2tz09|o~c>CYgMy9PbDT)PD$!kUdwCa4R>}dfj$03cKiEwZO9ed zzWvI&ZN0EXuZw>Ccy~_ny?gr&@1nx5s8DcspX=-E1Gr~*?pz^bYIb(*sXSQX`Bp;Z zS1slfsTm`xUi{WH$D%n`dDbvxi`4k1qR+S~Osr+%-lm?HE`i`IAN9w)ZvggZ(`#yK z#A2SK?QfvRdd6l^l9l}#=O=u`e1li7baPg*vTljU6G<@7(M12(q4JACK|#RPpkRKo zLGhzNCJz_a?gPO*bwHxh+JiiXLeptdBzGKR2!GKhnj+3T@N`Sr@|7#yA(d-bnFpv7 zM!en{n+yNw>zGmAHM{`5F6vRjin017+7&|3Kfye?@wqLP!x?&dDU9s%4Bq7BP4pL& z94ZQoA}_H#+cgCvXkretl4c{=TF~nK{SeM}b#*AB09qKUq)(u=UR`wFdMLF?VpQa4Z> z0i)1$!i}&_how=RD)XsIWO^qsLfE>~Ed$a?|I~2(%ettpdO;#g1ObqHyAXG@imo=~^0 zwO6EH3prOj+S)-rH61Af6kdd9k))pBVXn4|ubvqh=kc1j!LhWBZ$*7uEybeL{_Q?t z$>rwehJUD*025{cfyp0Mzj5QnO}F=hgM&RioGP0bV|`aMF$v6_FwGHoy(2=ME3_+x zCrq$%v`&Enjg_2?Zs=)6v+thL6p#4$_=Z!@pFhuQ84MT=NL_4Lee+nMM;#}B&KnB? zq8PD#nV>lQgi%F*!0=-zwCFhQ4NB{0nSak3|*M5*@rz`_R7lM2fz8sFHyK;BL_!fem(Oa zmaR_czwjZh_F9EUIe`rny>s{3E*(*y*8~dV-o1M(R;;*o?OH}g zhQ_fYg_KqL^80k>H!cl^G7zv7xVKZ{Vb!)?ZOI!a^3d2WvT0K%`b-*a2!n?uOP2hH z=R?G?4Pu{w<(aBHj$p5k4IHm_`xY#sz2ACB~a;4Xl=n*CEwiL0)E>~OPs_H`Z2Fw&7n67N-MUy zcjO4;@aK}+BUR;9%KPT(nRO*@w#0HV4?uMM?%g|_27^Od8ZyV(BBmlP9?0qe+6e*O zG-iA^Wa)CW0RxAi?cZ*NUD6sR0pgjb zE^Hj->v<{Mx~o5=)ewjp^}BOLCCSNLqN1-;ErNrCQ3%#C zxPqK?S}DF(^vQsGp~v?)BZ21#x&w%G!%96^=rb^kf?4+FU}t%B=ke;qFy-zK?vwr8 z*7p%}3O~Jm`SN9LE&L&35m2I{-e3mxzYECIyPP3K-{I$A+X}0SsJJ+m)vJ#RM^(t- zKjy(`$4%dt78n@lU^|)BNi;WcaZOH4s9)WB7^_hui^1q-LIQfcI8ENXdSwf9RmA6g zs+EN)=IE$Q>#n42h0o12ye7eEnVOn1nZ#bVxrO7ss!GYk#3bh{#9ohf8tMc^ z^wY?>y3PP~EOi<^WtJu{D|?>j3FS&D*c#Z*OxmSn(8U zMd;J(V>hHNYK;vI`DSWFE_0F!G#6ex!J~&b9WCPHw6S|@#ozDZ=Fr81n1~+W=a-h1 z#ckjvH2=!%&Bn#!kiR1I04(+m40MOx=q-9V8u_>X@aD&B1v5o>cut}vg8i<=!_n~1 zYWAdwY6oI~3mS~pu3fufLri>pdqacbwN*9`M~yGD?Pglgt-Q)ifq94+mq(Ii{mjuf zGDfwTN{(jXO4%yygCZ0p3EptEOXqvhwuuw>lUCT!Hd!JWW!qzSfr})|ofML~s@8@0 zA?ex*#dR{2o=j5W4wHKy94?lKd460pCTT&HYUexV2p2`WmkUXKiMqlJ3!;gpQc?%6 zy!N$#cnUZ7)lN_J<`UO zwFreQ_o5%y=wESzr|ZP|APAiY~X4d4{g8u8)vWZRm-qc$%Uf!)0ulV}Ncl4)=`u zMm85P0SJM}BTY)qQ?$E-cK&!4adIZdjU~ogFB>qN1Lzu7Ln!BkMXgli)Tp z0X~ZBp&|5Do=)kj*8A}hZcrru0zBgP?~dJl^X&N9z`5(ov0OC+k>Re-iALkYh;pOf4{+HDcXAvAXP%h3nr znXBY%d6sEPk@wnVr|k5na^IY%-@bm0ab9AM!`=7q-|y(?z{?TXN5_gOZR$D56;Smc zZ-M%uL{wGVL_$JC(R;wd2*z9FbhF4rG8~Mx%f60{jSUaeEuvqh!MS?k3z*@$y+5Zv znJ-2$#pUPpr*gX^qVoQX*Kgk*C~Ey=(B9T2D05N8F;@+V!}n!~(TGrRYjGe@O8&Ha52Td%@Xh<%4k~Frk5iKwoZ7_pb#IL-`y!DlEaxK&1_HlYsWr!-bTx zxEVCMrX2J%=Ps>Epqy$`pT8TsUte2zkkQa?I{la}(vumGf#}RQuzacp11(Rth;E*9 zO&jSqbhnIlaCTOmvnW5k;M!%Ttv2Ks0Ivem!&qZzMGCT7N=?1vY_Gr5620U#I7mj$ z6+Q%&{<-jjU=Cy&Tf9YDj$A9q{QTaQDoOQ|e42O$?GhO=v3w+vC=K%R8u~w~*>63! z(r#vZ1h%QqB}kqG46ptgh;dh7hso5m5Ketv8b5Ti$j1I-R=vCXqEzNmZ3!P;j4PMqpqKGK6j;#b{rD|Mc6p z>8OHJ1O|~^eNU9X-Drq?y>QVYPL3te2W}rdN|Z;|6*v1#>S*Ea&11~T zGI*|N$0OL?KqQ`_dpxB~0#-;d!NF|thKV}j5T`)3GI;#^8awb$Ypk%no*7+1-7;)! zDK_=Hdg}8m->B19Cc{q&uNRMt2n)OVycbmo60ISgh@_Pdb6rduTkA7cEw`$oVCQp) zLmL&8!VqwXXKdl;U$$fkLaZtr!Vyy+)uV#i5w69-@ApUtlVxyxAma*4uc&XaEIN(; z%3bo$dZUH%Bp|Ai$fvW>0eh5 zHwxn!4;y>Ue7UW~Y*hZYI#3zVax(;G#^7P2!NcR?MK!Ka1DKMX-Fz5&u7*>iLqoyt z3|AgPAb{(fnV!bPqin~o$5R@8GvMfpVG$u&7N<@XLfC=4C@o3jZKgh7;N$N8v5=|S zQyS(l)ej8~Rn#*Oh=BEm__c$4cWlhuy#`O|nVvUyhexs0o#X`q| z?)4*Seaq@p6~^z)GWwHCxrA}{T_dX}oRZ`hQBg_G==$oq4e39>)$Zu*?Cj|1Giti) zX`TyaC1TUj&*&fN@%CG>eEG-!xD=aPskBwXXi!0nLq6Bj-Oa(t2{H>Bt6P;ZG@0?4 z_e#t6>LIF@Bk}_0A`bzB{!uv*)O|aedGWS_`DTwbhyvS{AN86aT3;e?Gua zv*c^U?_`GQor#I2AHB`)Q(KZE5goRRiAhGlbzoyVlyMma1qS_ESb8)oSGHqrZ=jdW zq?|>Lz-cI3HuLcGea&;hWkI86KPk7Sk-r2j9x${?%PMU~O>$mJ*_5fELWzs%<5D&S zs-_g~@KKEuBA{APbV5r6`o%hC~WJbuZv~_8D zttXT0mx7Wn@JdFqtG>d=Yzh+ z4(K>3BS*EdxdS-FA<_i(RlOxd8cJ$vtBueMNo==9`5Ba`IL-pxOLfI{F?8eT(ZsB* ztR_c@Dot6<_JSux%Pt10JUL3YtW$GQl5o*XmBOv8EaF7OUDLQgVQ$x}+LXSDtVl{Yf3d-)zt}aYa+a66i?`4k(i@SwyPPlK)Y;Bl_M$ZACsO zh_!paYW;luu}W%V_btKNUyG>gcjwC;%5qA%fPn?XrK@o6WxGB>yp$xd;pdkgSz}XS z%uBm0h}-MVa#zV$hx9L|9D9I}a3g)y!^)M)S1Dp>TmW>hCqO_;>6Y>?TPHYzhW5jc{I-Osc~N`QhItQwd z*Fn6yvx(saB7@5#TdHA(hNPMC1op<)uiGhD?E^_`WuIbbWolog%mFI&Ej zz3cVk2bYlaX32Vh!i=~8nAbHzG7f_T>22Hgt~RUUd&@q#B;P`|bilrJ!9+D>+SC5= zdDNbM8K@BhbXF@VRsBds2e)u%OheF#qZO42A!Nd+Ta2S`GY+nw<_M?!)SSmJB&2QO z8xUX&DR`iXxJJc-?kBY2i(x|tZ_{0yduX2`+#SFB=IK+_I7*_3)i_EnV!J1Amn(%l ze&IRnLj!%Nd(tRitpqM&tY6M`UA8zT8Pt(c+sz|JMA+DFph^%F)G%Zhbirw(a!EUN zlXWcWGJr4ImvMXb-4s<~bX7h%ooahSMpWdV$)`wORZ9l2$$Q#PGQ_^bF2VNeqrt0X zzmOX$MfckLv4-BJr^jzM-v^%?ozqn{Nj-7ib<*q;LgASjQ?8uAU}a0|Lb7B_ zhwl&A3_5kL&=#nuti;gwvZSOQxSrvG;jQ#|LkzZ|(n6|(SdK1Q8ECKxLy$oRaXW(~ zN;Kwag{ez54~_w=Lsuf?=+WMbszN1HJdhm1q2{#?OHOQDoEv;w%;2;8omqI~qd@cQ z#fx)J4I4R?ZyuLR@}aT8oNYHXwPz@t5dw|!+4lurVa=&|F4iuUztr-dSOR%X_VI+LTHmjre(&Bu3=-p5tKZsO_L zM~CJFchD|dE2)Xdu$-E@z+osM;wkM@BpBgVC1}jW4Q3D5U!fBsV$AhQ_~ov;=4QA? zHlu2VE7IGXyB}<+YW(AYQ@BF0YPxHB`)rELjIzL6_qiE}Tuk4ghKz9k=3#y~?6%TJ z-kH-|z%=$dcj=0zhP@qq^?mPMzUrl6ze@fa{wnyq($UvOs0MJvhKi;JcDKe=jrRK0 zUzI^}6{}6KAtBMxx82lIjwR{bD={c)wG@sDJ0d;QCE5etFf!0UTHK8ol}-MG`fw{IF);Y-Xq%C!L?|n#hJVAJ+k(LX2sM#0nimKa% zfnx2D49CXCq8SuARrDvAt$R`=om&5VO{0+enKRkb$vy^*=3xQ-=k}-Ss?;+tprq6r zxV`e5f^M{I|A3R7iLyN#RZx~w%>1U(k#I9KjPASq7k|Jfv*M<;dSHx5+@_5iJ1`?n zLE!v_fkgTE#m=Kg7HSyD%gMcx$z)07aP-IlqSV;f_$`AE=f;{L8&+1Y00EcWz7Bde{Q9q$a?sr&&v(66`E?EBp7`!;oxhQlLV77d3} z?Tf4%LaBkIi1{guRf0bE66qpcO6=~Q#HDVA09AqEMlo)u{cxlb^dUrt=F99tYciYQd|FPpRtu2zGtmv*0n8L zy!83P&DSX`fiW?RTl6aHk^N00F{yiBq_+xa5KPh7|<3UCh9)8Kw6FoLbIXOe1PCNUt?Y#}oOQqfvX=-ks zgbU9Q92N;9&^>!9(N{t=@q)S2R24>CDj58u1^p)cj}=g*Nky*@MOEn4BVeq*G z;0$Kh+Dh7o{2px*%&t`D<2+GFK3NYnIriClq1VHr<&Qy>|A?G;uZQq|g+W(c*Pr(c zbejO9s-og0+b-G3{3TadS^2_Mn)e(~BB$8I$P+Y50~S6~Qjog`&>#q^PCXzK@luX= zs-LqbId2;H<{y?BfQK@1>f}zrMH8ngh?QbaE+J8RDy#vGbj>9n6&2#|mG#?Iy6gq+ zS=vnTi#M0`6`_4ZT3VWir|PJ%&!U%?eCF>a4^pFI^x=hasnb=K^(V(*L>cC^v21=) zYdr>Lf9L^tU<(KqPKG41Z98mk{(^RuT&K`h9!LN(q@zI%QS~AJNs~2p*!^4wpn6Y!`&V+GUqJJyib!>nCiH~}_hc)swoJPyS>#k4^p{-zdlC+-X^@7deBZqf`9C>8=BV`vX zxt)_Egl;V??V1{t14D4h)4KQhrmbdTrSopfte@_k??A#5Qmt}oH*Ftbq=cqF&@$a7 zEL``{t^+{A63oHGLWS0?i(6#%B%hO`*V=)XndO)JzNg@~1f#(@gsHHw&AS%}3kwrb z!K??ih=hAQx_XpkQj}h;u*w!{CFc~^8-ITNa+8B%1@iQyFR>b@u8Q=rMP=W;dlsT) zpcOSzU!M`~a>&lmV1rgln*zS03Xf{E7%$InNmAFl7dw9AL8uy`)`#hg8#t@d;c9-s zl)BXOXvlri@_A~6TxYB~xqxJ=!{h`CB)ZXIv82h%g$F*L(OYww*_t|tdsiZ@-8?WzaxD(MUf;qxBSmOdpdiQG zWlBm)4-XG`nCnBR-ttw&!_nRSXuFsZiL_K-Sz(v%-29}sJAe@KIeh{GGH>6uab7wY zdGGl1_1cSvZs{CKIYt%wWc9jryn^n~JiwTd_0@6HLP{x-Cm~svw|}+W)=Htf=C?{@ zH?!}0t6$OE;*5+zq(7jfV=xZSs)k>hfhsj4LtRzXD92RMD(g{8i&205&cXa8fOd$9 zcR@kdZ5HM~1(RQfbq!@ac(b^uC|<#%RnbqBh{H%k!+zt}pe%BgbZs@LCb_TVC%^TO zymr@>_&onib*_4ZtFS-j6W^EZ?J^P)PB7EL(`prLzt!)QFwegzAH#Trc@a#&cChTI z8yg$-r7YhTXg5FapJLIQHEKSc>WMZvuI=0Ph+NX|Ski5+IT;JM)|kJo*_)65JEoO3GY z?)@FPQzU)oL!}q+*Kkqv144dLJ(T+o86s~3X2%}X)#YGBJ;fc7$MpO(13_y-eo~a8 z$<))>Ff+yE_dB1Xaw1qpFDr;B0>i;|<4L)VyxfB(F^<;|Xp})pv}TJjSe7|-_(_9B z2&T6oO{l1r>eNV4hP%9SeAP>_4*5h9e_nU!x zQ&aPAVSie7b>;^Qn)@5#NLTqy$ku#zTq{)<=LT|%1d{0lR9^s?)|fjdc-3_3Wv{@aX9{I%ER%K?+u^7He-!tJH61_oV?d11hN+!?br5(?t)DEyl$>(hN^cuha>(3i5|nAHPdj)YVy{b_sD0X>94I zLDk$U?b^vxCio6P0Dhz^mn}Q1dx_^p-TrRP2L8mfw5Ow&5}Xt{rAA-vO=y5xVcW;= z`Q58+HL{$nqy020`YBv)KZH1$h@^z>y<;-`p{CZF z6gfEa^qrpQ=vaxAzIlzd}*R7QLA`5;6_BG5#8#ZhJb@%YW1Jr0ZNo2-5D8n_G z=F_%Eah*GGhJ}8N5 z6E`CeP~3U2)s%AN`ey$Aj7YRn!0&li>4GYK;yc9G{Uey^`90m6{|>657h78?Hg*%( zG&%bxzF)fz+^8oLaUFmD8c70s?qA;I>L=3t1N!S)`j#UHCgd*E;(xvL+Do7ghrELY zWPz~}gHFg_hq^oDY5)8W{=L2p`kJ4 UMLClass - 287 - 273 + 357 + 399 567 133 @@ -23,8 +23,8 @@ UMLGeneric - 0 - 525 + 70 + 651 259 70 @@ -39,8 +39,8 @@ PlanningContextLoaderPTP UMLGeneric - 448 - 525 + 518 + 651 259 70 @@ -55,8 +55,8 @@ PlanningContextLoaderLIN Relation - 119 - 350 + 189 + 476 182 189 @@ -66,8 +66,8 @@ PlanningContextLoaderLIN Relation - 567 - 399 + 637 + 525 21 140 @@ -77,8 +77,8 @@ PlanningContextLoaderLIN UMLGeneric - 35 - 756 + 105 + 882 133 35 @@ -90,8 +90,8 @@ PlanningContextLoaderLIN UMLGeneric - 511 - 749 + 581 + 875 126 35 @@ -103,8 +103,8 @@ PlanningContextLoaderLIN UMLClass - 1260 - 616 + 1330 + 742 119 126 @@ -117,8 +117,8 @@ PlanningContextBase Text - 21 - 609 + 91 + 735 175 14 @@ -128,8 +128,8 @@ PlanningContextBase Relation - 133 - 644 + 203 + 770 1141 126 @@ -139,8 +139,8 @@ PlanningContextBase Relation - 602 - 672 + 672 + 798 672 91 @@ -150,8 +150,8 @@ PlanningContextBase Text - 490 - 609 + 560 + 735 175 14 @@ -161,8 +161,8 @@ PlanningContextBase UMLGeneric - 511 - 1001 + 581 + 1127 126 35 @@ -174,8 +174,8 @@ PlanningContextBase Relation - 98 - 588 + 168 + 714 21 182 @@ -185,8 +185,8 @@ PlanningContextBase UMLGeneric - 35 - 1001 + 105 + 1127 126 35 @@ -198,8 +198,8 @@ PlanningContextBase UMLGeneric - 1176 - 861 + 1246 + 987 308 98 @@ -207,15 +207,15 @@ PlanningContextBase -- -- TrajectoryGenerator(RobotModelConstPtr, LimitsContainer) -generate(request, response, sampling_time) +generate(scene, request, response, sampling_time) Relation - 567 - 588 + 637 + 714 21 175 @@ -225,8 +225,8 @@ generate(request, response, sampling_time) Relation - 567 - 777 + 637 + 903 21 238 @@ -237,8 +237,8 @@ m1=1 Relation - 98 - 784 + 168 + 910 21 231 @@ -249,8 +249,8 @@ m1=1 Relation - 602 - 903 + 672 + 1029 588 112 @@ -260,8 +260,8 @@ m1=1 Relation - 126 - 875 + 196 + 1001 1064 140 @@ -271,8 +271,8 @@ m1=1 UMLNote - 0 - 441 + 70 + 567 98 49 @@ -283,8 +283,8 @@ m1=1 Relation - 42 - 483 + 112 + 609 21 56 @@ -294,8 +294,8 @@ m1=1 UMLClass - 1589 - 525 + 1659 + 651 147 112 @@ -309,8 +309,8 @@ m1=1 UMLClass - 1792 - 525 + 1862 + 651 147 112 @@ -330,8 +330,8 @@ m1=1 UMLClass - 1673 - 399 + 1743 + 525 196 91 @@ -349,8 +349,8 @@ m1=1 Relation - 1764 - 483 + 1834 + 609 126 56 @@ -361,8 +361,8 @@ m1=1 Relation - 1659 - 483 + 1729 + 609 70 56 @@ -373,8 +373,8 @@ m1=1 UMLClass - 168 - 1232 + 238 + 1358 126 42 @@ -388,8 +388,8 @@ m1=1 UMLClass - 28 - 1302 + 98 + 1428 147 63 @@ -407,8 +407,8 @@ m1=1 Relation - 126 - 1246 + 196 + 1372 56 70 @@ -418,8 +418,8 @@ m1=1 Relation - 91 - 1029 + 161 + 1155 21 287 @@ -430,8 +430,8 @@ m1=n UMLClass - 525 - 1316 + 595 + 1442 91 42 @@ -445,8 +445,8 @@ Path_Line UMLClass - 833 - 1316 + 903 + 1442 84 42 @@ -460,8 +460,8 @@ Path_Circle UMLClass - 980 - 1316 + 1050 + 1442 105 42 @@ -475,8 +475,8 @@ Path_Circle_Wrapper UMLNote - 1393 - 1176 + 1463 + 1302 98 49 @@ -487,8 +487,8 @@ bg=white Relation - 1330 - 1190 + 1400 + 1316 77 21 @@ -498,8 +498,8 @@ bg=white Relation - 560 - 1029 + 630 + 1155 21 301 @@ -509,8 +509,8 @@ bg=white UMLGeneric - 882 - 1001 + 952 + 1127 168 35 @@ -522,8 +522,8 @@ bg=white Relation - 1022 - 1029 + 1092 + 1155 21 301 @@ -533,8 +533,8 @@ bg=white Relation - 581 - 1197 + 651 + 1323 693 133 @@ -544,8 +544,8 @@ bg=white Relation - 889 - 1232 + 959 + 1358 385 98 @@ -555,8 +555,8 @@ bg=white Relation - 1050 - 1267 + 1120 + 1393 224 63 @@ -566,8 +566,8 @@ bg=white UMLGeneric - 896 - 742 + 966 + 868 126 35 @@ -579,8 +579,8 @@ bg=white Relation - 952 - 770 + 1022 + 896 21 245 @@ -591,8 +591,8 @@ m1=1 Relation - 987 - 700 + 1057 + 826 287 56 @@ -602,8 +602,8 @@ m1=1 UMLGeneric - 826 - 525 + 896 + 651 259 70 @@ -618,8 +618,8 @@ PlanningContextLoaderCIRC Relation - 952 - 588 + 1022 + 714 21 168 @@ -629,8 +629,8 @@ PlanningContextLoaderCIRC Text - 875 - 609 + 945 + 735 175 14 @@ -640,8 +640,8 @@ PlanningContextLoaderCIRC Relation - 987 - 931 + 1057 + 1057 203 84 @@ -651,8 +651,8 @@ PlanningContextLoaderCIRC Relation - 847 - 350 + 917 + 476 119 189 @@ -662,8 +662,8 @@ PlanningContextLoaderCIRC Relation - 91 - 469 + 161 + 595 434 70 @@ -673,8 +673,8 @@ PlanningContextLoaderCIRC Relation - 91 - 448 + 161 + 574 812 91 @@ -684,8 +684,8 @@ PlanningContextLoaderCIRC UMLClass - 287 - 126 + 357 + 252 567 63 @@ -702,8 +702,8 @@ moveit_msgs::MoveItErrorCodes& error_code):planning_interface::PlanningConte Relation - 567 - 182 + 637 + 308 21 105 @@ -714,8 +714,8 @@ m1=n UMLClass - 476 - 0 + 546 + 126 203 49 @@ -729,8 +729,8 @@ m1=n Relation - 567 - 42 + 637 + 168 21 98 @@ -740,8 +740,8 @@ m1=n UMLClass - 1211 - 518 + 1281 + 644 203 49 @@ -755,8 +755,8 @@ m1=n Relation - 1309 - 560 + 1379 + 686 21 77 @@ -766,8 +766,8 @@ m1=n Relation - 910 - 1330 + 980 + 1456 84 21 @@ -777,8 +777,8 @@ m1=n UMLClass - 308 - 1302 + 378 + 1428 147 63 @@ -796,8 +796,8 @@ VelocityProfile_Trap Relation - 420 - 1008 + 490 + 1134 476 308 @@ -807,8 +807,8 @@ VelocityProfile_Trap UMLClass - 770 - 1141 + 840 + 1267 126 42 @@ -822,8 +822,8 @@ Trajectory_Segment Relation - 889 - 1029 + 959 + 1155 63 147 @@ -833,8 +833,8 @@ Trajectory_Segment Relation - 287 - 1246 + 357 + 1372 63 70 @@ -844,8 +844,8 @@ Trajectory_Segment UMLClass - 784 - 1064 + 854 + 1190 98 35 @@ -859,8 +859,8 @@ Trajectory_Segment Relation - 826 - 1092 + 896 + 1218 21 63 @@ -870,8 +870,8 @@ Trajectory_Segment UMLClass - 1260 - 1183 + 1330 + 1309 77 112 @@ -884,8 +884,8 @@ Trajectory_Segment Relation - 588 - 1029 + 658 + 1155 196 147 @@ -895,8 +895,8 @@ Trajectory_Segment Relation - 357 - 1008 + 427 + 1134 168 308 diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/plan_components_builder.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/plan_components_builder.h index a89b3fbbd3..4c15153283 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/plan_components_builder.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/plan_components_builder.h @@ -39,6 +39,7 @@ #include #include +#include #include "pilz_industrial_motion_planner/trajectory_blend_request.h" #include "pilz_industrial_motion_planner/trajectory_blender.h" @@ -87,13 +88,16 @@ class PlanComponentsBuilder * appended/attached to the newly created empty trajectory: * - if the given and previous trajectory are from different groups. * + * @param planning_scene The scene planning is occurring in. + * * @param other Trajectories which has to be added to the trajectory container * under construction. * * @param blend_radius The blending radius between the previous and the * specified trajectory. */ - void append(const robot_trajectory::RobotTrajectoryPtr& other, const double blend_radius); + void append(const planning_scene::PlanningSceneConstPtr& planning_scene, + const robot_trajectory::RobotTrajectoryPtr& other, const double blend_radius); /** * @brief Clears the trajectory container under construction. @@ -106,7 +110,8 @@ class PlanComponentsBuilder std::vector build() const; private: - void blend(const robot_trajectory::RobotTrajectoryPtr& other, const double blend_radius); + void blend(const planning_scene::PlanningSceneConstPtr& planning_scene, + const robot_trajectory::RobotTrajectoryPtr& other, const double blend_radius); private: /** diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_base.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_base.h index 14143a0ed8..86fb36dbaf 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_base.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/planning_context_base.h @@ -128,7 +128,7 @@ bool pilz_industrial_motion_planner::PlanningContextBase::solve(plan moveit::core::robotStateToRobotStateMsg(getPlanningScene()->getCurrentState(), current_state); request_.start_state = current_state; } - bool result = generator_.generate(request_, res); + bool result = generator_.generate(getPlanningScene(), request_, res); return result; // res.error_code_.val = moveit_msgs::MoveItErrorCodes::INVALID_MOTION_PLAN; // return false; // TODO diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blender.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blender.h index ce647b5479..6c7667fe1d 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blender.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blender.h @@ -36,6 +36,7 @@ #include "pilz_industrial_motion_planner/limits_container.h" #include +#include #include "pilz_industrial_motion_planner/trajectory_blend_request.h" #include "pilz_industrial_motion_planner/trajectory_blend_response.h" @@ -58,11 +59,13 @@ class TrajectoryBlender /** * @brief Blend two robot trajectories with the given blending radius + * @param planning_scene: planning scene * @param req: trajectory blend request * @param res: trajectroy blend response * @return true if blend succeed */ - virtual bool blend(const pilz_industrial_motion_planner::TrajectoryBlendRequest& req, + virtual bool blend(const planning_scene::PlanningSceneConstPtr& planning_scene, + const pilz_industrial_motion_planner::TrajectoryBlendRequest& req, pilz_industrial_motion_planner::TrajectoryBlendResponse& res) = 0; protected: diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blender_transition_window.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blender_transition_window.h index 233bdd3e31..fd7608025b 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blender_transition_window.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_blender_transition_window.h @@ -34,6 +34,7 @@ #pragma once +#include #include "pilz_industrial_motion_planner/cartesian_trajectory.h" #include "pilz_industrial_motion_planner/cartesian_trajectory_point.h" #include "pilz_industrial_motion_planner/trajectory_blend_request.h" @@ -64,6 +65,7 @@ class TrajectoryBlenderTransitionWindow : public TrajectoryBlender * @brief Blend two trajectories using transition window. The trajectories * have to be equally and uniformly * discretized. + * @param planning_scene: The scene planning is occurring in. * @param req: following fields need to be filled for a valid request: * - group_name : name of the planning group * - link_name : name of the target link @@ -91,7 +93,8 @@ class TrajectoryBlenderTransitionWindow : public TrajectoryBlender * error_code: information of failed blend * @return true if succeed */ - bool blend(const pilz_industrial_motion_planner::TrajectoryBlendRequest& req, + bool blend(const planning_scene::PlanningSceneConstPtr& planning_scene, + const pilz_industrial_motion_planner::TrajectoryBlendRequest& req, pilz_industrial_motion_planner::TrajectoryBlendResponse& res) override; private: diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_functions.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_functions.h index cb600259b4..fc78cf994b 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_functions.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_functions.h @@ -41,6 +41,7 @@ #include #include #include +#include #include "pilz_industrial_motion_planner/cartesian_trajectory.h" #include "pilz_industrial_motion_planner/limits_container.h" @@ -50,6 +51,7 @@ namespace pilz_industrial_motion_planner /** * @brief compute the inverse kinematics of a given pose, also check robot self * collision + * @param scene: planning scene * @param robot_model: kinematic model of the robot * @param group_name: name of planning group * @param link_name: name of target link @@ -62,12 +64,12 @@ namespace pilz_industrial_motion_planner * @param timeout: timeout for IK, if not set the default solver timeout is used * @return true if succeed */ -bool computePoseIK(const robot_model::RobotModelConstPtr& robot_model, const std::string& group_name, +bool computePoseIK(const planning_scene::PlanningSceneConstPtr& scene, const std::string& group_name, const std::string& link_name, const Eigen::Isometry3d& pose, const std::string& frame_id, const std::map& seed, std::map& solution, bool check_self_collision = true, const double timeout = 0.0); -bool computePoseIK(const robot_model::RobotModelConstPtr& robot_model, const std::string& group_name, +bool computePoseIK(const planning_scene::PlanningSceneConstPtr& scene, const std::string& group_name, const std::string& link_name, const geometry_msgs::Pose& pose, const std::string& frame_id, const std::map& seed, std::map& solution, bool check_self_collision = true, const double timeout = 0.0); @@ -107,6 +109,7 @@ bool verifySampleJointLimits(const std::map& position_last, /** * @brief Generate joint trajectory from a KDL Cartesian trajectory + * @param scene: planning scene * @param robot_model: robot kinematics model * @param joint_limits: joint limits * @param trajectory: KDL Cartesian trajectory @@ -122,7 +125,7 @@ bool verifySampleJointLimits(const std::map& position_last, * @param check_self_collision: check for self collision during creation * @return true if succeed */ -bool generateJointTrajectory(const robot_model::RobotModelConstPtr& robot_model, +bool generateJointTrajectory(const planning_scene::PlanningSceneConstPtr& scene, const JointLimitsContainer& joint_limits, const KDL::Trajectory& trajectory, const std::string& group_name, const std::string& link_name, const std::map& initial_joint_position, const double& sampling_time, @@ -131,6 +134,7 @@ bool generateJointTrajectory(const robot_model::RobotModelConstPtr& robot_model, /** * @brief Generate joint trajectory from a MultiDOFJointTrajectory + * @param scene: planning scene * @param trajectory: Cartesian trajectory * @param info: motion plan information * @param sampling_time @@ -138,7 +142,7 @@ bool generateJointTrajectory(const robot_model::RobotModelConstPtr& robot_model, * @param error_code * @return true if succeed */ -bool generateJointTrajectory(const robot_model::RobotModelConstPtr& robot_model, +bool generateJointTrajectory(const planning_scene::PlanningSceneConstPtr& scene, const JointLimitsContainer& joint_limits, const pilz_industrial_motion_planner::CartesianTrajectory& trajectory, const std::string& group_name, const std::string& link_name, @@ -202,6 +206,7 @@ bool intersectionFound(const Eigen::Vector3d& p_center, const Eigen::Vector3d& p /** * @brief Checks if current robot state is in self collision. + * @param scene: planning scene. * @param test_for_self_collision Flag to deactivate this check during IK. * @param robot_model: robot kinematics model. * @param state Robot state instance used for . @@ -209,7 +214,7 @@ bool intersectionFound(const Eigen::Vector3d& p_center, const Eigen::Vector3d& p * @param ik_solution * @return */ -bool isStateColliding(const bool test_for_self_collision, const moveit::core::RobotModelConstPtr& robot_model, +bool isStateColliding(const bool test_for_self_collision, const planning_scene::PlanningSceneConstPtr& scene, robot_state::RobotState* state, const robot_state::JointModelGroup* const group, const double* const ik_solution); } // namespace pilz_industrial_motion_planner diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator.h index 09055fcb81..8637b73320 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator.h @@ -42,6 +42,7 @@ #include #include #include +#include #include "pilz_industrial_motion_planner/joint_limits_extension.h" #include "pilz_industrial_motion_planner/limits_container.h" @@ -103,10 +104,10 @@ class TrajectoryGenerator * @param res: motion plan response * @param sampling_time: sampling time of the generate trajectory * @return motion plan succeed/fail, detailed information in motion plan - * responce + * response */ - bool generate(const planning_interface::MotionPlanRequest& req, planning_interface::MotionPlanResponse& res, - double sampling_time = 0.1); + bool generate(const planning_scene::PlanningSceneConstPtr& scene, const planning_interface::MotionPlanRequest& req, + planning_interface::MotionPlanResponse& res, double sampling_time = 0.1); protected: /** @@ -144,13 +145,16 @@ class TrajectoryGenerator * @brief Extract needed information from a motion plan request in order to * simplify * further usages. + * @param scene: planning scene * @param req: motion plan request * @param info: information extracted from motion plan request which is * necessary for the planning */ - virtual void extractMotionPlanInfo(const planning_interface::MotionPlanRequest& req, MotionPlanInfo& info) const = 0; + virtual void extractMotionPlanInfo(const planning_scene::PlanningSceneConstPtr& scene, + const planning_interface::MotionPlanRequest& req, MotionPlanInfo& info) const = 0; - virtual void plan(const planning_interface::MotionPlanRequest& req, const MotionPlanInfo& plan_info, + virtual void plan(const planning_scene::PlanningSceneConstPtr& scene, + const planning_interface::MotionPlanRequest& req, const MotionPlanInfo& plan_info, const double& sampling_time, trajectory_msgs::JointTrajectory& joint_trajectory) = 0; private: diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_circ.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_circ.h index 080239a581..13dda37739 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_circ.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_circ.h @@ -37,6 +37,7 @@ #include #include #include +#include #include "pilz_industrial_motion_planner/trajectory_generator.h" @@ -83,10 +84,12 @@ class TrajectoryGeneratorCIRC : public TrajectoryGenerator private: void cmdSpecificRequestValidation(const planning_interface::MotionPlanRequest& req) const override; - void extractMotionPlanInfo(const planning_interface::MotionPlanRequest& req, MotionPlanInfo& info) const final; + void extractMotionPlanInfo(const planning_scene::PlanningSceneConstPtr& scene, + const planning_interface::MotionPlanRequest& req, MotionPlanInfo& info) const final; - void plan(const planning_interface::MotionPlanRequest& req, const MotionPlanInfo& plan_info, - const double& sampling_time, trajectory_msgs::JointTrajectory& joint_trajectory) override; + void plan(const planning_scene::PlanningSceneConstPtr& scene, const planning_interface::MotionPlanRequest& req, + const MotionPlanInfo& plan_info, const double& sampling_time, + trajectory_msgs::JointTrajectory& joint_trajectory) override; /** * @brief Construct a KDL::Path object for a Cartesian path of an arc. diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_lin.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_lin.h index 2d17768cad..269c9c0151 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_lin.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_lin.h @@ -36,6 +36,7 @@ #include #include +#include #include "pilz_industrial_motion_planner/trajectory_generator.h" #include "pilz_industrial_motion_planner/velocity_profile_atrap.h" @@ -70,10 +71,12 @@ class TrajectoryGeneratorLIN : public TrajectoryGenerator const pilz_industrial_motion_planner::LimitsContainer& planner_limits); private: - void extractMotionPlanInfo(const planning_interface::MotionPlanRequest& req, MotionPlanInfo& info) const final; + void extractMotionPlanInfo(const planning_scene::PlanningSceneConstPtr& scene, + const planning_interface::MotionPlanRequest& req, MotionPlanInfo& info) const final; - void plan(const planning_interface::MotionPlanRequest& req, const MotionPlanInfo& plan_info, - const double& sampling_time, trajectory_msgs::JointTrajectory& joint_trajectory) override; + void plan(const planning_scene::PlanningSceneConstPtr& scene, const planning_interface::MotionPlanRequest& req, + const MotionPlanInfo& plan_info, const double& sampling_time, + trajectory_msgs::JointTrajectory& joint_trajectory) override; /** * @brief construct a KDL::Path object for a Cartesian straight line diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_ptp.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_ptp.h index 09048557ba..2ec0097ffb 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_ptp.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator_ptp.h @@ -34,6 +34,8 @@ #pragma once +#include + #include "eigen3/Eigen/Eigen" #include "pilz_industrial_motion_planner/trajectory_generation_exceptions.h" #include "pilz_industrial_motion_planner/trajectory_generator.h" @@ -64,7 +66,8 @@ class TrajectoryGeneratorPTP : public TrajectoryGenerator const pilz_industrial_motion_planner::LimitsContainer& planner_limits); private: - void extractMotionPlanInfo(const planning_interface::MotionPlanRequest& req, MotionPlanInfo& info) const override; + void extractMotionPlanInfo(const planning_scene::PlanningSceneConstPtr& scene, + const planning_interface::MotionPlanRequest& req, MotionPlanInfo& info) const override; /** * @brief plan ptp joint trajectory with zero start velocity @@ -81,8 +84,9 @@ class TrajectoryGeneratorPTP : public TrajectoryGenerator const double& velocity_scaling_factor, const double& acceleration_scaling_factor, const double& sampling_time); - void plan(const planning_interface::MotionPlanRequest& req, const MotionPlanInfo& plan_info, - const double& sampling_time, trajectory_msgs::JointTrajectory& joint_trajectory) override; + void plan(const planning_scene::PlanningSceneConstPtr& scene, const planning_interface::MotionPlanRequest& req, + const MotionPlanInfo& plan_info, const double& sampling_time, + trajectory_msgs::JointTrajectory& joint_trajectory) override; private: const double MIN_MOVEMENT = 0.001; diff --git a/moveit_planners/pilz_industrial_motion_planner/src/command_list_manager.cpp b/moveit_planners/pilz_industrial_motion_planner/src/command_list_manager.cpp index 52941969d2..5a544b13a3 100644 --- a/moveit_planners/pilz_industrial_motion_planner/src/command_list_manager.cpp +++ b/moveit_planners/pilz_industrial_motion_planner/src/command_list_manager.cpp @@ -97,7 +97,7 @@ RobotTrajCont CommandListManager::solve(const planning_scene::PlanningSceneConst plan_comp_builder_.reset(); for (MotionResponseCont::size_type i = 0; i < resp_cont.size(); ++i) { - plan_comp_builder_.append(resp_cont.at(i).trajectory_, + plan_comp_builder_.append(planning_scene, resp_cont.at(i).trajectory_, // The blend radii has to be "attached" to // the second part of a blend trajectory, // therefore: "i-1". diff --git a/moveit_planners/pilz_industrial_motion_planner/src/plan_components_builder.cpp b/moveit_planners/pilz_industrial_motion_planner/src/plan_components_builder.cpp index 175a7deca9..fe078b2ef4 100644 --- a/moveit_planners/pilz_industrial_motion_planner/src/plan_components_builder.cpp +++ b/moveit_planners/pilz_industrial_motion_planner/src/plan_components_builder.cpp @@ -68,7 +68,8 @@ void PlanComponentsBuilder::appendWithStrictTimeIncrease(robot_trajectory::Robot } } -void PlanComponentsBuilder::blend(const robot_trajectory::RobotTrajectoryPtr& other, const double blend_radius) +void PlanComponentsBuilder::blend(const planning_scene::PlanningSceneConstPtr& planning_scene, + const robot_trajectory::RobotTrajectoryPtr& other, const double blend_radius) { if (!blender_) { @@ -86,7 +87,7 @@ void PlanComponentsBuilder::blend(const robot_trajectory::RobotTrajectoryPtr& ot blend_request.link_name = getSolverTipFrame(model_->getJointModelGroup(blend_request.group_name)); pilz_industrial_motion_planner::TrajectoryBlendResponse blend_response; - if (!blender_->blend(blend_request, blend_response)) + if (!blender_->blend(planning_scene, blend_request, blend_response)) { throw BlendingFailedException("Blending failed"); } @@ -98,7 +99,8 @@ void PlanComponentsBuilder::blend(const robot_trajectory::RobotTrajectoryPtr& ot traj_tail_ = blend_response.second_trajectory; // first for next blending segment } -void PlanComponentsBuilder::append(const robot_trajectory::RobotTrajectoryPtr& other, const double blend_radius) +void PlanComponentsBuilder::append(const planning_scene::PlanningSceneConstPtr& planning_scene, + const robot_trajectory::RobotTrajectoryPtr& other, const double blend_radius) { if (!model_) { @@ -131,7 +133,7 @@ void PlanComponentsBuilder::append(const robot_trajectory::RobotTrajectoryPtr& o return; } - blend(other, blend_radius); + blend(planning_scene, other, blend_radius); } } // namespace pilz_industrial_motion_planner diff --git a/moveit_planners/pilz_industrial_motion_planner/src/trajectory_blender_transition_window.cpp b/moveit_planners/pilz_industrial_motion_planner/src/trajectory_blender_transition_window.cpp index b5265f7a72..44b7c9b4ab 100644 --- a/moveit_planners/pilz_industrial_motion_planner/src/trajectory_blender_transition_window.cpp +++ b/moveit_planners/pilz_industrial_motion_planner/src/trajectory_blender_transition_window.cpp @@ -38,8 +38,10 @@ #include #include #include +#include bool pilz_industrial_motion_planner::TrajectoryBlenderTransitionWindow::blend( + const planning_scene::PlanningSceneConstPtr& planning_scene, const pilz_industrial_motion_planner::TrajectoryBlendRequest& req, pilz_industrial_motion_planner::TrajectoryBlendResponse& res) { @@ -86,10 +88,10 @@ bool pilz_industrial_motion_planner::TrajectoryBlenderTransitionWindow::blend( } trajectory_msgs::JointTrajectory blend_joint_trajectory; moveit_msgs::MoveItErrorCodes error_code; - if (!generateJointTrajectory(req.first_trajectory->getFirstWayPointPtr()->getRobotModel(), - limits_.getJointLimitContainer(), blend_trajectory_cartesian, req.group_name, - req.link_name, initial_joint_position, initial_joint_velocity, blend_joint_trajectory, - error_code, true)) + + if (!generateJointTrajectory(planning_scene, limits_.getJointLimitContainer(), blend_trajectory_cartesian, + req.group_name, req.link_name, initial_joint_position, initial_joint_velocity, + blend_joint_trajectory, error_code, true)) { // LCOV_EXCL_START ROS_INFO("Failed to generate joint trajectory for blending trajectory."); diff --git a/moveit_planners/pilz_industrial_motion_planner/src/trajectory_functions.cpp b/moveit_planners/pilz_industrial_motion_planner/src/trajectory_functions.cpp index 08491ac75f..3810fca709 100644 --- a/moveit_planners/pilz_industrial_motion_planner/src/trajectory_functions.cpp +++ b/moveit_planners/pilz_industrial_motion_planner/src/trajectory_functions.cpp @@ -40,13 +40,14 @@ #include #include -bool pilz_industrial_motion_planner::computePoseIK(const moveit::core::RobotModelConstPtr& robot_model, +bool pilz_industrial_motion_planner::computePoseIK(const planning_scene::PlanningSceneConstPtr& scene, const std::string& group_name, const std::string& link_name, const Eigen::Isometry3d& pose, const std::string& frame_id, const std::map& seed, std::map& solution, bool check_self_collision, const double timeout) { + const moveit::core::RobotModelConstPtr& robot_model = scene->getRobotModel(); if (!robot_model->hasJointModelGroup(group_name)) { ROS_ERROR_STREAM("Robot model has no planning group named as " << group_name); @@ -74,7 +75,7 @@ bool pilz_industrial_motion_planner::computePoseIK(const moveit::core::RobotMode moveit::core::GroupStateValidityCallbackFn ik_constraint_function; ik_constraint_function = - boost::bind(&pilz_industrial_motion_planner::isStateColliding, check_self_collision, robot_model, _1, _2, _3); + boost::bind(&pilz_industrial_motion_planner::isStateColliding, check_self_collision, scene, _1, _2, _3); // call ik if (rstate.setFromIK(robot_model->getJointModelGroup(group_name), pose, link_name, timeout, ik_constraint_function)) @@ -93,7 +94,7 @@ bool pilz_industrial_motion_planner::computePoseIK(const moveit::core::RobotMode } } -bool pilz_industrial_motion_planner::computePoseIK(const moveit::core::RobotModelConstPtr& robot_model, +bool pilz_industrial_motion_planner::computePoseIK(const planning_scene::PlanningSceneConstPtr& scene, const std::string& group_name, const std::string& link_name, const geometry_msgs::Pose& pose, const std::string& frame_id, const std::map& seed, @@ -102,7 +103,7 @@ bool pilz_industrial_motion_planner::computePoseIK(const moveit::core::RobotMode { Eigen::Isometry3d pose_eigen; tf2::fromMsg(pose, pose_eigen); - return computePoseIK(robot_model, group_name, link_name, pose_eigen, frame_id, seed, solution, check_self_collision, + return computePoseIK(scene, group_name, link_name, pose_eigen, frame_id, seed, solution, check_self_collision, timeout); } @@ -191,7 +192,7 @@ bool pilz_industrial_motion_planner::verifySampleJointLimits( } bool pilz_industrial_motion_planner::generateJointTrajectory( - const moveit::core::RobotModelConstPtr& robot_model, + const planning_scene::PlanningSceneConstPtr& scene, const pilz_industrial_motion_planner::JointLimitsContainer& joint_limits, const KDL::Trajectory& trajectory, const std::string& group_name, const std::string& link_name, const std::map& initial_joint_position, const double& sampling_time, @@ -200,6 +201,7 @@ bool pilz_industrial_motion_planner::generateJointTrajectory( { ROS_DEBUG("Generate joint trajectory from a Cartesian trajectory."); + const moveit::core::RobotModelConstPtr& robot_model = scene->getRobotModel(); ros::Time generation_begin = ros::Time::now(); // generate the time samples @@ -225,7 +227,7 @@ bool pilz_industrial_motion_planner::generateJointTrajectory( { tf2::fromMsg(tf2::toMsg(trajectory.Pos(*time_iter)), pose_sample); - if (!computePoseIK(robot_model, group_name, link_name, pose_sample, robot_model->getModelFrame(), ik_solution_last, + if (!computePoseIK(scene, group_name, link_name, pose_sample, robot_model->getModelFrame(), ik_solution_last, ik_solution, check_self_collision)) { ROS_ERROR("Failed to compute inverse kinematics solution for sampled " @@ -306,7 +308,7 @@ bool pilz_industrial_motion_planner::generateJointTrajectory( } bool pilz_industrial_motion_planner::generateJointTrajectory( - const moveit::core::RobotModelConstPtr& robot_model, + const planning_scene::PlanningSceneConstPtr& scene, const pilz_industrial_motion_planner::JointLimitsContainer& joint_limits, const pilz_industrial_motion_planner::CartesianTrajectory& trajectory, const std::string& group_name, const std::string& link_name, const std::map& initial_joint_position, @@ -315,6 +317,7 @@ bool pilz_industrial_motion_planner::generateJointTrajectory( { ROS_DEBUG("Generate joint trajectory from a Cartesian trajectory."); + const moveit::core::RobotModelConstPtr& robot_model = scene->getRobotModel(); ros::Time generation_begin = ros::Time::now(); std::map ik_solution_last = initial_joint_position; @@ -330,7 +333,7 @@ bool pilz_industrial_motion_planner::generateJointTrajectory( for (size_t i = 0; i < trajectory.points.size(); ++i) { // compute inverse kinematics - if (!computePoseIK(robot_model, group_name, link_name, trajectory.points.at(i).pose, robot_model->getModelFrame(), + if (!computePoseIK(scene, group_name, link_name, trajectory.points.at(i).pose, robot_model->getModelFrame(), ik_solution_last, ik_solution, check_self_collision)) { ROS_ERROR("Failed to compute inverse kinematics solution for sampled " @@ -556,7 +559,7 @@ bool pilz_industrial_motion_planner::intersectionFound(const Eigen::Vector3d& p_ } bool pilz_industrial_motion_planner::isStateColliding(const bool test_for_self_collision, - const moveit::core::RobotModelConstPtr& robot_model, + const planning_scene::PlanningSceneConstPtr& scene, robot_state::RobotState* rstate, const robot_state::JointModelGroup* const group, const double* const ik_solution) @@ -570,9 +573,9 @@ bool pilz_industrial_motion_planner::isStateColliding(const bool test_for_self_c rstate->update(); collision_detection::CollisionRequest collision_req; collision_req.group_name = group->getName(); + collision_req.verbose = true; collision_detection::CollisionResult collision_res; - planning_scene::PlanningScene(robot_model).checkSelfCollision(collision_req, collision_res, *rstate); - + scene->checkSelfCollision(collision_req, collision_res, *rstate); return !collision_res.collision; } diff --git a/moveit_planners/pilz_industrial_motion_planner/src/trajectory_generator.cpp b/moveit_planners/pilz_industrial_motion_planner/src/trajectory_generator.cpp index 2084f11e4c..8a1099b981 100644 --- a/moveit_planners/pilz_industrial_motion_planner/src/trajectory_generator.cpp +++ b/moveit_planners/pilz_industrial_motion_planner/src/trajectory_generator.cpp @@ -267,7 +267,8 @@ TrajectoryGenerator::cartesianTrapVelocityProfile(const double& max_velocity_sca return vp_trans; } -bool TrajectoryGenerator::generate(const planning_interface::MotionPlanRequest& req, +bool TrajectoryGenerator::generate(const planning_scene::PlanningSceneConstPtr& scene, + const planning_interface::MotionPlanRequest& req, planning_interface::MotionPlanResponse& res, double sampling_time) { ROS_INFO_STREAM("Generating " << req.planner_id << " trajectory..."); @@ -300,7 +301,7 @@ bool TrajectoryGenerator::generate(const planning_interface::MotionPlanRequest& MotionPlanInfo plan_info; try { - extractMotionPlanInfo(req, plan_info); + extractMotionPlanInfo(scene, req, plan_info); } catch (const MoveItErrorCodeException& ex) { @@ -313,7 +314,7 @@ bool TrajectoryGenerator::generate(const planning_interface::MotionPlanRequest& trajectory_msgs::JointTrajectory joint_trajectory; try { - plan(req, plan_info, sampling_time, joint_trajectory); + plan(scene, req, plan_info, sampling_time, joint_trajectory); } catch (const MoveItErrorCodeException& ex) { diff --git a/moveit_planners/pilz_industrial_motion_planner/src/trajectory_generator_circ.cpp b/moveit_planners/pilz_industrial_motion_planner/src/trajectory_generator_circ.cpp index 4bdc2a7ddf..f062677502 100644 --- a/moveit_planners/pilz_industrial_motion_planner/src/trajectory_generator_circ.cpp +++ b/moveit_planners/pilz_industrial_motion_planner/src/trajectory_generator_circ.cpp @@ -84,7 +84,8 @@ void TrajectoryGeneratorCIRC::cmdSpecificRequestValidation(const planning_interf } } -void TrajectoryGeneratorCIRC::extractMotionPlanInfo(const planning_interface::MotionPlanRequest& req, +void TrajectoryGeneratorCIRC::extractMotionPlanInfo(const planning_scene::PlanningSceneConstPtr& scene, + const planning_interface::MotionPlanRequest& req, TrajectoryGenerator::MotionPlanInfo& info) const { ROS_DEBUG("Extract necessary information from motion plan request."); @@ -167,7 +168,7 @@ void TrajectoryGeneratorCIRC::extractMotionPlanInfo(const planning_interface::Mo // check goal pose ik before Cartesian motion plan starts std::map ik_solution; - if (!computePoseIK(robot_model_, info.group_name, info.link_name, info.goal_pose, frame_id, info.start_joint_position, + if (!computePoseIK(scene, info.group_name, info.link_name, info.goal_pose, frame_id, info.start_joint_position, ik_solution)) { // LCOV_EXCL_START @@ -186,7 +187,8 @@ void TrajectoryGeneratorCIRC::extractMotionPlanInfo(const planning_interface::Mo info.circ_path_point.second = circ_path_point; } -void TrajectoryGeneratorCIRC::plan(const planning_interface::MotionPlanRequest& req, const MotionPlanInfo& plan_info, +void TrajectoryGeneratorCIRC::plan(const planning_scene::PlanningSceneConstPtr& scene, + const planning_interface::MotionPlanRequest& req, const MotionPlanInfo& plan_info, const double& sampling_time, trajectory_msgs::JointTrajectory& joint_trajectory) { std::unique_ptr cart_path(setPathCIRC(plan_info)); @@ -202,9 +204,9 @@ void TrajectoryGeneratorCIRC::plan(const planning_interface::MotionPlanRequest& moveit_msgs::MoveItErrorCodes error_code; // sample the Cartesian trajectory and compute joint trajectory using inverse // kinematics - if (!generateJointTrajectory(robot_model_, planner_limits_.getJointLimitContainer(), cart_trajectory, - plan_info.group_name, plan_info.link_name, plan_info.start_joint_position, sampling_time, - joint_trajectory, error_code)) + if (!generateJointTrajectory(scene, planner_limits_.getJointLimitContainer(), cart_trajectory, plan_info.group_name, + plan_info.link_name, plan_info.start_joint_position, sampling_time, joint_trajectory, + error_code)) { throw CircTrajectoryConversionFailure("Failed to generate valid joint trajectory from the Cartesian path", error_code.val); diff --git a/moveit_planners/pilz_industrial_motion_planner/src/trajectory_generator_lin.cpp b/moveit_planners/pilz_industrial_motion_planner/src/trajectory_generator_lin.cpp index 6efc6e41ba..40eadac63b 100644 --- a/moveit_planners/pilz_industrial_motion_planner/src/trajectory_generator_lin.cpp +++ b/moveit_planners/pilz_industrial_motion_planner/src/trajectory_generator_lin.cpp @@ -62,7 +62,8 @@ TrajectoryGeneratorLIN::TrajectoryGeneratorLIN(const moveit::core::RobotModelCon } } -void TrajectoryGeneratorLIN::extractMotionPlanInfo(const planning_interface::MotionPlanRequest& req, +void TrajectoryGeneratorLIN::extractMotionPlanInfo(const planning_scene::PlanningSceneConstPtr& scene, + const planning_interface::MotionPlanRequest& req, TrajectoryGenerator::MotionPlanInfo& info) const { ROS_DEBUG("Extract necessary information from motion plan request."); @@ -144,7 +145,7 @@ void TrajectoryGeneratorLIN::extractMotionPlanInfo(const planning_interface::Mot // check goal pose ik before Cartesian motion plan starts std::map ik_solution; - if (!computePoseIK(robot_model_, info.group_name, info.link_name, info.goal_pose, frame_id, info.start_joint_position, + if (!computePoseIK(scene, info.group_name, info.link_name, info.goal_pose, frame_id, info.start_joint_position, ik_solution)) { std::ostringstream os; @@ -153,7 +154,8 @@ void TrajectoryGeneratorLIN::extractMotionPlanInfo(const planning_interface::Mot } } -void TrajectoryGeneratorLIN::plan(const planning_interface::MotionPlanRequest& req, const MotionPlanInfo& plan_info, +void TrajectoryGeneratorLIN::plan(const planning_scene::PlanningSceneConstPtr& scene, + const planning_interface::MotionPlanRequest& req, const MotionPlanInfo& plan_info, const double& sampling_time, trajectory_msgs::JointTrajectory& joint_trajectory) { // create Cartesian path for lin @@ -172,9 +174,9 @@ void TrajectoryGeneratorLIN::plan(const planning_interface::MotionPlanRequest& r moveit_msgs::MoveItErrorCodes error_code; // sample the Cartesian trajectory and compute joint trajectory using inverse // kinematics - if (!generateJointTrajectory(robot_model_, planner_limits_.getJointLimitContainer(), cart_trajectory, - plan_info.group_name, plan_info.link_name, plan_info.start_joint_position, sampling_time, - joint_trajectory, error_code)) + if (!generateJointTrajectory(scene, planner_limits_.getJointLimitContainer(), cart_trajectory, plan_info.group_name, + plan_info.link_name, plan_info.start_joint_position, sampling_time, joint_trajectory, + error_code)) { std::ostringstream os; os << "Failed to generate valid joint trajectory from the Cartesian path"; diff --git a/moveit_planners/pilz_industrial_motion_planner/src/trajectory_generator_ptp.cpp b/moveit_planners/pilz_industrial_motion_planner/src/trajectory_generator_ptp.cpp index d2120a9f40..85216bcdd6 100644 --- a/moveit_planners/pilz_industrial_motion_planner/src/trajectory_generator_ptp.cpp +++ b/moveit_planners/pilz_industrial_motion_planner/src/trajectory_generator_ptp.cpp @@ -212,7 +212,8 @@ void TrajectoryGeneratorPTP::planPTP(const std::map& start_ 0.0); } -void TrajectoryGeneratorPTP::extractMotionPlanInfo(const planning_interface::MotionPlanRequest& req, +void TrajectoryGeneratorPTP::extractMotionPlanInfo(const planning_scene::PlanningSceneConstPtr& scene, + const planning_interface::MotionPlanRequest& req, MotionPlanInfo& info) const { info.group_name = req.group_name; @@ -248,7 +249,7 @@ void TrajectoryGeneratorPTP::extractMotionPlanInfo(const planning_interface::Mot Eigen::Isometry3d pose_eigen; normalizeQuaternion(pose.orientation); tf2::fromMsg(pose, pose_eigen); - if (!computePoseIK(robot_model_, req.group_name, req.goal_constraints.at(0).position_constraints.at(0).link_name, + if (!computePoseIK(scene, req.group_name, req.goal_constraints.at(0).position_constraints.at(0).link_name, pose_eigen, robot_model_->getModelFrame(), info.start_joint_position, info.goal_joint_position)) { throw PtpNoIkSolutionForGoalPose("No IK solution for goal pose"); @@ -256,7 +257,8 @@ void TrajectoryGeneratorPTP::extractMotionPlanInfo(const planning_interface::Mot } } -void TrajectoryGeneratorPTP::plan(const planning_interface::MotionPlanRequest& req, const MotionPlanInfo& plan_info, +void TrajectoryGeneratorPTP::plan(const planning_scene::PlanningSceneConstPtr& scene, + const planning_interface::MotionPlanRequest& req, const MotionPlanInfo& plan_info, const double& sampling_time, trajectory_msgs::JointTrajectory& joint_trajectory) { // plan the ptp trajectory diff --git a/moveit_planners/pilz_industrial_motion_planner/test/integrationtest_plan_components_builder.cpp b/moveit_planners/pilz_industrial_motion_planner/test/integrationtest_plan_components_builder.cpp index 43f0415771..fb86d128cb 100644 --- a/moveit_planners/pilz_industrial_motion_planner/test/integrationtest_plan_components_builder.cpp +++ b/moveit_planners/pilz_industrial_motion_planner/test/integrationtest_plan_components_builder.cpp @@ -60,6 +60,7 @@ class IntegrationTestPlanComponentBuilder : public testing::Test protected: ros::NodeHandle ph_{ "~" }; robot_model::RobotModelConstPtr robot_model_{ robot_model_loader::RobotModelLoader(ROBOT_DESCRIPTION_STR).getModel() }; + planning_scene::PlanningSceneConstPtr planning_scene_{ new planning_scene::PlanningScene(robot_model_) }; std::string planning_group_; }; @@ -103,7 +104,7 @@ TEST_F(IntegrationTestPlanComponentBuilder, TestModelSet) robot_trajectory::RobotTrajectoryPtr traj{ new robot_trajectory::RobotTrajectory(robot_model_, planning_group_) }; PlanComponentsBuilder builder; - EXPECT_THROW(builder.append(traj, 1.0), NoRobotModelSetException); + EXPECT_THROW(builder.append(planning_scene_, traj, 1.0), NoRobotModelSetException); } /** @@ -116,9 +117,9 @@ TEST_F(IntegrationTestPlanComponentBuilder, TestNoBlenderSet) PlanComponentsBuilder builder; builder.setModel(robot_model_); - builder.append(traj, 0.0); + builder.append(planning_scene_, traj, 0.0); - EXPECT_THROW(builder.append(traj, 1.0), NoBlenderSetException); + EXPECT_THROW(builder.append(planning_scene_, traj, 1.0), NoBlenderSetException); } int main(int argc, char** argv) diff --git a/moveit_planners/pilz_industrial_motion_planner/test/test_utils.cpp b/moveit_planners/pilz_industrial_motion_planner/test/test_utils.cpp index 0069c414f8..7aaa2ffe56 100644 --- a/moveit_planners/pilz_industrial_motion_planner/test/test_utils.cpp +++ b/moveit_planners/pilz_industrial_motion_planner/test/test_utils.cpp @@ -1034,12 +1034,14 @@ bool testutils::getBlendTestData(const ros::NodeHandle& nh, const size_t& datase } bool testutils::generateTrajFromBlendTestData( - const robot_model::RobotModelConstPtr& robot_model, + const planning_scene::PlanningSceneConstPtr& scene, const std::shared_ptr& tg, const std::string& group_name, const std::string& link_name, const testutils::BlendTestData& data, const double& sampling_time_1, const double& sampling_time_2, planning_interface::MotionPlanResponse& res_1, planning_interface::MotionPlanResponse& res_2, double& dis_1, double& dis_2) { + const robot_model::RobotModelConstPtr robot_model = scene->getRobotModel(); + // generate first trajectory planning_interface::MotionPlanRequest req_1; req_1.group_name = group_name; @@ -1058,7 +1060,7 @@ bool testutils::generateTrajFromBlendTestData( goal_state_1, goal_state_1.getRobotModel()->getJointModelGroup(group_name))); // trajectory generation - if (!tg->generate(req_1, res_1, sampling_time_1)) + if (!tg->generate(scene, req_1, res_1, sampling_time_1)) { std::cout << "Failed to generate first trajectory." << std::endl; return false; @@ -1078,7 +1080,7 @@ bool testutils::generateTrajFromBlendTestData( req_2.goal_constraints.push_back(kinematic_constraints::constructGoalConstraints( goal_state_2, goal_state_2.getRobotModel()->getJointModelGroup(group_name))); // trajectory generation - if (!tg->generate(req_2, res_2, sampling_time_2)) + if (!tg->generate(scene, req_2, res_2, sampling_time_2)) { std::cout << "Failed to generate second trajectory." << std::endl; return false; diff --git a/moveit_planners/pilz_industrial_motion_planner/test/test_utils.h b/moveit_planners/pilz_industrial_motion_planner/test/test_utils.h index 982cb7850c..dd5d06e6b9 100644 --- a/moveit_planners/pilz_industrial_motion_planner/test/test_utils.h +++ b/moveit_planners/pilz_industrial_motion_planner/test/test_utils.h @@ -430,7 +430,7 @@ bool checkBlendResult(const pilz_industrial_motion_planner::TrajectoryBlendReque * @param[out] dis_lin_2: translational distance of the second LIN * @return true if succeed */ -bool generateTrajFromBlendTestData(const moveit::core::RobotModelConstPtr& robot_model, +bool generateTrajFromBlendTestData(const planning_scene::PlanningSceneConstPtr& scene, const std::shared_ptr& tg, const std::string& group_name, const std::string& link_name, const BlendTestData& data, const double& sampling_time_1, diff --git a/moveit_planners/pilz_industrial_motion_planner/test/unittest_trajectory_blender_transition_window.cpp b/moveit_planners/pilz_industrial_motion_planner/test/unittest_trajectory_blender_transition_window.cpp index 2a0627ae93..4c97843b9f 100644 --- a/moveit_planners/pilz_industrial_motion_planner/test/unittest_trajectory_blender_transition_window.cpp +++ b/moveit_planners/pilz_industrial_motion_planner/test/unittest_trajectory_blender_transition_window.cpp @@ -90,6 +90,7 @@ class TrajectoryBlenderTransitionWindowTest : public testing::TestWithParam lin_generator_; std::unique_ptr blender_; @@ -158,7 +159,7 @@ TrajectoryBlenderTransitionWindowTest::generateLinTrajs(const Sequence& seq, siz } // generate trajectory planning_interface::MotionPlanResponse resp; - if (!lin_generator_->generate(req, resp, sampling_time_)) + if (!lin_generator_->generate(planning_scene_, req, resp, sampling_time_)) { std::runtime_error("Failed to generate trajectory."); } @@ -197,7 +198,7 @@ TEST_P(TrajectoryBlenderTransitionWindowTest, testInvalidGroupName) blend_req.second_trajectory = res.at(1).trajectory_; blend_req.blend_radius = seq.getBlendRadius(0); - EXPECT_FALSE(blender_->blend(blend_req, blend_res)); + EXPECT_FALSE(blender_->blend(planning_scene_, blend_req, blend_res)); } /** @@ -226,7 +227,7 @@ TEST_P(TrajectoryBlenderTransitionWindowTest, testInvalidTargetLink) blend_req.second_trajectory = res.at(1).trajectory_; blend_req.blend_radius = seq.getBlendRadius(0); - EXPECT_FALSE(blender_->blend(blend_req, blend_res)); + EXPECT_FALSE(blender_->blend(planning_scene_, blend_req, blend_res)); } /** @@ -256,7 +257,7 @@ TEST_P(TrajectoryBlenderTransitionWindowTest, testNegativeRadius) blend_req.second_trajectory = res.at(1).trajectory_; blend_req.blend_radius = -0.1; - EXPECT_FALSE(blender_->blend(blend_req, blend_res)); + EXPECT_FALSE(blender_->blend(planning_scene_, blend_req, blend_res)); } /** @@ -285,7 +286,7 @@ TEST_P(TrajectoryBlenderTransitionWindowTest, testZeroRadius) blend_req.second_trajectory = res.at(1).trajectory_; blend_req.blend_radius = 0.; - EXPECT_FALSE(blender_->blend(blend_req, blend_res)); + EXPECT_FALSE(blender_->blend(planning_scene_, blend_req, blend_res)); } /** @@ -320,7 +321,7 @@ TEST_P(TrajectoryBlenderTransitionWindowTest, testDifferentSamplingTimes) } // generate trajectory planning_interface::MotionPlanResponse resp; - if (!lin_generator_->generate(req, resp, sampling_time_)) + if (!lin_generator_->generate(planning_scene_, req, resp, sampling_time_)) { std::runtime_error("Failed to generate trajectory."); } @@ -335,7 +336,7 @@ TEST_P(TrajectoryBlenderTransitionWindowTest, testDifferentSamplingTimes) blend_req.first_trajectory = responses[0].trajectory_; blend_req.second_trajectory = responses[1].trajectory_; blend_req.blend_radius = seq.getBlendRadius(0); - EXPECT_FALSE(blender_->blend(blend_req, blend_res)); + EXPECT_FALSE(blender_->blend(planning_scene_, blend_req, blend_res)); } /** @@ -370,7 +371,7 @@ TEST_P(TrajectoryBlenderTransitionWindowTest, testNonUniformSamplingTime) blend_req.first_trajectory = res.at(0).trajectory_; blend_req.second_trajectory = res.at(1).trajectory_; blend_req.blend_radius = seq.getBlendRadius(0); - EXPECT_FALSE(blender_->blend(blend_req, blend_res)); + EXPECT_FALSE(blender_->blend(planning_scene_, blend_req, blend_res)); } /** @@ -402,7 +403,7 @@ TEST_P(TrajectoryBlenderTransitionWindowTest, testNotIntersectingTrajectories) // intersect blend_req.second_trajectory = res.at(0).trajectory_; blend_req.blend_radius = seq.getBlendRadius(0); - EXPECT_FALSE(blender_->blend(blend_req, blend_res)); + EXPECT_FALSE(blender_->blend(planning_scene_, blend_req, blend_res)); } /** @@ -438,7 +439,7 @@ TEST_P(TrajectoryBlenderTransitionWindowTest, testNonStationaryPoint) blend_req.first_trajectory->getLastWayPointPtr()->setVariableVelocity(0, 1.0); blend_req.second_trajectory->getFirstWayPointPtr()->setVariableVelocity(0, 1.0); - EXPECT_FALSE(blender_->blend(blend_req, blend_res)); + EXPECT_FALSE(blender_->blend(planning_scene_, blend_req, blend_res)); } /** @@ -475,7 +476,7 @@ TEST_P(TrajectoryBlenderTransitionWindowTest, testTraj1InsideBlendRadius) blend_req.first_trajectory = res.at(0).trajectory_; blend_req.second_trajectory = res.at(1).trajectory_; - EXPECT_FALSE(blender_->blend(blend_req, blend_res)); + EXPECT_FALSE(blender_->blend(planning_scene_, blend_req, blend_res)); } /** @@ -507,7 +508,7 @@ TEST_P(TrajectoryBlenderTransitionWindowTest, testTraj2InsideBlendRadius) blend_req.first_trajectory = res.at(0).trajectory_; blend_req.second_trajectory = res.at(1).trajectory_; - EXPECT_FALSE(blender_->blend(blend_req, blend_res)); + EXPECT_FALSE(blender_->blend(planning_scene_, blend_req, blend_res)); } /** @@ -544,7 +545,7 @@ TEST_P(TrajectoryBlenderTransitionWindowTest, testLinLinBlending) blend_req.first_trajectory = res.at(0).trajectory_; blend_req.second_trajectory = res.at(1).trajectory_; - EXPECT_TRUE(blender_->blend(blend_req, blend_res)); + EXPECT_TRUE(blender_->blend(planning_scene_, blend_req, blend_res)); EXPECT_TRUE(testutils::checkBlendResult(blend_req, blend_res, planner_limits_, joint_velocity_tolerance_, joint_acceleration_tolerance_, cartesian_velocity_tolerance_, @@ -587,7 +588,7 @@ TEST_P(TrajectoryBlenderTransitionWindowTest, testOverlappingBlendTrajectories) blend_req.first_trajectory = res.at(0).trajectory_; blend_req.second_trajectory = res.at(1).trajectory_; blend_req.blend_radius = seq.getBlendRadius(0); - EXPECT_TRUE(blender_->blend(blend_req, blend_res)); + EXPECT_TRUE(blender_->blend(planning_scene_, blend_req, blend_res)); EXPECT_TRUE(testutils::checkBlendResult(blend_req, blend_res, planner_limits_, joint_velocity_tolerance_, joint_acceleration_tolerance_, cartesian_velocity_tolerance_, @@ -682,7 +683,7 @@ TEST_P(TrajectoryBlenderTransitionWindowTest, testNonLinearBlending) } moveit_msgs::MoveItErrorCodes error_code; - if (!generateJointTrajectory(robot_model_, planner_limits_.getJointLimitContainer(), cart_traj, planning_group_, + if (!generateJointTrajectory(planning_scene_, planner_limits_.getJointLimitContainer(), cart_traj, planning_group_, target_link_, initial_joint_position, initial_joint_velocity, joint_traj, error_code, true)) { @@ -708,7 +709,7 @@ TEST_P(TrajectoryBlenderTransitionWindowTest, testNonLinearBlending) blend_req.first_trajectory = sine_trajs.at(0); blend_req.second_trajectory = sine_trajs.at(1); - EXPECT_TRUE(blender_->blend(blend_req, blend_res)); + EXPECT_TRUE(blender_->blend(planning_scene_, blend_req, blend_res)); EXPECT_TRUE(testutils::checkBlendResult(blend_req, blend_res, planner_limits_, joint_velocity_tolerance_, joint_acceleration_tolerance_, cartesian_velocity_tolerance_, diff --git a/moveit_planners/pilz_industrial_motion_planner/test/unittest_trajectory_functions.cpp b/moveit_planners/pilz_industrial_motion_planner/test/unittest_trajectory_functions.cpp index 655c34bce6..4d4eb79ec3 100644 --- a/moveit_planners/pilz_industrial_motion_planner/test/unittest_trajectory_functions.cpp +++ b/moveit_planners/pilz_industrial_motion_planner/test/unittest_trajectory_functions.cpp @@ -105,6 +105,7 @@ class TrajectoryFunctionsTestBase : public testing::TestWithParam // ros stuff ros::NodeHandle ph_{ "~" }; robot_model::RobotModelConstPtr robot_model_{ robot_model_loader::RobotModelLoader(GetParam()).getModel() }; + planning_scene::PlanningSceneConstPtr planning_scene_{ new planning_scene::PlanningScene(robot_model_) }; // test parameters from parameter server std::string planning_group_, group_tip_link_, tcp_link_, ik_fast_link_; @@ -351,7 +352,7 @@ TEST_P(TrajectoryFunctionsTestFlangeAndGripper, testComputePoseIK) // compute the ik std::map ik_actual; - EXPECT_TRUE(pilz_industrial_motion_planner::computePoseIK(robot_model_, planning_group_, tcp_link_, pose_expect, + EXPECT_TRUE(pilz_industrial_motion_planner::computePoseIK(planning_scene_, planning_group_, tcp_link_, pose_expect, frame_id, ik_seed, ik_actual, false)); // compare ik solution and expected value @@ -376,8 +377,8 @@ TEST_P(TrajectoryFunctionsTestFlangeAndGripper, testComputePoseIKInvalidGroupNam // compute the ik std::map ik_actual; - EXPECT_FALSE(pilz_industrial_motion_planner::computePoseIK(robot_model_, "InvalidGroupName", tcp_link_, pose_expect, - frame_id, ik_seed, ik_actual, false)); + EXPECT_FALSE(pilz_industrial_motion_planner::computePoseIK(planning_scene_, "InvalidGroupName", tcp_link_, + pose_expect, frame_id, ik_seed, ik_actual, false)); } /** @@ -392,7 +393,7 @@ TEST_P(TrajectoryFunctionsTestFlangeAndGripper, testComputePoseIKInvalidLinkName // compute the ik std::map ik_actual; - EXPECT_FALSE(pilz_industrial_motion_planner::computePoseIK(robot_model_, planning_group_, "WrongLink", pose_expect, + EXPECT_FALSE(pilz_industrial_motion_planner::computePoseIK(planning_scene_, planning_group_, "WrongLink", pose_expect, frame_id, ik_seed, ik_actual, false)); } @@ -409,7 +410,7 @@ TEST_P(TrajectoryFunctionsTestFlangeAndGripper, testComputePoseIKInvalidFrameId) // compute the ik std::map ik_actual; - EXPECT_FALSE(pilz_industrial_motion_planner::computePoseIK(robot_model_, planning_group_, tcp_link_, pose_expect, + EXPECT_FALSE(pilz_industrial_motion_planner::computePoseIK(planning_scene_, planning_group_, tcp_link_, pose_expect, "InvalidFrameId", ik_seed, ik_actual, false)); } @@ -447,7 +448,7 @@ TEST_P(TrajectoryFunctionsTestOnlyGripper, testComputePoseIKSelfCollisionForVali // compute the ik without self collision check and expect the resulting pose // to be in self collission. std::map ik_actual1; - EXPECT_TRUE(pilz_industrial_motion_planner::computePoseIK(robot_model_, planning_group_, tcp_link_, pose_expect, + EXPECT_TRUE(pilz_industrial_motion_planner::computePoseIK(planning_scene_, planning_group_, tcp_link_, pose_expect, frame_id, ik_seed, ik_actual1, false)); robot_state::RobotState rstate(robot_model_); @@ -471,7 +472,7 @@ TEST_P(TrajectoryFunctionsTestOnlyGripper, testComputePoseIKSelfCollisionForVali // compute the ik with collision detection activated and expect the resulting // pose to be without self collision. std::map ik_actual2; - EXPECT_TRUE(pilz_industrial_motion_planner::computePoseIK(robot_model_, planning_group_, tcp_link_, pose_expect, + EXPECT_TRUE(pilz_industrial_motion_planner::computePoseIK(planning_scene_, planning_group_, tcp_link_, pose_expect, frame_id, ik_seed, ik_actual2, true)); std::vector ik_state2; @@ -514,11 +515,11 @@ TEST_P(TrajectoryFunctionsTestFlangeAndGripper, testComputePoseIKSelfCollisionFo // compute the ik with disabled collision check std::map ik_actual; - EXPECT_TRUE(pilz_industrial_motion_planner::computePoseIK(robot_model_, planning_group_, tcp_link_, pose_expect, + EXPECT_TRUE(pilz_industrial_motion_planner::computePoseIK(planning_scene_, planning_group_, tcp_link_, pose_expect, frame_id, ik_seed, ik_actual, false)); // compute the ik with enabled collision check - EXPECT_FALSE(pilz_industrial_motion_planner::computePoseIK(robot_model_, planning_group_, tcp_link_, pose_expect, + EXPECT_FALSE(pilz_industrial_motion_planner::computePoseIK(planning_scene_, planning_group_, tcp_link_, pose_expect, frame_id, ik_seed, ik_actual, true)); } @@ -699,7 +700,7 @@ TEST_P(TrajectoryFunctionsTestFlangeAndGripper, testGenerateJointTrajectoryWithI bool check_self_collision{ false }; EXPECT_FALSE(pilz_industrial_motion_planner::generateJointTrajectory( - robot_model_, joint_limits, kdl_trajectory, group_name, tcp_link_, initial_joint_position, sampling_time, + planning_scene_, joint_limits, kdl_trajectory, group_name, tcp_link_, initial_joint_position, sampling_time, joint_trajectory, error_code, check_self_collision)); std::map initial_joint_velocity; @@ -711,7 +712,7 @@ TEST_P(TrajectoryFunctionsTestFlangeAndGripper, testGenerateJointTrajectoryWithI cart_traj.points.push_back(cart_traj_point); EXPECT_FALSE(pilz_industrial_motion_planner::generateJointTrajectory( - robot_model_, joint_limits, cart_traj, group_name, tcp_link_, initial_joint_position, initial_joint_velocity, + planning_scene_, joint_limits, cart_traj, group_name, tcp_link_, initial_joint_position, initial_joint_velocity, joint_trajectory, error_code, check_self_collision)); } diff --git a/moveit_planners/pilz_industrial_motion_planner/test/unittest_trajectory_generator_circ.cpp b/moveit_planners/pilz_industrial_motion_planner/test/unittest_trajectory_generator_circ.cpp index 540c40b6d0..5b0924c270 100644 --- a/moveit_planners/pilz_industrial_motion_planner/test/unittest_trajectory_generator_circ.cpp +++ b/moveit_planners/pilz_industrial_motion_planner/test/unittest_trajectory_generator_circ.cpp @@ -91,6 +91,7 @@ class TrajectoryGeneratorCIRCTest : public testing::TestWithParam // ros stuff ros::NodeHandle ph_{ "~" }; robot_model::RobotModelConstPtr robot_model_{ robot_model_loader::RobotModelLoader(GetParam()).getModel() }; + planning_scene::PlanningSceneConstPtr planning_scene_{ new planning_scene::PlanningScene(robot_model_) }; std::unique_ptr circ_; // test data provider std::unique_ptr tdp_; @@ -300,7 +301,7 @@ TEST_P(TrajectoryGeneratorCIRCTest, incompleteStartState) req.start_state.joint_state.position.resize(1); // prevent failing check for equal sizes planning_interface::MotionPlanResponse res; - EXPECT_FALSE(circ_->generate(req, res)); + EXPECT_FALSE(circ_->generate(planning_scene_, req, res)); EXPECT_EQ(res.error_code_.val, moveit_msgs::MoveItErrorCodes::INVALID_ROBOT_STATE); } @@ -314,7 +315,7 @@ TEST_P(TrajectoryGeneratorCIRCTest, nonZeroStartVelocity) // start state has non-zero velocity req.start_state.joint_state.velocity.push_back(1.0); planning_interface::MotionPlanResponse res; - EXPECT_FALSE(circ_->generate(req, res)); + EXPECT_FALSE(circ_->generate(planning_scene_, req, res)); EXPECT_EQ(res.error_code_.val, moveit_msgs::MoveItErrorCodes::INVALID_ROBOT_STATE); req.start_state.joint_state.velocity.clear(); } @@ -324,7 +325,7 @@ TEST_P(TrajectoryGeneratorCIRCTest, ValidCommand) auto circ{ tdp_->getCircCartCenterCart("circ1_center_2") }; planning_interface::MotionPlanResponse res; - EXPECT_TRUE(circ_->generate(circ.toRequest(), res)); + EXPECT_TRUE(circ_->generate(planning_scene_, circ.toRequest(), res)); EXPECT_EQ(res.error_code_.val, moveit_msgs::MoveItErrorCodes::SUCCESS); } @@ -337,7 +338,7 @@ TEST_P(TrajectoryGeneratorCIRCTest, velScaleToHigh) circ.setVelocityScale(1.0); planning_interface::MotionPlanResponse res; - EXPECT_FALSE(circ_->generate(circ.toRequest(), res)); + EXPECT_FALSE(circ_->generate(planning_scene_, circ.toRequest(), res)); EXPECT_EQ(res.error_code_.val, moveit_msgs::MoveItErrorCodes::PLANNING_FAILED); } @@ -350,7 +351,7 @@ TEST_P(TrajectoryGeneratorCIRCTest, accScaleToHigh) circ.setAccelerationScale(1.0); planning_interface::MotionPlanResponse res; - EXPECT_FALSE(circ_->generate(circ.toRequest(), res)); + EXPECT_FALSE(circ_->generate(planning_scene_, circ.toRequest(), res)); EXPECT_EQ(res.error_code_.val, moveit_msgs::MoveItErrorCodes::PLANNING_FAILED); } @@ -372,7 +373,7 @@ TEST_P(TrajectoryGeneratorCIRCTest, samePointsWithCenter) circ.getGoalConfiguration().getPose().position.z -= 1e-8; planning_interface::MotionPlanResponse res; - EXPECT_FALSE(circ_->generate(circ.toRequest(), res)); + EXPECT_FALSE(circ_->generate(planning_scene_, circ.toRequest(), res)); EXPECT_EQ(res.error_code_.val, moveit_msgs::MoveItErrorCodes::INVALID_MOTION_PLAN); } @@ -395,7 +396,7 @@ TEST_P(TrajectoryGeneratorCIRCTest, samePointsWithInterim) circ.getGoalConfiguration().getPose().position.z -= 1e-8; planning_interface::MotionPlanResponse res; - EXPECT_FALSE(circ_->generate(circ.toRequest(), res)); + EXPECT_FALSE(circ_->generate(planning_scene_, circ.toRequest(), res)); EXPECT_EQ(res.error_code_.val, moveit_msgs::MoveItErrorCodes::INVALID_MOTION_PLAN); } @@ -411,7 +412,7 @@ TEST_P(TrajectoryGeneratorCIRCTest, emptyAux) req.path_constraints.position_constraints.clear(); planning_interface::MotionPlanResponse res; - EXPECT_FALSE(circ_->generate(req, res)); + EXPECT_FALSE(circ_->generate(planning_scene_, req, res)); EXPECT_EQ(res.error_code_.val, moveit_msgs::MoveItErrorCodes::INVALID_MOTION_PLAN); } @@ -427,7 +428,7 @@ TEST_P(TrajectoryGeneratorCIRCTest, invalidAuxName) req.path_constraints.name = ""; planning_interface::MotionPlanResponse res; - EXPECT_FALSE(circ_->generate(req, res)); + EXPECT_FALSE(circ_->generate(planning_scene_, req, res)); EXPECT_EQ(res.error_code_.val, moveit_msgs::MoveItErrorCodes::INVALID_MOTION_PLAN); } @@ -444,7 +445,7 @@ TEST_P(TrajectoryGeneratorCIRCTest, invalidAuxLinkName) req.path_constraints.position_constraints.front().link_name = "INVALID"; planning_interface::MotionPlanResponse res; - EXPECT_FALSE(circ_->generate(req, res)); + EXPECT_FALSE(circ_->generate(planning_scene_, req, res)); EXPECT_EQ(res.error_code_.val, moveit_msgs::MoveItErrorCodes::INVALID_LINK_NAME); } @@ -458,7 +459,7 @@ TEST_P(TrajectoryGeneratorCIRCTest, invalidCenter) circ.getAuxiliaryConfiguration().getConfiguration().getPose().position.y += 1; planning_interface::MotionPlanResponse res; - EXPECT_FALSE(circ_->generate(circ.toRequest(), res)); + EXPECT_FALSE(circ_->generate(planning_scene_, circ.toRequest(), res)); EXPECT_EQ(res.error_code_.val, moveit_msgs::MoveItErrorCodes::INVALID_MOTION_PLAN); } @@ -478,7 +479,7 @@ TEST_P(TrajectoryGeneratorCIRCTest, colinearCenter) circ.getGoalConfiguration().getPose().position.x += 0.1; planning_interface::MotionPlanResponse res; - EXPECT_FALSE(circ_->generate(circ.toRequest(), res)); + EXPECT_FALSE(circ_->generate(planning_scene_, circ.toRequest(), res)); EXPECT_EQ(res.error_code_.val, moveit_msgs::MoveItErrorCodes::INVALID_MOTION_PLAN); } @@ -499,7 +500,7 @@ TEST_P(TrajectoryGeneratorCIRCTest, colinearInterim) circ.getGoalConfiguration().getPose().position.x += 0.1; planning_interface::MotionPlanResponse res; - EXPECT_FALSE(circ_->generate(circ.toRequest(), res)); + EXPECT_FALSE(circ_->generate(planning_scene_, circ.toRequest(), res)); EXPECT_EQ(res.error_code_.val, moveit_msgs::MoveItErrorCodes::INVALID_MOTION_PLAN); } @@ -517,7 +518,7 @@ TEST_P(TrajectoryGeneratorCIRCTest, colinearCenterDueToInterim) auto circ{ tdp_->getCircCartInterimCart("circ3_interim") }; planning_interface::MotionPlanResponse res; - ASSERT_TRUE(circ_->generate(circ.toRequest(), res)); + ASSERT_TRUE(circ_->generate(planning_scene_, circ.toRequest(), res)); EXPECT_EQ(res.error_code_.val, moveit_msgs::MoveItErrorCodes::SUCCESS); } @@ -550,7 +551,7 @@ TEST_P(TrajectoryGeneratorCIRCTest, colinearCenterAndInterim) moveit_msgs::MotionPlanRequest req = circ.toRequest(); planning_interface::MotionPlanResponse res; - EXPECT_TRUE(circ_->generate(req, res)); + EXPECT_TRUE(circ_->generate(planning_scene_, req, res)); EXPECT_EQ(res.error_code_.val, moveit_msgs::MoveItErrorCodes::SUCCESS); checkCircResult(req, res); } @@ -584,7 +585,7 @@ TEST_P(TrajectoryGeneratorCIRCTest, interimLarger180Degree) moveit_msgs::MotionPlanRequest req = circ.toRequest(); planning_interface::MotionPlanResponse res; - EXPECT_TRUE(circ_->generate(req, res)); + EXPECT_TRUE(circ_->generate(planning_scene_, req, res)); EXPECT_EQ(res.error_code_.val, moveit_msgs::MoveItErrorCodes::SUCCESS); checkCircResult(req, res); } @@ -600,7 +601,7 @@ TEST_P(TrajectoryGeneratorCIRCTest, centerPointJointGoal) moveit_msgs::MotionPlanRequest req = circ.toRequest(); planning_interface::MotionPlanResponse res; - ASSERT_TRUE(circ_->generate(req, res)); + ASSERT_TRUE(circ_->generate(planning_scene_, req, res)); EXPECT_EQ(res.error_code_.val, moveit_msgs::MoveItErrorCodes::SUCCESS); checkCircResult(req, res); } @@ -627,7 +628,7 @@ TEST_P(TrajectoryGeneratorCIRCTest, InvalidAdditionalPrimitivePose) req.path_constraints.position_constraints.back().constraint_region.primitive_poses.push_back(center_position); planning_interface::MotionPlanResponse res; - ASSERT_FALSE(circ_->generate(req, res)); + ASSERT_FALSE(circ_->generate(planning_scene_, req, res)); EXPECT_EQ(res.error_code_.val, moveit_msgs::MoveItErrorCodes::INVALID_MOTION_PLAN); } @@ -649,7 +650,7 @@ TEST_P(TrajectoryGeneratorCIRCTest, InvalidExtraJointConstraint) req.goal_constraints.front().joint_constraints.push_back(joint_constraint); //<-- Additional constraint planning_interface::MotionPlanResponse res; - EXPECT_FALSE(circ_->generate(req, res)); + EXPECT_FALSE(circ_->generate(planning_scene_, req, res)); EXPECT_EQ(res.error_code_.val, moveit_msgs::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS); } @@ -663,7 +664,7 @@ TEST_P(TrajectoryGeneratorCIRCTest, CenterPointPoseGoal) moveit_msgs::MotionPlanRequest req = circ.toRequest(); planning_interface::MotionPlanResponse res; - ASSERT_TRUE(circ_->generate(req, res)); + ASSERT_TRUE(circ_->generate(planning_scene_, req, res)); EXPECT_EQ(res.error_code_.val, moveit_msgs::MoveItErrorCodes::SUCCESS); checkCircResult(req, res); } @@ -680,7 +681,7 @@ TEST_P(TrajectoryGeneratorCIRCTest, CenterPointPoseGoalFrameIdPositionConstraint req.goal_constraints.front().position_constraints.front().header.frame_id = robot_model_->getModelFrame(); planning_interface::MotionPlanResponse res; - ASSERT_TRUE(circ_->generate(req, res)); + ASSERT_TRUE(circ_->generate(planning_scene_, req, res)); EXPECT_EQ(res.error_code_.val, moveit_msgs::MoveItErrorCodes::SUCCESS); checkCircResult(req, res); } @@ -696,7 +697,7 @@ TEST_P(TrajectoryGeneratorCIRCTest, CenterPointPoseGoalFrameIdOrientationConstra req.goal_constraints.front().orientation_constraints.front().header.frame_id = robot_model_->getModelFrame(); planning_interface::MotionPlanResponse res; - ASSERT_TRUE(circ_->generate(req, res)); + ASSERT_TRUE(circ_->generate(planning_scene_, req, res)); EXPECT_EQ(res.error_code_.val, moveit_msgs::MoveItErrorCodes::SUCCESS); checkCircResult(req, res); } @@ -715,7 +716,7 @@ TEST_P(TrajectoryGeneratorCIRCTest, CenterPointPoseGoalFrameIdBothConstraints) req.goal_constraints.front().orientation_constraints.front().header.frame_id = robot_model_->getModelFrame(); planning_interface::MotionPlanResponse res; - ASSERT_TRUE(circ_->generate(req, res)); + ASSERT_TRUE(circ_->generate(planning_scene_, req, res)); EXPECT_EQ(res.error_code_.val, moveit_msgs::MoveItErrorCodes::SUCCESS); checkCircResult(req, res); } @@ -732,7 +733,7 @@ TEST_P(TrajectoryGeneratorCIRCTest, InterimPointJointGoal) moveit_msgs::MotionPlanRequest req = circ.toRequest(); planning_interface::MotionPlanResponse res; - ASSERT_TRUE(circ_->generate(req, res)); + ASSERT_TRUE(circ_->generate(planning_scene_, req, res)); EXPECT_EQ(res.error_code_.val, moveit_msgs::MoveItErrorCodes::SUCCESS); checkCircResult(req, res); } @@ -755,7 +756,7 @@ TEST_P(TrajectoryGeneratorCIRCTest, InterimPointJointGoalStartVelNearZero) req.start_state.joint_state.velocity = std::vector(req.start_state.joint_state.position.size(), 1e-16); planning_interface::MotionPlanResponse res; - ASSERT_TRUE(circ_->generate(req, res)); + ASSERT_TRUE(circ_->generate(planning_scene_, req, res)); EXPECT_EQ(res.error_code_.val, moveit_msgs::MoveItErrorCodes::SUCCESS); checkCircResult(req, res); } @@ -769,7 +770,7 @@ TEST_P(TrajectoryGeneratorCIRCTest, InterimPointPoseGoal) moveit_msgs::MotionPlanRequest req = circ.toRequest(); planning_interface::MotionPlanResponse res; - ASSERT_TRUE(circ_->generate(req, res)); + ASSERT_TRUE(circ_->generate(planning_scene_, req, res)); EXPECT_EQ(res.error_code_.val, moveit_msgs::MoveItErrorCodes::SUCCESS); checkCircResult(req, res); } diff --git a/moveit_planners/pilz_industrial_motion_planner/test/unittest_trajectory_generator_common.cpp b/moveit_planners/pilz_industrial_motion_planner/test/unittest_trajectory_generator_common.cpp index aaba86c0f1..7a50c654f6 100644 --- a/moveit_planners/pilz_industrial_motion_planner/test/unittest_trajectory_generator_common.cpp +++ b/moveit_planners/pilz_industrial_motion_planner/test/unittest_trajectory_generator_common.cpp @@ -147,6 +147,7 @@ class TrajectoryGeneratorCommonTest : public ::testing::Test robot_model_loader::RobotModelLoader(!T::VALUE ? PARAM_MODEL_NO_GRIPPER_NAME : PARAM_MODEL_WITH_GRIPPER_NAME) .getModel() }; + planning_scene::PlanningSceneConstPtr planning_scene_{ new planning_scene::PlanningScene(robot_model_) }; // trajectory generator std::unique_ptr trajectory_generator_; @@ -177,22 +178,22 @@ TYPED_TEST_SUITE(TrajectoryGeneratorCommonTestWithGripper, TrajectoryGeneratorCo TYPED_TEST(TrajectoryGeneratorCommonTest, InvalideScalingFactor) { this->req_.max_velocity_scaling_factor = 2.0; - EXPECT_FALSE(this->trajectory_generator_->generate(this->req_, this->res_)); + EXPECT_FALSE(this->trajectory_generator_->generate(this->planning_scene_, this->req_, this->res_)); EXPECT_EQ(this->res_.error_code_.val, moveit_msgs::MoveItErrorCodes::INVALID_MOTION_PLAN); this->req_.max_velocity_scaling_factor = 1.0; this->req_.max_acceleration_scaling_factor = 0; - EXPECT_FALSE(this->trajectory_generator_->generate(this->req_, this->res_)); + EXPECT_FALSE(this->trajectory_generator_->generate(this->planning_scene_, this->req_, this->res_)); EXPECT_EQ(this->res_.error_code_.val, moveit_msgs::MoveItErrorCodes::INVALID_MOTION_PLAN); this->req_.max_velocity_scaling_factor = 0.00001; this->req_.max_acceleration_scaling_factor = 1; - EXPECT_FALSE(this->trajectory_generator_->generate(this->req_, this->res_)); + EXPECT_FALSE(this->trajectory_generator_->generate(this->planning_scene_, this->req_, this->res_)); EXPECT_EQ(this->res_.error_code_.val, moveit_msgs::MoveItErrorCodes::INVALID_MOTION_PLAN); this->req_.max_velocity_scaling_factor = 1; this->req_.max_acceleration_scaling_factor = -1; - EXPECT_FALSE(this->trajectory_generator_->generate(this->req_, this->res_)); + EXPECT_FALSE(this->trajectory_generator_->generate(this->planning_scene_, this->req_, this->res_)); EXPECT_EQ(this->res_.error_code_.val, moveit_msgs::MoveItErrorCodes::INVALID_MOTION_PLAN); } @@ -202,7 +203,7 @@ TYPED_TEST(TrajectoryGeneratorCommonTest, InvalideScalingFactor) TYPED_TEST(TrajectoryGeneratorCommonTest, InvalidGroupName) { this->req_.group_name = "foot"; - EXPECT_FALSE(this->trajectory_generator_->generate(this->req_, this->res_)); + EXPECT_FALSE(this->trajectory_generator_->generate(this->planning_scene_, this->req_, this->res_)); EXPECT_EQ(moveit_msgs::MoveItErrorCodes::INVALID_GROUP_NAME, this->res_.error_code_.val); } @@ -212,7 +213,7 @@ TYPED_TEST(TrajectoryGeneratorCommonTest, InvalidGroupName) TYPED_TEST(TrajectoryGeneratorCommonTestNoGripper, GripperGroup) { this->req_.group_name = "gripper"; - EXPECT_FALSE(this->trajectory_generator_->generate(this->req_, this->res_)); + EXPECT_FALSE(this->trajectory_generator_->generate(this->planning_scene_, this->req_, this->res_)); EXPECT_EQ(moveit_msgs::MoveItErrorCodes::INVALID_GROUP_NAME, this->res_.error_code_.val); } @@ -222,7 +223,7 @@ TYPED_TEST(TrajectoryGeneratorCommonTestNoGripper, GripperGroup) TYPED_TEST(TrajectoryGeneratorCommonTestWithGripper, GripperGroup) { this->req_.group_name = "gripper"; - EXPECT_FALSE(this->trajectory_generator_->generate(this->req_, this->res_)); + EXPECT_FALSE(this->trajectory_generator_->generate(this->planning_scene_, this->req_, this->res_)); EXPECT_EQ(moveit_msgs::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS, this->res_.error_code_.val); } @@ -247,7 +248,7 @@ TYPED_TEST(TrajectoryGeneratorCommonTestWithGripper, GripperGroup) TYPED_TEST(TrajectoryGeneratorCommonTest, EmptyJointNamesInStartState) { this->req_.start_state.joint_state.name.clear(); - EXPECT_FALSE(this->trajectory_generator_->generate(this->req_, this->res_)); + EXPECT_FALSE(this->trajectory_generator_->generate(this->planning_scene_, this->req_, this->res_)); EXPECT_EQ(this->res_.error_code_.val, moveit_msgs::MoveItErrorCodes::INVALID_ROBOT_STATE); } @@ -257,7 +258,7 @@ TYPED_TEST(TrajectoryGeneratorCommonTest, EmptyJointNamesInStartState) TYPED_TEST(TrajectoryGeneratorCommonTest, InconsistentStartState) { this->req_.start_state.joint_state.name.push_back("joint_7"); - EXPECT_FALSE(this->trajectory_generator_->generate(this->req_, this->res_)); + EXPECT_FALSE(this->trajectory_generator_->generate(this->planning_scene_, this->req_, this->res_)); EXPECT_EQ(this->res_.error_code_.val, moveit_msgs::MoveItErrorCodes::INVALID_ROBOT_STATE); } @@ -267,7 +268,7 @@ TYPED_TEST(TrajectoryGeneratorCommonTest, InconsistentStartState) TYPED_TEST(TrajectoryGeneratorCommonTest, StartPostionOutOfLimit) { this->req_.start_state.joint_state.position[0] = 100; - EXPECT_FALSE(this->trajectory_generator_->generate(this->req_, this->res_)); + EXPECT_FALSE(this->trajectory_generator_->generate(this->planning_scene_, this->req_, this->res_)); EXPECT_EQ(this->res_.error_code_.val, moveit_msgs::MoveItErrorCodes::INVALID_ROBOT_STATE); } @@ -281,7 +282,7 @@ TYPED_TEST(TrajectoryGeneratorCommonTest, StartPostionOutOfLimit) TYPED_TEST(TrajectoryGeneratorCommonTest, StartPositionVelocityNoneZero) { this->req_.start_state.joint_state.velocity[0] = 100; - EXPECT_FALSE(this->trajectory_generator_->generate(this->req_, this->res_)); + EXPECT_FALSE(this->trajectory_generator_->generate(this->planning_scene_, this->req_, this->res_)); EXPECT_EQ(this->res_.error_code_.val, moveit_msgs::MoveItErrorCodes::INVALID_ROBOT_STATE); } @@ -291,7 +292,7 @@ TYPED_TEST(TrajectoryGeneratorCommonTest, StartPositionVelocityNoneZero) TYPED_TEST(TrajectoryGeneratorCommonTest, EmptyGoalConstraints) { this->req_.goal_constraints.clear(); - EXPECT_FALSE(this->trajectory_generator_->generate(this->req_, this->res_)); + EXPECT_FALSE(this->trajectory_generator_->generate(this->planning_scene_, this->req_, this->res_)); EXPECT_EQ(this->res_.error_code_.val, moveit_msgs::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS); } @@ -308,7 +309,7 @@ TYPED_TEST(TrajectoryGeneratorCommonTest, MultipleGoals) // two goal constraints this->req_.goal_constraints.push_back(goal_constraint); this->req_.goal_constraints.push_back(goal_constraint); - EXPECT_FALSE(this->trajectory_generator_->generate(this->req_, this->res_)); + EXPECT_FALSE(this->trajectory_generator_->generate(this->planning_scene_, this->req_, this->res_)); EXPECT_EQ(this->res_.error_code_.val, moveit_msgs::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS); // one joint constraint and one orientation constraint @@ -316,7 +317,7 @@ TYPED_TEST(TrajectoryGeneratorCommonTest, MultipleGoals) goal_constraint.orientation_constraints.push_back(orientation_constraint); this->req_.goal_constraints.clear(); this->req_.goal_constraints.push_back(goal_constraint); - EXPECT_FALSE(this->trajectory_generator_->generate(this->req_, this->res_)); + EXPECT_FALSE(this->trajectory_generator_->generate(this->planning_scene_, this->req_, this->res_)); EXPECT_EQ(this->res_.error_code_.val, moveit_msgs::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS); // one joint constraint and one Cartesian constraint @@ -324,7 +325,7 @@ TYPED_TEST(TrajectoryGeneratorCommonTest, MultipleGoals) goal_constraint.orientation_constraints.push_back(orientation_constraint); this->req_.goal_constraints.clear(); this->req_.goal_constraints.push_back(goal_constraint); - EXPECT_FALSE(this->trajectory_generator_->generate(this->req_, this->res_)); + EXPECT_FALSE(this->trajectory_generator_->generate(this->planning_scene_, this->req_, this->res_)); EXPECT_EQ(this->res_.error_code_.val, moveit_msgs::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS); // two Cartesian constraints @@ -335,7 +336,7 @@ TYPED_TEST(TrajectoryGeneratorCommonTest, MultipleGoals) goal_constraint.orientation_constraints.push_back(orientation_constraint); this->req_.goal_constraints.clear(); this->req_.goal_constraints.push_back(goal_constraint); - EXPECT_FALSE(this->trajectory_generator_->generate(this->req_, this->res_)); + EXPECT_FALSE(this->trajectory_generator_->generate(this->planning_scene_, this->req_, this->res_)); EXPECT_EQ(this->res_.error_code_.val, moveit_msgs::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS); } @@ -347,7 +348,7 @@ TYPED_TEST(TrajectoryGeneratorCommonTest, InvalideJointNameInGoal) moveit_msgs::JointConstraint joint_constraint; joint_constraint.joint_name = "test_joint_2"; this->req_.goal_constraints.front().joint_constraints[0] = joint_constraint; - EXPECT_FALSE(this->trajectory_generator_->generate(this->req_, this->res_)); + EXPECT_FALSE(this->trajectory_generator_->generate(this->planning_scene_, this->req_, this->res_)); EXPECT_EQ(this->res_.error_code_.val, moveit_msgs::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS); } @@ -359,7 +360,7 @@ TYPED_TEST(TrajectoryGeneratorCommonTest, MissingJointConstraint) moveit_msgs::JointConstraint joint_constraint; joint_constraint.joint_name = "test_joint_2"; this->req_.goal_constraints.front().joint_constraints.pop_back(); //<-- Missing joint constraint - EXPECT_FALSE(this->trajectory_generator_->generate(this->req_, this->res_)); + EXPECT_FALSE(this->trajectory_generator_->generate(this->planning_scene_, this->req_, this->res_)); EXPECT_EQ(this->res_.error_code_.val, moveit_msgs::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS); } @@ -369,7 +370,7 @@ TYPED_TEST(TrajectoryGeneratorCommonTest, MissingJointConstraint) TYPED_TEST(TrajectoryGeneratorCommonTest, InvalideJointPositionInGoal) { this->req_.goal_constraints.front().joint_constraints[0].position = 100; - EXPECT_FALSE(this->trajectory_generator_->generate(this->req_, this->res_)); + EXPECT_FALSE(this->trajectory_generator_->generate(this->planning_scene_, this->req_, this->res_)); EXPECT_EQ(this->res_.error_code_.val, moveit_msgs::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS); } @@ -386,7 +387,7 @@ TYPED_TEST(TrajectoryGeneratorCommonTest, InvalidLinkNameInCartesianGoal) goal_constraint.orientation_constraints.push_back(orientation_constraint); this->req_.goal_constraints.clear(); this->req_.goal_constraints.push_back(goal_constraint); - EXPECT_FALSE(this->trajectory_generator_->generate(this->req_, this->res_)); + EXPECT_FALSE(this->trajectory_generator_->generate(this->planning_scene_, this->req_, this->res_)); EXPECT_EQ(this->res_.error_code_.val, moveit_msgs::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS); // different link names in position and orientation goals @@ -394,14 +395,14 @@ TYPED_TEST(TrajectoryGeneratorCommonTest, InvalidLinkNameInCartesianGoal) goal_constraint.orientation_constraints.front().link_name = "test_link_2"; this->req_.goal_constraints.clear(); this->req_.goal_constraints.push_back(goal_constraint); - EXPECT_FALSE(this->trajectory_generator_->generate(this->req_, this->res_)); + EXPECT_FALSE(this->trajectory_generator_->generate(this->planning_scene_, this->req_, this->res_)); EXPECT_EQ(this->res_.error_code_.val, moveit_msgs::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS); // no solver for the link goal_constraint.orientation_constraints.front().link_name = "test_link_1"; this->req_.goal_constraints.clear(); this->req_.goal_constraints.push_back(goal_constraint); - EXPECT_FALSE(this->trajectory_generator_->generate(this->req_, this->res_)); + EXPECT_FALSE(this->trajectory_generator_->generate(this->planning_scene_, this->req_, this->res_)); EXPECT_EQ(this->res_.error_code_.val, moveit_msgs::MoveItErrorCodes::NO_IK_SOLUTION); } @@ -421,7 +422,7 @@ TYPED_TEST(TrajectoryGeneratorCommonTest, EmptyPrimitivePoses) goal_constraint.orientation_constraints.push_back(orientation_constraint); this->req_.goal_constraints.clear(); this->req_.goal_constraints.push_back(goal_constraint); - EXPECT_FALSE(this->trajectory_generator_->generate(this->req_, this->res_)); + EXPECT_FALSE(this->trajectory_generator_->generate(this->planning_scene_, this->req_, this->res_)); EXPECT_EQ(this->res_.error_code_.val, moveit_msgs::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS); } diff --git a/moveit_planners/pilz_industrial_motion_planner/test/unittest_trajectory_generator_lin.cpp b/moveit_planners/pilz_industrial_motion_planner/test/unittest_trajectory_generator_lin.cpp index cfdaffee0c..4b8edf69a6 100644 --- a/moveit_planners/pilz_industrial_motion_planner/test/unittest_trajectory_generator_lin.cpp +++ b/moveit_planners/pilz_industrial_motion_planner/test/unittest_trajectory_generator_lin.cpp @@ -91,6 +91,7 @@ class TrajectoryGeneratorLINTest : public testing::TestWithParam // ros stuff ros::NodeHandle ph_{ "~" }; robot_model::RobotModelConstPtr robot_model_{ robot_model_loader::RobotModelLoader(GetParam()).getModel() }; + planning_scene::PlanningSceneConstPtr planning_scene_{ new planning_scene::PlanningScene(robot_model_) }; // lin trajectory generator using model without gripper std::unique_ptr lin_; @@ -213,7 +214,7 @@ TEST_P(TrajectoryGeneratorLINTest, nonZeroStartVelocity) // try to generate the result planning_interface::MotionPlanResponse res; - EXPECT_FALSE(lin_->generate(req, res)); + EXPECT_FALSE(lin_->generate(planning_scene_, req, res)); EXPECT_EQ(res.error_code_.val, moveit_msgs::MoveItErrorCodes::INVALID_ROBOT_STATE); } @@ -226,7 +227,7 @@ TEST_P(TrajectoryGeneratorLINTest, jointSpaceGoal) // generate the LIN trajectory planning_interface::MotionPlanResponse res; - ASSERT_TRUE(lin_->generate(lin_joint_req, res)); + ASSERT_TRUE(lin_->generate(planning_scene_, lin_joint_req, res)); EXPECT_TRUE(res.error_code_.val == moveit_msgs::MoveItErrorCodes::SUCCESS); // check the resulted trajectory @@ -247,7 +248,7 @@ TEST_P(TrajectoryGeneratorLINTest, jointSpaceGoalNearZeroStartVelocity) // generate the LIN trajectory planning_interface::MotionPlanResponse res; - ASSERT_TRUE(lin_->generate(lin_joint_req, res)); + ASSERT_TRUE(lin_->generate(planning_scene_, lin_joint_req, res)); EXPECT_TRUE(res.error_code_.val == moveit_msgs::MoveItErrorCodes::SUCCESS); // check the resulted trajectory @@ -264,7 +265,7 @@ TEST_P(TrajectoryGeneratorLINTest, cartesianSpaceGoal) // generate lin trajectory planning_interface::MotionPlanResponse res; - ASSERT_TRUE(lin_->generate(lin_cart_req, res)); + ASSERT_TRUE(lin_->generate(planning_scene_, lin_cart_req, res)); EXPECT_TRUE(res.error_code_.val == moveit_msgs::MoveItErrorCodes::SUCCESS); // check the resulted trajectory @@ -288,7 +289,7 @@ TEST_P(TrajectoryGeneratorLINTest, cartesianTrapezoidProfile) /// + plan LIN trajectory + /// +++++++++++++++++++++++ planning_interface::MotionPlanResponse res; - ASSERT_TRUE(lin_->generate(lin_joint_req, res, 0.01)); + ASSERT_TRUE(lin_->generate(planning_scene_, lin_joint_req, res, 0.01)); EXPECT_EQ(res.error_code_.val, moveit_msgs::MoveItErrorCodes::SUCCESS); ASSERT_TRUE(testutils::checkCartesianTranslationalPath(res.trajectory_, target_link_hcd_)); @@ -320,7 +321,7 @@ TEST_P(TrajectoryGeneratorLINTest, LinPlannerLimitViolation) lin.setAccelerationScale(1.01); planning_interface::MotionPlanResponse res; - ASSERT_FALSE(lin_->generate(lin.toRequest(), res)); + ASSERT_FALSE(lin_->generate(planning_scene_, lin.toRequest(), res)); } /** @@ -346,7 +347,7 @@ TEST_P(TrajectoryGeneratorLINTest, LinPlannerDiscontinuousJointTraj) lin.setAccelerationScale(1.0); planning_interface::MotionPlanResponse res; - ASSERT_FALSE(lin_->generate(lin.toRequest(), res)); + ASSERT_FALSE(lin_->generate(planning_scene_, lin.toRequest(), res)); } /** @@ -373,7 +374,7 @@ TEST_P(TrajectoryGeneratorLINTest, LinStartEqualsGoal) // generate the LIN trajectory planning_interface::MotionPlanResponse res; - ASSERT_TRUE(lin_->generate(lin_joint_req, res)); + ASSERT_TRUE(lin_->generate(planning_scene_, lin_joint_req, res)); EXPECT_TRUE(res.error_code_.val == moveit_msgs::MoveItErrorCodes::SUCCESS); // check the resulted trajectory @@ -417,7 +418,7 @@ TEST_P(TrajectoryGeneratorLINTest, IncorrectJointNumber) // generate the LIN trajectory planning_interface::MotionPlanResponse res; - ASSERT_FALSE(lin_->generate(lin_joint_req, res)); + ASSERT_FALSE(lin_->generate(planning_scene_, lin_joint_req, res)); EXPECT_TRUE(res.error_code_.val == moveit_msgs::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS); } @@ -435,7 +436,7 @@ TEST_P(TrajectoryGeneratorLINTest, cartGoalIncompleteStartState) // generate lin trajectory planning_interface::MotionPlanResponse res; - EXPECT_FALSE(lin_->generate(lin_cart_req, res)); + EXPECT_FALSE(lin_->generate(planning_scene_, lin_cart_req, res)); EXPECT_EQ(res.error_code_.val, moveit_msgs::MoveItErrorCodes::INVALID_ROBOT_STATE); } @@ -453,7 +454,7 @@ TEST_P(TrajectoryGeneratorLINTest, cartGoalFrameIdBothConstraints) // generate lin trajectory planning_interface::MotionPlanResponse res; - ASSERT_TRUE(lin_->generate(lin_cart_req, res)); + ASSERT_TRUE(lin_->generate(planning_scene_, lin_cart_req, res)); EXPECT_TRUE(res.error_code_.val == moveit_msgs::MoveItErrorCodes::SUCCESS); // check the resulted trajectory diff --git a/moveit_planners/pilz_industrial_motion_planner/test/unittest_trajectory_generator_ptp.cpp b/moveit_planners/pilz_industrial_motion_planner/test/unittest_trajectory_generator_ptp.cpp index 92af183fac..80a16e7577 100644 --- a/moveit_planners/pilz_industrial_motion_planner/test/unittest_trajectory_generator_ptp.cpp +++ b/moveit_planners/pilz_industrial_motion_planner/test/unittest_trajectory_generator_ptp.cpp @@ -82,6 +82,7 @@ class TrajectoryGeneratorPTPTest : public testing::TestWithParam // ros stuff ros::NodeHandle ph_{ "~" }; robot_model::RobotModelConstPtr robot_model_{ robot_model_loader::RobotModelLoader(GetParam()).getModel() }; + planning_scene::PlanningSceneConstPtr planning_scene_{ new planning_scene::PlanningScene(robot_model_) }; // trajectory generator std::unique_ptr ptp_; @@ -194,7 +195,7 @@ TEST_P(TrajectoryGeneratorPTPTest, emptyRequest) EXPECT_FALSE(res.trajectory_->empty()); - EXPECT_FALSE(ptp_->generate(req, res)); + EXPECT_FALSE(ptp_->generate(planning_scene_, req, res)); EXPECT_TRUE(res.trajectory_->empty()); } @@ -359,7 +360,7 @@ TEST_P(TrajectoryGeneratorPTPTest, testCartesianGoal) //**************************************** //*** test robot model without gripper *** //**************************************** - ASSERT_TRUE(ptp_->generate(req, res)); + ASSERT_TRUE(ptp_->generate(planning_scene_, req, res)); EXPECT_EQ(res.error_code_.val, moveit_msgs::MoveItErrorCodes::SUCCESS); moveit_msgs::MotionPlanResponse res_msg; @@ -407,12 +408,12 @@ TEST_P(TrajectoryGeneratorPTPTest, testCartesianGoalMissingLinkNameConstraints) planning_interface::MotionPlanRequest req_no_position_constaint_link_name = req; req_no_position_constaint_link_name.goal_constraints.front().position_constraints.front().link_name = ""; - ASSERT_FALSE(ptp_->generate(req_no_position_constaint_link_name, res)); + ASSERT_FALSE(ptp_->generate(planning_scene_, req_no_position_constaint_link_name, res)); EXPECT_EQ(res.error_code_.val, moveit_msgs::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS); planning_interface::MotionPlanRequest req_no_orientation_constaint_link_name = req; req_no_orientation_constaint_link_name.goal_constraints.front().orientation_constraints.front().link_name = ""; - ASSERT_FALSE(ptp_->generate(req_no_orientation_constaint_link_name, res)); + ASSERT_FALSE(ptp_->generate(planning_scene_, req_no_orientation_constaint_link_name, res)); EXPECT_EQ(res.error_code_.val, moveit_msgs::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS); } @@ -439,7 +440,7 @@ TEST_P(TrajectoryGeneratorPTPTest, testInvalidCartesianGoal) kinematic_constraints::constructGoalConstraints(target_link_, pose, tolerance_pose, tolerance_angle); req.goal_constraints.push_back(pose_goal); - ASSERT_FALSE(ptp_->generate(req, res)); + ASSERT_FALSE(ptp_->generate(planning_scene_, req, res)); EXPECT_EQ(res.error_code_.val, moveit_msgs::MoveItErrorCodes::NO_IK_SOLUTION); EXPECT_EQ(res.trajectory_, nullptr); } @@ -465,7 +466,7 @@ TEST_P(TrajectoryGeneratorPTPTest, testJointGoalAlreadyReached) req.goal_constraints.push_back(gc); // TODO lin and circ has different settings - ASSERT_TRUE(ptp_->generate(req, res)); + ASSERT_TRUE(ptp_->generate(planning_scene_, req, res)); EXPECT_EQ(res.error_code_.val, moveit_msgs::MoveItErrorCodes::SUCCESS); moveit_msgs::MotionPlanResponse res_msg; @@ -537,7 +538,7 @@ TEST_P(TrajectoryGeneratorPTPTest, testScalingFactor) req.max_velocity_scaling_factor = 0.5; req.max_acceleration_scaling_factor = 1.0 / 3.0; - ASSERT_TRUE(ptp_->generate(req, res)); + ASSERT_TRUE(ptp_->generate(planning_scene_, req, res)); EXPECT_EQ(res.error_code_.val, moveit_msgs::MoveItErrorCodes::SUCCESS); moveit_msgs::MotionPlanResponse res_msg; @@ -664,7 +665,7 @@ TEST_P(TrajectoryGeneratorPTPTest, testJointGoalAndAlmostZeroStartVelocity) gc.joint_constraints.push_back(jc); req.goal_constraints.push_back(gc); - ASSERT_TRUE(ptp_->generate(req, res)); + ASSERT_TRUE(ptp_->generate(planning_scene_, req, res)); EXPECT_EQ(res.error_code_.val, moveit_msgs::MoveItErrorCodes::SUCCESS); moveit_msgs::MotionPlanResponse res_msg; @@ -806,7 +807,7 @@ TEST_P(TrajectoryGeneratorPTPTest, testJointGoalNoStartVel) gc.joint_constraints.push_back(jc); req.goal_constraints.push_back(gc); - ASSERT_TRUE(ptp_->generate(req, res)); + ASSERT_TRUE(ptp_->generate(planning_scene_, req, res)); EXPECT_EQ(res.error_code_.val, moveit_msgs::MoveItErrorCodes::SUCCESS); moveit_msgs::MotionPlanResponse res_msg; From 6012934e38efd29b2587df04f6bafec784175675 Mon Sep 17 00:00:00 2001 From: Vatan Aksoy Tezer Date: Thu, 19 Aug 2021 18:38:02 +0300 Subject: [PATCH 06/14] CI: Update pat-s/always-upload-cache --- .github/workflows/ci.yaml | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/.github/workflows/ci.yaml b/.github/workflows/ci.yaml index bf261531fa..6ee362ed46 100644 --- a/.github/workflows/ci.yaml +++ b/.github/workflows/ci.yaml @@ -66,7 +66,7 @@ jobs: df -h - uses: actions/checkout@v2 - name: cache upstream workspace - uses: pat-s/always-upload-cache@v2.1.3 + uses: pat-s/always-upload-cache@v2.1.5 with: path: ${{ env.BASEDIR }}/upstream_ws key: ${{ env.CACHE_PREFIX }}-${{ github.run_id }} @@ -74,7 +74,7 @@ jobs: env: CACHE_PREFIX: upstream_ws-${{ matrix.env.IMAGE }}-${{ hashFiles('.github/workflows/upstream.rosinstall', '.github/workflows/ci.yaml') }} - name: cache downstream workspace - uses: pat-s/always-upload-cache@v2.1.3 + uses: pat-s/always-upload-cache@v2.1.5 with: path: ${{ env.BASEDIR }}/downstream_ws key: ${{ env.CACHE_PREFIX }}-${{ github.run_id }} @@ -85,7 +85,7 @@ jobs: # that comes from the checkout. See "prepare target_ws for cache" task below - name: cache target workspace if: ${{ ! matrix.env.CCOV }} - uses: pat-s/always-upload-cache@v2.1.3 + uses: pat-s/always-upload-cache@v2.1.5 with: path: ${{ env.BASEDIR }}/target_ws key: ${{ env.CACHE_PREFIX }}-${{ github.run_id }} @@ -93,7 +93,7 @@ jobs: env: CACHE_PREFIX: target_ws${{ matrix.env.CCOV && '-ccov' || '' }}-${{ matrix.env.IMAGE }}-${{ hashFiles('**/CMakeLists.txt', '**/package.xml', '.github/workflows/ci.yaml') }} - name: cache ccache - uses: pat-s/always-upload-cache@v2.1.3 + uses: pat-s/always-upload-cache@v2.1.5 with: path: ${{ env.CCACHE_DIR }} key: ${{ env.CACHE_PREFIX }}-${{ github.sha }}-${{ github.run_id }} From 1d75d646ffb4b341a84574bd779d5a487ebff89e Mon Sep 17 00:00:00 2001 From: Robert Haschke Date: Fri, 20 Aug 2021 00:33:24 +0200 Subject: [PATCH 07/14] CI: Enable -Werror only for TARGET and DOWNSTREAM workspaces (#2821) --- .github/workflows/ci.yaml | 9 +++++---- 1 file changed, 5 insertions(+), 4 deletions(-) diff --git a/.github/workflows/ci.yaml b/.github/workflows/ci.yaml index 6ee362ed46..caf9cc450a 100644 --- a/.github/workflows/ci.yaml +++ b/.github/workflows/ci.yaml @@ -27,7 +27,7 @@ jobs: - IMAGE: master-ci # ROS Melodic with all dependencies required for master CATKIN_LINT: true env: - CXXFLAGS: "-Werror -Wall -Wextra -Wwrite-strings -Wunreachable-code -Wpointer-arith -Wredundant-decls -Wno-deprecated-copy" + CXXFLAGS: "-Wall -Wextra -Wwrite-strings -Wunreachable-code -Wpointer-arith -Wredundant-decls -Wno-deprecated-copy" DOCKER_IMAGE: moveit/moveit:${{ matrix.env.IMAGE }} UPSTREAM_WORKSPACE: .github/workflows/upstream.rosinstall TARGET_WORKSPACE: $TARGET_REPO_PATH github:ros-planning/moveit_resources#master @@ -38,10 +38,11 @@ jobs: AFTER_RUN_TARGET_TEST: ${{ matrix.env.CCOV && './.ci.prepare_codecov' || '' }} TARGET_CMAKE_ARGS: > -DCMAKE_BUILD_TYPE=${{ matrix.env.CCOV && 'RelWithDebInfo' || 'Release'}} - ${{ matrix.env.CCOV && '-DCMAKE_CXX_FLAGS="$CXXFLAGS --coverage" --no-warn-unused-cli' || '' }} - CCACHE_DIR: "${{ github.workspace }}/.ccache" + -DCMAKE_CXX_FLAGS="-Werror $CXXFLAGS ${{ matrix.env.CCOV && '--coverage'}}" + DOWNSTREAM_CMAKE_ARGS: -DCMAKE_CXX_FLAGS="-Werror $CXXFLAGS" + CCACHE_DIR: ${{ github.workspace }}/.ccache BASEDIR: ${{ github.workspace }}/.work - CLANG_TIDY_BASE_REF: "${{ github.base_ref || github.ref }}" + CLANG_TIDY_BASE_REF: ${{ github.base_ref || github.ref }} BEFORE_CLANG_TIDY_CHECKS: (cd $TARGET_REPO_PATH; clang-tidy --list-checks) BUILDER: ${{ matrix.env.BUILDER || 'catkin_tools' }} CC: ${{ matrix.env.CLANG_TIDY && 'clang' }} From f8f82810de907510700d65e33fa949b50cce7b8d Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Michael=20G=C3=B6rner?= Date: Fri, 20 Aug 2021 01:44:27 +0200 Subject: [PATCH 08/14] Add RobotState::setToDefaultValues from group string (#2828) --- .../robot_state/include/moveit/robot_state/robot_state.h | 9 +++++++++ 1 file changed, 9 insertions(+) diff --git a/moveit_core/robot_state/include/moveit/robot_state/robot_state.h b/moveit_core/robot_state/include/moveit/robot_state/robot_state.h index 4c7669adeb..b4ac421b8b 100644 --- a/moveit_core/robot_state/include/moveit/robot_state/robot_state.h +++ b/moveit_core/robot_state/include/moveit/robot_state/robot_state.h @@ -1289,6 +1289,15 @@ class RobotState /** \brief Set the joints in \e group to the position \e name defined in the SRDF */ bool setToDefaultValues(const JointModelGroup* group, const std::string& name); + bool setToDefaultValues(const std::string& group_name, const std::string& state_name) + { + const JointModelGroup* jmg = getJointModelGroup(group_name); + if (jmg) + return setToDefaultValues(jmg, state_name); + else + return false; + } + /** \brief Set all joints to random values. Values will be within default bounds. */ void setToRandomPositions(); From 1859ec2d248074c983367735f3034f3172de07b2 Mon Sep 17 00:00:00 2001 From: Yuri Rocha Date: Fri, 20 Aug 2021 16:37:54 +0900 Subject: [PATCH 09/14] Fix Bullet collision returning wrong contact type (#2829) * fix getting wrong type ID * update unit test --- .../bullet_integration/bullet_utils.h | 4 ++-- .../test_bullet_continuous_collision_checking.cpp | 15 +++++++++++++++ 2 files changed, 17 insertions(+), 2 deletions(-) diff --git a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_utils.h b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_utils.h index 7c91212cf5..bcaf4210c4 100644 --- a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_utils.h +++ b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/bullet_integration/bullet_utils.h @@ -443,7 +443,7 @@ inline btScalar addDiscreteSingleResult(btManifoldPoint& cp, const btCollisionOb contact.nearest_points[1] = convertBtToEigen(cp.m_positionWorldOnB); contact.body_type_1 = cd0->getTypeID(); - contact.body_type_2 = cd0->getTypeID(); + contact.body_type_2 = cd1->getTypeID(); if (!processResult(collisions, contact, pc, found)) { @@ -476,7 +476,7 @@ inline btScalar addCastSingleResult(btManifoldPoint& cp, const btCollisionObject contact.pos = convertBtToEigen(cp.m_positionWorldOnA); contact.body_type_1 = cd0->getTypeID(); - contact.body_type_2 = cd0->getTypeID(); + contact.body_type_2 = cd1->getTypeID(); collision_detection::Contact* col = processResult(collisions, contact, pc, found); diff --git a/moveit_core/collision_detection_bullet/test/test_bullet_continuous_collision_checking.cpp b/moveit_core/collision_detection_bullet/test/test_bullet_continuous_collision_checking.cpp index c3132ec945..0334fa531f 100644 --- a/moveit_core/collision_detection_bullet/test/test_bullet_continuous_collision_checking.cpp +++ b/moveit_core/collision_detection_bullet/test/test_bullet_continuous_collision_checking.cpp @@ -311,6 +311,21 @@ TEST_F(BulletCollisionDetectionTester, ContinuousCollisionWorld) cenv_->checkRobotCollision(req, res, state1, state2, *acm_); ASSERT_TRUE(res.collision); ASSERT_EQ(res.contact_count, 4u); + // test contact types + for (auto& contact_pair : res.contacts) + { + for (collision_detection::Contact& contact : contact_pair.second) + { + collision_detection::BodyType contact_type1 = contact.body_name_1 == "box" ? + collision_detection::BodyType::WORLD_OBJECT : + collision_detection::BodyType::ROBOT_LINK; + collision_detection::BodyType contact_type2 = contact.body_name_2 == "box" ? + collision_detection::BodyType::WORLD_OBJECT : + collision_detection::BodyType::ROBOT_LINK; + ASSERT_EQ(contact.body_type_1, contact_type1); + ASSERT_EQ(contact.body_type_2, contact_type2); + } + } res.clear(); } From 0d38983cc75305a36121e6cd4925ac7335e0edbc Mon Sep 17 00:00:00 2001 From: Robert Haschke Date: Sun, 22 Aug 2021 21:14:38 +0200 Subject: [PATCH 10/14] Bump version: 1.1.6 (#2832) --- moveit/package.xml | 2 +- moveit_commander/package.xml | 2 +- moveit_core/package.xml | 2 +- moveit_kinematics/package.xml | 2 +- moveit_planners/chomp/chomp_interface/package.xml | 2 +- moveit_planners/chomp/chomp_motion_planner/package.xml | 2 +- moveit_planners/chomp/chomp_optimizer_adapter/package.xml | 2 +- moveit_planners/moveit_planners/package.xml | 2 +- moveit_planners/ompl/package.xml | 2 +- moveit_planners/pilz_industrial_motion_planner/package.xml | 2 +- .../pilz_industrial_motion_planner_testutils/package.xml | 2 +- moveit_plugins/moveit_fake_controller_manager/package.xml | 2 +- moveit_plugins/moveit_plugins/package.xml | 2 +- moveit_plugins/moveit_ros_control_interface/package.xml | 2 +- moveit_plugins/moveit_simple_controller_manager/package.xml | 2 +- moveit_ros/benchmarks/package.xml | 2 +- moveit_ros/manipulation/package.xml | 2 +- moveit_ros/move_group/package.xml | 2 +- moveit_ros/moveit_ros/package.xml | 2 +- moveit_ros/moveit_servo/package.xml | 2 +- moveit_ros/occupancy_map_monitor/package.xml | 2 +- moveit_ros/perception/package.xml | 2 +- moveit_ros/planning/package.xml | 2 +- moveit_ros/planning_interface/package.xml | 2 +- moveit_ros/robot_interaction/package.xml | 2 +- moveit_ros/visualization/package.xml | 2 +- moveit_ros/warehouse/package.xml | 2 +- moveit_runtime/package.xml | 2 +- moveit_setup_assistant/package.xml | 2 +- 29 files changed, 29 insertions(+), 29 deletions(-) diff --git a/moveit/package.xml b/moveit/package.xml index bf78c287fc..9c6ee7c1b7 100644 --- a/moveit/package.xml +++ b/moveit/package.xml @@ -1,7 +1,7 @@ moveit - 1.1.5 + 1.1.6 Meta package that contains all essential package of MoveIt. Until Summer 2016 MoveIt had been developed over multiple repositories, where developers' usability and maintenance effort was non-trivial. See the detailed discussion for the merge of several repositories. Dave Coleman Michael Ferguson diff --git a/moveit_commander/package.xml b/moveit_commander/package.xml index de44ad1a76..68268eb3be 100644 --- a/moveit_commander/package.xml +++ b/moveit_commander/package.xml @@ -1,7 +1,7 @@ moveit_commander - 1.1.5 + 1.1.6 Python interfaces to MoveIt Ioan Sucan diff --git a/moveit_core/package.xml b/moveit_core/package.xml index a15f2fb200..5e983e1c0f 100644 --- a/moveit_core/package.xml +++ b/moveit_core/package.xml @@ -1,7 +1,7 @@ moveit_core - 1.1.5 + 1.1.6 Core libraries used by MoveIt Ioan Sucan Sachin Chitta diff --git a/moveit_kinematics/package.xml b/moveit_kinematics/package.xml index 52f9bb0309..9ecae6dcf1 100644 --- a/moveit_kinematics/package.xml +++ b/moveit_kinematics/package.xml @@ -1,7 +1,7 @@ moveit_kinematics - 1.1.5 + 1.1.6 Package for all inverse kinematics solvers in MoveIt Dave Coleman diff --git a/moveit_planners/chomp/chomp_interface/package.xml b/moveit_planners/chomp/chomp_interface/package.xml index 5b87e9430e..a540ef8a77 100644 --- a/moveit_planners/chomp/chomp_interface/package.xml +++ b/moveit_planners/chomp/chomp_interface/package.xml @@ -2,7 +2,7 @@ moveit_planners_chomp The interface for using CHOMP within MoveIt - 1.1.5 + 1.1.6 Gil Jones Chittaranjan Srinivas Swaminathan diff --git a/moveit_planners/chomp/chomp_motion_planner/package.xml b/moveit_planners/chomp/chomp_motion_planner/package.xml index b0d8515033..3ddc837c28 100644 --- a/moveit_planners/chomp/chomp_motion_planner/package.xml +++ b/moveit_planners/chomp/chomp_motion_planner/package.xml @@ -2,7 +2,7 @@ chomp_motion_planner chomp_motion_planner - 1.1.5 + 1.1.6 Gil Jones Mrinal Kalakrishnan diff --git a/moveit_planners/chomp/chomp_optimizer_adapter/package.xml b/moveit_planners/chomp/chomp_optimizer_adapter/package.xml index 98ed35836a..964630594c 100644 --- a/moveit_planners/chomp/chomp_optimizer_adapter/package.xml +++ b/moveit_planners/chomp/chomp_optimizer_adapter/package.xml @@ -3,7 +3,7 @@ moveit_chomp_optimizer_adapter MoveIt planning request adapter utilizing chomp for solution optimization - 1.1.5 + 1.1.6 Raghavender Sahdev Raghavender Sahdev MoveIt Release Team diff --git a/moveit_planners/moveit_planners/package.xml b/moveit_planners/moveit_planners/package.xml index 4fabc73b82..4d366b59e1 100644 --- a/moveit_planners/moveit_planners/package.xml +++ b/moveit_planners/moveit_planners/package.xml @@ -1,6 +1,6 @@ moveit_planners - 1.1.5 + 1.1.6 Metapacakge that installs all available planners for MoveIt Ioan Sucan Sachin Chitta diff --git a/moveit_planners/ompl/package.xml b/moveit_planners/ompl/package.xml index e7065a9dd2..cdd71debcc 100644 --- a/moveit_planners/ompl/package.xml +++ b/moveit_planners/ompl/package.xml @@ -1,6 +1,6 @@ moveit_planners_ompl - 1.1.5 + 1.1.6 MoveIt interface to OMPL Ioan Sucan diff --git a/moveit_planners/pilz_industrial_motion_planner/package.xml b/moveit_planners/pilz_industrial_motion_planner/package.xml index cd61709a74..8c1b056703 100644 --- a/moveit_planners/pilz_industrial_motion_planner/package.xml +++ b/moveit_planners/pilz_industrial_motion_planner/package.xml @@ -1,7 +1,7 @@ pilz_industrial_motion_planner - 1.1.5 + 1.1.6 MoveIt plugin to generate industrial trajectories PTP, LIN, CIRC and sequences thereof. Alexander Gutenkunst diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/package.xml b/moveit_planners/pilz_industrial_motion_planner_testutils/package.xml index 8e390bb990..425b86d9b5 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/package.xml +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/package.xml @@ -1,7 +1,7 @@ pilz_industrial_motion_planner_testutils - 1.1.5 + 1.1.6 Helper scripts and functionality to test industrial motion generation Alexander Gutenkunst diff --git a/moveit_plugins/moveit_fake_controller_manager/package.xml b/moveit_plugins/moveit_fake_controller_manager/package.xml index 1a4cbeca7b..90fb3a88ab 100644 --- a/moveit_plugins/moveit_fake_controller_manager/package.xml +++ b/moveit_plugins/moveit_fake_controller_manager/package.xml @@ -1,6 +1,6 @@ moveit_fake_controller_manager - 1.1.5 + 1.1.6 A fake controller manager plugin for MoveIt. Ioan Sucan diff --git a/moveit_plugins/moveit_plugins/package.xml b/moveit_plugins/moveit_plugins/package.xml index 12e8a23038..322d113cbd 100644 --- a/moveit_plugins/moveit_plugins/package.xml +++ b/moveit_plugins/moveit_plugins/package.xml @@ -1,6 +1,6 @@ moveit_plugins - 1.1.5 + 1.1.6 Metapackage for MoveIt plugins. Michael Ferguson diff --git a/moveit_plugins/moveit_ros_control_interface/package.xml b/moveit_plugins/moveit_ros_control_interface/package.xml index 554e2368c5..d8f3ad47bc 100644 --- a/moveit_plugins/moveit_ros_control_interface/package.xml +++ b/moveit_plugins/moveit_ros_control_interface/package.xml @@ -1,7 +1,7 @@ moveit_ros_control_interface - 1.1.5 + 1.1.6 ros_control controller manager interface for MoveIt Mathias Lüdtke diff --git a/moveit_plugins/moveit_simple_controller_manager/package.xml b/moveit_plugins/moveit_simple_controller_manager/package.xml index f27e10c83f..86f1fa2e3b 100644 --- a/moveit_plugins/moveit_simple_controller_manager/package.xml +++ b/moveit_plugins/moveit_simple_controller_manager/package.xml @@ -1,6 +1,6 @@ moveit_simple_controller_manager - 1.1.5 + 1.1.6 A generic, simple controller manager plugin for MoveIt. Michael Ferguson diff --git a/moveit_ros/benchmarks/package.xml b/moveit_ros/benchmarks/package.xml index bbcf07f174..8073661820 100644 --- a/moveit_ros/benchmarks/package.xml +++ b/moveit_ros/benchmarks/package.xml @@ -1,6 +1,6 @@ moveit_ros_benchmarks - 1.1.5 + 1.1.6 Enhanced tools for benchmarks in MoveIt diff --git a/moveit_ros/manipulation/package.xml b/moveit_ros/manipulation/package.xml index bfe97f7ada..30792de339 100644 --- a/moveit_ros/manipulation/package.xml +++ b/moveit_ros/manipulation/package.xml @@ -1,6 +1,6 @@ moveit_ros_manipulation - 1.1.5 + 1.1.6 Components of MoveIt used for manipulation Ioan Sucan diff --git a/moveit_ros/move_group/package.xml b/moveit_ros/move_group/package.xml index 7a6d9afc68..b8a1bca95e 100644 --- a/moveit_ros/move_group/package.xml +++ b/moveit_ros/move_group/package.xml @@ -1,6 +1,6 @@ moveit_ros_move_group - 1.1.5 + 1.1.6 The move_group node for MoveIt Ioan Sucan Sachin Chitta diff --git a/moveit_ros/moveit_ros/package.xml b/moveit_ros/moveit_ros/package.xml index c4f489cf2c..f33313f1a4 100644 --- a/moveit_ros/moveit_ros/package.xml +++ b/moveit_ros/moveit_ros/package.xml @@ -1,6 +1,6 @@ moveit_ros - 1.1.5 + 1.1.6 Components of MoveIt that use ROS Ioan Sucan Sachin Chitta diff --git a/moveit_ros/moveit_servo/package.xml b/moveit_ros/moveit_servo/package.xml index 9a67faa7f3..bc27fc32de 100644 --- a/moveit_ros/moveit_servo/package.xml +++ b/moveit_ros/moveit_servo/package.xml @@ -1,7 +1,7 @@ moveit_servo - 1.1.5 + 1.1.6 Provides real-time manipulator Cartesian and joint servoing. diff --git a/moveit_ros/occupancy_map_monitor/package.xml b/moveit_ros/occupancy_map_monitor/package.xml index a9c304ea65..2daf9b3638 100644 --- a/moveit_ros/occupancy_map_monitor/package.xml +++ b/moveit_ros/occupancy_map_monitor/package.xml @@ -1,7 +1,7 @@ moveit_ros_occupancy_map_monitor - 1.1.5 + 1.1.6 Components of MoveIt connecting to occupancy map Ioan Sucan diff --git a/moveit_ros/perception/package.xml b/moveit_ros/perception/package.xml index c47d72468d..7509d0f741 100644 --- a/moveit_ros/perception/package.xml +++ b/moveit_ros/perception/package.xml @@ -1,6 +1,6 @@ moveit_ros_perception - 1.1.5 + 1.1.6 Components of MoveIt connecting to perception Ioan Sucan diff --git a/moveit_ros/planning/package.xml b/moveit_ros/planning/package.xml index 7e789f5527..aaae5c0805 100644 --- a/moveit_ros/planning/package.xml +++ b/moveit_ros/planning/package.xml @@ -1,7 +1,7 @@ moveit_ros_planning - 1.1.5 + 1.1.6 Planning components of MoveIt that use ROS Ioan Sucan Sachin Chitta diff --git a/moveit_ros/planning_interface/package.xml b/moveit_ros/planning_interface/package.xml index 776a934c83..058d0cf408 100644 --- a/moveit_ros/planning_interface/package.xml +++ b/moveit_ros/planning_interface/package.xml @@ -1,7 +1,7 @@ moveit_ros_planning_interface - 1.1.5 + 1.1.6 Components of MoveIt that offer simpler interfaces to planning and execution Ioan Sucan diff --git a/moveit_ros/robot_interaction/package.xml b/moveit_ros/robot_interaction/package.xml index c5d71ac43b..a6f592ef81 100644 --- a/moveit_ros/robot_interaction/package.xml +++ b/moveit_ros/robot_interaction/package.xml @@ -1,6 +1,6 @@ moveit_ros_robot_interaction - 1.1.5 + 1.1.6 Components of MoveIt that offer interaction via interactive markers Ioan Sucan diff --git a/moveit_ros/visualization/package.xml b/moveit_ros/visualization/package.xml index ea3b35eda4..f4933f51b4 100644 --- a/moveit_ros/visualization/package.xml +++ b/moveit_ros/visualization/package.xml @@ -1,6 +1,6 @@ moveit_ros_visualization - 1.1.5 + 1.1.6 Components of MoveIt that offer visualization Ioan Sucan diff --git a/moveit_ros/warehouse/package.xml b/moveit_ros/warehouse/package.xml index fa8a77b11d..0e56a433cd 100644 --- a/moveit_ros/warehouse/package.xml +++ b/moveit_ros/warehouse/package.xml @@ -1,6 +1,6 @@ moveit_ros_warehouse - 1.1.5 + 1.1.6 Components of MoveIt connecting to MongoDB Ioan Sucan diff --git a/moveit_runtime/package.xml b/moveit_runtime/package.xml index 250300e7a5..0416e7fcd2 100644 --- a/moveit_runtime/package.xml +++ b/moveit_runtime/package.xml @@ -1,7 +1,7 @@ moveit_runtime - 1.1.5 + 1.1.6 moveit_runtime meta package contains MoveIt packages that are essential for its runtime (e.g. running MoveIt on robots). Isaac I. Y. Saito diff --git a/moveit_setup_assistant/package.xml b/moveit_setup_assistant/package.xml index 7db3e4727f..456bb0559a 100644 --- a/moveit_setup_assistant/package.xml +++ b/moveit_setup_assistant/package.xml @@ -1,6 +1,6 @@ moveit_setup_assistant - 1.1.5 + 1.1.6 Generates a configuration package that makes it easy to use MoveIt From 7cea1f219fae3d4e1d0fdfadb08a71afd0dd8022 Mon Sep 17 00:00:00 2001 From: Robert Haschke Date: Mon, 23 Aug 2021 09:53:07 +0200 Subject: [PATCH 11/14] MotionPlanningFrame: Gracefully handle undefined parent widget (#2833) If the MP plugin was created in a non-rviz context (e.g. directly via librviz), there might be no window manager and thus no parent widget available for panels. --- .../src/motion_planning_frame.cpp | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_frame.cpp b/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_frame.cpp index 0629c78828..34082ce602 100644 --- a/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_frame.cpp +++ b/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_frame.cpp @@ -577,14 +577,16 @@ void MotionPlanningFrame::enable() ui_->object_status->setText(""); // activate the frame - parentWidget()->show(); + if (parentWidget()) + parentWidget()->show(); } void MotionPlanningFrame::disable() { move_group_.reset(); scene_marker_.reset(); - parentWidget()->hide(); + if (parentWidget()) + parentWidget()->hide(); } void MotionPlanningFrame::tabChanged(int index) From bef8f7cdde399287dc8b75b9a36b4da54704b69d Mon Sep 17 00:00:00 2001 From: Rick Staa Date: Wed, 25 Aug 2021 00:25:59 +0200 Subject: [PATCH 12/14] Makes rviz trajectory visualization topic relative (#2835) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit This commit makes the trajectory visualization topic relative. This was done to make sure that it respects the namespaces that are set in launch files. Co-authored-by: Felix von Drigalski Co-authored-by: Michael Görner --- MIGRATION.md | 1 + .../rviz_plugin_render_tools/src/trajectory_visualization.cpp | 2 +- 2 files changed, 2 insertions(+), 1 deletion(-) diff --git a/MIGRATION.md b/MIGRATION.md index 93034bc6da..b6f91b6173 100644 --- a/MIGRATION.md +++ b/MIGRATION.md @@ -26,6 +26,7 @@ API changes in MoveIt releases - The joint states of `passive` joints must be published in ROS and the CurrentStateMonitor will now wait for them as well. Their semantics dictate that they cannot be actively controlled, but they must be known to use the full robot state in collision checks. (https://github.com/ros-planning/moveit/pull/2663) - Removed deprecated header `moveit/macros/deprecation.h`. Use `[[deprecated]]` instead. - All uses of `MOVEIT_CLASS_FORWARD` et. al. must now be followed by a semicolon for consistency (and to get -pedantic builds to pass for the codebase). +- In case you start RViz in a namespace, the default topic for the trajectory visualization display now uses the relative instead of the absolute namespace (i.e. `/move_group/display_planned_path` instead of `/move_group/display_planned_path`). ## ROS Melodic diff --git a/moveit_ros/visualization/rviz_plugin_render_tools/src/trajectory_visualization.cpp b/moveit_ros/visualization/rviz_plugin_render_tools/src/trajectory_visualization.cpp index d74fef8176..854c872312 100644 --- a/moveit_ros/visualization/rviz_plugin_render_tools/src/trajectory_visualization.cpp +++ b/moveit_ros/visualization/rviz_plugin_render_tools/src/trajectory_visualization.cpp @@ -68,7 +68,7 @@ TrajectoryVisualization::TrajectoryVisualization(rviz::Property* widget, rviz::D , trajectory_slider_dock_panel_(nullptr) { trajectory_topic_property_ = - new rviz::RosTopicProperty("Trajectory Topic", "/move_group/display_planned_path", + new rviz::RosTopicProperty("Trajectory Topic", "move_group/display_planned_path", ros::message_traits::datatype(), "The topic on which the moveit_msgs::DisplayTrajectory messages are received", widget, SLOT(changedTrajectoryTopic()), this); From eb6135babbbfb8167fa7e78c50dad91288d27602 Mon Sep 17 00:00:00 2001 From: cambel Date: Thu, 26 Aug 2021 09:44:46 +0900 Subject: [PATCH 13/14] Consider attached bodies in Pilz planner #2773 (#2824) - Remove convertToRobotTrajectory() and integrate its line of code into setSuccessResponse() - Pass the final start_state into setSuccessResponse() Co-authored-by: Cristian Beltran Co-authored-by: Robert Haschke --- .../trajectory_generator.h | 6 +----- .../src/trajectory_generator.cpp | 18 +++++------------- 2 files changed, 6 insertions(+), 18 deletions(-) diff --git a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator.h b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator.h index 8637b73320..4cb7d261ea 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator.h +++ b/moveit_planners/pilz_industrial_motion_planner/include/pilz_industrial_motion_planner/trajectory_generator.h @@ -204,7 +204,7 @@ class TrajectoryGenerator /** * @brief set MotionPlanResponse from joint trajectory */ - void setSuccessResponse(const std::string& group_name, const moveit_msgs::RobotState& start_state, + void setSuccessResponse(const moveit::core::RobotState& start_rs, const std::string& group_name, const trajectory_msgs::JointTrajectory& joint_trajectory, const ros::Time& planning_start, planning_interface::MotionPlanResponse& res) const; @@ -234,10 +234,6 @@ class TrajectoryGenerator void checkCartesianGoalConstraint(const moveit_msgs::Constraints& constraint, const std::string& group_name) const; - void convertToRobotTrajectory(const trajectory_msgs::JointTrajectory& joint_trajectory, - const moveit_msgs::RobotState& start_state, - robot_trajectory::RobotTrajectory& robot_trajectory) const; - private: /** * @return True if scaling factor is valid, otherwise false. diff --git a/moveit_planners/pilz_industrial_motion_planner/src/trajectory_generator.cpp b/moveit_planners/pilz_industrial_motion_planner/src/trajectory_generator.cpp index 8a1099b981..aebdfaf90d 100644 --- a/moveit_planners/pilz_industrial_motion_planner/src/trajectory_generator.cpp +++ b/moveit_planners/pilz_industrial_motion_planner/src/trajectory_generator.cpp @@ -214,23 +214,13 @@ void TrajectoryGenerator::validateRequest(const planning_interface::MotionPlanRe checkGoalConstraints(req.goal_constraints, req.start_state.joint_state.name, req.group_name); } -void TrajectoryGenerator::convertToRobotTrajectory(const trajectory_msgs::JointTrajectory& joint_trajectory, - const moveit_msgs::RobotState& start_state, - robot_trajectory::RobotTrajectory& robot_trajectory) const -{ - moveit::core::RobotState start_rs(robot_model_); - start_rs.setToDefaultValues(); - moveit::core::robotStateMsgToRobotState(start_state, start_rs, false); - robot_trajectory.setRobotTrajectoryMsg(start_rs, joint_trajectory); -} - -void TrajectoryGenerator::setSuccessResponse(const std::string& group_name, const moveit_msgs::RobotState& start_state, +void TrajectoryGenerator::setSuccessResponse(const moveit::core::RobotState& start_state, const std::string& group_name, const trajectory_msgs::JointTrajectory& joint_trajectory, const ros::Time& planning_start, planning_interface::MotionPlanResponse& res) const { robot_trajectory::RobotTrajectoryPtr rt(new robot_trajectory::RobotTrajectory(robot_model_, group_name)); - convertToRobotTrajectory(joint_trajectory, start_state, *rt); + rt->setRobotTrajectoryMsg(start_state, joint_trajectory); res.trajectory_ = rt; res.error_code_.val = moveit_msgs::MoveItErrorCodes::SUCCESS; @@ -324,7 +314,9 @@ bool TrajectoryGenerator::generate(const planning_scene::PlanningSceneConstPtr& return false; } - setSuccessResponse(req.group_name, req.start_state, joint_trajectory, planning_begin, res); + moveit::core::RobotState start_state(scene->getCurrentState()); + moveit::core::robotStateMsgToRobotState(req.start_state, start_state, true); + setSuccessResponse(start_state, req.group_name, joint_trajectory, planning_begin, res); return true; } From 865c2611285aae9c6f733a1c40f87e5b5f4ba1cc Mon Sep 17 00:00:00 2001 From: Rick Staa Date: Thu, 26 Aug 2021 05:40:16 +0200 Subject: [PATCH 14/14] MSA: Mention optional Gazebo deps in package.xml templates (#2839) --- .../templates/moveit_config_pkg_template/package.xml.template | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/moveit_setup_assistant/templates/moveit_config_pkg_template/package.xml.template b/moveit_setup_assistant/templates/moveit_config_pkg_template/package.xml.template index c0555ce40c..7db6b8c009 100644 --- a/moveit_setup_assistant/templates/moveit_config_pkg_template/package.xml.template +++ b/moveit_setup_assistant/templates/moveit_config_pkg_template/package.xml.template @@ -29,6 +29,10 @@ rviz tf2_ros xacro + + + [OTHER_DEPENDENCIES]