From 779345308cec705a67365a337eecc4725883ba0c Mon Sep 17 00:00:00 2001 From: Walter Fetter Lages Date: Wed, 28 Nov 2018 11:25:20 -0200 Subject: [PATCH] Initial commit. --- .gitignore | 51 ++++++ CMakeLists.txt | 17 ++ Makefile | 1 + bhand_description/CMakeLists.txt | 30 ++++ bhand_description/Makefile | 1 + bhand_description/launch/bhand.launch | 5 + bhand_description/launch/bhand_sim.launch | 9 ++ bhand_description/manifest.xml | 14 ++ bhand_description/meshes/bh_base.stl | Bin 0 -> 143884 bytes bhand_description/meshes/bh_link1.stl | Bin 0 -> 41384 bytes bhand_description/meshes/bh_link2.stl | Bin 0 -> 48584 bytes bhand_description/meshes/bh_link3.stl | Bin 0 -> 183584 bytes bhand_description/xacro/bhand.urdf.xacro | 63 ++++++++ bhand_description/xacro/bhand0.urdf.xacro | 72 +++++++++ bhand_description/xacro/bhand_base.urdf.xacro | 45 ++++++ bhand_description/xacro/bhand_finger.urdf.xacro | 60 +++++++ plier_description/launch/display.launch | 11 ++ plier_description/launch/gazebo.launch | 7 + plier_description/launch/plier.launch | 4 + plier_description/launch/plier_sim.launch | 6 + plier_description/manifest.xml | 6 + plier_description/meshes/base_link.stl | Bin 0 -> 381184 bytes plier_description/meshes/link1.stl | Bin 0 -> 23984 bytes plier_description/meshes/link2.stl | Bin 0 -> 20784 bytes plier_description/urdf/plier.urdf | 112 +++++++++++++ stack.xml | 9 ++ wam_control_gazebo/CMakeLists.txt | 33 ++++ wam_control_gazebo/Makefile | 1 + wam_control_gazebo/mainpage.dox | 14 ++ wam_control_gazebo/manifest.xml | 23 +++ wam_control_gazebo/robot_sim_plugins.xml | 12 ++ wam_control_gazebo/src/robot_sim_wam.cpp | 102 ++++++++++++ wam_controllers/CMakeLists.txt | 30 ++++ wam_controllers/Makefile | 1 + wam_controllers/README | 10 ++ .../config/computed_torque_control.yaml | 16 ++ wam_controllers/doc/urdf2kdl.txt | 9 ++ .../wam_controllers/computed_torque_controller.h | 61 ++++++++ wam_controllers/launch/computed_torque.launch | 14 ++ .../launch/computed_torque_table.launch | 14 ++ wam_controllers/mainpage.dox | 14 ++ wam_controllers/manifest.xml | 25 +++ wam_controllers/src/computed_torque_controller.cpp | 173 +++++++++++++++++++++ wam_controllers/wam_controllers_plugins.xml | 11 ++ wam_description/CMakeLists.txt | 30 ++++ wam_description/Makefile | 1 + wam_description/launch/wam.launch | 4 + wam_description/launch/wam_bhand.launch | 4 + wam_description/launch/wam_bhand_sim.launch | 11 ++ wam_description/launch/wam_sim.launch | 11 ++ wam_description/launch/wam_table.launch | 4 + wam_description/launch/wam_table_sim.launch | 11 ++ wam_description/manifest.xml | 14 ++ wam_description/meshes/wam1.stl | Bin 0 -> 58484 bytes wam_description/meshes/wam2.stl | Bin 0 -> 26084 bytes wam_description/meshes/wam3.stl | Bin 0 -> 53084 bytes wam_description/meshes/wam4.stl | Bin 0 -> 112184 bytes wam_description/meshes/wam5.stl | Bin 0 -> 76084 bytes wam_description/meshes/wam6.stl | Bin 0 -> 139684 bytes wam_description/meshes/wam7.stl | Bin 0 -> 99484 bytes wam_description/meshes/wambase.stl | Bin 0 -> 49084 bytes wam_description/xacro/.wam_j1.urdf.xacro.swo | Bin 0 -> 12288 bytes wam_description/xacro/wam.urdf.xacro | 50 ++++++ wam_description/xacro/wam_base.urdf.xacro | 48 ++++++ wam_description/xacro/wam_bhand.urdf.xacro | 22 +++ wam_description/xacro/wam_j1.urdf.xacro | 56 +++++++ wam_description/xacro/wam_j2.urdf.xacro | 56 +++++++ wam_description/xacro/wam_j3.urdf.xacro | 56 +++++++ wam_description/xacro/wam_j4.urdf.xacro | 56 +++++++ wam_description/xacro/wam_j5.urdf.xacro | 56 +++++++ wam_description/xacro/wam_j6.urdf.xacro | 56 +++++++ wam_description/xacro/wam_j7.urdf.xacro | 56 +++++++ wam_description/xacro/wam_table.urdf.xacro | 30 ++++ wam_description/xacro/wam_tool_plate.urdf.xacro | 45 ++++++ 74 files changed, 1763 insertions(+) create mode 100644 .gitignore create mode 100644 CMakeLists.txt create mode 100644 Makefile create mode 100644 bhand_description/CMakeLists.txt create mode 100644 bhand_description/Makefile create mode 100644 bhand_description/launch/bhand.launch create mode 100644 bhand_description/launch/bhand_sim.launch create mode 100644 bhand_description/manifest.xml create mode 100644 bhand_description/meshes/bh_base.stl create mode 100644 bhand_description/meshes/bh_link1.stl create mode 100644 bhand_description/meshes/bh_link2.stl create mode 100644 bhand_description/meshes/bh_link3.stl create mode 100644 bhand_description/xacro/bhand.urdf.xacro create mode 100644 bhand_description/xacro/bhand0.urdf.xacro create mode 100644 bhand_description/xacro/bhand_base.urdf.xacro create mode 100644 bhand_description/xacro/bhand_finger.urdf.xacro create mode 100644 plier_description/launch/display.launch create mode 100644 plier_description/launch/gazebo.launch create mode 100644 plier_description/launch/plier.launch create mode 100644 plier_description/launch/plier_sim.launch create mode 100644 plier_description/manifest.xml create mode 100644 plier_description/meshes/base_link.stl create mode 100644 plier_description/meshes/link1.stl create mode 100644 plier_description/meshes/link2.stl create mode 100644 plier_description/urdf/plier.urdf create mode 100644 stack.xml create mode 100644 wam_control_gazebo/CMakeLists.txt create mode 100644 wam_control_gazebo/Makefile create mode 100644 wam_control_gazebo/mainpage.dox create mode 100644 wam_control_gazebo/manifest.xml create mode 100644 wam_control_gazebo/robot_sim_plugins.xml create mode 100644 wam_control_gazebo/src/robot_sim_wam.cpp create mode 100644 wam_controllers/CMakeLists.txt create mode 100644 wam_controllers/Makefile create mode 100644 wam_controllers/README create mode 100644 wam_controllers/config/computed_torque_control.yaml create mode 100644 wam_controllers/doc/urdf2kdl.txt create mode 100644 wam_controllers/include/wam_controllers/computed_torque_controller.h create mode 100644 wam_controllers/launch/computed_torque.launch create mode 100644 wam_controllers/launch/computed_torque_table.launch create mode 100644 wam_controllers/mainpage.dox create mode 100644 wam_controllers/manifest.xml create mode 100644 wam_controllers/src/computed_torque_controller.cpp create mode 100644 wam_controllers/wam_controllers_plugins.xml create mode 100644 wam_description/CMakeLists.txt create mode 100644 wam_description/Makefile create mode 100644 wam_description/launch/wam.launch create mode 100644 wam_description/launch/wam_bhand.launch create mode 100644 wam_description/launch/wam_bhand_sim.launch create mode 100644 wam_description/launch/wam_sim.launch create mode 100644 wam_description/launch/wam_table.launch create mode 100644 wam_description/launch/wam_table_sim.launch create mode 100644 wam_description/manifest.xml create mode 100644 wam_description/meshes/wam1.stl create mode 100644 wam_description/meshes/wam2.stl create mode 100644 wam_description/meshes/wam3.stl create mode 100644 wam_description/meshes/wam4.stl create mode 100644 wam_description/meshes/wam5.stl create mode 100644 wam_description/meshes/wam6.stl create mode 100644 wam_description/meshes/wam7.stl create mode 100644 wam_description/meshes/wambase.stl create mode 100644 wam_description/xacro/.wam_j1.urdf.xacro.swo create mode 100644 wam_description/xacro/wam.urdf.xacro create mode 100644 wam_description/xacro/wam_base.urdf.xacro create mode 100644 wam_description/xacro/wam_bhand.urdf.xacro create mode 100644 wam_description/xacro/wam_j1.urdf.xacro create mode 100644 wam_description/xacro/wam_j2.urdf.xacro create mode 100644 wam_description/xacro/wam_j3.urdf.xacro create mode 100644 wam_description/xacro/wam_j4.urdf.xacro create mode 100644 wam_description/xacro/wam_j5.urdf.xacro create mode 100644 wam_description/xacro/wam_j6.urdf.xacro create mode 100644 wam_description/xacro/wam_j7.urdf.xacro create mode 100644 wam_description/xacro/wam_table.urdf.xacro create mode 100644 wam_description/xacro/wam_tool_plate.urdf.xacro diff --git a/.gitignore b/.gitignore new file mode 100644 index 0000000..c1edc29 --- /dev/null +++ b/.gitignore @@ -0,0 +1,51 @@ +devel/ +logs/ +build/ +bin/ +lib/ +msg_gen/ +srv_gen/ +msg/*Action.msg +msg/*ActionFeedback.msg +msg/*ActionGoal.msg +msg/*ActionResult.msg +msg/*Feedback.msg +msg/*Goal.msg +msg/*Result.msg +msg/_*.py +build_isolated/ +devel_isolated/ + +# Generated by dynamic reconfigure +*.cfgc +/cfg/cpp/ +/cfg/*.py + +# Ignore generated docs +#*.dox +*.wikidoc + +# eclipse stuff +.project +.cproject + +# qcreator stuff +CMakeLists.txt.user + +srv/_*.py +*.pcd +*.pyc +qtcreator-* +*.user + +/planning/cfg +/planning/docs +/planning/src + +*~ + +# Emacs +.#* + +# Catkin custom files +CATKIN_IGNORE diff --git a/CMakeLists.txt b/CMakeLists.txt new file mode 100644 index 0000000..28105dd --- /dev/null +++ b/CMakeLists.txt @@ -0,0 +1,17 @@ +cmake_minimum_required(VERSION 2.4.6) +include($ENV{ROS_ROOT}/core/rosbuild/rosbuild.cmake) + +# Append to CPACK_SOURCE_IGNORE_FILES a semicolon-separated list of +# directories (or patterns, but directories should suffice) that should +# be excluded from the distro. This is not the place to put things that +# should be ignored everywhere, like "build" directories; that happens in +# rosbuild/rosbuild.cmake. Here should be listed packages that aren't +# ready for inclusion in a distro. +# +# This list is combined with the list in rosbuild/rosbuild.cmake. Note +# that CMake 2.6 may be required to ensure that the two lists are combined +# properly. CMake 2.4 seems to have unpredictable scoping rules for such +# variables. +#list(APPEND CPACK_SOURCE_IGNORE_FILES /core/experimental) + +rosbuild_make_distribution(0.1.0) diff --git a/Makefile b/Makefile new file mode 100644 index 0000000..a818cca --- /dev/null +++ b/Makefile @@ -0,0 +1 @@ +include $(shell rospack find mk)/cmake_stack.mk \ No newline at end of file diff --git a/bhand_description/CMakeLists.txt b/bhand_description/CMakeLists.txt new file mode 100644 index 0000000..f8f1c9c --- /dev/null +++ b/bhand_description/CMakeLists.txt @@ -0,0 +1,30 @@ +cmake_minimum_required(VERSION 2.4.6) +include($ENV{ROS_ROOT}/core/rosbuild/rosbuild.cmake) + +# Set the build type. Options are: +# Coverage : w/ debug symbols, w/o optimization, w/ code-coverage +# Debug : w/ debug symbols, w/o optimization +# Release : w/o debug symbols, w/ optimization +# RelWithDebInfo : w/ debug symbols, w/ optimization +# MinSizeRel : w/o debug symbols, w/ optimization, stripped binaries +#set(ROS_BUILD_TYPE RelWithDebInfo) + +rosbuild_init() + +#set the default path for built executables to the "bin" directory +set(EXECUTABLE_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/bin) +#set the default path for built libraries to the "lib" directory +set(LIBRARY_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/lib) + +#uncomment if you have defined messages +#rosbuild_genmsg() +#uncomment if you have defined services +#rosbuild_gensrv() + +#common commands for building c++ executables and libraries +#rosbuild_add_library(${PROJECT_NAME} src/example.cpp) +#target_link_libraries(${PROJECT_NAME} another_library) +#rosbuild_add_boost_directories() +#rosbuild_link_boost(${PROJECT_NAME} thread) +#rosbuild_add_executable(example examples/example.cpp) +#target_link_libraries(example ${PROJECT_NAME}) diff --git a/bhand_description/Makefile b/bhand_description/Makefile new file mode 100644 index 0000000..b75b928 --- /dev/null +++ b/bhand_description/Makefile @@ -0,0 +1 @@ +include $(shell rospack find mk)/cmake.mk \ No newline at end of file diff --git a/bhand_description/launch/bhand.launch b/bhand_description/launch/bhand.launch new file mode 100644 index 0000000..1875c7c --- /dev/null +++ b/bhand_description/launch/bhand.launch @@ -0,0 +1,5 @@ + + + + + diff --git a/bhand_description/launch/bhand_sim.launch b/bhand_description/launch/bhand_sim.launch new file mode 100644 index 0000000..09797be --- /dev/null +++ b/bhand_description/launch/bhand_sim.launch @@ -0,0 +1,9 @@ + + + + + + + + + diff --git a/bhand_description/manifest.xml b/bhand_description/manifest.xml new file mode 100644 index 0000000..80a2f17 --- /dev/null +++ b/bhand_description/manifest.xml @@ -0,0 +1,14 @@ + + + + bhand_description + + + Walter Fetter Lages + GNU + + http://ros.org/wiki/bhand_description + + + + diff --git a/bhand_description/meshes/bh_base.stl b/bhand_description/meshes/bh_base.stl new file mode 100644 index 0000000000000000000000000000000000000000..dce76f7256e7f9bede2a453a9a408c195cfec7e7 GIT binary patch literal 143884 zcmbrn2b2`W_x@cZ$w4v_BxeyM?@o6Mm?h`5z>-A;$&yDr+gjUqq|pj##ykx!HT*b; zz@9cWFmlw;am4B|MrTi+Me@oSkat4Ldu{K;)48SNzSI9uahP7osJZmaA+PMeUP|dv z{9e5FN=J?~W7M;ka(NQ{k%F*@H~>>mteFQ zle%iDujs0E$d=BDNKj1Ll7BuZiwbRvd`AK;sZ32?(I_$EKmsk9glw+c82U&=O2Lk(tkLCP&KYPGZx=@hQV+|Doc*R{DC3#!+QO6Z^e~ z{SnN3rI6|>$%lj{%3c1H&Lv8qH)TnGoyWlc6IKGYTW$0A3szur_-TZ6N5kx zk!Gw##nZg>lqbU{Z)KjAb&jc+63Cgelv-7yXu90FCO&@TVcPMM7dq_lUFTFO`s*82vc97 zU8KL9@_UN5%QNk( zfrLcO%z(5>$b4nXe8nkW;f#a1#EirDD@FrbA+7SRO}UryE=G%bNc*b{PODd(w~;_g zYK2TI89}QhB(N3sy1(jE>k|58IDb^_ys#CH7`4);wJ5DJ93)T=X%z>p!c`o!cGfEy zw2LEDt&nMNAZYD_1nMFE;B3%2Uvji_%77D1B9vvW)=!9^_gnP1=$t3(7OB=o{X1hn z@6Kdf`^Sj*EN@iQpVU}0!qUgFG-EACKE&7W93xu3@IlJf&7D%nE)l4Qw9??DvAA{r zib!B9eN2|pjw8$4$KnUish27yxgyKH%}yEpidb-AX3D-cUE(QnvW1Z&t>Un~IO35& zPmngfqAN$POH!zR-uk3cf1lwIy6%2%S5J9`t&lb~j2>Nh zEQM&&L)s_8bk1p3lesoktD->rgggif%6)R3sC>tm0yPvtGk{ztDh;I5CcJq`5lE*^ z&}=DJ$cjKZZGvWGnVl7ZblL>=71Ad0=f!RIm?p1?UJ(|;Gl(O`Bp&o{SkTHM^Rbz# zcOU(;NvP1i&Z$NWW2@hJ#fd+(mER99OQC%J#_6LeG@3q9c*C z^|4QciNH@#11HwcZ>;XlV~;NzodU&UZ@D9(|=k6qZvUHCkkp4f2(Jhnr9zCoGq|+v_uYLqNhUi+`*|DOQxcPXY5S~FCF)@VS zUD5L~F#pVWy0-5<)+RJQsoW+yHqUv5Lt~tUuVvyN@93CJtu_qmw24LuwnEw$P-hU& z8Xaprq#5hBsJ`>w*k^d&s+Annz?e+pfl73g)GK;e#ewS*(<@KImKuU={r+O7c!~pC zA^kvsMk0-j%@6HS8Z@r79?~X3BO~tLb&5bbZGuKdwu1{4f%N}D$dPew;cP`9oi>5z zfX0=kO~O0pwmj!?v3;e_ze%v@NOa^#jL?Xq-5vEV_9(6Z&A!4OB@gvZ2x&iG*)m_n zqXv3t5)V|&wJ2rLvcsE%XtbMNd3o27c{f7&m3G1u2ev|*F>kJQ+wJHPS%47@xmRq`rzr zLfeg{)fp6WwM1tyLMs;9<4`NKixmsTGn;RVK(QY=yM1A$893VXpMq>A*2{zS)B)1A?^4-vFxq{z)U zJPn%91=*tYCq<5}kd7KB0n(tcbTB2lBBPP0^^o=ng49S{GA+95Lpp7O#?r_x(Um2Q zL`|nn;5k6rB)oG@tEITu$o2U*iD=XmPgvEdWnE0|CUEZ*(^t{4ORK&JjZxYIQtx6b zq{;S!Ge~t2dB0X^cokZ8jI<)W|AkeBURDHCwL)4o4o8u&ph}9YY^#xhdZ{#g0`~w& z2NIHsUW0m{fpppg)rxf-R1wxaor<6^lm=Z<2fmN4+v)sky|f7&uSlDOm)mLQ6^~~S zM~q2$GY;(sBQHGW+y~ft2^1l?Hl(qcZhf zGEJaeq#28?@5(#wDHJ){#c`avW~m8^N$Vk88ml7EF4lm|Cu@*E50O^m%D+G8Rb`b1+Qn<$ya$N{ z>LIPhm4Bbpt1c@Iw2K+lyqAgu>LG33;l-;K?cz1B#+84E*Q>EBuTT$Z^G-EtAZ-%a z20mxk$uY|L`}ZN`^$d{v_&7@+)7l5~JmuUwv(ujwQ5R{qHpL{mA{XOBE>6K)cin zdiU!0t{S`ARxCk%r7ihq&>y>0RU-oJ(%IDeU4N9Qv5U5lpb?`j`6JOEyHx8V4YW&y z-XZ&h8oOu<2|Cu6e6RemOBG1cK)d9v-c$RLtFeo=kf4~fCBJw5u}hUr(m=b^>$)cA zpFuTt(H0VPHnpYb_@H$t9cf#np^s@~VBOCjiHbm5Na$m-qzEoEwb-*i@5kB}eWH&^ z1M7@wdxeBPj%vufD`eiK$m>(}l=_`MLAzM%RlUn)-lg76LR(0nC3Oac%)4|3?%tC=oL6(kMwrTS%ZKH4=r)yEGEx$QE4(q=9y^p6nAe+LO^15@^Zyims?Q z@`SEu(m=c9t*$`(k<(S1jJA+KOMdTCW~fg+N_k0XfL-c!ox9Z7r87v`Ckbt#CuoUA zNp#$@aQq5wi!}7H9=i{6yUe>Z5}o>A{Zbxn#S-KdS$Z&b{6wOG|(;)`VO5>_+wYwLV}L9CEqK5>{11aG|(l=7cLDTs4rvou51`sRJ^MklNn|SZUVNicQ4O?9cTDtC3yKIw zxv)S2Jw!Tf4YW)5iu65iljty@Vd%&5LzKVRitc&o`(KI(N4c;-0zE|9)cB^@kWizs z4MWr?XczBhrA?q7(moNUytQg#!%({XLzD*E#d}jeArDLfJw)0kl*YuInL`D>nyfU? zF5Wlt38jGqdWf`7C=Gd@TOrNZysl%N=Ho87T~2(H#1(LiTX$yIj6gm05PB89xdR!IACSTc_KNT4T3n_juY zCr7sYl{rMch~vuCn6$sWowKvPVS7D{O_duOSc2$Waez#{LKoboQKFW#4U` zH4Zf}CX+bStEN-9Pfh3XPqNrZpeHzvO|Q@syn>NtEPsY9PQ{yc|>@^AOYIWzMwP4=?0(m=b?lE1=HM4U&&A%S{GE3dfcl`GY0u2mXn zS9<8LS5)NOi#!gA7(MXHJBMK!SMp5x>k`?!AvuoK6=iD3^C7(RktF+_RvF4GY=yKs z=fXSZ^^rgik@m-x@=A`;ki53l6(z@RNaik;uS^X&+J!gTlRZLtg{_eGHRORAIqD(J zn7lrOcYScLuapMHWD@c^7v6Oqhh8CV5}scwa+zg9GCQkGEwfKZex|as8HdcfLgrn{ zSCn^&P#F$eA?+!szrq5eMLnb$lUY=FS+qWCU`!?MY-K40`yd`Gv=K^;bm&NCPH4O z_D3aNH!APaNaSAL^$FB7z4FGD@ba!tpj~f_sjI-hqJ)=4DFZ04u$6apd4zY>3NMTL zgg5$9(S9xwUKXXCp<1C`FRyqSGK*5a5?&Vd3GdoYMf*8Xcv+P8oT?St_41>q;pJT- zD2w`pmlIRber_kPD2vh>PPIb2(nEh8?9U$*Ib~6wh|x>Y>v?~UqTZ#PNNZ80fp%q2 zNA$|Tp9kp-Qcm;<)I-{z&uLsyhNJb4(m=a%jQMLjm9J<%r*TF3idNx@Ks}_@Xs2}v zjdsdcz6R1J;jORe8l=oXt4VbYB5iv0Ape9#*L3G1)23!{>57uqAgw=DmhcFb#~!q& zOx@$%X^|~mN?6`??&~4#6Ja8Te0w(1c0~q7U@O%233*@=sE4#k#7Cw@%C{<^;y~ZM zzKW2yX%pxP(rFWD*Bd1P8abBlNZHf4s`3h3c_aUS5Ev8ErdLJwl-x8Ve>J6ncD*Y& zKm!T%5NT86#lN@5Uu_nR1MPa5=z&H!%7q0IsE2gg8fe$cs1Gze%+$bEUe^8}1h(>K zg8)K~zK|U4s&}y!&WXyQaMUezefR|S0@7XxQIM`EpFq2Ew9`zju1AxQ<259&TFbj? z{Z?}9`ZH?Oc$8CDR7hTfDh|~9f76gxuulgPVY+JNcn!&GP9h&7i}O|51h&HYDs2K=;e6#2VLBf;17Ith z?R-KWm<09$(k8K0W@+}x4mERbZd%n%h})s&zELu>Qp@Q4akKq6=hu=mte-oN_(XrQ zV*XQ>KBiVkGiFQTm4P$d4<0L%|_yh@TrH{#yA4ixXN4sY; zR&Z}Nc}it9)2p3jM>;Eabg(O4FP-EODP#*9vv@{a4pdQlFtF_bJKRb+b-frGM$;;|mPgb_0`-tq zUUAQ>WN%(l8faH~=&x5)Z!n+2OJwjcz*h*fHKJ9DB1GT&JBS$@?8I##Zc-bcoH83WVc%Tv% zGWS_>mQiuYTw+nyraW(YC9{w4vX6}#*b3FOAkY-G-0ED*!sE-;LlS#;RiI8g__jhYWd96;lT_1aEA3r{| zk|DzCl>A9~)IdTXlO^9P?yXDctf|!!#(`&6txKq{XnjTN5}!c3Nc(4yd#emO&mnJ> z;g4e+Z;W}PgwqNDHP939oGVNI6(zj+oHCC31npv0V$8eFInA}+s7^(A*Py52T~VCo zb5utSwB+Y2;myvJUoCHT_OpbSyVNd2&9#&h16T_X-KL`=t5n`68B1Y3Ed@_!KMA=0K-ceZ48)2+XvY@uE6>T*+`b0pA1 zq)m?x@J-DL$IFLX+q)m;^RuN0|h+eg5*INMwXdr=lNShjiH=205yu{k~4B|@OYIO^evLYlEklIS*ahPC6DS2uf~#1nyfNXw_ZqZ(?qLIPXqW3uFhAU&el0PSKH zHNARG?ust&?Z7(>cy+T!q>wFag|r`sE90n#1bTurW6OT%D?ZzBlvg`9KFOPlBBX(K zF$eo`Q0E$P;7o?J{I;yz*M9PRM}BEmhWe<19-2hrUya3%o<&5a8Xc14SaNB!lUL{o zW^KmW4j3T%KempilxpY7vEo>z~Ca;mz?~mLpGiM6rcJc~aVb+%GcDXA`mb;=OcW>820`-uVr=Ta%Jb!mo29KfG!K#n+QqD`2-hR(A%S{GE3a(NtIbk9o@P$cK)cdIe_m0MTVCY# zkciRqXFGL19PfN2$$k&fN`^GhE@o|YK5XxNxbhr?XqDmhuJ0kzYLwXCD5-}UNSlNl ziHsxZRR5PcX4b*%@^Ps6A z=Rrr#gEW88JV=C^aj+HAe&q5%?O6QCQ4eXxZq9S9R-gtFXvz1=_U2kTYib36cJa)rxt98h)(kY)`UKiV+UzU2 zU!p2`h|Ym`2Gy~tA!lbg=e9RH)5r)>N3e2$T0 zD{mw!Z%qxki}Ndx-Zhx27yPT%@m2toWt1(97HLxhqeVTW{p@4Y3c$OzQ)zga!HdJo z3^uJYFhaD8mQ1hYPSLM&dilzt^KZuCWjM!MW%!X}E2K>gj288fHVJIyWoqS>sUcS~ zl-nI|B}0203-YcakX9=hnm-&`$zU&{U2ir}mQ1hYj@Pf&dUI5OhFts5tmb%YADV@g zE%XFwQv)MMJ*55F*`d`E`irf+nKK{`xkvUZ!rp2?#bJ6S*H<*3JKp-rj{{pFZN`DV zqaM;GfvvoCiSo+SkZU+v$vEB`j#exxLTrV!zglu=4TpV#gtu}E=qs%6dMh&Jm8l_D zeYA#iyj34nKa?$Og|v!19F0FLuuhG7NT=ObNSlPW7A3D}_3HN(wvxxbx26VGon^n# z8eTv;cIkrMtX@sLn>NzsMrjL3^`|EZ(=d?oh{l!+OZN`C>ZF#NG zen-V&dgbju=!&BCE>-SS9M}qJGY<3}^^o>=MU)xp$?JgXaH%v<+u!5RHRxi5XcsM+ zkz@5-W;@!ks#(p9!`t0aPNX$8RUnmD*a~Sga*P)BkoNbSl&R}ugxCtT%{Z{8FK05^ zN2@qYue`l8&78Dury8=FA+Z(GW*q1{>LIOG08|5@6+nGCdr=KJl?H07y#ejdY36h> zLbQvP%*e4qFXwi@zHi3i)fs37psNweD{O_d897FadPw{A5?Wu;-hl2+C=IkL*Ij-k z%&+3mI+6A`{`o)xEvfY`)s|?zTMs`$yK?nP6*jdFHu}oJRbT4$b#!%Z5@<`Vkf}Du zX#L>nsa=Li1bC%dc`-$ZPMbizv^BhQkjk!iJ_0oKy&G>89(!&A2-HA2?Kr$qqHLij z-Z&1>KmzrUHv7uE29+(e>tzWyb?+j9dPtiZUcOSc(5{zJ12m98J)}(yZ#Gc2(5^RM z1!y3FdPtiZ-a0|qLc8AF9-x5)>LG1vcq=kx3+;LGiUKu^4t zWq?=ST2y_4t-RIp{~)jzkT&D+*6qp`+Vyr80UAi4he#`pa8xPmAc1zheN@0T=Dk6HVk5uI`cc33;G0gC7UdX%jN5rO;Dh zq=7pN)H5~EF4BR7iUV88eD3etP|w#;gq$ z8ub+6{V(jGS4amEQYY-l*;0LLi!|hn>{mk2LuFpJraxf^JwZAZp_&sRXMOdAA!*2! zg&*S?I+A3NH)wSSuX*Yv`?^vTEEofq=Nca;R@M>Fqs z_;sAKwA+c$Prr_+pg*BEx9DTiKyAhjNMcc?W0B>jM^w-nZ+<({AT%9)la3~+*EG?z z$QXmr|4x=3Xdn^#bzC4pmL3q(b|qBQwlWlZBak3V4~S~4&Pq+(nJ_+(AWIJj^on{{ zM@xN$mKdx2{V?aouWjukub1PAohrNitlW{+YbF?H4R;odb(%QBIlL~tz5e@n8worI z<~hHUshN|Zq-&Sy^&9WLr?k6h>9ELaQUmSc&O(0kzV<+8aj7ZxFMl<(kw8798OwdA zoU>Yk8f6oo?}GhujXGI`gL*yXXn-cNjZY@g|?sq=B=!-Z{Ru;Gs~y8rhXssE4$C z15Ls5!r2#ce#`l!jT%Us1i#Zol&k%h-SyHncV}`@tMLc(l~?Eq?p_#6ITR8TI}~?X zS9zb8x|Y)#JAJnzP!DN&-+6C)Q8Q0^=gZ$p+NgoFN!&QmUwpV_t-UJOI(Ojla@K;R zR!Rds!5tD~FO_*&jHxE<`c*R7NT43la&|sELgdfb(Z2o7Gw$2zs#>kv98aO_gLZLG zCGXK^d|i|*+Ry$bywySi^^j()hJ2o=r~D?;)bY!bN6H;!q1jJvA`P@FXCHYbMQe+U zefslQF|6bwt89^W780n3G-JO?jbG&VipK6(7Ka4d#r2AO=J3P_F=0XnzWkr(-0Cv& zQ@xMJhd)!Zn!j?wH4$TxGh;=SVGG^AU+iQdfqJIK#*sb6>7;}F*2hotE(gn5pJ!?v zibxH#D`x|L#mQLptHVXb7yI#qp1Un1P!DPOiwKqKh5 z{L?kN7!%hpvY|=^rGa+k{NeBPH+Y7d#d!GTLhik-tCd&i309`$ntEkEr}l{~Vtbhq;Q@{gqsW*S*iTJU!m+(>lRvv$(3-2~W=Srm-`{ z-HXiB-o92&jA6ZZS_r#4+L`Kqr#&^zp!A1+yM{5XvA@!IzZKDG6W{i!qP)6);0>dd zwnW~NW%?7^i6QyJXz9RaAiQGQ`a{wj28D)@@;Q*?(;FS zufB-sD zpHArU5^uLgFw5u3uA2C%JY#SvvP`8E4Ojzjo)9nRg_oQ z3iniuJ+vj>Ej4H^?|5UdL10Ws%U|c37_w?S{|g`0wwFPmUEEVKw(3$b``)|x#nv5- zo#xkSgwmZWr@X>exTj+5xwkEA`i*t`aMu9_fiWR1f4SGqZm(OinE$xxHG@FAxTli8 zkvnLConhnOJj**Rouu8XLmA!t$}4Pzdn&o-JXzYFFhj1CzUylc7!%Tr&0e(LUfyya z@AYbX=kmorL-Id$MWJ2XQ_0^9`>Cb z554`WL7-jSQ^_66TMs)YI%VY@_cn9n2(e_ZDzC5=?vNPk^Hq{P=x7n%V(`lbfiWR1 zuk$g?Db)W__v0D~j=VPLm!LOMEkMLcVD-4 zHb$=3B3R{)_LcQ}Z->40yxo1%HoNVR%I?!$b4Ggbk$SZhp;l&JVedY1ExKliZRM?& z6wTO_gg#D#kFHrMNr(Nr0Mw(Xm$nARfvr$mj@?LSr+4j-?bbi-vt9RN3TfHCX&2|AEMfb(hTn7a9rga-G|+dGsP|kmCws=T_MKzf z?8XHOySw_VQgL|eXysvySAHO22jjq2NHaG6`xef?CEwUnYX88|cho~#-Z$u$+sS+5 zA3NX1Do(aJS0i;7{-?b1_8cyqe^bMEO0E?b-OKE5Y;i>Sj;)ZEE7nP_U2N5Ad+e?R zr`B6p-4Vl&DGk&^TJApNSj1jUSYqPM5aMk?ZgRj&I^w+=e_)M zBO5yubLsl<_JAsKGY-@^KX_XtG%9DRR!GYl@~sy3nYC-}c?J79wHNJ(bhw>MX`r5| zasGM%r@-^|oM~%0$NoXuB+~K<&y7iJt~bTr^W|&KH@vZ(`2nz7L?#dnbw7kM|V-joRn_I5Sr`2D4_*{~#SJsttlk&=|U#OVOIMUL8hz(A^o5|?eLJmvuSEn z9#@bLy?NhG9M{o#EU{LoVVR1mue>Uk(o3Zgjw*$nB}ZC@o_#1fO0X5ujBQVx@8+@d zIp0obE--S`L)whv$$rP;Kd4z*d4e&eO`umuo5VY89)I%PtM*mV+R0t!i_liLpo-k9 zIx0Og4(XR4`3rCF3QaDWBULM;8JlzCRi5&8Zs*3(7X?O(dZ{$L@Wala)AK^JFBMT5 z7*pB=dWEz}49;|ocfEPQZn*C`r&hh2p=uRws!Z)wfmNP2g4)D#o^W1m4~KR z7{~Gzg{{z*#i?2$E%$0|i;BZ-uGrsSD=W}<)Jt2V;ec$`)sp*^2F8?%@FPdBkT!`% z0|txkS6kUB(_gl`m9J=h_C&47OLA6|Yc0C}p;pCa92mL1v6A(6=08%kLYlD>m)nSg z)z`?o`lmQXi+X8mG%a1mnz|%GMUFA0BK*kFE2K@rdk3AWWXZL&`nyp?t?tz^tz^tN zJOSzeN3K8B`{80+X-o9)^2z@5c}3ms^Q;2fn+uFqw<5h%8sVr;*jZ&)wVHj{C^=RG zwIBFIULk?KU}}628YfC+UE~t`jlAcz^!elQdv==DNL{{EZ2zVk03yJHVAc3EYs`K5^7tNG^!Ey-VY z7@y1ORlSb&R_E3Ny+RGNB;R?~^;zf9G9U9D$yo)C4D2CH9?mcBCw;*2N<~jFV=$Kf$rO9(ntuF) zKY9ziCXhf&@>ePgmUWiSoXqo%t7}A#1X^OOoLFt26=!&%6>S7&9P|Y9F=MTNNU?7` zzl`_Z*j1o95@<=r@#P}>hyIS})V!d;SqAOmY$rEf-MiSIUERcwcjzlHpCf^m80%KI zm~-t=eeuOxOKns~0xiiIr{-Pj->U<}vWqJ?&id#Hu0CXLpTEmm)Ak5&a=4Gc`4tJY zB=6TwpKkyCYYovVZzUsgB+wFLk7q6B{`M&oyNe_UT)m(txPD}8RGE_2@>NWHSSUfD zIud9}R?l;mcRRJJ$tNBiWoV#XTwlv|`w@#*D}04dU63GfZHTRKbuOQoD7L^o^UpoL zpo|#@5@<=jMevU>Up(Y{-oIoQfopZNi~Ak39v-Ow9DINLqU@CpgE#8^V3CH#$B z+j!>2rUu%@{S{;H^-kgUH?QJX=64aecfwY<|77gK*f?I~qo;WNGsBEHkU&fFe(kP9 zywYcr_$&8J4YZ5Z!qYV7~&0$6yNT4Og zzF2gXUuM~O`#Git+Qq5}V-@1=^URmS?)PmI1Xet-m9BnKJ&3U??I!T!bvwG7a}77* zKmsl4c`$lED#Ojn>JApoMQB$aQ%x>y0_|!d>ea{l$~ZkbuCxlwZzS5aE9(|n)+d#T{*JE*wDXj@`>NQ;g*D>$@6}V=L5V z?4wIXowIG8cIr2FY_z+)_?F0>@p)Vt?WR{7&n)2^7wzH8zv%2#|N3I&;of&u9M}qJ z`8JZ>8+fY>pYj}=x*CxqftDD{I{Q!CPHO99O?;QfwSOzpdw)sQyDzkv8JU<=TzO?` zoEsJ9xrUzQqpNgwF79w6O^fDs>B_-YNXs|fp1fdpn9#^MI_a`;22l@b#-4d*F7K3U z8{ePQ)rcHhp|;!`6j^H**zt<<>Ep$1w985~jO=)dYhc`A-FI@)@f;IpgBr zk6eGan2N(_1vFzlA0Nag_V|w1O6h7ujs#kg>yrG&<$P-dT_C)^zq(uuW|J2~@5#6_|{TTXd}tqhtqThz&(`9^E!)omFB zMvi(&%a!GgDtvLjU-_YLx*CyVD?^*5&)nQ*16?Z)k!5tlAgH5G^HRg;@1 zBOTLa67xRl=%oC+Eaj&+j@O0X5uj14Kh)m{C`4W9jIS0i#H(2{(fMwt?!-@)PchRKWondMm0;B`FTJYW(OI}9hNj~@7P(JreahP7sZj;rXoi4pNa-xItQ~UIx!XH&sabPQ?8T&mnkKcZIkW;?& zc^7?0J){|1l&_n0fBQ}T`j1_WzQR_hEx!wpWe;EaYaeG_#lkk)oxNvSXyt+;Dh|`D z(vkM|+tY6Gegir<&lh?rlyiD16$iFLnz6=XGuR7?UFF~1>S{!e1X_~6bJXM_e|=GH zCo&?NSiA3HDDT;Hs&{7Gs$g=lIWgIyg0oe;k^>u%Pk^TOrL@ zu~#ySySH9&GXF7;W8|oZG-FSOU$k#8{h8k_+|7s_TcNhBI+rRh;!lU1kGj}4+AaL* z?NFS2Qh`Q^>D7!s*V%by?&TABduQv0Lm?+y78M7!LR#)|9(~*HxN$$9_+&RDawO1_ zeCj1%J@L`dB2J^s>v@kB`K%$MlhoR0`K6rJ>=nC}SEk178;9)rS-#}yhPQVnHoP60 zn|N8xYS;>CdM>=WC_A-)^F*yv93w|Pq!}xi>0`U;;f?(MfNneHZs>fMSb%2|uPYNfm~HTn;@XJ7rHDStOd zd#BaTN37Pr%~D=rE2QNU@e5xNWj1ZFOYOR6oI%t>TK;P2`$y~%9}eZOoa<&pj;&Ce zvCZ>_i&86Jvd6!1&O*DFW!*1xgX1YQc1^F|K9k8w|LK43>`U#O+OL+i{(a*a6$iFL zTGrtTowYNMsLp?_m}o?f1X^P36Ip@e=@+Rzn6B3ScS=3=p#F`#GBuh$o7GwMPbGKZ zp>|H55|yobha)L8e_$(ZiD+5(`KGPt%Whap?q(Jkxo$;zNHbRc_GNp{vj^OCgA$F% zu@!2|x7;}6#JY->aL%N9$Q+{{z=f7%yDeLVytJMmf zFRGpp@gqk|vZ{MGkFz27JgfR6EuBLft5|2AapEX)ZI_}&OY({M4A<>FlP^YWk!bW4 z5@<=TOSblQvZSQvyAB-T7@;Ppudojpo3=5FQ)yL2>$Pg_1=>R2k!I|v(^u`RgD*s; z)*aS`;OKE#}9gf8ADc5%U-u9|8dy;__=NdfqF>GYw*uZ&b?W` z@FB0o3CsX!7c-xHzt4d_&hKT`^AkT0vhi9&50RF2(Xrd@agBQMze@HpG>|rlekab_ z1$bq#;lIKHvp#x)vz`1c?8SAQ1v&DI$ntMF=2wgfX<27zGRwZ+csb8?vbUjuv`O53 z{2e=g&bDIzg1cSGJk7* zcYzv6o5W|MvhXT-GKyVG+Y4MfqbIm$kn7#Dt0F57+~#L{bu|doLt37}WuNl0Z{-m) z<*$w5?g#DSepmj+$e%W!`)Ysja`7cL?laIsq~*7M2NmbHlaBHB&-5}hkT!{v1#*iP z=hmKYP#@-9H*iG0wm)jYDekD-CIN&NiL zlVaVr9lT+!ECQ<>=m}PL%e{(JYKeCXsph6d6m z@p9L0qHo>myiMo=$Eq57qN{jR1C*7buQQ13H(%##Mzs`JL&BJlmd{y!^*!HHI~~vU zPfvjwNSg%BW^^}^{;%tXXKOupq7k2Nq$dyM8GQUcU;o%dw|A2SLj!$BON<3oQhysW z-mfP%EB)Yk$f!n8CAIo6vz4w65*=JgrKcu!w4|p!jA~HCI&!Q!Vk;d7X-C@!5xN!j zTT~;c_DY`U>R^89yBSAN?UlZpfvu1ZuDz1KNa*;;QgH2+KEYN<2iIOH4qZ>AI83jC zYOkb$t&k3`y^@B$iemdMxb_;Wp+|l+@}Sx)+12$#io^6OsP;;>uocq5wbxieU%^qY zf@-him98g}SEfc#?Uig{E2M*KucV3Sl0WoiV~Uda}=LOQtiN*a2$jO~Ts+H0(ap5dZ#1l3;2 zuC6Ci9Hv)6wO6ubwDM}NLeDo~Y~^8bP&JWeZvvbYSh3H1rB7 zwikkHudy0>RTGUPsP;;Bbv=>dFue+@y^<|#g>-Q3HI~q;v#3`=wO8^=R|m-}QzNMM zO17{S(!sS?($H(%*j@;(y~b+jm25PQpxP_h)%8S*!}Kbs_DZ&}71F`ASJKcs2s%bO zxb_;Wp;!IUID%@gWLMV{DGt-CpxP_h!d6HJ*Ir`@y?cpz6;yjAuXH_;yfQU{YOiDq zTOl1>dnFCMYmDuM;M!}fhTiE#;|Qv~l3iU-q&Q5kf@-g13tJ%_Tzicr^o}*^RZ#7f zywdeV^2*c*s=bmeY=v}i?Ugiir69H!f@`m_8hUphjU%Y`N_KTUk>W7D3aY)5Eo_B! zaP2jg&{c}4S3$K`@=Dhe$tzPMsP;;>uocq5wO7*6)uGs42(G=xYUqkiG>)L!E7{fc zM2f@oDya5Kwy+h_!L`>|LRY4uUIo=&PmNaZ3RC+T^2*c*s=bmeY^5uALpxWyzph2FXUU2QTY4HcGh|u**vJ_lV9O>ZND-n35nnY0Tl?e0%*AKz9S0XU0Ast+MB?7avNd(nii9kVe2Z*L_+x58shsPDvu$tz6+c}13d!jmxLAm4Q>t*43q+bgZ7X&phd z7G8Qu^u4uHXT0tAZm&A;_{UL=&wd*tx^+#@_to5ArP08u?#nB3MPgg&-lcyxHLyp6 z^r9NCpBW=oe3pT4IXpOiSBI+Zs+aOa=o4+1j!|1{(BEOPEL__y_++n?SOP7jP2h+@ zJ;tWizR$B{o8Z=Nl_1b}jLG!sY58H&f_VKfN%~ z7?q4Y-~AqEj~sUI&hPAGdAOYWW51!1te?o=8THUAuZqPxZq#j zA@3o##LExfY(#dk6>7`(M*Ww>S52Ddu1$W`h#U$1b|A83coo+E*2wUdf6gf;{qNKZ zjQ!W+9?w|xusb>?a%`o0nrK6VX-}|sNe^kGcl~ott&lb&2d@Nvf}Us%vSfJWXE@4< zIuFwOs8G)!0?#1PCIM&A@CsY$^Fci#pJAzXpZ`;JqWcBh^FpsEJ8PQ$-SEnfgP!Ej zanK!_G>O1Ch&G8JuTX>TM`?oo-SEoL&|c9u27(A8!w!8{Lg#k;-UMDZS|dux?;^VL zo26}L2e zSE$l&W-Fv+{uucocY2Sp4xJt>DC@VFIv_;0v>qL!CArei`vLzb_bBVhBGLB_Y65!! zY4e=xPbd!EKh#&IS2>=z&(F#@Cd9;nt&lb~bgOi7meH-~w*d5U^p^ypj5)5bcae?~ z2`9!l^YUcmMfWs|V6@mjrbf`X>L#max)pha-aZ&tMQhYtsWp(G-#S2AR%-*s6%l9` zd)??OKl@M~)Wm<@d`{zvdW5l{aW(MG=&Y|>Assxf$QF8{`;9CGk1Hau7mzmMVEPk^ zL-!B$mFZQ`xFU6Ig|w-mTP4U>pF(n9S|9%D-vl zX_4UI+go)j@(T4B`$=9=*UG(VwTmIJ6?$vL;g1rU`}C})*S>WAsn`7#vL*K)YGpYi z+t85Sf9O_7Gq(4@EPiM1NNen%Ah5KX?Q%Y zSg{v$zeNe}9EM}pKJrZ}?#(7orCJ9uw(EKy=dCNx^A9!)8&?^)vOrpolIU+#U4N~B z`^&9Qm0kIs8kc^9iPlsmvH7Ds&hnCP^1~lJ=S=&)v^)CN&=9@91Y03(YV0~y(p@rk zsIrTCNc)65Fjsv@o5a>*3C`S}Z}7aGf8gj9_JT=xDq+%SJMtm7-RPH12jw@KZTDspUvv>69Ri+V^iwsw3aC;RzDyz9bhPU9hk z+`pHvRvH+SNzCoi(E0t3^rB~u{T#hQ+9WXYb=i3&@B6t`wDRpzk@BrdsADsZFJGK# zpL*mxe|dX*=j)nVB2z}?vFMy*E2PcHKWKR=Qmf=W)w`&Nv`Jw9AZ-%IpQ+>&_^y~( z^wE#@nogG^S(n{ceTBVX5K68l$qKeA~?F{OceNc)652s_xL zNSnm>{qETL-%JoEcK&1?d1+=Od3|x^750KjG<pgtU5o>1lkogfakN;y zG-cAQ$|?@|rn*f-ne(*>r8n`j4wBudo%;X5`pEsE4$? zqC!pWw_Y4B3TH0QQ3GQ#35;XssBh!S`d`@j?U{a|DpyJ= z-{o5tLtDB;uXEF@k;{7XQInn$Ev6T7>~eSFzmmUcL2+O!q*WZg#^8<_LK!kwQW~g- zv`>&@4n~W#Nn9?o(@mfIHSw?eDMzoc7fgbTNB;{u*+(1>9d4OLc_rVh8EU&Cn%m7d zu6Ii2?^SwOT(4+3GdC;?y|uK6iX2-ZEvN*BHpdgzDCDpSk% zuUZqPL{|W2)qW^Bau&-kD-nZ?Yz z&p7F`9tzd1lU+rQF`2|?XA6r1zdR<2_ddnZE2K>VBX=4VwXRj3tsD7DfUKg(=wdW7NbHl>-++i!E%{b6^)I*xF9s>r6(}#NU z9gSWw-tdPpnS@l4G0-0~4t(dG=~abIf7q{QJ!n<45{>uup;zdwd@f__FLt9k)$PFz z5(RpKt?)cCmi?=2PVo!r?F*lo?*v2wEircdnZx$O*@oC3Hck|H*3d4FeEEjIf*G7X zwc6OXTemU1LIN$xXF0b=?6+=xXzys7C~$&d()nB<6GMvk|;2% zp7iX*2g`fg$)_TPhi7sUI&?I= zLIN!@mg#JH-hRk@CpgEB!3qm`DK3OsiXGX z?ui0-5NH>7GP1s#HIDDAaLdltvXkKz5@?CBLlx)nMlXMD7t59?a9@LVaW~1>Ki9(i z!xHE0F;_YnULk>&7;|4*$FrRI#QyTbZUT3WXcu>{@;6z#f5aD;+G~$^y|dvJ5@<>_H)_ zY>)h|v^zKFu+V;4d&erbd>i78JAC`3ymp4-o&Eb!bQb_yAuWGfHsdg-a{np3Qi;YP zyjOsFNXz$&F6-lLul*g*JT;%&wnSmK<+H1lS65yu?hrV?`L)ICmd5= zjd&%C+pN*aP;Kdzsqy9$Kk^sy&9+~f&{5DYSxp#qI7EGgt&nEy+Q>GJbw7uA`?ow6 zdV+dLGd8B5KcJkc`9hs&CwSJ|*`j_J^~(85-CMX~wF~vz*7~RT0e#SQh$@dPvK=WSvVmm3uxX zp7~;ud+5s@k@y?AEEl_gZ9+w-3<+Fg*0RN2BdR(*Xb-i%lD3j zzM~$}jKxo0XP4U8Uu@m9#;seTd8GfN<&{@&=W7^ww^{{jsr1U!c;Qq-KK=D{PNTl< z1pTsD@x5hK?_w*Y<*KikYo9Lis^~szzJ;Ek9@31xa3w2$>AT7HUuy;%8hAEMqS5Eg z?DZo@h>}^ixsP`^oKmwuRTak*pRGx0zOt%SSH@v_b$bI(~fM?IwF8!*e*dFSJo_H(vO071g`g3Teh>R+wj%Ejw2HQSoaFJwZLB89QCUcK7s|Z|7J# z*wDbUX%a;iZgfkO>?E2ergtuNuN5j+rlN{t-`{uQFUM7}O2{}&uNoxwwW=@6?$plP zR%HL~X#BKUl~f$q3TgRWRuR~07T~al-tO#dz+Sh9@3?o;+7<-Q12bqhwXLAE^f&eS5- zH*bu$OpSF@yU9Cb%*mYCRuoH^7kaXN5!Jic>TRGI3*B7D`xojUS{B%2W8|oZG-IcF zKVi4bd&*w>Tn|G7d%+~?&B-DTmTW6NYRNd-&Cuph=#wJZt&B1b)2qsl&anr)^Sk}d zl(wSR&7JZMf7w+W*a~U++klS@v4`B+ZKtc=!yvF1ke2r#uT&KM);Xfr%+c+h6eVVNmP2gy~xxzohaR;Hb=Wf4;8g`TJuBO#*Vj4 zui6y2Vvk-r)h<-Boyd{1u+?+sVigCrLR$X*;4i!Edh z&3rGP>c8`hzAcyeQaLO6hnAs-rB|j#_Lj`aUaGmhw?#WqW=3hNS%U=S6}CcJ{;KZ0 z&f=>L8~KS9n{A97znzCPW1R+`vderMZ?D_j-O#{ZFo`L(hlx5x`tbWVN^rD`-@7xt z%GC8Cr@_MitZ8%GiKUNKvYyU$Sv@<1t&nCc$Nmd;hHjUwCLeY;2Y{#6Sg*p-F0N7KRl7dU9W(nwTNE5(c!dP60OfDXwhZwt z#V*^E>zNv87uWNQ@ttA5p~&}ki%=H_*Xq~`_a%&dKQ1#rkTA*KP&)cc$~q1t(2{%$ z)Wb`7(?#3tult%BXczZzjMW_<;d>W+YQI{mi-Y?!Y=wJKnM+Q$;)(sb+D}%9{_3>e zK_Y>c-?JmbObxV)`*z0W47|t>yx7Lxm$i%fO>cT)i*h2i!uo@JVr$Ao z{=|&}b_V&Y)2NOF?(XGX{jYEEFH7dIhjlkK&@NV9g6lr?JhiTPoRiNa>zWKbpB!BG ziGB7M>EOB#X=tzL*whHB`%o)g@#y>eIK#u>x(|7Uo**4u_aP14yL60naNUPm>H5W5 z>6NJwRQDmTuocq5bsy5ulg3IYunTas{4>v*b3?3x({jS`Gby; z4zBxeuY&46WEWc@9bESz4Lx(xG19?xA8Mtm5o_gp zGEI%3x(|7Ut&k3``;dlSGte>8!F3EOB#Y3LPFte#xM1=M}WuC8Cyx*&fs#;f~KOu=;@vWu;d4zBwUp;wc! zba35=ywdfHZ_kZ0Je0pKA5ixpyXXnh!F3pn#29YiespzhNX>OSO^u14(nd7R-PV?lKvvWuP| z9bESz4ZV+w?S)pt=vW!oI>$8C>^?CD6m*x=$>D9tPKah(J&9nh&n~#1c3v zgX=!A1fKukx(^ZP3Fi6Wx=$>DS8#CMhX}NbGj(v?Czimh9bET`B``k**L{dUPjDR+ zT=$73aHbBf`@|ABCkEGjh(J$p%@|zwi6wAV6I}Np0`21ZI=Jo=OW+DHxb8y)+Qpqk zaNUOpY=wKO;JQyNfvf)Dx(^X(7k87vbsr+I74D;h>prmr?(~A|K185htRMu}eTcwT zSP2QP`@|BsyAQ7W5P^1e-G^o(#$F$L-`?Hyy0v?EC+FhAGS;E#&DHlgtIOZuIo11k zeE72oR+oe2tj{yG4n^d#eACoxbL|ra9P8$_!3Ob_TZLBQo9Nr1NHeyo<#oH_l&9?W zUF2^Af(F`sb9GUx?a}$3hWphSJ7M5Nd#l~q>6#&jRd)9dr3FZn!5jY<}^~IN%O1`(Y?<(CsZ<*QZ%Vovj&Ay8lDEPp){Zgc|~(k zZz$d8Ip;)CA$e&eBz|Z>#uB>!wbnU%-|v2&d;fht>bQ4**LSV8_g-u5;XKchiZRFX zPPe*${BqRodRZL@Rau z*3&(`i|Tmkd-vBCt+3VjoNLo>&|7JdRugWo?B9E0u3KX00~P{pLNt9I!22zN z$@713+ji__AyDqoUQegnZKxV^%xyF_NZs?f+q^|D@9i7I^o~iTMJsI8sn*-+3n!J0 z5xu9Vp!t%=-Ns`cun=eyqUkeC8!QY)9(dQ?JJjYtxodAfmhQ1CKOXHfUd#)=`)##* zaot{Cqx;YC>)f?l<{-8@GW%&;jcTiS3bv!qx17W z4o`EG;QXA05dHDmy*H@T~3WpO=*N z`Av9~%b9aXnNmLUQRW=6F8K6FDpIQ2&IDK)GD|P(Fz{`aDAK z{*TNLu5T56EBl9+H509{Rfprv6UDx%6C=vq`n&oS$_GLW9rq5oQoQk41a5LhlOCdT0=xrWZ3wq8+^4k zxa5KUVe0W9QSGYo!hv#+efLX({)7xg_6%-h?>LZF6-rX7~+LN__`(qM0`!C|Xw zt2>Q{J|!F|m-@mX>tl|Ux0UrKjoTQMI>)sTs3D@2da*OT$x-nR|HAEq!!P%N!^d>j$Ow zHEiLX{op-IQ=eRAAy7j^(~Nq5rThNN4c*HhA1aog>pUf&uz_;18lV;Azy{v3lkMD7 zy;@la=Fl1<1x4E-6ntS2S!7>s{Rx9tYuTU;#YWl?9rhDCw?>Om>y}gZv;6B$HBAQk#EuV7^ zSJ>r_YCceA)a}327Y>w*c~_|pos;f$$&y}`dN*4L9=lpYL@V|AiXr~4bG~&|ZeO_r znJV8*I8ZKTQTp!0PhN6zXO{Aob?R&(cn)d}5l!!A?72SZQGAd4LG^niCZ^7e>_EAg z6RDDEw8|f}xrEno&>a?nV~N%f(ey3HcfTC$II`B=bfk~O_Aj3-D|Vn<%y6XD=l2I) z-Z|;+Y2VdCa7@%1BAQ;FTfaNFX~{_U8M@`oIb-^|y)v#)E`Ev&eJa=G9XOjEtp>F2WNO)W!pUnZ8Q_jyhzv@ps(Vw4*8P3Xsa(>QP zm=V|t^Ocp)EriamWe%TrM!I%?0|<+%2;@VwQoo+L-(5UOJjtra4W579~unR>$grP~F< zv8GiO=i*?7aG+ewKDJhfKt4p%F3w-d+xkiErQGMYo^IgW_37pm_ZrH@>|<+%2;@Vw zLAaV@bH&Z_iAg9IvrnW|o1@E@WFn9c(Z+J&U`>90az=vfK)INGY^@N%99ly}n;sMn z_UOrX4+;m$#q48ig$U$Bv>A!Q!6Tza-?9$dfpRhX*jgb1`4DYplyL9}Z~EWb!hv!z z``B6`0{IY4w-cf&+@&hq+&t6KKxZ|~KDJiO&bRp)fqb@Baolxj{b6pNF#_dc_A%=Z zm)0NV2A$SQ^C8+qQI}Rl7Kh$F&Ezu~$EB5*xv|BqP!r5>CL6f4y0Z`*sreRKCfckZ zU0Ok!dt}@Sme!|C-$^BbX~$|8v#{@)YQCQ=2oZ)=3S)@ z_?7)|*Val`6O2GUL>q*wIe5LSIdne9yc=nCB!3jwK4wMF2;{T1imN{1(6s?0P%h?O zTPsB9>Ln9xdQdoYZNRNiF6Ld+A6W?GL$n!*g3z@AbD&(zyS7${Kn)RXW|VN~+JHGw zF3&EVcWtc@fqaNI>kpUKA7*{d94MEg58p873}kjZ!0a4G1?>+#j4dtVIG5$cJe9PVYTVc|uiwh(JC>(>D;Ws1c62zg_s?o+r}n>;9B}reiUmzcB#i zVjZN^@Q-uDvEMWfdpDYuKm_t3nm$|P?PB4V3wwk^K6*L*%;YWUs?9DG4wQ>^kW$k> zx-^`+zI|9%txO;S`4CN?EwafElIy4%`zn>5*K|(0)6><21Lb1nME6Td{T;H)6`w#KIcDGe`0vJ@!|C0+h0%Bdb5depj?i2x^hx#ZBEDFsc~b&`??-aAOiUiP4~!# zUEu!v;JEP6_Q`(w;iq$kR&6F6C>JXyxWe(Hhfe#>PRwpwCO*&Cpt711o9!8?kCNUbvv&MZtu}KS_)@Qc^fj6RfpphyK;=Zp~Nwhv&cCDp<98 zNkUDkEC}R7G<~;hv*KRsrCq}Y^#(e~foL1Cy;)~(f6w#6S4uYxUY%dYso&xQndhhp zR%i4nX}juqFCTZqZPR}C8}|A;G3@8x1%Z5sR_f)O>HWt|wZgHpyF18%XdChOT_e0= z=_iAOH@U&ryXrZ?@GioEnqWOgpVm{nySIPpnc?@Rpm%KtIS_3lCfxk6*Lv{rrAxbB7j(a@nX_te^9>xYP!p^G>E3JAFdVU~dS_hpf;0KCsR=|NAEN1#>!0i5Z8%!o+n2x6Z!@>5vwPse z1Y3@Bxd-_aDB>7&c&PWo^S#|>W#iA?3Y(f8SunyfV&ZXMZ3F zCnW`ee2Av+m1$hu+qJB#x3tzk2RRUJBcADB#y!?` z41E$*%V5`~|Kzr9)mS)C6Rc$ETXm~{;66ENkoV=OxBV5b4M;q9b6r6oAEK3dugzrl zme!-aSufn^AP1st#6rqA%j-|{HhlPf`l@?gPwn_m6X8Hjuv(_`+G!s95N+ z5DwG?>uY-7pk2q{!f|80*MIpbfe7S7v{GBCW|*~ZsJG$KR61-iCp~3sHQ_+HSdlAr z*TmO@ZKH>KJ@WP^5P^J%rhOl(eU2{d;axoL<#f|Wwxk`49Ex6$CpjFVz zYjV@u2}B?tqLsRZYPd=FxAQ7J{zUrL`ah*-UtLT%P%hT+^q$wpmxj4-wD&eIUy(qB z#TTD0M)Tu)szrZ(qmj3uPoMN@szvXc_NmNTl#5kA?Q(vS8`k~0vDf>vnF&N7AEK4& zMm6=(GfH_s9BPyvM>X|V_q`$PfWN*$wmciGX>-odX1B@lsph^7@itqsao+v85V z_;9M;rrLfm=po@ixwtN&`@2-PFRifOJ?~WW1R{_R(R6AVtytU!HHN0}TNh9+eglJ2 z`)U2ruF*`l;XTK#?`c3jM9YV;#(yQlvJ0F0r7x+T<_L!?7F<~rjll1QM0C*zl#441 z8*!|DHGlEPYeg$;h3kZ(5oi;lZNyc7l=a(oI3OG-7uN|zBTz#`+lUty?9Jlq*FmY=!HDq7i5lq6LwRaLMqB z2PY+}Ue-`JP%f?$Yz{=AhKRN~22NU=7~@6jT9k_`3!4KG$cJc~qhZYhiSXPD#152; zD+`+g5y*#Vn`6z=Vou4W`7&!!F0Msv4n!ayqHT_!XI|*^FTPJWP%f@T{y!YBrb0Pf|wpR2_ zm=1l1w5+4B6|P>2=0F5WvNyvW`NzxO%ZUP!=LklFdO`#-Yra;FySValK=6 zpe#h7BpZRhLAkizv9+SSPgMHV4W= z1WK|I_#2dqYbqN-c_~4;Rdl;tI(igac(E0wo!Qa8Ty-Dc1@I%Ec9uK?nyTP%fekLO3W7`jl&h1Lfix z&LD&X5y*#V8-d>;jcA)=aq1uU#Xrvt5`K5D`FX2TbFV9r-ZE~CQ~J99$n&0A4>>Kz zJ(n7G)mdqNR_dHjYkQ~HG;^QX>3V;k_hRZmP*D)v%D?SGX@zK|YQB2Poxkcfci1I& zSsaMA5hL2Ja_PTd?Gt^3-${lUR^ZEmp;XcMB9 zVjIYoP}`w7Q10*xr=+HJITdrTpU7Y0EB?*E**}O@*vkEF5NO3#ll1{xjtI6~^C6nf z?#OCw`R1!`Hmy+ZtsU=x{$Q)g`j9P01o9zTdN3sG1GXFyDEEcUx0wD{imfK=>D;-y zcW0|B%qYQDjMn`xeIAhYVmWdk0wo#CUG8&6=y8Q|*^V&}RftC-TTRxx+H#FRxrmlN z4|x1)%QXV!vfuu%d&QW8t>!txmh*2$2i0V>V=Epp1zNGyJmPhqYXsVaXtA6}yI78M z0_EcDQi`qS5wAzPwgWXpwCNAlD%5?jZs1r4eT5oQEQ!3!Gb+?0gAv%9h&H2y=ZD3C zXd4laUA80CeV{oCv&oEIjy|Flk2pr4O|~8JjAHLv9C~DA^3na0Xx56abWd?B^e*-j zz3mi51|B6LBG4v8i+4F*@z@P@-!ccv#n@%y6_4Fe_pR27$7?3q8dnwvqLI%;YM!;B zj>s$*HDQE~UDD^AKg4ph0}&|6j9rdbVh6`?t-F@XzS7avWE_rHVh86UMxb00*!f}0SLg-fT`Qk60(%oZZAJ;t4~s*OrA$6E64?%uoi&H< zP4t_YA67nR1lnZVQCL1_1j@yJGP72ErF)7I*a|&uA_I>Slg}BUM_(q|WHqr|_Y}86 zxfma1eq`lyEtls+CfdYAE1z>Kl#B7vL~5S3CZ96`TVZ@O`9my6I}o8`J4-T_bKEug zTx+GHHpWMjajbmK2$XAU#Z^pZK4%2V<=)is(ac)0oPWdFnGx6u*+ zi8iBMEXO&4a&dN~TKSw2*qi8SGfH@VSR8s> zW%8M^Yvpszfxgl|M^andrjvxo)NTY>vY6IU{s7;Ab0ASUw+j*?7xW=mq0lE1xq$M;zurPZyrg8KK8+ zCZ8FJRzBApoX?p9{buHemCqTWM`9-0%nxgQ&aF@`_LG^l+=C`NGXh(orwh;LjL@Sm z6K$f8mCv~q%EkC-Vj|BEv)a~jc_e0{O-!`%Ik!T&7#~ff=6GfDIU}$Y#z&Jscz#$~ zAwp*ZmSilq^10TE^SK_!yb|VTlX0wk&IpuiYgJf2XGCV))$!5HTCtq_nKKI`_*u8Y z_-G;nXHFR<8o~39b5thUjCL!Zb1RgKv&+OpE1zq*nh(*YKUgc1YX@I4!SWSqXuNCX zb4KX+!F=dxGfE`F>3(K}9#@%sX6#z|TyvnWv`uF0TKSw2$Y&-t9#@%s zX4Z%jet*HNn_bcs|cW=xo40H)Gez=UNla=XxCL*kv+~mCqT0a&4^&%jb;HnJkmf z%vz3D(u15|xfS=h)&xhsi3~E@xs^t+cR8PDq6^RGx|K%T9EIg`M(Aw7&o-j4eBSk} ziI%U>3&y)vK4*lEILv{bEKuh;(x z&f0xm@ag)3^*JLDZ6lr^Iyks@d?{~qty{v~Ee5ChO{!oxbpNB*>6Z6%wZgaeG7R`3f~eG`+R8Xq9_$?N#pBiG3^%MB9kM@;Q4HHDLtjT^?`J z=PvcR%YBY^AVOyYmPDU{J#?^3eI9b3-(O;OYI=#&DgF)0WnbyoC4KHup9kFMSN4A{ zRjYn95>YOqrO#dJ^MLytIS_3lsLuoH^ML#Oyx%9My4-b2v_egABIUWc`JWFt@(YJz=ZBXAa>wK(T(1o{dQ zD9J|PZ%{7Ic^mQhxZCr__L`e2vuC1{Tm59}p{~*MnkSE@&fWdA{M;at+~;++J(s6{ zgXlsL1Wktgn-S%o&Sefn7meUnUa#H4&aL!w)n+GCAME^LBm~$wEFvM{P9%IS`$NNNU8B7q#2?QR;Qk3N`t6 zy>rr|Mn^xlIS_$-h!%w5_`Ln8jW5nxC>$tvWcOm}llMkHHyngYhKN8uL}zfoC_%Y6 zVlp@YfqaNI2ztmKC54R`8^M16X5pM%9#`BShvr7l+?yJ0BXA@lx@ZKp;{N#8s^_!# zY!2?J^FNAOv3C!ye@zgGwh_pI=%NwaQ#pS{a@o6O54|TG$Y*n)TtpX*;GTN(ocBd8 z&-0e$KaQS(&*nh67P?3T_s5EbyF@Pcfqq6ln}bK()s-Vn5M49^H9@qEh;O8rT?5($ zOz2Z~stpr-dn>NU1%NX)pUrx9`WnuX5ZHP8r@ zi=NKjHK6sG$i-IZ>FiwtjbO_)AEM3L+3XtVRwy@K35%z*cMUXx!; zu9$;HN#-p*u^d}5TKB(MrJ7v>&4Gw`1u2q@Li} z_O5|OuvVH6(WXCe*C4@XDd;QI(0JFJ0`Ry%hh~{w#Jpd-6kA*WMuN0NG(}SM`Uh=nqch8 zJ_XQrAOa}eglOvbVDIU`W6trg@Clg}BUGg&5|+3OR_nVs`1w?a*D z)IX~No!tyzvtDvvY3&y)vK4*lE zILv`)GfH@V=v#UTM(EL($!A8QWHsGWnnTAG^qZL<<`jTO1|#&i%0!#_VNL-w0_9@Q znpw*|sP}h;16!e|O=RFvVj<8bM4PN8mg}Bk-BB*aM-vlye(2k6Mk}5ZnP?Led45<3 zl#B7vL~4##`V>IqVk?Y~CVzTBHGL- zE1zrs6c!)NtQE_-r#M?Of}eF1#rS95V0WFiBP5|hsvp~q_`+Qcg>pK~jei?PeZD=VLC zxjYgx(bl*!`J7wnk&%rksgPLIMDmz&|%**UINw6CH!u(>ivUjAP|< zMxb0P_SiHTM| z*K&DIWTH(>wDLK(Lb(_pO{C^{W%4;Au$9i7+&3nFh~;|3Wg>Jo;GY}It$ePv(s38# zqscf{K4%2VwYADT)#seS2$ajcspF%WwPHE{hO;FjuocEf6B#%gNS|v2dqMLd+KhH9 zpEC!_#o1+IqLt6JR+ zpH6slH3#}i+mwB(Pba*>p+{mSI{Q>#bMU#EM%$KWp6b&HuV{t+kFhKJR9_?bBu?`o zI{Q?g?o5asC>LW__NhLd35!;I!l(HVoqejWIrywlqisZC`J6q9nlOU%E|0hDQ+>^W z2%QaBQue7n-Q+NqYq{(z9lNqm_30*uAW*KY72V{pPW3ehpYUq5jmSLJr<)wYftujR z&py@H2tE_me2C6I)u($I!oerU8f|lAp6csa#AnbNZ6hcu#(&JIewMG$3%WJ`8=dOw zIf35A*<~a6q+0hmB5-yIA{pVLQ+=&FYJz^VIWT@80=-}(P+vr#BpZRUP!sGM8-cS3 zt;IQSBhXifKuIV95mzJvUU%KT(XVERo>UBNV z)bIE64w`qf>Mh;cKz>e#8OajP+xJfm-mEd&D^;UqV)G9TvRc{b0=<&ncfnh^%}PWZ z$Y*nGJu5%4pz{~Opway;4n*6C{~O%GKiq#sa7L#QmK~&FT5D))_4-%7Kjelh!t0t} z;g!2Px85^DuJHd{`@Us4qLm_qqY*!C&q)OBnq(nRQqc(Xo2^yJEeHGu+(&{oFFoiT z9_gibe^XQZ-u2j;^ulhJh^K9>sx+P!)K>My4$>;EwZc}2rq8EddzYUsH8vQ3(C%~O zL$ugYsIRaUa?@wZ)@d7T8kG#LI55(y+3kz;Uma95e%?QsR`ef_D_g5nzt4jouPZBd zJTv6=^tjel#Jg52Kr8jZ=_`W$AC3r`KL3DMeb$C_=iQ}+1Nkhpn)=NqKT)q!@ZlX} zEbk)PMik{;Y=zn?HFjh&XjQFkQ0eoLUa{MhzqZ#GX`WHsdyJA9W!b@2v-La@r`FF; z^M5=N*-zS67FuoD-89&@uW3-D%R`oTkq^;SGZf)nY-Mq)(!V|%wCSmWMh8cDiNTfp zH|sqqcJOTCerG#ut#}l&zt|4$J@yORfvpft zt<+ynO%1MERKg!sb+q>)MX_CbybatR9Nm83QGW^BVQa;6oTCHV!Lx}+Hrs)%5Utdi zwY~^$?~JOqe|~-cx@{Cmi39l%t<>ngHwMRx4f8LbJl66qqHRP`-o;j^EqyBR z;1$8BVJ(~iw~z2%DqY{t|7TM!YZW6B(Ht!B0)6L8WVyqZb3B|=(pkcmqqT^p?;aRF zHCTAoyhIt-_Ac@v+Hhof7h54W`Ran_f(J(__rXs`czs7z^2h%&JpnUH?69?pedR(A zCZGoe5sw&oR%*{ZHwHJ{Kh$}f`U7=GKAWQ`Utz1bKZKh;O?PoJSUjYyJK^Jz-huwg zf2!UWVn;j&3(+bb?P5nfszsKidlV&NJGy>!MeuN?@12&njJ14)d=^?2Nq2Eko$nq7ovbfbVSAXtrpZbVfe%^!L+HbvdhXXamjyS7{Cbm{_HV`}F zsP9Dcqrh@RD^+LJnZc=}Yup}nhk2DoJ(=!sXC>i4KAU6onB)E@v%0%eb04z2i)b5B zly|WeYAZFIPc@v&HJs`_V;NO^5<_Kl^55$ z1;2sbM8DYxs`L_6S&HS@3P)wp2;@U_(Fl}_S)|>}OlB+(0K${Q^ z0P+>ph6$=gg#+bcd@LGa@j>LX5!L2=m-qAypGj;-xtL1~BFR0-|M%+kUkL&=M6``S z4n!A?e1f3X{3q$fV=0RRxudqx-w}f5hah6hv(N^S z%;aD`jn2|4h9x~78595erN~A9;EL7e;1Paqhd>bg8|`UC+Xx=v=?xzU0?~yc2pY|g zQ_VjU1fq*ZpdCCvG`eU6#o7ebi9U}+v=&$1wjGF|sOC_$EE*zO5XlHmrz zun}le7Do(Aat)WD8cys$-Er^4a3q-n5oi;l4T2u*Ju;MQ@0Z0G;h_AQpz2k$viM*J z$#4jQ^0wKBLp1WycksMgJQ!T=q43qSJG;2QGxYj)=`qck`q%tto1>D4>Rxd{%jj7> zwy|Vz$Bgme%-@Lyx{Wj zeZsmEp0)Y|`4Fwt7bDgLpFDhDxUyxdH0q13keg0rUaAomuh=Gh>h2Rxyk1K48t1Pw z&hZ}_|3{kp+}7%@k7|aGKH4^H-Kc#6zsCYwA(~d(Ph1$@aLNtu&w17I74jikso5W& z7yi=o&hYr7qf)3ZwnA>&fn3)y?AGdn@S?-7IJhHp=A@ebt}7Oc9kx~n?z=twCw)P< zqIc&6ey<3&LbOs_9!i9BUML$b+ZMQ}JMtl#);O(Oha=B#5GG&jm%{HA!B)skbMWfA z;f6KWhP&4u$wdnhfs&N^ebm|YH zKVHwpZ-&8Eh*oOizB|J*i(d==Z_o!WT8n&$R%&Fk;bG7F)(0J198cjl!(c1qrg+t@ zOE}}V65;pj|C@_GK?F)tYUq@S;la;)`b*zGp1?h%mcy>}8xOocm&dMc$E^z{hF>1< z={Kv|FM;3GgRKy)RMR&7!vT-{;=k8zuZz|qAEN2|ysC~5?@Ck*ru<$vg%)BfuSp>1I0qwFX=eEp&wk3Ot2lcR{eu9;jDjpyLsQ9m5ZNyjja$(--Fez zZ}{4fb{H)4fA4@tfOt$h|4tb<&?O&X(JD96i}Ptkd#0cY5a`3H*$3Y=vm0DtGJ@ zPA;>?t?=9b=^hmCA|IladT!;Qa6sMvxgA?Sl7|*zE99nc=>vrx^9Yuws z`2|PQZAzAK*bZB(HoxSA?l(=m7W1B}r+>rW?4X|+foK}-E3XJIUv$3L?z_W!4hlyc ziR2m4O5NJ`&an6P^Srw4r_@J%v6X&iZl(I)Rx-Tncqeb!CBHeihr|(-=AqbOYt^|! zsc^&tcX&_t_#qcR>mFMnn!XRRVaf23l`TCUiKsjBA)3A~b;Y&e-Ye^R-svd`{H%M_ z-9}9Qqkg!)V{7lN9Ya&76{2m#$-1uu4IUrj4fvs@&b6|?Lp4L1Dh{#Swxi9TYk~v! z+~>X7w|)Y@5dm8vn!d@5A}B>tkE1ABi+fgxR;tFf5@CtaUA(UUS)GgDR)99yh~Z23 z27fde=$-hYT?(~Aw2h$p%BT9uo*L-6LA}mRYDockdOOGo{{5B7?3DNd` zBC@0IxN9ihb;!F?Uy)Btg&d=OuIH?3na_kBIumyJOc-V1ULWqTDLzYe=q%OcvsBt? zPSAOQ>~dl&+%Hp#&bA#o+jjYE8xhEdXgT3^>4ewi6JA81Tw1G{9X(m&(E5h|$Z9)> zR@(_)bJEJxp_5p7wh?re>h9gw)aA2OIx9%haXM#))L~tv;qbH}~E}e$E zd>W1%Xj3MdxV-h$bOv$dkLRF}?D9X?CtzF^sG2ev|VBwYR`4%#Wmp?wD7 z;GgNeEJWJ~+9}ATeFi}wx@ZLL6y(rOfgli_g@}~O=s`r=2s&|h>BQaT6L+*6J#8b1 zAQ_RE-6+wDcDWonyOmQ?+gEg6>(Y6x!{@cUpU-2Ky^F079h)HknB6GhhQNUvCNb_i?-9d-Wxvz@%{ftd=Qti@7b%IZ-kpp!{bO8g8MARL3 z(hyxJLbRe?PKVB*^~t!=P)?CuIz>+NDKeiwoj3dJI_zE41krM;@6xHh!>9U)K${R9 zbws3_u|u@N{Y0CC&V*e$6ZZK`IF_4ct*{lM<;2|`HLQitC+>(q4H0c?#j}Xc4MZ#4 zv$8qpgx94LUY}2R}&s5rP7X)gEd{I;R zn-DxxX}?_%h%OpIdv7^fD@5A}x(DFWJ%E7k0ifmRX&XVO$S$2C2YiYgM+5N{`Um&q zA`7$~Xf6MY;(1ozkk=L`T{_hd_*5S`P($QXYSftH4xR7@e8L-N0H4PdYJ$6Xa^mjN ziF?2&?ubA>M9aCeOXto3pF1N0<>J1doW44A`Wo=*Yn+iqD{O_khKkS69XdY``1~9Z z$cJe5VU*2^_t~~W$CAU<&vG%A=$~`!Vg&z5hEzS&)qDCY{!*@f=2nP~+G_;u<0tr} z0TKLcBMyDFV<{tAHmy)vBl^@U?&{}k#E}y->oB52k3Z{ZS!{k#B+znv)(ElO`@iv}H3uRR+$#2hJd5SY$bS2@FFuyG!h2fgMcM=*!at#Y?U<0=!ul7wS=Y{wEU zOWVN+e2zHAjeJNr4!&HWj7Bhre$GZ{Uv;{%#uC&@BQiA<&qh7i`uP>y>W;VSC;q%_ zC;P{o_QucYNGq}-Tz0|Z_5auQ>t+0#r;d7woZcT91Y3*fh-28m?e#wWedKcf4RU0n zHHX&h#l`Wsk~xT)=$~s}o#Z|be;=~sN!YU&)MW zKr>3u!6FfnNQhR7I0ELF(xy^9MA)s6yWA~9y!U?H5=`r%Qk28_Oi(yb6RHNx*}Z7x z##;ID>04|^fm}q>x65Bz#=HBP&f(lSkLMrdqhWbWMP(GWiO$q8?;ld2tUK z4qI-)y3O>U_f8v+qR^&AyrR>iM6d3M8&-Ysxbl8()o=-F#eJ?3wj{D6q&{amxX-!j z6AqM1Hkoyz8HsEM_c>R6u~r2dB3ir~QlGPTa}a^8kXw2%q(0{!RX9)+M(DMu zLGUQaMOlbINk%IkiQMO0w+jc#Wo-*)SL`dEA3Uy%R)|1J(t|S3pSi!x5_;Q#doT?> zC^3oKh|t;QTE zmo?NkJhJDxMzCDu)AuKgugpBx2wQH!TBKl}Us7T^Rk6Jn@hTUO94HrebmW$|(FzgBhiG}VYE*!D7g0SR9<4X8!tq_5H7MkBg;;|dD9dWM-2kvFy4ua`((FzgB zhiEg}g(Dt)a^`_@amT`p-7Ez1A=>7^a~0&XIq3F|OSgACzP*EILO2Jlxx)8kJh~?% zr(|@~B|-OyMrN9iIe8QIv}# zUv3C_bVJDF8$yUcK19oH5s%I~T|VdJQ)4=B6b_V&BVTUscyxQm))RE=!H01b zM*zR!RNJkz0B$-O}^;mLA=1GYC8% zMzm6N=gy-$cV2wwE^*!T3xxya;#`p%bRONH^Y{iG-6JyyCr7x*2TA?O5yQr$|*2SZHWFFrmqx)jc;*Zw~0{IXvchx+)tLE}uHM+57I1p_k z=pLCz_sE?19+`7->wdZHE7Sz%qudJf=vJ7^x5DUdltCaLqG{{~V?4U!6~uSEoK0=U zq?rTd;(V0*S03HJ%H{i4bkEB9Vp2|u5y*#Vx#Q*09j}1zc+pKK!+~fULHDmbx_=eK z_ph8YE3Fo-P!pWNa+}Jd+f)JHrlMO&27!EtR*LRMd2}}_oN?cLz8fX+itW(P99M7# z%S|VbZaRgXhEL_2PKE;!`k5usJ8>OKd30|njPETa!gDY1`8OyR=e*oP^5_;)7~ev2 zN-oV8%TX?(m7-fn9^FC;`4$r0JTeGuMK^g2H(CDY8kg=Ah4G!DMAge0idLuzMkS@_ zzK=`yeL}wPLw9@!F=&3(Q9txsrZx7M82D0SXhU#_H+hK7u2@z+b~3Fp@`2;Oha zL@Ra1taP3CD^3=UOoZk@Zq|v;C7xN`=+(bdOC$CV(wQeeS}XoJy+8Qo_e-kHeo@*aX6g#jLqLu3Nky`T99Zv{?^61i++O`w~ zwjw(Ww^GGA@2Y+4*?qNE#=D3>NwMXsdfh5lp1V3~^?}}@H+`Ug9$DUg?92xH@4UP$ z_s8j}yAvHx|5_v>+NZAk&ezLE{p+-7HRGrE5*2XxWG-|Ci+}v;!rv z9m+d!e(#lgU+ZaZClqxO$3Kq{-UZ2}jF>n$P1b&puGp%Cb#@o?B_hk2E~&7RM()X*~bnXMKhcdH4K5}xUQiQ1c$JnZT$`EoZ_7x)d+2)x4!GLTTF(z`g|k_yov&V7@7`f|>2a0T;|lo@t<g;wS6_EjP0_xm_|m>)D!Qhf;B?1k2J0d}ee3Vqf3o^|%#jlHgOaLJ%S; zLR77^;?j*Du3g5hwB?xyEr}6yL*dz%*t_N}Q`DWG(LQdUZ3iGMo3tG&sX1azN=n&{_fMzL0BjBhuKvW}dkQcsC2-3mDh5StDxUvkOR zO?A0d21f$tinb#e{xNpplJK=ZG{VfN40JpPe>rzST^fm=9*L|K_j9b3dDbVfO5JqR zy>wm>-LyboAwvH=8i_o1Y23Oze)%`LZyBNG^0PiAmC@dkT6=o5YXr(gH1~)8lN1gu z3+2Yoa;~b>gO|U)n5=er9skFm_|a&Sb-tIvd2XHmjAE6wMF6!lQNjeDU9fP@T)|=VvFF~Lkh_(^e z|283<{ll9Qv)fMJoo>1BR})LnSK5cP^7>^$cw*f~=dLY7HzET0m_wuOK97Hs)_p*& zbX{utNk)|9j<}MM-^7)SX{9Aab;+CQ{Gi&5R?gF7dU|WSZcLxO_Qymfg6a|@NvVrc z`N5X)t(=NudwOVx)}7^|q{#A<>o)pdcUo5)GcszTpQAn}OF}jO(*{M@A(qElNu{RL zX0qe&39bC+$&Og7tX7&MvOMlV|KV4MZA7gQZ6n0L@|QiM2+g&x9{Gua9;80^$a3fC z!Z94%V=F`}Mg8IN zj2cV*L4A;b8D;#2Xqx9QkMb^S_PD$B=Ju_S1JO1@TfyE%kH)JovBTDCU5{?wkQdJO z?(Y8k3jG_lLqBs5BD#QqIhvll)SrKFTONP2T+XJ7{(`dG<#}4SD*oT^?3ZWSRl9q* zcPROW+h_BqOSD|(K%4Z>&HRXoY&+r=q>gsHvXp0~#_Xx&E&lu_@9*WE-aJ$(mDv7O zMQ80b#Vy?tt{8J?x_|Rk zh`?6JZTkxQBVNmj?zUEM-}|cj!LjUHzS;h4VTM&p=>dlWTd1oHF$@_4? zpmoTu(d<$E%#w=MDp_;+N?Lgr!g10+<}{_Zox<(&)4wz=mFV?x3nwoq?xH4$R;uoz z?d}t!2YVm?`#-+(+1$j|AL}^9Ub7MJOnD-4#xh~>5&leZo7C%2#AZMx;j%Wl|Jl6NLVUu=bF zrH(jTof_LGcxR3oz8dX71WGDeE6n;fN9V4u2L99cc^7XzktYA7wHL7!qQ$!bdv{#q z-8A%|u^c5Sbx-rHe&vl5yc09uNTa^ULG~F*Nc>so8nN>E}3>n3_nb zXY0Km^gA`!`@i6D>dDXNrd!h}Ig3UKYJzCmtsQyYE~#)Z@8^n z`0(7bz2vmD=?^MxNiRKA&N)rmy#jb`uaXO<-SBjo(CEXp5g&QYBEP;OieNJh0sBF6T%vn%*t zHGDQJ&eJ<_=L`?e&V9o@@K{fu;<@2KO^}b?aBFa-tks;Qr>wiqSPkgssFESQyysHI z>lLwo1=T>5=cQV54^3$0aJ3ZgI_av<K&CUo_Rx?>ilNdE8VTMbB9`?T+~phfAv4% z&YNG{of_5DMk_?1B&D{uXy@KF{2lky&;7kqU0z7ceE%Y`9HTSFd76W3X1jBS?RCpf z?cps=O-?kfQB4qtwh^N*Ebj(q{^2&hucwD`7tuDNTDQmCTB+^s`WAgGtuU9MhNRW{ zJom`SJhxK2?iQl3ycp`C8^+^KHwLA@;w^r(%X zv6zg;Bh|gF)~5BiLInEF8oL$(*ENW?5jcLZ6{2kfv8Q#PqbArlf=EWVBwKC}XcMAs zjyl(zo$%hRFQbIyruB%);)r232ev{q-Q+mGyu0r7@9yCdJ-rMLGb(Ys(fP+2?fo^Y z@&$nzlF(_bp;9j|X@1^iqHWQ3U@IGa^w;bCFaDb^qaCv|@*!HO&(CS^>?A~WnjdHf zqHVq9{eqbib|Td|s;|AEL>Q<=+SQw(lAord*30h|WM1 z7_T#@^Z{kjH19@nAK2dAo|hlIIlYx%t6--n&HaI`5M4mP{egWDXX-*Ye!AyGQ1`jw z0qjNz2l@y33EYBc{Ut^K)HxU4VCKH z_e3yaUU3(^E0rE{#69Rl^W)Fqp9N)~nI<(u>>sIju@%mFdc&>XiJ;W;#a*rw5rI`P zqAfeZ6;*2aE$&~so_9Zn&cDdN?a#Rz_!+A~r3Sz8Ua;y^MfZ{K2Ur}aNjyTO0;IQ0 zkL?WJukN{(&*G@$=k#|j8q0E`e zcV8Lb%C8j7D1$)0c*MjU1wCT&xx^*1gR4v(uYjZ4eV@7YpP3e%OO++{Iq%%*=wn(T zTB()&PPpTrFCNSy%i}s)>_FX7lIWC-G)r>z%C(4SLeE??WNE0>je{R^=WN^_EToLn zglA{<0`i8($$e z?OCpQ&;4#^#o(o*12~HEDn)#S*4iBJ_TTN^@$Z4bz)pQE4n*4svc&i*&h%nOoJF-w z#&1edUE)$*5^yCGSM)ybMxlQY9rZ-?x7{DehiIjK8`H<7DkI=3W5(xm6SOno^Uege zLT;rlzxOe>@rLcenN($<7ZHJyY^_iem7KhkYQroqNM-3zWf^cS8dnx#xn(V&rM_~h zz6!X$LVXc|lB7=bsZJE{vW|QghrOGj6<4yNp;A&aIcaT~rhQSL_eHT4qGjzI z(AqiRwKF166GWSRpMdv$;=LC+SBo>8)QoY4lQPv(zWZfh4J3B@fG?|_ICr?-wpFeeeTD* zjy@yM3tCdN+NRy}fOgNryc>RPu7AS_MC+eNh&`uo4tI2^7;ap&`Kow_PB>5#tQqB` zA*7Rru-phbX^8d^1)=3KAEM=?AuKcft6&YCG#~=yY9B^BcXTQf(y2_?yyovK5P_}q zGxN!QdqDf`A@8@NwKz)9Z)Qh0jQ88kXh#G}k{w}(c7(&fX-AlTV{YTw@dF};nzHSf zL%Zi;ry;HAR%5}vK1AD*fp*V*+C2})gf}#_=Xn9zM#Sd^Vh744JNR@#=De*T?K-=( z>l_}VU1#bwb8``+GotCHY}Z%a^wal+m1(~nIS_3lh7LdAsxkw@_TQ}H(QY^}Ga#Qi z!3wJ$>UstBIiGFGxIzR?VRCWvBVp}?@#vhX+E1fkXQlGNHmp!IkgP<)DjU`IU$;&XwPom%!Ox%SCyXG zM9bn)t)F>LpiQ)*r_)#3JrC0NpU1oB!p;cf(?2&eiqAR2bC&(E9(|=-G1}&c&uje} zE6yq8zG!qi0d10d03O|d@b9D>5U7c+UYWy2@JNpSM4v}S@1@EcJoL7tdEecB|6I4{ zwOafRr$(4JvI|8d84oXvczS@T5wq2Hs%x767S`aN;on(Jz@19UHV|D1hTAjx3j z{wUDB0AYIp5hx2a;r`HXmKU_ow4D0`-%Bp=Li4=FVV%!ry8Q3g`?uwMzpAF+{J&!y zx?7O*!pJKA!~Vn0v&%~5@-zQjssFs$IP7#}X2AcRG3?o#t5#LWYK3T{Rg$&(CbwAX z@x9eV7Rnt~w`8h-!(a$e);}ZnwNe!Yfvpg2+6xETfvu36V#$rA!XcM`?SJ=7C(91x zLo~fd|4QTVor5#o8t>Y^VlSMXQ$xI9Ti$faknqPJH@oE?uaSFr%l@1P##Hfn{{mYf zTB(hbhlJCA+#C$^=H>cxp3C{_^$LPOPa|5X6=jEpH@I&FpERkJLIk!#Zlwl3JTu5^ z(bzlHxk>odrsY?qTh|fqR-W7Xs&}raC3e_aT|emUVAtxwUiV$6o!N66G6zcMTM<(bCbd#~BPLOz>g&#Kbl-Wi>}RTG=!{k-DYoMTtj$l^e5s*vv)63%^e zi(9kofE=_C<)S2|mRvj2ZTaJ6-u%T)!aYxI$vgN)G}>3(J1?(rJ1+WZv)gOR5U=s@ z+O@TX+=Kd==Le#d%AGO8?fYmG??|)8mUod4(Mla3ctfx=f2`N)uJp@jA-2-b%q?@! zqdDmE9K<=Xc=Mh-J!@^PXk2+Tu3R2h{hpqm*S%TfU2KJDnI9g_4~ORm&K%@JG<`zs z!3y4ik3MkKo)(sO5p5$Xe%;1hwEupu-0BhTy#BTG7Q7OTE40=|lzF0z_twcy-haGi zDYOI8Hi9CXM-eXI2sdr-J9(X3T`Z#=twoz;o_jRU1D@wBOGh|Fpd@-vm_`WA^ML31 zthe{%ZM!#`=ZHW_GHX4WwJy(EM4(NGHW7{<=831?`yw5!ec6 zu#IRkXKPN6rjd6)TH&@#E-ojYMhzu0xD**ejtuA%Y=vl>1EVwYAzJ2OKyxtUImlz_ zp|uxDR71IlmYC>LObj_DA_6r;w2bzUMti`c9iubKMQtVe1QdNjjy{M$K19>*;Gnl% zin}4l-Gj4h<<)9=vBX5w3egf1J&K6|$HWE8=H+#GCCVQ-#t=>4o3X02M{zggxQiT! zwhMTUSPL&%Y#{k;uy zUcM@_99!8O6d6K_3?WAbL|`k-kJh*f5mA_ikyeCBMz~~HSfu7w7>T56!x($cJc~1M?ut#s0TB5P^J%wmHy?C>KYJ;YgCpLPQ`RqHPZB50s02V{;$^`4FuX z*1LUQsp<4txh;?DTB>_^1a9DwSo)ee@|<1oQjNgbJ}0vkqAjhwJ-3&4Dmgub1LZbZ zTn;!4hT?Ajr)oQcuI`e&E+x0FYuoZIK_3kSVS8>L@R4T>ZrAmn_ak0bJ z3hUjUN>+39t!r$BXuIA;Um+i&CGMJf_nX`rj=ueet&rQUchN#bpd`EAJ$=o^PT#}Z zWh7EXV|viGL)W{H&0W7z|AzZRKXacW+OBueTI54?LA~2;^II#?LTsg)lg}DmeP?AhtrZUGL(|K|Vy=^)6bAXd8j`?x|fB9euMOt+f$Y@1h-u zwh>tG?z`$@=e*_bNGw5X(I&gzWm!7HAp#}Y^=^{-K%dbg0wvk?E+Wt-M4Jdl4|YsM zO>8>~Fm_DD{=j}JXrCEHu@#PK8{xiO(<%AgyW-uMgQ_?kYLv|7xPltm^)C7ZTOr!! z!03#8h_>rp9!s=xkQ{|_5pCDIh(HYyZP&XTar7ubxu~sO?;-;E5N+4Hx9qFvTvPg8 z$p)wuqV0P3&J`7$$Lh}$1dcI8+x0GTAlgRgdbeb)C?>LZbxhQrM*9lt-T&VB)=K0+ z-Su-6;jrGlwrn-0^%w709Nfz0z7^Jcx3!|7{LLARnS_4)h|*#SvpTlH{@w5y*#Vn*;j;+<7$}Mxcg>E{G+=zdO4gBCwTyj%F?IWAGj??`2S}oBQlNRm8izBTVlNN^ja) zW$rq+zodp}g{=^+6z|~h9xw0Wps$b*(Mn;2*l>%E$VZ$ z7HyJw?$SK>^!{#P{y|AH&*c=L`tO@%p0gMA*wr588LTB0ta0vHcjj`mFjFfnsUW^_ zgu@txn%H&}VC6{01IS|=v6Xtd)<6!x(7$p#Gb6`wFx#%~W0};rF zXqy9b6v{r)Jo zXR7#o>d_5c2g{DIIUl6TPJY968@58U%|V&j$U;6u8$^<|qFUFd2%RTYIG}9=XJ&o+ zO0}m?`A_yK5p5%Ij|>sm3hgsm(L>UsO3A0#B>tg#(Wh7_dl|On9M|>P9dpoplYItk zg=m`t{eygnws)hD19i6%oC)-4AAc?eMHCw4+=^+xLACff^#(){5!{pQ;Pd zgz5#KstehBw>j{(2+P%@9a|wfvbiwJkq^=KX$EqjO*R5=a&WIvy)JVQH99=_3O95N+?);u}>sqj2QgbqT&}g?xy%D*)s`w2i>C?E}AE>g&Be z)CA{>T{HZzRt;b8^&uak?Y%zaK(vj}EBZzM8{0s$bJo|-oEdQB7p%{pDECMMEY$P%V_J2WpuHkS_U@PoRgGe$0IS_%8 i41yk#*87|&7kkqngac(E0_VIz2nYHK3L2Mu>*n3;ovi1V@brpHajJ>bD zyY}v?EB5Y}?p%`Jxz9;XGMPyx3>_5OH>5;RV3S5wNQwW4KbACv zw4NAh{1RNY?9;3Jw6V5y>Zv-HEPJ=lwB_BLfnQrMmkKtoE&Q60EAt|aqve(LPl7Hw z22FC7dU8vZN+C^Lf1(U_5#{G52+PdHWo0~>cTVkxRhQY zEfeRPk1}e6&2!BDB~Xeyx3@E4EgwzT)CjRbjc~dM0 z#c0oN7d36o^n9jGCY&lx4Og^QURPKOY1u0z&_kpN={;|c-a6lYi}E#;e$JXowE5_! z%WOekiD+|v{l95oDWqAJyxgxV+kdl`ZX7B_j(SK7LSux56Hm9kQ+Ouw`dP3-Tw8fo z${JW#C)+rEzuo(s6-yy4BG*{t)|8Q>9@0OrT`Yy#qDRr)SD&uqJ*uDmm577)9M`qT z64@(^BhlL#?ZCgYN|7T?2+Li{a#!WKJ81uFp~3SN^<)i}iIiocm1iPGi?mFjR~R9d zLT?EPemao47h7Cr<)s9Dy)zC=+7nq#uSDeNAt9fi45Zh`Z}9DXB|%497%f^#ZVx^( z5c~<+#h4@_3JENQH6jzP$SpjtuoUL8L=YrU59yy1XctEeK}5O6M1tcW>d8c}Ll3kY z<2UT2bwUiRUGxfRp+RfzUs&$q_D;0U+4oBAt~~=nGR(JPDbyxp$AJghNo&Ooo0x{H zl$F;N>LKmanEPpJ{7*ClEfYiA3^k5kzU%!Z)iNDNIP?U^d8fwCh0Ef&Mo6!sDvQI` zq^V81f1o8NaqLs9HxL0S3AE%ShWP2Cu3SG61lAjRNC=PPo?0y~WgO@`j@nL*LBD3& z2wq_v;?97z?j)XssUi-SCpO-K===9XscX*2(RZX}!Y%(iFP4e)LfUQd^S|a3wVSRl zv7rXighZC9OK)|q>s>pj6g^nWLv7S9z5Vgz&n6-24QWF5MFms;uYJ|2Bs+~bQ$P^y z+cvlTfEG1ENWI0q=&DJN?9DD-)6grVWsM57gK^@ByY~dIw6t)gYs#1xmF)+c-m#(Y zSR;hYao-{$-`6}siW~|1usothitWi3K**lIj|#%S>Xdl*8F|G|9;nL$uoTjSaIYG) z8B;E$SM@6v6!h?B?utxQ+S)jtx5wBe)61d;mO`44TWeRv@v-FUp3UB_x(eVe=psa) zch!|>8$v1`b_im0jWOOX-vfArNT4M`etCIS5O=mr@oqO;L>{nY&vJ=CON3OJnv=(2 ztgg1$JN?xHJlcRWx!+0zT4J@^eTUF!c5H&TE5ZP%9}x#ya@KB^*lMD7InioQStTWb zmYjrj?)-S(9!T(v;WT87&~p;LXIuU(uS6-N3EARam(FZ>DIrITQZ!#((La=CtL6TI znNP@tMZM^}wf`!2FI>}jgsev?y;rrcVH?OT_^eAXZM~+C@> zdTr)m)gC)eX#8?Nk9AP)@uF>b`}1qA?aX#g^y$!%6An)B7UbEErI03MqW{!+yv;+d z$BHcBw*E^~P-vKTd6t;hGEpMN=@ri_EQNZ6c=a6N!8QJ!8S9-g4%05rD^r`0VS6Ht zG5@Sf+`Z|D6bI_b8r!!;8cls}S;ovdA=Oox2xl#H@b{AHjgZS%S9@}=rf9L=yNbn% zx*Bz(q#f%AX+rF&s|mtVBi8$5YG)ffJO4f)Wli&1cecmCev8*|jeEYa-dh*M2#u4s zR|Fu9dW4)gzg7_Im^l!pyOrw5UZE#Q6SD47u+cW}DO=ZpgJ){Zgsn<6A*V+S?l`T!N zRF<$|!mGw=YP+m)ZQ@Mf)%jwv-ql-&iBd~G7ne#QO-T9bWHoPdw@NaBtto4)h%Rc3 zT6rTN@$W!7|MyT)SAPyFY(L(%ztD@`T+A+O9I@RKJ*r_5Sp!QUO^9!xyRoF8)i&p2 zT`6+ZLz<9To9^hF+ow{-2lk{(*K`+NbzfE4KJs%{;nj2MBYDW4AdlV^UPTs?y+Tir zCM0j%bA3a{OSXP5yGfCw9@2z-YVNE5IUsE0Hm#aKTN^s(B$uzrrE zKEDv7k8MhTE_p~upE*N$Kc|0KWUtT@q}iMye^=wcpA7<5Ons|0ydlP2JD&kub&k8X zn#bGQWFk}C{k2@f`&5k7f>;V^LiTnIHabk}t@f;zU5W$skS1geyBm~oEbUR2qE5Imx|o|8X!lG(Y8x3<}0>i zb>6e5qNiDU2_lOU8_#{`cKI9*OCkOJjLh^3X_+{tP07n6XEV!q*W56<1v$-Y0qczr zzkqLqYd&b_USYIoDS2i|*~~KDH7`l7D^mk4u}u8KR*HM|W_WBoKAEB?*t^)+{xY23 z)o8x;vEm7m+vT%xB+ya{ubgw|@1o_;iKZn&etp_gXnZ;p8;{Q!=n0NvY@WDlmx!a$ zpK=^Xpd~_rQh5uFqL*Uh(~$~7ozF7RF5VdkxnwxK`ute-3JJ7CNUFqVLSrt|`25mW zXz)1$+QoYb8{ytR5yW-Y9%u^*v_!~;mvyx+m-ATuE+^lku#~J38vk7L&sWQT)s>#^unka;kfy%b>H15t z_RMF4C9m-LQzkrK52G=eLzUID=Sgo^Fqh;^WMc_E-?y`uc!GrYBG`+NCL}gv1hwUV zZGRY2P}1OpIr_*1*T_Gm2iI`$pYT%V8y2$%x7nlKugJEiFkH)jW`M?u#~J(V^o{fY`ikk z4vY21ry`64-#M_EjPG#X2aPfrCP>fcNT4M`@>Q=WG$tCc-uN7ab}^3$d0eKQAolK( zy+Q&lC68AI8?U_aDFy9feu?1Z{RcSQfjntZK4)<{wz4+y?#0B%`>AVfhEWtKMTCQE!9YEo4 z?p&jf60@eRA``aD!F1W3TZ+xuP_eOLzU|*1t!P}X~!3ivdw4A%>JL(}#$i;+U z`aYtz|6c>MOBxuHOkkF{?qte|=HZI#o}na-50_#hq%XTi6&h658uzN3!E=en!3p#o zX}N!(@2H0~YY+A=|KD&yRQ4IV)TxYVj^T7yE~75Pi$MujW&4C z;c=uag)||@*}ZmNnmEhG3^IYWAV@1c#Wc6^j3JKGp_=;S4g0TNQ=5M zSY0`IUGXu4Yw+wtyIAX@1$EYf7T$tLpdQj9uMCz~i9E0P*vB<^Per?!p@gt(H(0j& z@oYx|^^g{Q&|rNqk@rD9hI0)*;-FpZ&4jR#!C)hUg^vtKpdQj4we ztPy{`#2S9bnN=@VS~tKRg;`0+e4~pPcgr`7^)Aq$jEJLPwq6RB!i*tg^Z6!1qhFI) z?~nf#6U3c&^%PuPK$_h@CN&mBsphf<(lYTP=RrOTHQQ_wEv7$J)eybxZ6H;VO6yP=*Su6&%T zNFGApB;;=T{Lc0$BWoaydh8vUwY?y+u(zBwuJ;xi_cKH(=m};eA*GidbjFccCNL(X z2`QNLpC_-~#l2(#?P69E@+`BT@aiag-~MZwQNk;~^MMMM!mK3ZMYC*zc+KALB7rd> zO-QRC=UdJfDOLf{F7^WUp1RdZ4<5%?_GTO3{G%SyghXU(V)XA|DcAOK0cp((a~HFc zkOjjk8kOdU?HbiSfcC9dMy#t9&(ur7QkY|Gyn3M-qYD;RE2-WRfop6?vsL5?4|R>q zsEH+Ql4WJA?)wcT`DLSPh>XDS3qiS|X%Vj>%fj z)>Hk;uOBXHpk2%uLZE-VfzyjT4A!brS2sEFRNq? zB+wFHwQNV9Y{_ixxF`eFa*h%j8$txt#61zv`98MqD zRwibm)3sCV9TH!0%~s>Rw1S0eQ!LM$wxjEOGg=~B$X=l*Xo--RqD%OjJEK^Dyz*nN znD8e(StEP-NV@Qk-_>7UJ5;oVrI6hYNl1C$jwqFZCWCvn=L_kKOkQ9$U2rrvZo4v4*(w+n*XHLv+y+v$}V2WL59s-uSa@0@mO47{3s9rfB=+EvQNZSiZ=`=&AP z_}^;3YRkRr{}uV8IFjjaMAm!D91Hif_j+ApEFEecDRwdP$T3=6vmhj3#%X12^Broj zN0D^r%Lq|d!4-?yvEGm-WM_jj_KhpwD{qb^Ygo7j(lWuln%gLLLrSk)9tv6}e$NqX zq)t6fqj6ugJNewyzc2eKsohH`xLW|nM?w~MU0XKKU(4t6c42FnYoEskiX92Kp9N|5 zes?!pwHz6yjTlKNYK-iDLz$e$FPY{o%l9@AGWXufvR_}=*8NDsEQK^7b<+DA<JZr zY4%oaY-3|(>6wo9OA63~Z^Vqu7F?jdMDTl;X^FkX*=TIwQ5WvM*qc8oa&|dw9l;QP->ay?OGL*erDqqs5v$F!dY~Q2p zD(0q^boWl<%tsl}(`@FTV`mj`8Wz1za<<}>Vm5)^#2(M&~+T$0OZMdib--#sk zK`ezdAuTUl({G>cNW-?qY6}(>R;S#rqeSN@q@W(sglx@R#Q2ivL#s`&OLc{`Ox)l2 z-mxqsf>wxLpth@8T;(Iffu6aPm}buvbCi(1I(%(m*~gX3h?O!NORyBuggof~)bV9a z1bwk^hMJ{$QMF{t21?Mgd2eb(MS_T1b&&Of1{4zv535wB_lf_*Yd+i#XyveHDyJjw5~I zBz;b)!E|olW*TZBEfa_4EY$NY>`!kUiZa()|NV;k|^AS3b3jVM&=Z@2>J42R%WW?IZiAhkkS3NScuEWqj_Nn{Cf#RsSwa zu>ILsvi~pdQfKyx^;8_;Ft4Uxy`!|-SyznU%&XlEye&nV2!gHm^1HM6iCpSiR(gN63gV_Z^$+N76x8{;|u%H@k9td`>3Ds@nfaJ<7~PXJ5g7 z!^;O8kD!k9>2+ReYOe-L2ER9~M|~?L(-Bi9@A}F|hLM?d5>;n49~owJ_@4M?DKT3& zz0HttTB$$=-MGELw%FZQIam6Fq#;{M`q)h$H6fgCE1yP}BmCx-Y)M4TgJFNTzj@v3 zDve{`+0l3NnvXHOoby{8e!+iY`fHZrb;YkuOPt_;qG*XjN%29A>WF@x=Fc$2?RNd- zvCE`Q4fY1TUO0U=K1S!IOj}qAX+lPJS|Y}h*fUA-x2pRKyIN#l1@(|-(WWXO_I|`A zB*pt=tR#rPG6X9~%fy7$1;l=a)@SAM3Tc_>Gx|XpGY+9E=3K`e#Zg#5kX ziO@K9K#l`F!I;?I^ZcvDeX!>KqT&8__X_a3Zm@X zE(+2z(Rq+VXq?-V6yH972SFTK`m2JpOcZThSG31l)*hG{NXx{d4}CPhz>###*ni{q zUl^y3E?G}GKF)5(HZZSwO%t-}^+mNy?~$}~*&r!*%~HJ0(GpwLe;ut|8y`+T*S@V( z%QRlC9#mJnXD|tF7u$w?gOzHWmUc-vU2`+ag0_%AON30$-%soI>j=8`{8IJn>}WCf zS=RWnWEWeLkn8_^&=!!6bl`z}8rnin4&@rJx_LUiCFGR0NE>))C>_wWp`?MOkS1j1 zj=9>n?1O2m%~dq?3O&J$VQ*4f*3u?d4W}OIYG|{EjS_LRt5#9UE6f=7bay{gOUT9U zIBp*$uh1@9Vk;(lGi&<>j-U;qg0%WyLWM>iwVRZQm}7)IFVRLjxPK_U_PM*{6?%e} z2x->#tGYJdU^*sgnWTYsF)Ilv(6xeE$v2$F`j6NC^y(ji}x$`KIwi2wc(zjbnL{%l2=He zB|>uF+2L5K45qs88c74~;vJ6dB;WMbaaRqe36J_|j~CYvUfr8HLb?y)9ggjkwe@nm zN)=8wb{j8gpk1`YM#G`S_1Z&5&}|bGX@-n;aSl&NEuWJ5TYV^P>@`913JH7yAmm)q zP<{QfFym8&LfVi+ZffL$+V-1a#T1-bdQbY7Kk2#VqKhv5;@w@VC-z$6Y!XW$&E9_O zT&*Y69AMm;TTcrfT$GQA_94sjDX51uA@uqjJ|-GtM?dj)%?<2)hJ>_CxIOtRA15+J zK4G)uZ!=`1Wnx;xl1AZk6^v?6c5CSp-PAI{we9N{7E^FWF2`ZyC}c$S^)*&*-X+x) z(lRlzZ*`;d^c=?aT300vd`E(MgoG7!H@4I4#?D8Xq&F-`pdR}|A=NW|;ovI9)b!ct zfQh9klsuFfuKhB1MjR zNE7n=ft`-H1AUARo~N|lb;VrWereoTCF`O<;Z^Z-lOzw>`^527zuxnM-m*}8v5v#v zk@3|f^aN=_hSb{T*cKULY?^;tn^sj7k%z7bS5OaWLP|sw(O2dgYy^(`U8*ajWg_F8 z+xmr*J@tdXbe6orH=8o?%jf!Ph4mrEA2;r5_a-zKUfn!7RvCV%qli3iRg6>%Z1f2= z)H!ui8qq*<0!pQu$iR$iY~XsD#YSNP0&lZnRt7HM7c z^)gC7TdBPs9VXf%(c-W44;&-n=yt$Iiiv$)v&fC|Ok9xLU97}$yL=@MeMg#*EG_D5 zOY#gct`Clt>I(IcX1lyk=cl|qGDQYT8hlOAtT&k`5O3FVZ0cjYeOF&Q?J1rn?8P!X z3`iR{PQ=l?!i@mgtKi^K15giX)<16S(5~MYV2n&U zrDC*5%S7J)_Gz8Qv#vYH=6|tLjF>a8(OWHO zK95|+@0*oGj00)etH8KIeD%sG!R~5igxs!q&Aq~UBjjO=-5Q_!+%J9A8#RzHuel}m z);ZlA{>*7KANIuiPG@JfFZ=AUqg`w#LP~wPD7;dJKJo6k(Anlah9@R_#qA=^?okcW zi}xiP8G#x|%Y^n(yfrX9Q+S1*V4r6*fC0zcc^nzTWDP8ZqaFKpX`I;EZ(L46U@08u z2}wNtkEp9xjHnsXL}dGppd>q%!h0fn&+sr-%rbTlmkF!|qzN(pO5{)U#`?kXyaesy zU6hc2jvV9fmW((3pLoYw8VRp_m%X&3he#8$yL1`R9{GpJ8c55;*Z(q!8FC@k9yq^3 zPjHSx$bVCoh&Vb7lnE?_vorQQ$o8;A@Bf@wo$XD^RHI7B^I<;&#b=(y@&uo2DMJebZ(yT`% zrlZ5NcJiwj)Lzm+S|-M^JuF8{^xrj>?O}P9TkIpVjhh{)peHy6v$I9^m!su8uK9VM zQ6&OnLYkehF?ckM9+T5i>b|1k7hq`D9KrecNJyLJ?PyS`2?;ZrW}x_`7J7&@Tg@mr zoaWgV;y3j0G)V(#nYeZ@lK#>9e%bBk94c4mYvx=XJ(Rs-Jyx8^#oxM{Kj9-M(&oQA zhDubAzam2BSrTWvwO)s_j|6M!^Z^QyX?k5_bK6X$nDT!Zi5 zMZ1`l?5QX?H6Igc<0>-2cXpc|BF&zbBMS+y+7ynB=evh_DZbYk?P69E67Bz(k0o^A zs~GWp6erBR;HHO2v;9~9loT4ri^>{&N3==Hgx>dpAZoT@1pBg>m*P9g(G$#kLYkBt zCF-h0d6~eNkY;O9=hKKdJ~fpIw2PTfNSD5K_+5=23XYBEJCwOse4jp+!aOEq`@rHt zV^SxXz?hIGB)qWLze~gF#K!X-%3Ong(|~p{^Vze3XI@cPRoQotNT7#Ev**FjErnNa zeC01Ek(M=h)Vy!7KT&3%F!x_^4|$(3`-gKTbGFBDny@fi{9kXU=pTGz#H{$tE#tdg zVSGO4BwQ&n*Xg)dYd1a8DT_*5xPdLp(h76SKycJI}0q=Nax> zLz=C5?KrLMpSj9W%q@9epU`maJQK7`9I7;ucFLSlo8m{c@?XY@Rek#Irf6rgJ+Ri< z^GCu6I(&5@t>Idt8kWzTq$G9_GV&VUtFgTcBEyZ@}gr}Qs4)z^}%{ZXr=LL@Dm^9VA6g& z(lT*;VLf^{=dxX`rj#`7-p=RRHfavnk(P-Qwd>JrlYiN9_GL)}`vlT5F)MQ@9a8n6 zwsvYqe{2KHCAkF?Th!L~&FO1Q+MK9;*#1E&96i(8v_Wy(?eQO!Ory72pH2(3P4rK# z&W~PeJ{mav=|@vlI4tcPKmsihlJ>Vs+KMKXX?)vi27mtG z`+X+Fe33E{bBvHm^UG-7^QuzzS0XrVuH?%a9%pZAd>5j(C39-mGGC zaXpuQlJc0n#cA17J5wq`o7H--q=B9w&Au@ybX&`q&QH6Np_|k{P!DNB1`mFyEuC^V zK9yUD@QRQ6DZN74NsOA~B)B>!xbNr*CrnH1Te3#mv>S&X#kcbM)i}8!Nc`l++^-UW zme{W165F&5BUjaEP(>z`^+BSp7R;AvLJs}CM4MaknRa(YuvAy*71Hc&ZT&p7;qlY) zB&4|%IYx`41UpObN^aU>(^|hfTboN`2}UauYa6Gc4|l%MudVPi3SS$q`YNjZTsp&! z1dc20Y1_D<@i#?<>@AFT9iqjXv}v{jqOQ!EMw*?f(kw5{Ib^rqwzR)QU@6olWXv*3 zL%WXGcT6lId4-GxYBg7l^VZnF zrfj@AdMlLH|07CoGhnuk>Sz~dAMEtKU7IvIJ4jF6qQ5cYRWtF%>uSf3_LLc8)&kr8 zdGWC}@?m5B+PqE@fw_crNQm0;xyol_`2r$EmT+5^4#dHGEx(`hYdK5O)qkjFiW{#D z+Z-n46_!GpeOHt_NoBd4(A_Um%64AL)I*y4WB!RU_?nRE3ED-Py~Rlvy^igR(%8Nt zL73weFNN2pC8vEP%%5<*9~0{IBWj-=uc%$V1G_-c&teynSqgK(slodPd!s5MH%p;c{Mxj{c2gaBwC-iv>XiKz zggH9%Qh06F0^5!ICa4S&=1+JWKPK>LLeyySy2?rK57HhutZ7k4=JSWxbGHfz+)Zcd zNrc#Q*S&TXCEq>bK)d|fY}xOLbY=aOR(V_m=$Y|JgzySAB-(X<{GQLQm54tZR=}KPJcIjKeL{mvtpl zhZ)!V%@cE?ZNgy*^9D$uV@!*gzfm9 zS5HaXX@OpN+c443o1Uz0XJ5pKvE9@|T0}1OK|NJf`4UEK zVHr7VHG8_V-*NRQq`yUe<3bI;g)>tbwT^WZaj<7Kdx3Psk&^yK92)sBv28nFBg1AN zDRN#5CM|pQXljlcY));kxwVv6DeKM59zssEx#u|CBhonF`N(^<>SL=qvW{y%%(vXd zeJ6yx)H~{NM+O_O?njurik*E8`ih*pMK1QxpU)U+B(>>cM-A7WWLHl`y#hPP#?dWT ziJh!SpeOQP?tWe|8d)~n2yvV5*!W#-aKs}@h>A1Y2SXW!t zaf9BkRWq>$>GR~B9qry@jp8g*CfxI`R2+ReK&5~ige63O>-Buq<$j3@8(J=ZpAfxVkZU!~k0>nmoKHUEiL z@Ou;XW@5Qb&(Gd7Of6G{;{H7>g)}?EG($r@bHrgScivvox8Z$f1qzK!0aFy2h)|0N zjmFQaP~3-zrI2P%6E_~PQ%@JDE5mz8aq!hQJ{RG8n2?s^Kn;vZCW0#+RlPjVYgfDX zmcCeD`nIEp}mc2@ODi=T7&OC{YujBA9i*Y?toTMY2vBe4Vj4e*^FPU+5@%t0A zOu}^%o6wUrQl5Xs3G@6buEEz;`I%1qny-I;f0~s^@UwSJJ=v?2XH)S~=Gj!HU0jd+ z{-i0B;HT%9da_q3&yC`x%yXl-hIzgdzvln`{kc&l!B5XI^<=M7o*TtWrL>Eyi{GCc zWfJ@>98(WhNxwfgikC9ajpDxZdc)Pl@6U}g34RuisV95I&Lfk~jpC)ubECKhZ+~2m z{Qlf1li(-mn0m5T?Cdt_+$dhkJU5DK@I2;cI`M1X3%)-$$|U&dIi{ZM73)#bxlz0n z??wD99Fvwc_^iS8q)KLfaGn}*>tti;)CfEef{-N-0*$>jrf>MSdr{-RkIpkWs+}rh z5@H=sULQn_Nx@DcUFv%FAJ7)QHt8(?Bd?JDxdz68zT+tsA`aRx=CwDEW9EP1D*xSZ zJPs^{E10rZ8S9BNIV@f!>Pdvll7(AxYSggyj!UV5rBLtZ8W__L3H~%3b^VEGK`U=T z^c~k#lQjg4W3tPiWc=snOCkX z5p5$AP8H!*)St~nURim2U@4@3?iCVfiLEs39ck?EJak>{ZC&-VjmPmUu@tJ}V|QI! z`SnjVqRwOygf-_dRVszFQ)5eyE~U8!_6gMcsRluRu@q`Me=DL}gYt3wcer6MLQhan z{6@Cq-zJE*kU&exwaebFu=8c1pQBxjPbQ9>6n)Ub>k9kFp+?Ss=QSG$Ee&F@Dw;$u*eD>pKGqBTJ#Jg9vW6Q4IjLKe7+JSZw_VLr&i;YDb(Ttj z9wDgVDwX^ehd--vJ&88co&7h;_)nQ*YwcE0)D_Y)apry-N3|EBx^2q{$*UjGE=x`P zmO6GVIiSM|)4Q*FWa0LP>&yzf^Yjb3rp@=_?6lAg+4ajoK1QDE zKC%Y1jclpLiX8g&snv`o530x-@V*`2q_b@Q9Hwu))yDYX_2#>G;pRF8C(Jb@b~e?D zdivT$BaOaWt~v1ix8w;Ul4&ycQH&oM8cMTh`=ygYcrM}kpt)|yc0d$sv-(>{Pss*e(KPd+y`}bI@xM|rc>!M>}(M@nS>K2&BopE za)0p?nr=s>k~EN(iOf-Fd_8LI*E$Yi{e#s(_oJ>i78@<&Lu^)(YxS$*jA z#=a7fGA5H|zxm|D09)=%>9t+QSg&Oo{Cv1^#heC%5ogNIv%kYMli3?5!^?+J&@T7T z)lO_jidzLeI@<@Wfma7(>$cgpotA>m@dHb-YqQqbnP(>yhf;QcHgj+C$dIgI+LbJk zf;0L%o*s?XJbc2x)A(jrjKQw4>)U`Ok5{tY|Ak0>^t3HwrL@AXOvg`j)9(%q(@M+; zlj;gfA^puKK8mK(&e(2|v|{Xw{3nfl#G*3+eB70Z>s2f38TVAy{;EI1IQS^Fo&6Pc zg{6>|HE^s&J*3(1H*l|_-<}quHLEvNiUUibwyfdtI*t90j%RG#_vLvD+Q&4SBjS*~ zTG@1(o_Tm>Ep?3{QXE(cX;}k(M?Iuv;zX2(J#J}!;nlk79`-|ye8MYP|HP92(LzsgIhI0gc6LI`R(iLOxe|+a zA7!w;7xp2;7Odi4p(m)ve*eeQ75az^QL5H*h!h7BXo;QT@o#Ot=N+5F$8VHL*tiDT z#rW8JhAS)d0f(X-6Iu_Eyh6eihp>UuAOV3U2IwQT~Wgr-Ro#& zy?M)_l2=H$GErD!zj10$WxcpQO`ljQIj_V|&@T1@_C@X!5B>R>;rgL(?I8#(CC{SP zWk_e-E>PcaFSbLvpNI9zV&{MPj6=FplkFvs>FH7xG*W*XcZCL)LYk0+f7LR)2BtC! zYUlJ-Gm6?5HTr1dyF%D`UcxrlkO^*|>u?RM6D)-^duJI_+)y(#Fj9GEmu4BLhcx?| z1L8mptRI=kQJ|Z#w}6lS^vZ30lj)WDcz!j)GP@=DlswVF69PWH-GS0WCV zT`?wNDWsFzL*wm%zPsAyyLwBG<2wzE3H8{nNoOCV&<7RX9ypVcy>jI)h5n)N(FaQ* zo!mbt?;q$po|1=ja$bozT)8APu-;?>y}~&h(y~_>mKHY(mu^7oHSV2wdBGOjvF_Cs ze$p*^h29bpd^1j8GIlWiCtYrTByevG(uCYw)5}O*`nuNpj$>E)bw%xWvwaNU8fX_= zmOZiDC~lm8UZ1v5_xmA%dPws-XOuDE(gM#1D?<`Jrq{8byj{h{HPEi>+UDF3S9n7& zqf5@~+L70_cG-s1v5!yi5niDl(uBPJI@UN*>o?2vH)H%z18JG)yS$fSEpc79w(erz z^=Eavf0NDVmGHzBhs!I^LxYWw`s?)#Z&UdrfqHTre!mwtT9s^I1a0VIpHc0jOFq}lHV%u(HV|Gt{BY=@^GY9K8W z1IlJJb{%PJkRdO3{PuaX?b^iZ!Yia@uat6edbeeRjetAuez^Y%X_;`%m!kN4eJq8U zh#BK5Fa8rnQ3DCIluQT>^d0SD#v~K$LiP#?w3JK;4QvCni#e7|2n}olB+!yfpgIz0 zNhZ)1dV*O=$drbyjXaMo>*dH+?O4-MYKfvFt!W#UvX^xmsm>Z5pBO&C-F_$c2-W?M zn%3$G)!4i6x!d{}C0otXyU?Xt!5!i1o5L6UCJrwzl|q{3u0=6U)G28^P9LScYB^f% zdMVNRa;3K&^<<5Inw2wbFI1y(c~AA1y`$9*d5&36##Of?EfW<}dmAq@`56yr3w^<_ zqt*5Can_DyYub^PiG3&hj0VSZ8P(|#y+q_FRoh#~I;coJJJK?dE=MDyQN1gArq$Q= zH4{dtUo#g<^bV_KM_MN0mP8t%=gv8XHXCcpwIN&$$<^C`Xc|AMuCNZ-m)HA-8P*wv z_3ibeBn`BSmI!goAV$m0OZ2SSo6^$9MycmJR@^lwtccWtSkvsA>Y0l1c)>iaPp={r z)v?vk5<7!#+ylpgyETmIwo3HKmPoa_hnKZ!g~Cz`V%xCY32nCP^xts(#){r_^t&;t zZO|zH-ml#x0xhw#c-L2Ryt{HnADz0d6bJf_me_B**-%CuVjX3?8Qf62nj=cRq;0Ua zo9!uO3AX>w<3Qih5+Papw`KcRLXCX44E<`SDD}~jeb$j))up_`jQP1&=m}b4ZT{yv z$JGmYjHXFVjY1w#>YPsVtmjA_DHAcre(n`|f|dyBzB|8uq)%;Qyy9*wUphv$EH7ex zlE0B1OUW8{?H~30beN-S&(6k&tfSS~g75sx?rva5S|*gRY)1WrI*!I^T1f~$YUs}n94w~!50*yv*| z*_C=t+Ns5TUaRj;8?9DdJ>2r+JF{MtKXr?#D~3Fp+`R=1Wd zX-8TntfgAex(Bvvfh+H8%XdVnb=*8Gu|Xy5NXrDBRhup@M`%v(bJ~Z+QEEoA#M1Js zmmO)DsF2o|HvF#&UDfM~`es3tx+ZLcg-)w(M_ML|U8B@%ttUO(IfqocNXtZEC0}~- zNin@-?@C6QnNjMz$s2c7d>AOTAl5V?H?y483VL7D-gjthU<+cap(U2>^=r_L4T~Da z-Z&le742f%u=S`6pS5-s@)^g=c(Ps}%PRd1;ejlk~Kw>qvbN zX_=TEP>rU}Ue5R&JY2*6jGkco%W)uqF(J)uV73> zJ*3%5Yz>xc`PNQTUqlX(#&)!eIVO9BV>o(=`G1?L6)?U&;yY4|_)f*+> z`7dfxnDz7hCpu{L>QtcNzf_|yJ4C42JH}adUhuSIDWq8o-i+4TJ*-Y=rYTD?!;zMW zTZIa02Zl7a&nOik-J>uj)FY(u!RL;I&$;O663ry9@V+DyO)RCf$NPF}`-%)VQnNc} z*SCEvIZoD>G7)o(ooBi5otAp*aV>X-`cnVE+(k?5TY$gzsaqSSH`>l=D~;`F7juk# zC;YmC9!Y1ZmX)KWks1jc=h=AxzZP?}O6;s1-Z)Z<0|~rKu=9Pc-PMbiJFod~X-NM~ z9I1Xe-qUjOP-#2PEU@0#Sz%3<>2D8br;|R_k!lxdnFttK+Zf&@So1kuRMNm%4eGHq z;bR?)LeB`j)OWv%^C%=xk3B~nx}vwv7(yc^7t^-Ija0Keo@%Kv!rzXiFvnyKBv21& zb}I1Xg4*3ZBWX}>PtDpWLS52jucg>TKRepRoR+;p0`-uVHE=vfTGr@Y<`?7lF8j5a z!_pae-^Mslj}T?RGW~WcN@uUnFXa`MLOr&V12iyyP!DNVyM;z;3(|C;14cd4u^*sa zj8FCo3DiSc*1&rd(z3?bg@fp|E|s+XbC+sewxv_EOv_}Mbv(bVn^$`EV|3}n$(!@q z+V;($9$MPKzxFSkZG^ZT4yRRz$2jWj9HGUBq*pUnu4SD!xq?&*X+p}q?m;ufAJZPT z?5>UWPN!~uG1;;rua6D&WQ}6Y+R;3<(7Jhooz_Vguk^VUD-Yj zy_>7Q?y)tkdNd}|51wHgI9$`+GBONXx|hvVG|>%LPZLamV%G$LZ9?vszo9?}@e{EfXvM z9!i&={#E~Qxt=~hD7~sJi?#;bXk$ZKCMNb6Nw4~J(;LS$SFt^imWg%^Z)-stpQ`hB z^q^bsrBXMyeVXV#>82H14cmt83S-{@#231*U;e64Jgox>wDfZVJw%$_qq1()o?P;v zL9Z*(cLAx?=?UpA{;~J1=n1wz8yO%DB+wJ23CVDMm^MovLMLTwtyPO4>Ti|SSeDc( zEaequ%+I|-PtX$E!*aZ)HgHW}>b)~jkG}g=>2YYkrO1c2QYK=K{oE_`1TC@OWqP=& zRz5>Ex?XK+bYK2ed5~*?WnkzODR(g|f9@4}f|h=+fp#-`5cSpX8~hJ{UCc&?o>^vS z8x~KpguDzhFvGDF(rkCZxp2dM+IY23mJxcBpts84FU2iq*N?Jo-TPLt=$ZZgvro3& zt@~Ojd}&SMuW1`Hjhu0VjPBhk=|d|n)m#4gPMPZGZEd@Gl2i(5_AY$TNaOU7u3GD6 z%^W?)yj6l;bhG$|G_#?etWoKop+>PxziL-D*V7i(e5dqoUENahw1*98nebQo8mqj{ zt1~UfwO5VbD|ybA_a8DZqYY`982(2mYww1w&iC4Nf=Yu)hlHl$_Z;E-0v zyDSNMk6st0lXQ@liJ&YYM%$ssbYpur9nY`8QdoyQVo?*QK4)(7W&=IA!5hq3!_ zqCQ?w#yT!)k(4E9NhUBt)IdvwY;2U#=r+0$eVcv0j{N{V!StLA!XTmc2p(^^hh6HLymJmNkCew^2WM%EL%? ps*-`d7UMuY`LrG!m#`G-v0e)rNT43l?5tuq!3;+-w2Sc(@_$OdoFxDN literal 0 HcmV?d00001 diff --git a/bhand_description/meshes/bh_link2.stl b/bhand_description/meshes/bh_link2.stl new file mode 100644 index 0000000000000000000000000000000000000000..f74e52958ad15e41f6b77a3314d0d539cdb44578 GIT binary patch literal 48584 zcmb`QcX(7q+y4hb5d@`66+-B}6OuD$=tx%)@R0`sN$4eX3=pyyq)Jn&pb$EQB2tsx z>;R&G2nt9qBE6`fGy#QoX3oy$J4yEay?^|2UE*AO=5v4Vd*+@qbLO10J0fOK|L8L9 zT6bt$hm`sM@b`TXA+Mhr&+APnW3T+TU**bGhSA)EkGP+Vx*UFc!!Y_`f$i?=y@D-W zmY)-Hgf$2zs#mHyLUn4Pg)$ z+f{KGJ$mQ!aA^xY)Lv!OSiOE24ehyI5m*bgO${Va4{1W`G>_x;e=cNCZCA&Ld`#>x zy7i6|Q{XsI9cv*?2)_}-lb3yMA30UtgROhzy`eOD`UQ8rCS@#>xYzWf@MhnqrjEHj zfuRQ0LYk0I?H2rIfAx8|HQ_#7J?YF_n>?ByTKOHCQ&x_m+*FL{z!evCKz!b zZ4$rC3gR0Vbz|Aamaz6O9YFg%As#snQi}|v7upa{p@ia=8Ts7S?XA}e9`NowIglON zG@M4Qf9xJzyQEPIX+j>w72yv~bYK;WRHE2EsAp=d*ni4;v~Pj;+N_a=2KJ3f92?xx z`}>x$tkJtayV0)aQeQgbaaPZ-{fb$pSM75*rXQWn$M1XIH8ijm(uBO%_W?anV**=Y zEe^l?ZZr)qkVUms^1^6Zxla~Pu}Q@(lQ2kBG2x zmpI~mIdy=cfwhn(Px?3)E%%s!nrnt{y>y7dzwp zt$%vZ@Zne7-J6!NOpRoVT3d%r@p>Y+rUF>70G$!)fkvUw5ZXKXGQxcNTP~CsV&y zbBXCyw=!447SH0TpI@F}Xkaa*37L`@#r8M3WA}}m6pp^59@2#De{U=cTHD$FxBJJ| zE48}Q0&i?reZIGKcUoZzS6-PKX>*Q?6&~oZ@?LIOU(Q}w3u!{a4v%M%@xk`owbR4V z6VyXGO@WA+bNi=>R=%%FC{Mhc9AwU`c~L% z?JQhUX`mj`Cb8?nHfwy9?214-FfnH6ZtLfVdsC$ENCzfD`?{@&xVDNwIxvC#fwW2N z?Gev5e>R(b*KA8g>;qkv9-2Lv7Q5N!SPN;jPGn-8=xuhj*}8*Yb*J$jXAOt7blF*v z6*xMcJ#4AgaLJFicBg9-opqwFCA~sRX+Fs;*Ri^Uz7&g#j|T*0zE|9B;p?TqJ5g&cQjzW z!g(byVR#6%Nt7Jem!4k!LTR8~oV88jm08jB_+QU55NIhdfia<;B3usVV&u#q`sZ{f za`Xh(U8Y9g76WLWoX?e4=n2v$ff`5$CLYunO24?~{Z!CFY08kpgzhqOujl{J#)oito|Qq7L0!$-Bt;2|OXzbwLLk&e7oL7PpHlow+EAQjs{9?P;=pz@iCWXH+eJ=B z^LEcZPQl2LHVGMo_;X3GMqL|3L*5vnB5xWsm>&HrGDAxfGB)PAcj|ei5f&=02j>rW zS{GXsX>DK07(Ix3NE7nq+Y{X%I6de_4UEYol!`BoXTJ@huH4g=@69&F(0+5AF=%=f z5>b~ApQl-;jFNB>DS=sBZm z(ZZH4%T)%>41`Qu7wp~k`8Ym(**EkEiKKZZ-gip^=R~9ld3XDl-ZIf6`1x^h8<4)*4D5?>Vd@$6DB%guMBv1FOEd2;Wz+ zKo}CJhcqGEA4Ri2b6mIY|1vQpXPu$+NzE^n2HM5!A>@MaDo>k)l*$)>3qu0+kS65H z`1%ZA`)m9*AFTa zxyZzDnTfqN^q^VtI9YH%nTdDT^`PVnC)?33uCG-l za*>H)G82(NJ*0`uL@qLs%S=Q9?c!=#WujMPBA1zn=Mt=iXCjq}Tx24bnTQ1HA?=?H zM8U<{m5-o3D@+QP*MqqB!MWWewr=T8TV`3J2)trN+9Xf|>Hiynp5Xey)EG&l>D6rQ zl~-5`XX?NNdWf`1beJ-LTFcrg4YZ5%RbT==MA{@qM-HZArbj6aw2L!bU;;fv+9dG4 z3fjdP)g-!XjG@ghCMd7aL!?atHINQW%rB5&-St#d`xm>4Bv>Dh|JN2G`O6+eb!d$9TAmI)zA#!BYayMcAkQV(qNsA*z6Y7z9)OV<>EbYKGGKsr-GI>vC^bsF`VwQ5pq)o!tR`P!gp98@A&grw=#l*QJG|Pj?q))~87%(NTB|X7fNXv#* z{h>5=iRUurra0pR^^i7+lG|eFnE6ibA|05(QG|4QLhK5PIO0D^-hksAYhipU3}y@B zX!Vnu@d!qXci+`BEKEGZVkdw7>Kc6pkXI18EXN0~&IrM~8I#1SulCL(;gZ1dh;-T= zlUBz{tV058>9Vv$h`6F>;)>oDJCMnj#rbN;jn9<^dV;GnLd0`2OgtxJ%jaZ}K)Xn* zeFi4>8JO5lOc@}~KC{mzC=IlWt208x?gtaQAGX*X3_}9-kXAcI;bNzViM>AeT5%Q~ zzOP%;ChY_v1jQPdzLbea3oLHoFc&+*vIoPEKs}^Y?s9P_PG(8+burG@WM85*&@PU7wHMCC zUbxJ}Mo6F@(rHhHh zAlk+AiW(pO=g5#iyGWb+a4(Z$XsavNR9m54JddgI;oluZ4J6Q#xs$qY@&NjySY^lv z(JrnZ%>CULy#~|PPai9PxZHhdC zp5Qf=Ie#F5c9Ayck7Yv_TI+)LDGjuX*Kp?ifduLyZO$LX+=1dz0`-tK=MU6C+9YuP_@TpQtL~-}N&`K?=RnN)0}0ea+MGX-K)d+lh&g|3 z70)wF+Pg>f2iC$TN6h&H3DiT{oImD^Cm@!rX`?jIEP|leEOG=OYP#>AMY$oy}0$SD*A}Ly3=L(gfTv6 z>u9tP8vEi4Rn@g5fmcZSb4e3Y;)gNp&si?-^fT{;m#jI0ZohWhEeW)X&!-Zy{B|5G zFd(b9&D4c%Z7V&2mI&!JB7#*v{?yx@T@4?VIEnN96kqFsEVm5^d%2D9T$xOe@P z#cs5P1X?2G_>Ek&^MJSbqE}0^ER7aeAKwf0bZzoHJb#ygwA<4IZ6Lz#qI@eBy`!)&~emi{HPqN>snF+EfKOl+Z%lB z*B$u5o5if5P3Kuho;FbZfu7(K#)PbR*OOXm*91QD(_k9;;Zo~*6|Jr7hG;ui@Wy=E8UDdeSquB#<_V z7vib2`V;o=I{Nfp^54R%!-9}!YNSm<#*uStpI!fMxUyT;l5t1^YhiqZyc8NT4tv$q zWJxst@o5GEEfF$m{7CNp>#XN!{e?Dqg&Jr{tX_S0;^JFe-6@Z3++5L;Ug^7JvZVvJ zF8YhLkS1iA&=?(6LA`aUHDv4RveZMGkgZSR`R169thNQsViOX4O z&+YxJE59aK*RIr4ap*f3G7i(Lv^;U~1LA)6Z~VE+E3AbyAt&FMz{4j#rHR*PglbQu z@2H1#nu6?m)WCK#iPj6p@=aylv761T;6b~a!alYN?WfksZY4dYS4*Z{4nI4foLz3? zc&_h9$Y`+^(xz9j;%%2dKY5`dM*=OG1jc~`S|TKQ><2uhe|GVV*AsVG*2&g^xF)JU za*21>9(vxfo|n$=F};eay2{ED`q+-^-IM=yXE=>s9c=AfU&5$`G$EVk4CiY%uC$|9 z_YKFkLOoMs=l*=wpn`4el@G^qdCf6M+>Z+0Qrgf!ZE*!TrJTEa!ysBo+)b8ue&&li zyoo6$ftCn4)+51v_Gt~v^V}q`MNO~PyG?rqatkT>SAHjs!p+{6>n)J#1^-ZHi>gLyYlKYbFssP z3K@Nlv`PFtd7Cw^X%<%J#(#}I$66SlxK?|mx%XPLaZKjqld#p+tH=9Va*eCY@dG?= zGxFJsD$y6IAF>sFhj{DM7)ZCh(#i^N_t>a~G$A{;cJWr}IF>CKS2-NpN7s^irbgW5 z+;qebt=ZVON*VouwNRUolB;XbzWd`<93^r@)9EieWQYUx#GSZeRp`nRv8-_UenuR+ zmW*6mlI1jwzV^UX`iS&hmt`%a#VX@oCEB3h7`E=@L|fOw)|F*!5kl@(&q15_X~Bvd zD$7DD4yAkAG_Yz$n0bX6LrBlduhZb=ZQ0yw#o5c318D0(t*l-}|2FKRCGoawNC@o~ z70XsFjxxMLPtXz}zq|HYC3ELx*=Bb(yh2YfD+!4j)Stf=e%wxCxx)4NL#};B{yxc? zU)r+1p7N$;5-%UcS>4vA+N<{tW=F0Lr@#LbZ2eoUlu-+5LUOK-<_q4sVawdr8gl;7 zWvORsbUo^^+LIs_bg`Qe2i8JuLIyn@#ZUe^(~h6BD;ZaJA6!nbUOQFKy7*2R%k=8+ zN!6{C=ELl&2R=07z*qb}$SFEN+ z*?HNln?bMH36tUsudo)I*Dvdij~a!rkEXKV%RfBzMvIy1;sMk}u~ zb7C!Bmf4d=ERUl}T0^dobS;@z+LHV{jc8nAX$5^m+S29pbQ)nDnXj*F)inTWptj6$ z{pV6^>hy7>UpWy{{@A{CQKOr$m8&J~N%~sybG=5D_FZa)EK5jWEnRjZmo>$o3pL~s ztc5F1Rr!C_(6o%t(2z1R4$<~O!Rc$I*N{4nSHA106iHw$ycSWlegC*P5~zo?N%*eG z!=(oHnrwy4OllwI004 zkmzYcQooxM&q|M5TU8&CV?vjuhe)foayc#L;utOJA#Jv<=nuENc9wSkyJwF3);y-X zGBvIoOz_@}7{l7%th7NNkzVO?dfN0VIoo^gSIQSxk)s~cCV{>qZ4$bzdcM+Qy*`3% zmEJ=$@-H^!_55_Dphx=dE33${6$oiQ?G=9DllPhTTF`oZMB3Hm^t7qrtA!e>jIjw3&` z^LR!U49VzK(XA8sivvgLk?T3u>1d@bU6usWX_2?+owXvWBcaQVS3Zr@Zzi2xD{Vcl z^xxI;2-@`#s?`b6UbXAgtpeIY0xkKy@^+syppv!)aVWb!Z%vKVxe=eQLtC1Lwo?1P z{{G-2O0vq@mekN?N%;CnWoVjLu9Mev>ndAF=(5vRzH@HqOACb0nIX$fugnjwv z;$rS|%f0aQzT=t5sVl3eC(uLG^N(|W;rYIG7$Mfu<&2Swc`!xZ1(06(<~|iUwt|1I zsZC<=AVA zKsqoX*HL;hq-rldx~G zmM%Meo-NLkdiM4NzN+^J)pSqEs|j6B-#2M}{@%);RleAf9;UTsp$dTmSA(q-uh_J5jJ zld_&!j~Ynmva}?2yt)kJ7d|@V?L44*C2dO{(PgQD8I$JKJnk{PLPD1vjp(E}-sgNS zZ^@(!4ZDln?J9Ct9zna9p@e+fc_42w<&ZaY+mVK73kkGD$i}U4{JY>>-cP&!k&H*s zF5VX*Wbw)I?BKLA-nV*Jlvl!Pohb81mu2L*8YHC5k@0MIk6?R8g@%oMN7P+QJZmHE z*RVG>t6TvItfk9N?tb-}`1Z2Jx4hQVQjL6e)txx>1lRC>ue`#mWF*io(u54(T7)J4 z)q(G8(mBjGXQ&k!+Qn-I@dQL_6gzSHwzvAYONIs#Xi2>FJHJ}EN8H7_H(+*{Z=5R) zv@1TBcbCJR5!HTAVKzFkBR}2#lN7X-j*v5vvLyCo_7vtmBFuOGP)E?Nuq5wC`!s}C zZl6~v=oJ!ZNkz_mkvH<4)szO>6|FAsV5_S>)w$imjTJn!t8M(||xoe;_(5`4*|BBOpW{|BbbJy<`5@<e%^)a9CYDD?waJ9GSo9BJc8q6I2{pt$iI;@t2uh$fTS&6iG zR?Yf))$89qR2sfMPz2H@ku7}5^3R&y$lw*yCgESj39qoNGFziKd4&Y_Aksb!PeuY; zF|)OAMgsc-Y4kA7C)v8_3DSWH-_?Zbsm!h{GJ56n9SK#&m`tz4nZZ9hBORE)XfvTR zX21dI zxFXlfd-Kny*S{~M)}mNTmz~wCbjR^cd?yDy#hRI((Yh)Q`;)nJ_@EEm@`$!8%ijs@ zpM|zVG~ZO+{z!P$smu8K=oQvNTKVJm3ZHvL4>J%>7@~FYiC?4x6Zot%(t!zl0vqYT zM1vVqY3mC!)jWZ8U?O48G#Yn5hiYA<0~6JQXHw6z|0n|Kzy$Un(wP#XPh5PLcp|#s zi*iO@$y~xKJzrO-+;Z`93+F1YWG(D}t>Mo^-GjWX$i%NImQ@;F@r?NCx18sNGbNN) zg{sX|nJ8^xEu{TkiGmpi>LG0ssDUvBCh#its(7lr@t;)1lxbUK@Cs`oZFt2h)}Bg9 z>}M<0=Qk##ve9asYi%wtJ7Z^gIk zUM30OCPzY-owp#;R9r?J6Tcfy&%76+;=q{16Q+B|ux6KCcFhB0Q}77^tc5fo-|ZOB zrj7}*tL?oXjs$vwwBIL}jK|mKYX0!`v+~N+@I9^09*z94vOXd+QI}=wBJI}@1@W!G zpG>83akJEng9P@hpHN;Em_LmM?aZmXLJyHP3DiK^BuXvp$(AQSvYTxSsiKd_IPh5| z{kfA@Pm{Z|KW@LYe|fK*(Yja*Y11p;C{l6w&J3z`&9?H*YV6viHS6^e80U&WT4{)O zl7D6oqMo+oi^F+uf_?PSAVWjPkzUWSE(N4U)hP?a80;M)ZJnOGn4X!CEfcS-kP~*< z(Ee=Pg|YR0bDt&cqVGs64PoEWC|P}hoIg~SpdQjD@ngmLa{f@Qi*%-hlwsIDNSlOj zK4)S+-=SMEeH<8{@=E^Wk{Z8?_E|H*c@wGB`^)LRvkR4nX5?MZhq6}1YP0=cwQAra zR9j&!q?LxSFaON`Ks}@hDOc`<{d>dyENIQ49q2FCLT$&o^RJ5?s=0!m$zIAW`}}|? zdvlahahP6po-&xdeCV}>M*R>GZAlTWY%8pVv|qy|$RyELg+yD4@v#Hd zkw8m?%n=$}nq~Dip84T=Ws4+-$ks)>=&hfyU+Xt!J=#J7E&09j%2Dg{L_MvJcCn=i z@kQ>H;{$CWftJKC2{`@1Ww!hJKxv>|%wzFSIMJ`HdE!B;CFfwfRuJd>I;njP4A%YOClx4V6IQ=|rZf>#!P zuWaE}C=zHFX+pefi?Ab4JFpSQi>3J1A}ZU_E?$ce^6|DPR{X_n`~JdJjZgy#v_weF z>+QqWi0_k`^2LA@T(_fL?0@mSYV!-Tc6&OqW|95E&=wMCNfF#fq~P@c+QocRUb%f< zg`q7Z(2|Or`yx;F&B&^)&@PS@)wub?)IX=)XuA=-s=#{yPwva$e{w(1#cYT?mG|(=t`u&;6W$vOa zB+!yS+a;0W%W$QEcJVsFKcb{pVQ32pwB#SPGV)~KNL3nW7tdY(GlOj1FtmjPTJoQ- zWS@uP5wweEK5>Wl*QxgW&7)cK^NmyR>3V#RLBAv5yl+rGWU~F+Yh#$TdHZU8M7}YA zwEo;7awL~$$KGtl+JAdF8K3#bDrvMNLF+pX6O z^j~MnOvLwmP>+y{9eS}6g&){t?%qad7q5y>b!Bd@Bz6T1T0?t<-pbk8#Rd+z5PEl6kw!@1n@<>%B=nz)<24T2MGtjt`F|Hj z4J6Q#B3$ZULEsUzi!CDSieJ*%a3%C`d}$*NdbnH#+sahDUr`C~qP(YB${PmhY0G2GZh}%*0z~ZtRNYF`04feiYAhmYnOkl4!pBitj;UOlj}FzI)@i@$Rd*yWoFw)+83( zi07M1U-LY>nq;(NDGK+tPm@#YKPdwn>) zegB?&=(G}^GuINVtWR@$Vm7~Ncu2_iKZsvL7!vADjHqa#SLg}S;;Lx<8`j*5?YuRA z8f!$3dPoy;s7DQ}So2|C@s^O`RfWGMSp%CE@HD?x((q8co!53W-;{NR_lGUV46o1= zqzOrB6K~yKlj;?3R2do{)tX|xNlSVPpDOAxiRNtv@*nmhy(SICgc_I)>i)$GrgBbzG|Tc#$*yhFXf;odbi+t z50y3IC>S)~YIUQ5=Z{_gxJ|G6j4#H2`L!J%QR!3n#$NNR`m}+H18X5o$cM*k@|o8g z@e(fyMFKrUnvga&{%f*ehLfRzsx2oLxxzI+f zE@w_%mT{n-crN2+l()saSYCelqKy~_61prc5wa~_D7Gg%nfI}`eYRenk>dN7&Q1(cnTVd?nMk}Xc_fr| z%Tb%hc0OmJIud9}yeFJ8p0&>x;{DH{WA2LLd!tHJx~0}WXcy1Hgk%{#nEl<7dk0Kj z7LK-%KugX%`1#WNp?L-X%_F!;vtRD781B7k{bHY#qlm#W;y2M zm98(>SNIGho=b29r`4APJ{O9$P|qar$xPHk+9XiJpyBLl5*RtsnR?}tao|-d?o4I6 z8>NU0*UrKP*`k37yrM@sQ$koX@9-iWn85vA+{MF~glXr`B{h8ed+KTe=}Za1nQeu1 zU;=l9aaR>R^!X$Nqy~C|bYKE&;qEZ%`88A=ct!8qfmE%4F_{GJGawz9z`Q~_FoAmj zc=duFnqHwNNM|5i4(H-{<&NhM)Khi+1nvPK9hks<2BZTM=sVIG2qz4YCAb%g=SPgm zSJ?^2h#cv_1lGdyJnESmxRZ*r57Lf14(H-XU@g@4Yq;e2z@1dw@kBk7Kn^ujii1RLEtwG_i=eSrKT`yHh_p$d2GW6vPhN|npR(Rc13kfSW;ZpEKs}^QV%Fi_ z^!dZiN(1fU_pF-)Y9N7@6yb6>7t20;Agw$+QfZ)F{GN4F!?U>`{XM7S71~AGBv1qC zz(kwbL+QdIjelvlX~J@ z;gY~J5z^wDTay3ucHP*EZ@f7<2??yF%hD1dT{h3NuRj^7exLJ=p#$lX9+64|J;5UquZ1B!;$2 zouj_4}NYW)7tf7o;i;w2Qq-$eE|( z*s@dgyz*BOkw8792^m`SU3RHMKJndcoFajCF^>s(drS$IH>$1rea^-OhR}_l-%ws* zEgW6qHzx=8VaxLUV#{AeL<04YR(WNMyi&i=R^YS;#pf|A{Uux%S`OsE`pZoc1n4LwQwDzGLef+RKL%O1nMEJ zGLef+RKL%8qfHMwa^iZWfp&4_q%x6SpB+xFdoKz-qk%{W} zIq_VAweU=&GLef+^vX;`0`-smr%d`@@F>__jl?yU%n32E^y=G))1w?tLv zBR17DG>|rlmA4wQEB^#}PraD{6}ih~?#{i`kEY~(s5HaJgyR+3MOtN|S7aiS znTQ%YfHnz{iCko&Ei-Xx^`5kA+2hJ9^aRJe%0wGl zTV^6^AZ-#N6S>Glugt`b9V6()xD84JJ;Aet%0ww!&K2(tg4v<3IxSkoFUz;9|q~N7A3dQj`YT#lA5K)Ib6)nM8$% zXv$YC$k6B5n}G?m8`vwH0njeaSEdG@&yhe&CV}U3B+!yc+|JRThCH0DB1Zx(1tzfF zkTwbQ7o){lR1q$Rb20P^J;AxeB>pZqh%UakQN@9^aAt6xjqorQY#M5t*Tp8)mth zWq%x8#K8t0*icQksH~-FSxbLz60`o3ubQqEh>)KXA|mIab-jyf*W0N3KpsK6`g2D^ z6C?9c!>h~)M?*yJ6>Y^AM%+o#eISpZUH!SEp^2PT7A5Igfe1%K_xa&zi#KXp@`x@= zySmREqGe9LCagtb1w2#BBUnrKrb8qxu2uex0;3gyt*bR;Et42m{N$S5_ZO9y8c1MF zNE0%yc;||{?-yN@p3to;HIO#PApSa6X1_R=aZewA^$CAd4}bg4)cAVG0;~M9uIl&I zuonK3ok{EuUSQ?=Hoy8+E7U{UBv1qCz(nxe#n#@lZsiqvg1?q$Y9N7nNSnl-^Iuq_ z3O!RAXcvDiFED|6NSj1R&6U=LeEHn6r_e6`_FZ5CJw#d&E{AimS&KJY-Zx%V8fX`P z`_9xrqVB_W)*q(}WuQ$0<3J6hO=68V+4^Apo2qru6U<{pxE#*KaxL6uZP8S`YT(gBNN~ ze_NSkYwU;)VX{roF6M%`|FJZlt>4m%%AHgsP!DNB=2foBI$yBVo<0(27sm=AZTA0U zPv6sD?dey)x7B(&^P%zzYvD)}zZl|b$u6%AW^yML3DiSc^nW*;k=eApFeK+D)6*-=} z@QkW5(JL}h?dc<-?MgkQRVH$giL7AcTaA!FyEw0?OynXHQ)MRRD!srOu_B-H3Txr2 zMr9%wnW*;kkw879RVH$giE2-OH(y{K?%FLy`i^#SRiiSIi%d+FnTQ1HA+0izi%e8| z`beN%T-B&d^omSWd-`}T!CH7GQklp_CUTjHNT43lggmUD9K_+ zeeab!shvLf+L|%rNQ(3dJ;5-mjaif$>iifqF<2^50>*?4VI4 z)t)|TAZ-%g%?@J|cbB7bC-ui4c3JLKxs(Qaf@7YL8{boQ`g%pRr$6_b9oCk!vlW4Q zNQ-B-J5^x6#mrHA`lx}lN$jnZkL~>7j@r{7S#Ov1`!@~4WLu#pIOYk-KPQysdRjy6 zq#}WONUJ`#MW3rZ{rTlKTKCF4QyOR&$2=i3F22r6ExDui^q-&n%DQ^tj3Q7EY4N+r zQJ>ihx>ito`lx}lNr>F_iriIu`XzF$weB{}qIPl66CCp@6RF5VwWp67NT4M`L?&{P ziMGtdqLaU{qKX|*aiCos^C}a)A`{h~evy}nR@1zHDgx~ytuoOoGEwd6qXyC@Au^GR zOiWdK`UMwRCtOb($v#I@hX)e2xTKG6_7NBY~DoVrR)s)|hlI*3!CE*oIM%fW5~zo?sj;;FM(c-T2`bys zF6ObRfduLyZ4yTAf}W`n{B{>MIC~z};GY{+bsxx`P0U37xoi&gJW? z>ROUOJ^i^uXpNBdWTUo)8d!FSy<+7$Ok7LFf9_4vEh=kiTGrB^o5X~~kyZ5(B(Urd zA`UL%u&15;teS37SxeKhmj2u%n*PyZqplT*ke?GGBIlxY`L0!$s_Gt;N6@bR+|kfP zl|u6kuQDSX4bfIqv=vXj^-49}2l5Eo)t@^WnkbxFaD%QDh;TG?pU?Pio}qzub)P%L zl6=3cd9<&W+M(CA&97A24*zYey8fvDq(41W&+!WNkS1i};?;J|Zo%sM12vE~i2-NA z*yhzNMXvhFhR4vzlLwVo=t<5xL+O*6U;4ZXE?AG9X;nvEe>5&Ugl;K*UJV(NhbD`@GtDC6pbQn=f2G z$$Q>A$bLlm^=EwV?;il1KNs$V9KmM0NdnuE8Otfu7)5Lj3;6l~67+(JeC(3DiSc zJn0l#gp0gV*B?t3N7AHI&Y1yeQ$ysHSLBtt{=hR1(k79%&Jb@RLAGNLV&A0Im#c8h zSFD9CZ4#(~1X?l)Jc4$yZ%iUMe{Y(z)I8N6SPNU)Pq<_pNT43lenJ#nY|Gb?^x%c< zN(1d;-$(m=b|n}G?mi?m7L41jhqdrSh)=SZL>lfd&i5@^XJ zjveYx?{9G;M*=McCa~R*HVO0>qs3WN5iW;wG4u*O!MVgFnpGM^Yu$IU1Z&~U;8@oh zNT43lrpDdF{i(ZxlkI31^Vrlt0`-tKH86LPHZ@lK+?_R__0ry5blgVW2XYmLnW#T^ zR)q3~n(hO61nuh29Su!9u@elhG9w%f5qXMeEAFxjRnvVSkDy)sxucH3=HyvW}#4{DL6u6Wq&(zquT0_<{iS7+tiGRP0 cRZj>ZfiWRX$lAm+Ywpd-Na)s;8b}lJKVG))5C8xG literal 0 HcmV?d00001 diff --git a/bhand_description/meshes/bh_link3.stl b/bhand_description/meshes/bh_link3.stl new file mode 100644 index 0000000000000000000000000000000000000000..d9361c65d5809debac8f7fa3868ccd38d582c9e0 GIT binary patch literal 183584 zcmb@PcbpVO_wEZp1i=JIMxx{(ncbb~CP_Wv(cmxVm$t z$l3Ig8nqH{%5G)vukcpXl2?O2jk03nX6r<9|+lFp^SF zt+~eU`_}GY+C962i#uK)t-5}B&VA?o8ed&waP)(NmE(nn6;6yYzi;&R581CiQz)U- zRa5pw?|f>eZhu|@ClB;a8V5I@j#GY0oj>lq==}1tb<2M9+0~+!1rmeWsz@p!Zk77$ zjeXHlpUl!79({(1g{2E5+I?0ajgUx6WuJIA`q%@rbkX?%6Gcv{M9{Th8X=LCI#TG} zXvcQ5^w-@#W}@+XD)H1qh0+L#q*Sqj??hiZIaA+J^JgZ0-fT2pJ~xe!NM`K*z9(8_ z^-SGtWdVl>b9?UM=$9;Q}-ENjER@Vszi~c=cN%6NvWH5?TXes zcc$)qe<>y&zDgyw3@MUENF=3>y|6RdXgIw6siiq3i~y0Fv?eOHABOk7t)C7!K(ewv0vQfl_lH={?lP1pCV zZN|jBqi5n17N!#tNvSq%-iRI?H(fU>6k+1GH_yZuexFWAB&Et#-Vr^&!gT#_W;-Uf ztvwU}rg^b6R}x97YhKzGUGm&Cecu1NGErsTnfL<_q!SWJsdp>C7M*kWHa&FW047Ft zIukEcrg)l$L{h5JY#}VLIPvci*fFYR;LUv$HSEK@H5wB^KV_NYl^OwbPtD zC z{wiHHD5$UgVXn7-Pr=0L$L4Z%srSe~xpFmrG?i^*D!e?%%&2zviFn3$ud^#`g|u-s z$kTtVDXF_%zRAfP^^jJo-4)ICV+We)iy!HbjT)GfOT2wxu&(?26TzQ9yy4B?SR!%V z*x#~gl+f&@u|;{fuKJo$NTYFkr}C{{Y+XFD>+kuT2ev|5sYtVNy5^$Wg7fCy>C_7K zkXGv2Px|TFmlV-MW*>bOH83ZaxT3&RJz(`0xmhP~b@HIKvBLKKt0)iG6|Ge(%$oH? z-*p*#O{^{AR3N4J!D!Tad7qKTY%*DUCdEXu=m^`pt->F$T4KaV_+(em9g ziMs|B&7wT8Rj9$VIrk|tQ9txtNpIldB~GnS4{4<)kDIOUF7-`x>B}3kQ3G>wiBpAd z(Hp0)@pe>HFn~+K1;Vw<(z;ngY! z33Q0GQh#64L(iL0z%R7#DR25;AI8ge+r`xl=LEZQHNsiz_xr1C#x=K}h&MX+I=jMF zNGo-&*F)DHt^8Qu6;9@;hqO}7kM+}^{&Jq*_r5Q)Q3G>wi4Tijq0Nu~@&jX?Ji;}K z^Ke~-Yoh=C;>L~!wnAE|n-k~gjTiUwpI-EU*W`^6@ku8OM`$F5t8;`#qD#=~X6ohN zSUhO8^t^5HcH>TPt*{l+N_|`Qe0@*X4*mtj*ExBh9@0wPSfaU({n^a_zQMV#q6XH@ zC3=)!6?B|+vp=WaR40#c=j1$GSK(gkFRWQJyK~*U;ys!b=W{r0g|vD7QMZU5|8_rL z|1+;866g?VrTitI=l1+yvcEHNho@A{>h-=T!PTWR6*H6Am8%h+U-_etO?_qgr1Rq$ zx(vH=TjkM8ZL8QeXjf#kU-95ZCv((u>4zJx3-&xU!EgN0x>r#Hb8?AKtBhRxLx-vU z&vztWpNn_Q1NF@7s6mHwU%X+qKe~L!XG|-54u^U!P5+-cfAi_Tat=qM&-}lZroZKB zM?R_%6dv2jkM1vLsG8Lej4u)?_hnu4syeUIIL6GZ?YQvre@b@sAN!($zjsf!XkLHh z5pJaKe;K*v?3w2g6e-VDkE>^77hXHnfArb89{r`8S2D8r>537zRUWO>thp~gvtayS z|Hm=^G9j*z#+;Oza%x|2ThY>f#YRp2-e0td4}9b6tjD`Fk6^aA5-D|Wr;muyBSwF4nm$5Z|>;f;MVx=xO$60jz-sE^r zr$U?g*v#|KD&#gV`;hlU!O707by@+<@x%Yb{CBE8oH6EqThcU?0&PHIe(oh4 zw=?VAE25@Wc`Fgt4NRFGfm}&Nv6bUiU3~P1H5HmqiVj&g$N!;jhe+Y=+q0g2lr-}C z!-=GZow_~#=AAXXk{f3_gzGSmwyt8-=Ys|}iytifB-aXi@Ttnpm1&#@KKR>K^`{J-bt3|8 zU5zNaIX2M0 zYR!b;joV6lYrdcCWR80u(yj)^LRW3fs<*nvf|rtc^sah$uo^>K&9 zx*@I9)_?8^`d|M*Zi}xbI~qv4#8qz$3U2OLH(1?%inG_^h(SH2DkcU5?~kh+lpQw3 zafSP)Zm%Of+F*R-#fbm?qn|Azt4fl(dX_6uIoCLcO2OV zkwAw^wJJC>cfYEnS3c6&IWNIhSU1z>Cl^FJzFl6QsMVD<9^1Y<{kTKEBIg3?#i#D9@zGKR`U+c`IVP_6^47e`gQAq zX7S4ZdVA&%X5w(ClUYx^(41ctS=u2UuGAv?aGwp{Ezt?iIRm{a652U`P=i-D$$G0$ zbDw^wmBgiEc}?ZMy8C#;1JV5hE9y7D>&%(Uc_L*ledG2=xGKiXuBP$zGQP8o?U;QG1kzB(3fA-Zc5*W!6F>;0PMxYaXci0l_^lG0FqqNyAq7KCC6oK}@3t5*W!6tby-3VqAQW)Do$>LZrX@ zK_ijgTcG!PO)EPVh=}P!PiL*CBWcy}!KdSNET1mQ??c)k=Ks>(VWIgU?_Z=5q~j2x zA+C_lyT0V>lBd_o)f8K198Ysa4k;43kLkKQGuEqp^J=5=p5o|L%%r{5x6iynbGAvigL~ zvK31t4xB2N5CSt#YV6o>jsNk?8qT-)N6ch2!xfwG&9^T}`!9pWjSA`%QI%RadIXuMv%rl-f1w`_;Mgujc+x>fvf;T!r%>uRp?dp2wRxhclm_w;nRv?>_E= zOnFz9;<~N!Xrfwl?KBs@_D+AJJBa$mn zxZiQ+m`Aw#gqeS1K1HrFXM+Fhq*$iBuTHM871Bvh$^XXuaEDCOKy8=6{=m2xNvYoE zQ_3gEGff zNLvka5c4rZY=zq9vkCJ#&JpuD&fm?la?m^KA#F7{k8tPYJkV9RQ-^tkpH%y8b6(7l z&!8v|Y=yMd;5^VTwnA+)Kg=}%=Ewhe!%x}h9rciQH82*s3eN_@Ji;XKe)c(&9sIoiX|&!bl!h-F}0Y=yMd zFb8g}uoY@6HOYLoJ-^g9xw-e2&!jc?{^#perCMPt)H6M3K5<`eK5-vEvTP2zLfR!- zm`|$9wOJdSesDx)NW@74D~ftbeQz|DnX3~rH?+&axJbK16Z0wZC%>GhZ*0;zGwcu6 zz;TRv<|+%*gV&lhYhT?;k_Qt=yF~cut1gl~u2ndrn85jndgdCh@LHTg?=6>k&IHmf z5zY_YbK^bP=p>vgX*txJbK1_{pfA zcA#uVxVEzf?f|Hlcg0rOdzNHiT%=th{A5&ToouoG{^vK)Sr}{J?t^;DUUN62+LtXc zF48U`*ABj&awg-R4d5AoTnVU$v~pazXD>*Udv#ajrfF03-8=7b&f$+IOzG5_jDfxnnlo8XSGTL}Jn8-?Axl zY=!HX>A_y3^wNnFgZKMybTp8_NJ`auZ<5~q#=+>rB^Nsy7&oM|X#Sgbbc)@gADy+z zyY8+r!HFG36Yss=H49vEt1zdK*i~kn?tADGuiU;hjt0iXNJ?F}vb%25ynsLRw-t^C z#tkbSYMd;7g*HF_x9!IUAD{j(UgPRr>n(D-apa5^T1pub0pkI$=o^fm}E$P<(STp+;>=zkiQ^7 z$MXB+^)s`_Zi}A&cs9R_b9%y6QU9xQkzt?ynI)~#iJQvT^6K`v)gSo59Pg&Pu8rys zFN{RGlyk0OAzH3&G1t(4yC>@JnBc!S@M(uQn_kkD>A_lO>p{sJUD2^p9}nFV{doEm z|J?<#;0u#SUz11M?!R%i(*Kx~QY}Yqi(dH2Y(L}C9?j87Ds9%5aI~K{`{uQDm6N&V zM{`e^ceeYTX`J|Mc_x1beaTyy335oEN7He#H^M&AMJ6|n+0GgvYb4y71Bx_edqqnI#-wQZXGg9 z(>#!I_0Y=Ukz=K{XZ?I#X2K;hTVEb5T-`*|5B=rX1p#M{t&mo#(8|e~gJ&1@?%bTz zxTpNbS(R^Yl|VhDm1?nbQ%;L9&w7`Zo9JXtgwQVW?Q+li;nT*Nez1zzijKvtIfq-= zx7P3TM@D-+GRMih_`q>?rn-6Tsr5xLXH;qZ%%=_Y2Zsp%)EQ79f?R_B&BE+%1FdKkibaho`&p&UT%{@ z-Ze)jXl(JXKkCqnbBF--Iqfv!*xZcMSkda2d@%t9(lRPH2TF> zNV^*Mt!oo~tJ6@{Ks}^gB4cc)sQ%<~CXmjbpuf!f@q8wbb_v=!Ny+SK1h3@*$dMMnU7d?rE1@I^3}m=ySH)c=(PE9-K3LQ9}RB8dNNm(8nLXQ zmvQ-PUY+Quv>udJz(`|IE7a_QtG{M^x;$-@BmNQSZ`P zo%I*cYtEUoLf8k%rJp-5oUXN)2k_AFk9S&6UK(NJ_n$<7F&p+S0%G-6ly_ z;rSKCl`}F|bnk*wkNIx~cB-Lz{TN z55DGIA6@Zrcs8IE67Jb{ULJ0wJ&zU3%@{w=t5I#L4zH%*^Ab0%vgZ%x3ZeIg=RQ$s zfmik9JRB2r>mCvK#yiJwH4R(mcOI%T|mZDEP{ zxl4YC(-{(;S>QQ}c~@=w$B9pFnIFtJHbr-gcg~DWImralF0ri26Okh=<^>nEpQ`En zW3jm|qvW(^38Y=3``}k1T|XWgd}i){C8E5!%A!bkZYZ=%)cR_LH*`=PUA;s@jh{ii zoYOP<*A21wMg7YszIwT5)L&F3KK!l5=FGCn$B(tD(J~|Fe`n^f2A&~_o~x0&^4y4? zwlWy9ZK6{v>;tTuxhwwKi*g^o@~+_H+$j#>_JMQ8ne0UF!SG5T9#=?&SLuagVdBtT zxtrdd7`!}ks-uCekWLDOGR`Q$R;Xf&E7 zk6*JohervvLfUGWgP2BjY=zoNovD0&P=CR+VEPx6oy<`WX{*6`gjauY9_T8(N-xZ# z%D92S^%H9cXGTxaKQH(!KIXH2oCmf-+G=nf=oed|wt3&@$iSdNzj{HZ4pW?3p&rs! zgYyWll*^=Z26Po(*T;LXQbq2b5OizvR_-_Rr#g9HE2OOk=Yf8)6>7T#{slF{YX_Sr zUllF-Yi{sYv`FsmsZ;gralgm!KeIENRv&DIv{L;m-5d10^MTy@2PZpuAng*@O-3+xD!Ai#6>sM?Q}w1sFUB8gvyNTih(TJZ$B#}3u2@;x`{$dt`Q=MH6cOTR< zPrtbIy`WyD(!4w4UW*!-leyNea|M0!`qw?$&+#2PY=wQ}Y9N7nNGmmee=~jH`Ol)H zf$vRXTpSCoD*VJ1&#H~|FjH91K*X!xH#usS4f~9(&nA81sChNSzoaRz8{To zaeZ`MA%S{GoA=urybug4UPV(L_`W*E#j^p|6%we2v{J8^TAX`Dp%$!xpD18lJb!Rq zA%S{Gn`;en&JT_@sHFW%I%*^^ZlcK0%uT_0iSriMGUp8aPv0NSJWyUgSfVSRGt@VC zz7#lFErG3&HfOKj-WP2%q@q4?w6k;WLuWNYyTl7qpUEw{xvTy?r<}&CchDi~nYARb zJleKF7hP?81;-WAF0rTkyU|1Dew_Usz7Nm|9n;f+YCT;vfwcLY^ToBf-Ev+G*8e%y zr|XD5iWW$;%Kayft&leN#C_B#S~YuyZc)8CKPjZr`~ry;Gfy~IY$0uW@bZPx*4NL` zwbr)eYn4jfSs<~c*-0jZc8S^_Esow=caDDjhBCS2>eo315`T66oe7~`qDl56(MwLw z)|W2q!$h?i1rm>`KbR2OB|iJ=vFOBiX6r)@r!&!WN`b@|%aVl9E^&JK(&%d&X6xVd z0w%sQPfyz4?@!hc+9jSE@?`X{d9(H54NIArKcYaQee=JV5ZWbLSA8nFqW^5&^5i-u zUK>~-k=62VCWLm0=#k~oB6Vi#or!EFF6vnzQS^pWObG1~k8W8J?RI>YzP;WqCZx}) z(n7n$%^&ZL&Ydt#SNOMkK&`HyekPu^eAAdP$wLxgtHG z^9a+DUjdUE`K1>0gWl;_=Dbop%kGFC>o-gHta^~EJD_%f#QZM*a(_srkv7-j9DgHP z_mWxq_?Tl%ym3K+#CI2+VM1t^D4F|Kw2+>u&y6YWj}pgJqWL|FGZ)$=){NO19W!*M z?si@=CQ7|wo=vr(024yH#P5IXiZ(bgLm$1NG!vs9R*BbtJ104VL)s<&?yx7i;?^1Z z+RfFNnATq}Z!6WW|7=B)5`AFQWeSyj)u`g5mw zh5cmx+vCr_SJt@_RH;#=WAXME9nS4Ge70WlPm4&SrfcGLwk2JmUY@H{`>MS1^VQv6 zq?v`E6}-E$apaG(i}>}Kn@6Xs&yQ@|u_gBfH789&;v#K6!8-Xz*6!vRIh9Y(aWpV4 z9m{(ITr2aA+Mo>=U(>N(>iR)X$)nHG==ZW;B?c0tTMTG2E|4m3MB4iEz zZ$erTA#3n|6Vi$ZS%d$ZkXA&<8vNgcv?4-Q@c$;H6%n!q|2HA6h>$h-zX@qYgsj2; zO-L&uWCd5Mc-92}kGT_r-EAiZS?2Dna@QPc_35d7aeRuTd)JmxiIEbmC3Kd7=M1!m z%NcR{%!-{vJc{+WDt@UfLe6Kl+M`m`Fz^E1hn(B{3q&eJk3URxu++q|DB zXEGF*2%%jf=_vVbExJP5C3^Qh_j1aCNFiw7pjP5tj_LQ*E_w9>9noLpxs`N`cM=Gl zPAm+cfSF3?PsnpCi9kAkLY`Ym1k(8v^4v-ykj|fw=T;JdbpC`qw~`2?^C#rFl|&$& zKOxVpBm(LD33+ZM5lH7x$a5=+KstXyo?A%-()kne+)5&l&YzIyRuX}9{)9ZYk_e>p zC*--6L?E3%A@qO z`x^Pn_ThE27Y}78 zq=BtaPvX=6x*C|1OPD+Y%A;odlUk^Ot>l=rU5!P(+eA#yv0v}WDSi@eF3GXmEY^~})98Eli7V4`vVHE;{6G!#jrk@-bC8f z==1DIJ8RbsxsgXDX}GRT4{9@OsRy%PUp16RIB8%jq^(Abs*ANkJ*2q@X@#R6Owg)E z;}vU_s>icdn^{X^Hv?TE?P^$G#uYjtnpPsp+|9$xT5V=6&A}Y{3$1G81Y04^vz7>& z=b1>LL!|RONv&kZ!L{AhFte62r}ZkEGNgTpTwyDuT@B2f`bPAS=2=U9PAhc=YNX~Q zb#pZ^E{#6f;nG~ilAN7`aq5F`2J>+^cKO(jc3oiel(q5~7$s@6>xu|7bJF65BPP^H z-D}M(ijxMm5^Zvuzeczwrs;7Wyw{eRIj(j%Mp*;n$}wrX8sUz^al=)VkFjoc-L-qI zSzlQLTOsXgpm)?m+TA(B)iO;Z+zt5mcBQ5>8NSNXtXF9SMq*d7q&K_Qa<&xLjJ~ug z*qzhvwPx0`24;)2C3vqzzev!rL~>nGt;{T9C*<9nx1~9>wX%DynYHW+ogkge`D~e^ z9@4hYd9Ovk*ot~kw5>)=_F6Mj**lFsbB>#qlkGvf*Geq(j3DI^n!gZIuhpT8> zPIle3do7J{$^*S4Z8c)Be{fvXLppu0rSXcjO4W1s+Heg|a~19%{Cn%l9N4{zF{=C8ltNC<05UoALr2levf$t{etf-NFaf&P+KW|^=QBKitRz~lMSO=*S3ocEj)}h z&H-^oOSYC^oZuWXI&F&0OMAPSXEMmEBO! zZ}?JF&mT}c7h|CljHHwqC4m_w^uB0JV#z3xxH#UFGJWouKG)ReZR=hY=~y6xU13~_ zlpH0d&!eW#`Mp;pu$3I!KG&wt1M2ew9Y#jV?4QCK=mcjP_no9Qs=qpb0)}%&@PcW z&xOENa%}tDndhd@Sp&U?b0u_@I?qj?JDF2lq|@iQ5ZH?5rf8?nbJORnfli2)*Hql+ z&ODb`NYLDrNa^$3th+XIiA%MT*Hr2ATwZn2UTq32hM-D^=1#4!6>7U06MtiR!Cb7a}e{VvL(LQnN*pK{t>hPGKN$uv*eauL2@@H-Q6>n7Z zU%8-bq<5(@>KR%*f-8?4rx;FUv(#Agh&|ki4a51~W zR!FmkiBJFB>Y^Uf=6gnG{T+R0LsOrAFhgvG+R5l7KpKZ5w??{j@HmfU#irOf=(?JG zx{SVK?-{Sh^s4^Kw?;<3-q?`yz*b1JhKW!AVm^9DJ*3TZ4c6u4uAel+A|G~dwBh{w%NYg-VbM?++rFEx~KYByD*L5<-xELwvM_kE$)Re8< z8=hJP^B%ym+WL!)&jxkZH}JdtI3aS!efP5~%ob^@5u;Ip*`glON|mqGO!s^A-o(8h zHg~Fvtx((5pgV8r&TH~c$FkSDu73I|SaV;`x#q6ism{};u@%y;hTIP>8ls1^OUOOv zL?E3%f%QS!C2qdAPUO;QOQKu4&+!X&8qQC=7_=ebzqDJ&18Jl2ZG>FQgx?dpKw|Jk$TK%h*Wn&=qL}MpA0t10D400*?pJU2~x` zN>BqMnP(?Fw1Yp*sd{XVzvfi;=#)7{a*qERb$SqcR;f+H_C&j`k9nU?nc~yaT8@}I z?}v4YFd^BxJve;Jw&*LBAI_Syf42W_t)9{Sr3&X5vWqJP#boi(D* z9EZTT=vJw|e|3vgD|T+s``uZ7`~97w_nkhF)As!=b|s?(``?^}Pq-`c#GE2Qh0U}4 zw_0|OmhQ7J=bz_Y0wXC^f63vSuhW6jIaB~=FmlM1`8kibYvt?6Gr^7N3mbJuR0?bj$hInwEiW%1W{ zMj{v&*BGS^-P}A9x%g0S-{Gz+BruXv8~XeDgU`DJd#|p>W7nKt#p#?HWY# zVBGMGgI8CjTIXyG)(DIlp2Jbb{xPe72Np&XhErEulIR;n@;LGAs3@a(-rk{{^)ktIDr&%()N$ z1>@q`xtZsE;$E~#DV?z}(;-U7JJY#H8m&~nHKV+xMcU|Qn=1LETKA-LpR`s;o2N~G zACFclI!-UB{ep)CdPj%mOuu9oe_OE?x!#u*_)OoNm#_wU$5%^A6K8p|H689XvCQ(x4(F3+efOLMYl zO+*bEm7=ZGy2YD<$E%mqrN7B=&N7goxhav%^RK#8^v)b^qRkKILC6mOC<9lz%$xA_wh11*xbUWxwdUdHfvy9d{@MLor3D^-Tzl3eRGW_JZmc-OQaDP zNvTu%ndtHEz4SjfmUQw!4Vujo$vsabzu&HYA`3nf=Hu`)dOmiEA~}O1s^7!>m+-UZ zG};p8Am*>!+CQ>r`{QY?P@9PuHBTi_j|lUL`&nEy?9wfA&n-z;=smm|;w;2%ZF@!D z*Lkj_3P`i7@INshHIP0l!FhDv+9}exUh+CJbP`@`;<_?A=1J*5pdQk$Df0pV)v*@b^ z4`#|Stt&WJlv=g9Q&7F=3>|NCX~wwh{yYbXNL?jlKAKOkMs^NJW7B68yUgcP8{W@JA>NO<;35<)hdD86-qy5Eq z?Fa_sJd{J@wQ#S8Sp(zZTv4jgy%+hv{&kJMWNFn*Bv21&^GzuikMXbfUiV%ew>^hq zJ^c6WtbuWHu2>>4L?#lbhqQI&8&^4`zHZ_TtbuWHcG=85lX)f*sd}=;*y{SGy4h64 z(!2Vx2F9gIo1bugggxk+9?U=j^^i8t<=nSD$i8Q^|7iISYe*~^i4qrQ7mq6%yZ+$6 zhu1^`_2l<7j+OeY!f4(2%Qw80jd$l%)`NHzB@K*=v&+0YcuAMw{dUv+Z%;4DouT{l z3Wu&zX{8$8dy)S6uWS7FM+au22GXc!o`7lY3-4F0b+EtX!knkf>O(sY#YHDLgOz&u z;xYPKGp>GWQ7j7y)I-|5HfYjY@4u_K-s>-pB7t#n#V}9JE_sn2(D_<@LS3Ab{lXyL zoyirp!Z~kT-7s1|W@c2Kan&=CKs}^+o@<)tuYQ`DjVlAvu10b_$)Ij?GjX)h!n&$wg>eKi$>R$zYrnEG*@tawBt(GcwqEe)IdUxDH7+w_gYe)%PU3t z3&zD2)s95U!`?ZGu2N}xPXkpqgT^cEgQ=}hn|shVeNH`?Ew4<8Kqt5cTY^T3y*o3N zz)04WPkoN_1LNZCvbFN4&oLGf7>QQ~vyRZen3ikD$ko~UhJK%HOU;R(o}w$y=r7o7 zSVKz?(OBzDwPhcxL7HuYCNiJC{y4Nz*3C>_w zL#~07T1nirJgkOXXGa9a#TCQVKmzrU&Y!@z*#DL=&fHOgdS@jJ8q;!(DCL2p68pw# zFo8XYbp8ak!kLPC=^At$D!Ib(inL3hhFp_Mbp8akqOl}%1@%}XmQ=FiDo$~!qI9nW z9fzZmkMma1_v6E5caF;$nHk|}w9UilB z&rTlX-6iCH99rAa71AzYd>Kdd&&`}@y1R--iJQk+&NA2)wnEyTm*ANU6X+1>q#gdR zaYePFd*a9m*Ks{Fj&l9PNbZ;N^0ePo8wdmL- z@>J{|#olT3(S2~KIoUp^^Ih33IWBrfI!}Rm5WQ0?vof4TBaeyca4q3hG#@D^a^-4- zPx0`d>_1k{$k-LOLOM@@T%iUM=+Le{eysgSUVW%OGQy?ONV^*0D$3qzb*BEHJX}}u zv;{ho3D;NFz*b1R8kh&_A#KkSsRtwBitN;ia&ieXcIgQld`5<@kameYUv?klY>B4( z2Ptzm4>N1&%#zO&!`+KrVJoEVnI)c!GJy_}&hsRFPWN4r6I|O}jWBaQL#7OAU!wY8 zE2Lcw>;vi>(L>svy#{oqj~ZA7m&j8|j$MgMqfd4?*Hw6Dn7{Ph89a7r-kJA5c^1hW z#JQPwC(_0z&(Hp=bjQeuubyH8$Cx`mF8yV@H~5ax{zEeg)?2Rt(9?d0^=fWHG&^6-umigYxsE?oCn4wLTYHf zS?-R}nsWKP*w$B30||_jcRvo*iil%(_h1c-OAe)PtVWP={L)q!3ki&5`-AVhlUUM& z5*NpqtrZg(OK4d|iMIXWoBjx>Kd1*K4~&arnl-4;HT8$YrC3N{B<>H=@Tfm_UCU1$ zVs(s*V~lI%Q@?*^`U7JjfsriXQFU=7Vk=ie=0~&s6?uM`nq)zBv#3^K-|(^R4`1eo zsTC7p=G-c*NJz;1@Qy!SJIo_ZLkQa+&ioJ!bP|rrJPl`l2!U~tKI{BoR~VNFdCg$Q zuALvEfkZf_Ia2!kFl!0_1>=%Kd7WT2aDJo_;oQvApgSk+{GeFUgAzCFbGKG@euyh{ zBFDBrocSRH#tlbho`y3#_Z2o3WvYhvpB;J;v89AkF0+xa1`kO)V9s6i_zjYgRt z(u3H_)%aoPqR8H!tAh&uME~yUZ6bSHyb|B|R;D>e%)91_j^*wurFND3Au^))lwjQO z+nlSZkibYv4Lv+AdQH=c`pql5_})WV(SM(48IL@kyw6MG5-oREDfP;NGSR1>emn5` z+~O}N+$HkI`rP=?t{Ln~2pP%65f!CqB8hanu9IgG+^?Ky-@4XfkBhfu= z?v8(ULGqqB$(9JY$IN`gs+tttJ+_iQ)U~sZL~7lHR_d~)uS8$!K313N^O85ZYb09k z;YZ^$I+o{JNnClBUh)pmcl6`YuSWOQ-(FbUM*{U+R~!D_9BoqX27U66BZ0)Cm6KZ0 z|H`pEv014FdnZH-W>(URrgYYCmXAc|?Yb+z^`h!bNGqb{`OD^es4mzP{e0M1ec|Gl zf~d)(^qr5!Z@j3C^Bh1Tgf`D1zi3r->Hcf=RXd7nB(N1~D^>lW!;#}P*9P~zFoEB> zqw&+RQge1CPKcH#Hk)s#s4^kC`231`+x1=2@(`l!gIUo68=J=$-q*~W`&@Zfjp(^6 zKMJlMJ<`#@R&M6E?=70U=#v_{+{Sjg!L98gpAO58$1ZBg=WysS&sDR3RP?hB(}P3h zZ*!gmjkKEwo>|JhUGyC_a%CnR%QcY6@2*)gwv#_7u{^hvx=fp0lb%Nwr*Fca^38uLvnyZPzdiF4Y>H+$nPV&Z7EW>NYRJ7-=9n$g zu1463vqe3ml}i2AQ1Oec=vcI^MvQ8OapfBN)SS${GLM|2Zz^++-n+W7rf=1hafRNI zR;uYSFDPEUiJo>}WB%4qbR|xZR;tOl=Vxd@0W{qgje?()wWyVCiGGHsDT@AV8jN+mm(v~m>Zgr7%i8gB*>pMq!LCX?Noa$mL zbgR^dHR?x-PWv*q=;Yb@^GH_of2GdkeB3m{$z1LQA-CqKDql9y9~QpI+qbN#9$IH| zWcu=D@%Y^t=BfC3Rd6%k`{`wo>2JQ7JL|344uP#u+uY$+@XyFtb3e|o5!3X0=6;-u z%>6hwT-q#wPUJ3_q^n62i+IBpypbEdW2Tb_5*W$6HmLhhf)_W<(oGL^if-BS zc@BLKFUFO-d6F95s(%xs%8m{0Ie44n3JHv))LlKhMuz`cFc|g8EPZaX?$MpM?#@~E zaH|ByrEAaWuB4>Ku{nj!Gop(I`%_#YfssrPmboW7>aG9fzCLA^ZXW9yJ<|K_oHGSl zC9svNQTX52B0c90j_f!xN6Xz=rPpUBuoZq+t5Utj9F0`2ST-nlp{s!eMpEjff*o{` zXJ3o{d}|e%A6c|>;%LWlZ0=tEtGaF(Gzz9H_j&BfcSs`SEph=XKsu zLq@qXWWFKqmzui$k4?PmK8rX6#zopZkLLfDsb^1| z3e1mJ;m%f$1`^?_6y{;>koLkmq-AaAzhGS4eR!n~%y&Ec^!?5l3yE;04mC`ze5n^H^e-J;+sOkpFcOavUq(rIp1>OD1ka+l z2Yu;5R7V0M@woD3T!m*vtbwgujl7jN`MH6qqG>S%U_t*E;4xrimqK};io zdPutj#WGi5+UiPN{M5k`G18!`=FD~BOrYLbT`_?gNas(`RfXoR6xKi|^bS3Jj^~UL z)}Sj4&0Q%r56KB>n}<1wY1BYEjWF?(SESJOl;#>?)<7rt8G@^U1nME3KY?*^1~U;$ za_&4wJ(rMs0j{cY2S3fq)IM(BZ_A=Spkt~i&J}y@IbYcyUcbo%&UvKGJCNZ$4OhQ& z=jBLXD>)|Zyz7wZYW47HOx8drIJ?+Y5Z-TKzVDB(3wQFMxJdI=_d2}aK(60p0^{Ob z;Vb)fc)x*Mty|W!Kt(z zCI0m1ujIQ2C>FKCxHun~p!-<-*zhamK9)2>Xo_U-W8u3X!fU~qz_>Uc?P%vaEs(&t zNV|7)gx7zw2FAtt=-x4c8c1NIv)+}$8W`yyNtQwH;uMLj5M$&sDZR4%z^6)o#49S5_E1LPtChjF|uXNJN?{eRcxppj?YV8mO1QE2Pg#aILVFTqi*qsAn~pzg(pG~Bie)~p<%%MK zk(8>o`IPtAhMwNovid$z_>`e1Zp7d66A=S ziN@szM_3IR$JkF+BaJ{kHxHu`hz7-)*mD4DU|bw;<~!E&afJj%VpoAwcm6HiBa#Qk z#ks;7))f*M7wP;pFz(}>y4aqz1ot4tl5vHtkhUuWk1L$#NV^2oN=w}vK3F9|eJ)kN zoSf?N`&TAjoCu`T2&t7$t(DMe1dS`soc>Z{)?>EMX_uju2*khTPCP%ByoNdswDBb5&HPCR?{qAYI1ky?^x5_d8kMdFt+_NB zsa7;Hq*mC=5I__cwY0SKL1X{Wlpwj0m!$>)^kwM0e+ zI&{XBJp&*@)+lm_ed7```iPJ@k*a4ir&{s;L34syp%bivn}>`Bi7PoFZ8f+DrKgC% zxKcOD$r9`e3DiT{x?&CKDanJ*2BcQ9+F6Y>0`**1up4j>(heY*OI%#-@^?jjBLp2w zBz8rwCfJp%$fSXBakaC3oE+I`N(Z5`v(!&|88}|IY@ap8q&|HdNvOxq>9uEonTH*f7l&I;?n3#rL6|l zN=p@~6~@IHT7q36few+ju2@6rE>39wkP$`bn)yG_4Y4;Cuh$AJhutVht_9uB7fnphKjsE7p*@ixb*EWW>k}wi;;!>bb7M>M}ufr`4G> z=vd<749?#b5*UeHrR^W2fpKvL+fl-57NN6SVK#&E2%pX($A^1b;TM|cgchH4;e8sgRMpyfqJehSmC$_X>}$I%3R{& z49?#b5_Bw)*j3v8K^hnrXRz&a&O=r;aV2q)wi;YrS!Ia8xH!fv!5T=Q9@3Uz4IF() zyBbhkyS8`jU)b&+e~H-2<(5iy5St8JRA+_=TtqL2NP07YK2ZPC#OH`{vmN` zl%&#DgKA~>4{C*Rv4)mlS5kK(&>_;+6>CV{#R=^nGGb_*r(>&;MxdVS3RXC-F0Ia_ zL46=`aR%q_3JE%vNbD+Y{~!&Fi!<1c63#=`C2=Kjk+vFKU0I`uz_>WZEWsK`pdQke zU=197NV^(PU0!{tqT@;wwEG7+L_MdvcK;v(``@i@I0q>YM??BKRnO+ZgjA7Qp%cu> z=?}YqNL`GQOaU~9swi*HThpaM0U|bwymS7De zP!DNKum+Akq+JcDu3g(}JbEUM^+7$Sx_18{0{b6nmykXnLi#yX&*njy+ueX#p%cu> z=?{lMJ*2G$)ynQ4q=9jM{~!YU->q&q2PqFnL;5*Y&*s5| zRFPVt6U@o!54(RzT*(P(t3kE0`v(yi7i(w(*-B@U6c8XonBtTIGk zTpVMTU=1Wt4{1xV297?YT@9$NUE9qQN$mbX4pGmkuH8R~!2Wlu8_q$>!_km_PSvw{ zFdR_FwCa{9yW9}<`PJe9T@R4coGP%Dg!HM9h~lDZRt4w1I5SVQVAPH6v-5hF9$ zYNQdU=ei23%LLV(R%gE+IM+v)Z=B z3=tR?$CxEp0}0ea+7hgRqYr6U1FCD+_O?S0+x>$aqMlP-yMGXY{qI&coP(5yqappA zs%P_HLaIou&P`eYMB2Jy4XL|0q5VTf zjLcxGkw&1N>nf}+6I6Fvok@d^B`(h3{9Pe|k=Rw*{y`cT7iX{?CG1L8HE|^lk+vEh z^@pr7L||MTW0qhIBv21&ORxrxKBQd@sIFbx?|J_VyMK^F)N`t9_YWel|J~|_bCB|I zG^C$X^=uwYNEN9SI>DTr{;>Op#HCS^N?Q%8mEAw66~@IHT7q3k-HAYlNLyE|A$1og zw13Emkr`|?(g@UZU4_+Ug6dAIGilJV#Kjq$zbhm#61z&M{~!YU->q&q z2PqFnL;5*Y&*s5|RFPVt6U@o!54(RzTpA^*wAG+m+5LlBVO*@CCD@hJod|S@v~|TA zQg?Ae`-hAenZZ^gjX*uuRajjnsP42nlLj42T%5uAyFvmZv8%NGgETNM&R{!A*p;km z;z}GMZ8bdV4_Rf1z_>WZEWsK`pdQkeU=197NV^(PUAwlIdF4I3e~?4ebE<3i4E<1f?Y}7i9m-) zTUV?hbr&bJf5?cD8EiGu2-I_3h1F$(>Q1XOY0$C6#TlHxDLG0j*1*w+w5tKtwQKv3I=k)uK@L&Rsjl5W zh`|1Ls~gTi%EQr+eooc1c`zYWq*mwzb8`B_?jI7DMoB7dHKN-P|tN0R+kB?JFU*7LB|poXK?e~H-2<(5iy5St8JRA+_=TtqL2NP07YK2ZPC#OH`{vmN`l%&#DgKA~>4{C*Rv4)ml zS5kK(&>_;+6>CV{#R=^nGGb%~Ta7dV^;}nBb(x^L)9OqbbS!ak2Iubz35>+9()JJ1 zz_>Vr?I>YavZ{$Iafr0l2&g|~l_3J-;uy08YaoGoNLzw6aP%SVYCv`E+J5YU!0sR9 z5cQnu+WmtF?0>hq;T)tq91ZE`R6Uyq6H-NLg-$Rhr$6leA#rJxq|#P{YGwBiYK3vJ zhL&JgQgP#AREOBuL=kE#$jKr?e z_7Bp)xHyCDC}CH!s);Lch_u!4s6S+tAp+y#7_$UxAc1;FTY@!k^daqPKy~ff-YoWt z-9N}7>N(Z5`v(!&|88}|IY@ap8q&|HdNvOxq>9uEonTH*f7ty);?gKdrL6|l%I+W3 z3gco8Ey1p&?nIzNq^&E~kh+T#+COB($PBg`X$0!IuEOdvL3O9qnKbBF;^GX>-xU%V ziCv}bAEbeCaR%E_!meah6IbF8X{!-Xf5<9B1jfZNW(n3n0`-u#1Z&{vL)z7V>e{t^ z=JDt4{y`2=&#A86KZwBocdHxDLCV9?kbX|pvw1KfRiswv1aorw!|opvmqtk{Z8fM? zcK@JO7#C}333erQCjuQJZC$a3)Lop={vjhqX0X*rBT&zE6;_uCsynUDq(R3L7iVz( zu8_b;>?&>lAPtO*GuVz2b|tHtxDtm*TMdu;Lsl6gFfNWUORxqKsE4#ASOZ5N(yj(n z*RJjKj32BI>M3>jf>A+@b;WhYJKg;!5B7>I{NNGuM4BUPI>1R?iSoJy1zqUPHrCYVxzo|))e=ze7C#5wNn4cvZn^y%q1@6By(P= zL(iV_D&5e_yX&I<{&f!xjEw(&1QY1cb@kEm2fb}mKlWy99_VNw?Gmtxau3oDAfrT_ z;3}cisvGx2cfWetyX`So1HIF+L{e&Q$A5xn>-O@d9qQ+Ay1sj)*f}Fv1LNW~go*eC{=W2v` z1e6EPBGM4rCGwsf8FTs^YlT(FYfsOb#F2rmFejJ5v5N#oatR!-7#FMH5*P~!jN}qH z?=UXb%_T4v5*W!PaQ(oz*iSBjv5>$>E`fi+xYV1pC(;OYpWTK}-=kL4f}UY1qlBJd zr_>J}ruskMF)w)ek&f%=yLQaCdBo}aKjd3t%#$|lG5ubtpFf=GKe@Du*L>TU+N+98 zh%8+>%3TdVO8gsp0@AvP6t4Ds2 zi{5W~ZFFSYnboY}5}^ufeEZ?($j7g?PHTlUw>PcnpX&!oS10BO+kKDYdGZ(1v)l`1i&v2T8K-$GrT>Z0CRH8>B{ zK<_TGXVM|>j(s=i5|?kw#kd#zGAPoxL!2GDt|*D*KQ|9-g|t#Xc1zT zIYF=HXe>SVe%HvuRgxMmAp%sZM}F$Zvxr6pwnEx`BU{j?KOTPCLhELINY1Z?!6XFfc#ft^2#`4=Rt0 ze7WwWc*#jE5*QcvVDp;u`K`eduQv6I_rFY!IW#zO=8r_Y-!;u00wbB%gKeJ9ePR2% z-kX(1@w+&Z2Wns>rT%SOK_8!d#`}HRWsWO!g5R~ryFp-f1D|$-Pm6bp^vk`J=Lc0+ zzVDDSH_y%B`OkY)mf53x+M`<485~(uq%;#qyM$SHJ+tomwC<93iHo#L&|Xe^I_>8; zJ8|@(Lq5yU<}Aafvy5{-Xcze~Qj=XF?Gk1`56ph<(|(TLk#-4lex=R%l}G1S7#HUX zI?S8pscQ++sFy#1t$q$#r|(s_co!d6IgW9y1`WXT*IA{~ZLf_%2L_qm(6R!HYhj4ydz-}eRbEZ8{{uU$T2y=GeD(8 zY)Y_a-4M4X8!h#rZ4;}e(GKSz1mmuxhVBH#>F!y>A{%aS{JV`ttgfpldBo8 zcjZV)jn=KRHj&22i=M1^_|Fdfmy@}*omNQaW&Ujc%j=_GY$eA@jdOq8!g&mwFy6@n z^@K?FAdL{phTff^%xRue=9n$6sLA&-o|`bLeky@=Lt3e=H*T*-BR%%T!VRQO8srz_ z%I}k|3N~uqfQS{-&e@deN>(Bvl9@}75Ji1%;_&RGy2)xML{cLhS9Q>;|tpC-fj_er8}vDMFBQf3kp&lK+wr?E?fv_jg>!Qi3z%DU(m zTgh==9{tzNS##A#b<^@dJ*l)(do!okG~<_E9|W}aVdj!8{a%ihTJ%d#S`*JooQ>wp z^~5JPtrYK3v-_tcw7;#G=2* zF~!Awmq$rJRR7BDH^^UzkYgfn*XI6Ujq@wFuP1R+389m&CO+AqCXIBp@0t2#KDg1Y z3>X)8QKd#K%~?Z4YrU|Zw4zvYOs+;}4z}}OsU^F9uTR9BiAU?6Q|Jc%3ymvmg>+u# zzr1x(ee{d1aYHIu0E+#Eb@zS<@ZTf^(OtXfoAU1A9ivc=t`Ujk<6UN6sKX%)|I%agwRP>)ZcxJU2fKr z6E!K;!poNPT0+M|7cAi_xEe%Ie<*c|2{|vpR!CFJnC`#s%(GX0w4Mn$FQHbbmzPI4 z2fcOQ_pOJ1Q#C|esfyP{Hmq2(%6op)MBZ`GJ06Q3xsrd$JqlY%TsMyo8n@f9^3!Ym z7cwto4T+VShvcW!j^S*S?p6_Z%%+l>h@4oB3&)WN*zt1P^%z2;n zU2DB%?S0Ofv#4i(o@KMFxzf~58fI6tU0V$LZ*lj^GtuIpULv|hD7&i2TqU};Oxr4n zR3!9@X^{T^6IPc<59n18D(1s{7h!anC@SY0CttC=Ua>6d+UPRTABXmb-TMr*S6t-L zD@IG2D>T~Izq%C%PflIixk9}x+j-HgZVjXJ>z^HRo6bRv(z(k~q?3kZ;(Os12lYsY zcZv>QG2ZXq^!U3|d5UrrwX-a&+m@8Hqj);g6Y3Sj`S%fKF3yscoh9_j z2-0R>|MhEEqfF0hT(iKuQ?ssjy z4s`EZ)u3I{^w4YYnM~KVj;R;U#O0sU+HD{F>MpD3*-4|cKRAlC*PtiVBb{YGJGm7# zZoPJ`Rrrjy3H1u%j+vLa*$9h+1TD#WcRul@$CumS%~RuDI8QjM z0G!z@Q|);BlpSwUjiSG_%V)!axO2`^RuaL;Nqb_EPX@0TblM`gcDY`4ZF@7zo;dY4 zs%nX_SIV^gdGxBi^7bzdl?Klxo*%rQD~OlY9ywJ6PdL(^2wm%3576-KmM*R8zHbq9 z>6-(3Dn4YMlj3#i^cVYQ_IUn~8Ne@WG?Dl<^tD-?VX+%P{Y(D4}ExB(S+BdMf)B%ci>1`tPjmG#b@6gXH60}R& z6Mf%xj6~nJ7%O_|o0<9!qq>jg z))i?_^nE8)al~(6Yu41=t?&D^m6%+1<7am|8ARBu>Dp%(GuSTY%IFH=dVq#+E+$Wc z|1k?($LVB9JwPpTj*^DaDUO(3u5gVqJ<@5;BcV8KN6{{6PjC)M&{8@@QxDMabe+yY z^PQGDM@|i0nl5uShFV1T)%kKI~h?k+8Wb>!moNSC&PMq9=^W%}1&@W><4wrjv$pm8zOX(XR9? zhlz+@S>8p^L(<8ss9||GPt2}zWhYV6s1VfiUUfR*G#>+NfQa*~3F*#pkkGYR zig8#~YY$X2w2r+-U$@N|xmJeufxP0Vup;A~lW4DD1Ugg3Q=4>JyA=)k?ukCHTG~;z zUZtT?c1jHBl?eO$Q85mVBAw!h8q5{-NGBr3VT5vJSMD)t+Y82^?Ud4NAy8|$~ zoN1TcRGra5GG>7ux^88=5wuG>X~gW>i7bM4c^)SsYLK8F=|n^gu0GOU z1KEw|u4c+Q?^%AR=dzn>tq9IPv)~Dv0}(dQWxW)KB2Sf5qv#1^a`WK`>XA+w%2leh z(x6@DFcHx!%ex4h=Q5qViW-)8i^KN3JhUC0G%5u3yjKHNPHE6CcW`H~Na$K8oGeAJ zta8RVR~^(Vw96fw<~+t>r-Eeu&`w`|S4ZLB-)TY@W+{DUL{37Bz~VFeW!2sp6Pjt-dmyG?Xj*JG^le z?J|dnh+bLVWtSe3PF_U~%e#4^`e7@^PNk$#A*koQ!U>n^hed97xq~}WEqWWPg#&&Shs1VfiUiD=+63TlR8Kc#;+2s!I>=g-Gie6RfhvJ}J z?%=daqE~jRiJ)E5Nu#0puv10^?Q)GJB5IJJ9_d6x4X!@YUIW=pXS;RYvrJRZWjECi z5uAT!!4ozIB5a<^dMOS?o~nUH(G$kx=ED)xBb_vqt5iRvLA%UhBBEE8cM&$vWjc8k zH7xHIhw6u|7~8=~qe4*6dxaA&&Y(^;X()2D%N^X=D-yakOVO)J{g4LjatEh5k8#+k zW?q?H(n%v`*G?G`w97S?h^Rq=dZZH(HMsgndkthao$c0n&*Gq-%WkS4A~^p(yM235 zaX1Z|=dxakBNCQHjiM)v$<0TqA7)ppq)aCbMEPuLuY zuz4=)r8pFMssEu<^u)JFwsvovu zYzHTe3PC;Z6;8M~gF4lup~%fHcW`H~Na)%uMXxILLmITp9h~Mo#$l(Ld1ZDhgHy^2fm|d-sGMzM(t5iQUigua9L`1JF?;_|S>Eu<^u)Lcmsvovu>{Ln` z6@q%+E1YmKyJ2LER&!u>xq~}oE_ZNeuSn?HEJd#>^+Ou8%N?BNJjP+Cnt5e*Nhgh%T{~q&&@R_lBBBNf z>XA-F)UZ=V8l=4jvYXC!>%3=iP|syI)ejMzf1lmHJ*YUGhRt(XFU1iF%c4fn6UOA` zBh?SHt5s5_lZJAY>W4q zjEvE04$LlhaA&Vb=-MnruPXIJanLSza9SlX4m+1b&@Snu5wmM&lnC188cRgfAVEFS ziHI6peWbkxvKvnyWz;(FS$?SJvYYCM2+lvV;0c=p^iHhkr8pFMss9+hoqBNQN!|Xo~VA=g-Jo2BSgrG6+5+T{*Tt0cx@=aLB8C7m>4cI}K3LAzXIiHI5`s7E>xQG=_GwAVm( z5A|GjQ~eOZ`DYe9VRL}qi50yRhaykaKmMNb%$n~zjK%&t~RnNAwYRjMBvMZ3&l zBBEE8cMc+`*l_BB5)u6uqj{ z55+;d+`(y;#5n9+5<$D9lSa(0olzoamuoB$QG*2aNGBp{aP^V)8pv)ueUwq_yl45L zp382kA0jya%z`Iu4$wQXqL<=O=UJSE+tTgLaw2L`1JF?;>oT z%XIQ8YFOSa4%H7^F}8z~MuniB_X;OmoI#yx(op1Pmpiz#S0r?8mZDdc`XLS4uAMR>XqRg&5mAE#^++coYS<|w4bol%*-dA=b>6c$sOPeq>W2u< zzt3*p9#kAo!{)iHm*R+oWl^K(31f2ek?M!p)ha2|Nkh3x^+Tg*mpM#C^vd!sf*z7i zUPTSdyLqDeVJpT?rKC|IsOP=H2^X^)M#gA02WFQ$xU*LzbZwTRSC#sqIB1tUIIWTx zhn-6zXqR--h}pF>N(Ak4jU^&#kf0vvL_`g)KGI$T*^Q@1?;odlm=vTy|6a5W)HP+3nkdio{V=;)C1pBkC|9X|XcX--hlz+@S>8p^L(<8ss9||GPgFl_ z#n`EoG%5u3yjM8kVs^vG7_H{O>~aTp_KJkA%~JHLQa=<2?Q#dFRTAT{b4dj4l1>^i zyLLv2pk1!9L_`e|)FYjUsKM1o+G`-Y@$^wft@EDchk7o%seXvy{4)!lusJ~Q#EM>u zLy@OyAcCGSCO03BpdRU@pA1c`nn*tEgdlw>VTkY{l3PP8t=0 zdfqFXaB&88s!2nUn_ceU&R&twwONW@RqBT{XqP)U&3TN&PBrt&?2=9zF}rrkh@f4r zu|z}-64WD|h^S$wj5J7l4P-Z+?bfBx;-H?(ZmJ(5IR8GoeS1)GI1QWUvR;ZK5|%}c zq9=^W%}1&qW>>4EOeYQHD%B5-qFv@N5z#Bly9jznI(Zc}Ebr!t>W8fuJC%|~g`l4I z3MX95ZWtM()f|{z?%>W|kiTDT zK8|t^(6e8>C`E2|6_f4xY7fvGRy{8g>RxDi-m7vCP}5LPMWa1|Q#7s;ot(Bx%oCmx z)gGXxLEm+4ma08KLodsyLAyL9sy#qMH`?Tt*(F`=0csk3eH1HtSvEiq&^U^oaOH;{ zht(dSk?8C0SfQ&uKtuP_II6GbWW4qoua`3ir=kOrw#o+{G_ATi#K<9GxXYW(+%tqSB!N~hM+*C%9u6FdaX#4uMRWhC8=vEy1-DArxqwVaK zi0~WX(JRuOiN4>{PK42&iN0U4js)oei8vq36=_eDJ9^rVQrF1PBRT5%>~cQT<1X|m zu8bmG?dWN9-q#f`&c}cnF%EUb3w??!8q|(Hbr+r${W-($o>vH3D#nI?2g(!7oA)a8 zkd7TaZydamb@YtBht*Qk?;&eH`pACKfBKmrD#`voJAVX*47_D|x=*b&L>0Al#G4&ClXR+%C8Tu4QLj3@Z z_C&cKq}f%EJEJ{O?gweBguc_mYCp)(X*znvmEnnUKS=XkofnPvM7bZNdBypshy81$ zyb|dZ^*R$A#Y}rbXOw=2T=UFP%ycBW3$Ew~X*){$!>&ntf*Lw~1}4h=AZ^ZBohx1y zPK6z%Dr0szige%L!ns&EEpmEDx=Mtu3o%!!21a)#`g(~Z!syOKUk8s!knT*l$ct`A zk@iHnAEccOyvy{tD))o5`RMBu8~3&+`m^QledwVlZa&WUgA5%5x~v~$SdlRfR?(!; zt^Lv0!KH|{=>HP0S*a5dE>cIGIEr+c@ckg^l~rd?TzZ!82T6k07L&Z{>l4@Av_5h1 z*SHz2u1&8Xu9@TS%l&T6RbxL$vpWz`JQb-wl{)dAv)-$*AEa#Q724(fL+X&1fAGQh z*bg%F5{d*z@%|z8qH9e1`9ZNCq-l__>%yzE4lVjYj()7@2dO(t>j!CfnXJ2tT>pf8 zU0w8p)F|1aCw*Nv;-6>P)K!aqklVj@S?mWXLOn(}igbVE*N!jxL0aS-W!FUKUQawdn4sNc5!I*MlQQ&S-g}7Q{=t_xFR;38!53b@r&xS+?eL zML)>UCoXng6d`|US6<1}NYfGF1+NHOOBNE-ZvQe^S*IF664*kRW)~<-fzI|r$j9dL|S-ldv z#Kg74QKZuzY%Q?b4Y41jMb1%n-5*C^54YHjmT^$eGA-}Z-DT_tNy6raH8JeL8Mko# zAW87rXeo4uevm6K7kbg%C|gpOzqD(AUhF6lTb?^%`717e&pP+U`51^OBJb-(*E)Bb zq8}tRELzsx)P=9zv--xdAEafMqgb_5r@zqqe3RG@(lkiewarHn{m1_)`a#+rq+M1~ zjn+T0?`!M_X=|56U#G6Vb@l5Hihhva&hpRL4^o8ngB*zNk9_KlML$T3oEmmr#PQgm z9b!Mo-F7VcL0TMrU3;RQ5$Q~9|Ki?nm$UAUc8W4uUF*;L3HF0DqOVI(oPW|;_QhpI zKgdJhD*8c+kiWDmulhCS+r8)q`OIfUKSXL0ZM(D6QlEI{?$z@Qv+aKS{?1tWFX?OK&XiXJstLO)5 z^_-rNE>X5qHBwT zdY({rZPyNzXmc@5Ikv(fr*L0I*ohXZ;Q3B6*zi!i!O^xYu`Mz2_|NS6tD)c>9( zPqp%1sYcFd?TpeW<}KP!8a!Y7dMCymWqZERxMS|3ALPZ46#XFOiS>gtuSh2ig%bNg zS{&5#8s&bFva9<NdZmH$3o^gwK2VnOJWx_1^Txm7f{?N6pE3Z-R2WhrAigZ=O)-Lr(XW4IW zTgvr=?4)6T?lpAJY1M%DpVae&UNNsocP8w~L~GRU!gWnOuR*({I}?1`(zUH6>Sfuj zs~7zsANpI-57Jg5N0Ihk(G%*C4xiDVRrG^=`G%q&q%`cA)4b~Iso1|iTt7%#?ev6t z)qao`2MInKDh~f_z!T0Y0B5$^57IPfm(PX;art*Ar+$zYIivN&U!PsZ^@FrEDo=QA zdo#;Uy3O~4v{$qz1}4-!lKmhpyF5R5KUeJsDMB;IQ_T}U4Bx6X`yW=$kH2t@_IfLB zSsQWv&0SaBvT|*gp3$|vcfKZkJ7LAz&yL%?_U-U?QdM9D&yiHon`wi`J3La)?X%H z?zZ(^4^t{GCx3^pK%yxhL{?+hBHmwcW_{^w5-#ZiZinJ%bJ8OF5*DFqM{N%CC z+b|AOE^h`;}4q)tciZ2_)(-vCgt$sLiger`jj%sj+8?WL zy-#iTL3>0E>XFW}-JjSXf9&dydjJ07;x4+8I|C8RaO_@no15PKLIf4B;s; zdPUk3VV~E-K5uKEGY;)@qdkFDlG~~dy{~Fq`OKSJSGlbv5u`nV`N%mRq$@;Q`%t;s zdZA5g(;hF@)iJMZP&;98v7>krWm(vR?XU+&Xb;YL_qw$OUpg}8ilazpndZVYct%l= zbX{GC~^k-4nXE(jEybF}L-qJ7lhQ?-hu)c_IytA|2;E zX&505>XCMlI}OI<33_FA<(28_x}#U_F2iVfXtb{VO0<;`x;VP*(nGhd(mjI+u6)jo zC#YdNs;uX7mD}8E6g{yxlm#CL3F?vdGiZ622JKqj3Jt9GoCNhq$H=Xor#dJN+U05I zy|TF#K|Rtja=VjB)ma4X^0e#h6$v}rWhu^wo$aY|>J{4MY3IGNGh77il6I$PsWoNhu>XG&uTz#ay#z3_;blY@sP|syI)mjmpO=iIpHU}bXp38bJ@>DrBik>hg zHy@6m9%+}WR5_(VyUd~Y%JMG4=DAGA$Sbv0qiB~q*n4F&C4zdS-N}$DrwH2R4({v~ z2|M9rDMns-64ooU%N^{!vU5oU?UIg>Tg6HBLj>(|jd`!^ToOS&(q4nBkF?j&eMw(+ zPS1m(+oFqudM>-Eeu&^~G7FxtIS^sW2u< zCbQrPn*$Lx&t*Lqd8!5)MNb%$n-51&kF?8GsvpvzUFOhxWqB82^IWE5yLj>(|2Y2?0gq?7*6eF+H54}RW+`--}JC{VzF6kI~rGAK@U9K_j zm7QuLs7KmsaP^V)8Uxjj@ON@t9Mp5!P4zEdLtch&4%5<$D%!JWM# zK}#|6O8t-q?Q#bfUiH1do1R!i&@Sm1d8K}cpk1yp@0FcuBJ3P2(_VwCkF?hqsD6ZQ zi!Ki8x$LI;A%e5XEO^4^K!nY6SYLkyq-6UZGv?;KHl&yJ{k6 zmvoH0Qa?n{F4vg%%1$*Ab`F+luff$v+H0tO=zTKX^;v#Ghea0$^;~vS{Sd*~WEMO@ z4V&k(o{KzH1C635jLEGMM^KNn%T=l$(x6@D(0gUGCc@^qOvlJ8^+Tg*mpj;dWius$ zdZgXSke)w8&@OjyXRk=u2`5W2@=E>CE40fU?7gycNd)bZj*(aDhX~r`8uMP+sV0JY zq`d}LA8D_l`q5Vh)AL8@w&>!Zp382kA0jxL%z`Iu4n){Im-SrasTyb$Jz-34J{&9%-+^)koTE3{*ctw?!8R^;~vS z{Sd*~WEMPOb0EUzxvb|RPt`!9=m}$T^Wg~Uk#@OC^+Ou8%N%;IEbk(0p38KMyiz|j zigvk!y;n9C5pik>hg zHy@6m9%+}WR6nFayUd~Y%JMG4=DAGA$Sd_jqiB~q*n4F&C4zdS-N}&ZhX~r`4({v~ z2|M9rDMntYA9{s$xq}O@%FiDnXqR-1yiz|z&@R`Q_sUK+5q1uiX|KW6N7`!)R6jzu zMHdJ4Ty|6a5W(4G7Cd2dAj0Oktmh(6)j*@@31f1r#1YgZ?Q)gshcsxHIrLuHtckFB zF4HmcO8w9%+T{-RUfE2EpdM*=GNk$;f_AxsJ9|aKPB>YLkyq-6UZGv?VDFWkOCo5O zbd0=GKSaRpPBjtKBkeV~`bc|?f$B%-w&>!Zp382kA0jxL%z`Iu4n){Im-Sra zsTyb$Jz-34J{&9%-+^)koTE z3{*ctw?!8R^;~vS{Sd*~WEMPOb0EUzxvb|RPt`!9=m}$T^Wg~Uk#@OC^+Ou8%N%;I zEbk(0p38KMyiz|jigvk!y;n9W2uyLj>(|2Y2?0gq?7*6eF+H54}RW+`)xc<>wC(v`achUa21?Q#cuuWY77P>-}b8B+ZaLA%_+oxLJqC!8$B$Sd_j zuh1@caN(7Gs&D6#2-+nbBd^pC5wy!S=Do60O$7BwdkwBW(q3br`VqP=g++;bbXBUa22?g?71vy;pWFiJ)E5G4e|N5J9_K zW8Nz})kIK_wAbM3BkeT?svn`-qKkuiF1x9Ih~R883!bn!5MlFN)^m}kYM@c{gfY4K za0K;8yIiIEAr0DP4!u{FcM&$vWjaP)sUI3eyWGLvE1M}1)FbUqhEzX9&@OjyXRk=u z2`5W2@=E>CE40fU?7gycNd)bZj*(aDhX~r`8uMP+sV0JYq`d}LA8D^KQ2hwq7F`_F zbJha;#*+T|+M4{6XYbLhRYyo<1TF4Hmc zO8w9%+T{-RUfE2EpdM*=GNk$;f_AxsJ9|aKPB>YLkyq-6UZGv?VDFWkOCo5Obd0=G zKSaRpPBjtKBkeV~`bc|?f$B%-w&>!Zp382kA0jxL%z`Iu4n){Im-SrasTyb$ zJz-34J{&9%-+^)koTE3{*e# zOZbd~dM>-Eeu&^~lJha;#*+T|+M4{6XYbLhRYyo<1T zF4HmcO8w9%+T{-RUfE2EpdM*=GNk$;f_AxsJ9|aKPB>YLkyq-6UZGv?VDFWkOCo5O zbd0=GKSaRpPBjtKBkeV~`bc{X)sMdS;nMeaL$^g22lZTbQ~eOZ*<=XCN2O7%k;w96cNuPpB(Y@W+>jJ#4mG>Ue)gS}TaQzEEG z+MNukeu$u5?%>W|k+2g^mSW_U`k_~7mpj;dW#^Iz+9e$$uhb6_w97T-y|PnH1ocRJ z4X!@YUPJYx?|r!R{oT-$(ZxZ%EL-}->8+~=Pj9XL^ycj)4%@u8(j)t-i({%E7o%&0+67*psHv*4QT z2REFfHR!0-+JiUVq;~UaCq=^MTpp4RzkhYk_pQxFJX@dl^X-_=5)3<9c`sGjZ zn?Bf~z4~Wc)L#GlMNxyEFzZ?N!mGWlug2crIBEQjj$llr!>^=uPj6hk==8?OXEtyD z@prq_9;}}iHE5T6KFekrba}4BSE{Qv+VM}ec$-YBhU1{ z^!P4LgS02EfAX9A)((5*k?^ZS_k~|vJ0|?%n*60FJjb%^%4OS)Rkymob>*_2U`(XL z@3-Hy@`%av&DtLP(hlwaeX>PuzLN_L>UoU=Ryn8D^~3a*;@~bK?TP+hG3|D9&Rj7I z{p0nkz+4#|#h4<|9sV8u=QT*sQY8BR)$R5N?J^5-aIjx!&=v`<{66yq==M47GH;3K zRvffNf;%`7;UaXR!RbT0oTo%Y4ca0>ONppx&@NBA`0JFd@avRq{W>LoiOp8VL*W-m z`P+TrmsNkVO6#`C$F`T>|GnN><{VwSvwPmIpFcXH_NO^Et!+Esg8C)-NQA$67_YNz zy*IAweRA`O?T0DG1Bxf%g+1H4DHK5*t-4dLq{~| z329G!zVzSqYZY*-yTD4O) zJT7{5+1$fxcdc?rBuIy~F=4m%i+`ThI`JPjxHw3A;)LN7+gqIXP|vto|JBP;zk6=2 z+5r!q88xUEdgOk5So_YEuWo#B)q}mSj2d2>I`Q1-)%-tDD?mNPFV`5gWI+-Egt|=&#P~J@(PA+9s2)i5jEUShsf2)3-(q>SbBu)bZ^b z20zf4@#iPiX_vGodLEgz{q?vV@(-4{Vd?_SjcX5Hcwf}8Ypq1;h2LzyYnJw0v+tDO zz0uI#Yo1-V_UPYkbA;BhCypGnetVQVdHzZ zs*QfT*J;Qr^H6$Oc3Xa4>+u^7%lH4k6&m}mGp4rq$2~DWHcA97xqY7V6(eMq9(v;4 zk9V$}ymwFZilZ2xC#XS!mOOF$D;w8_?|*&Npk2;vBD%x6&q>fO=|qGJPtYz`s3)G> za^2eXHy# zf5%AB6VjfzdhIc_y)Hg55~Mp5bJe!0oqAzGknT+EvdcEL6XxD4YLM;3nxP( zoDA)!ubVja*>!fWtu=VzxX`$drL%-|mW5L^52t8* z=%~H^aP6b})&4ehm5NuS<0+blQ?#v9lmtCAqB!BgDVm2tG)0V6W=nE-M^f zd;j4hqE}Dvet7K{Gn`(me0bQ|D|$jYR_8oa=a#B7J)s`yc+ZfBdxnPY8Q$OI;9BqQ z*F>*o9d}^uh4D8>ue?U^tGn>6J709lezh~7J)<&;bi9+v!<|e+cQTuObXe`Av(Anh z)bkqQz9bL#B{kib(09_FpjY!;vvck2c@K$Rad%aSB8*TC7zb%jguA{x-1X(U>s$4c zv9&*5IxWV*isK`vSK|h6S!*9KC3?kCq_ZsCi#Ec&Xs&zFNAKFVw%tv)M-A$c&a!Z4 znTI>eTz8htC}~g7s~v70SNn3OOQKiILWM}V+UUWZYEyS8?)peqi0%UE&R=eCUt46S zf*{?QIPcEz?Q$N3=bi3fi3P~*Ex#$4KTn$9X zQkESw@z*21{_%wT@Y&CG8nnxMlu(^lUNhhF^)>Q$zB_cNy&_w7El+rl(yuY*phKMo z3A--5Qq;=ugEwt5^{0<-U;Fz9>&EQTF7F@0Z>#qai+=UmEjCKF>{?zO{mwSEC4Sg7 zc1P$Ze!TTBQzzWBU2XkMH|zTA%qzK3r28ZP^*o18rN10y*FKK%zrM)DK|Ldi84N4E zrIn)9-kxK(+7};f9wTS8Jm<5l6T!TZj*+*uQl3Be)~Qwj=4c7v7m;D!m$rC?XH5aGK_QjU(osYPR%>UCS;jbvzl` z%J95LtUc6T5n@8E@{MA;q16REvW|wwZcl-DG zolk7Ml8urryOvjnEWB;)sUeg4&&0UT7u@ial@8xv>ssx{tKz!iDAN6rPZ~C91^UZT zcJ1RhYDj%0#z8$JiWyY(*V@v$TKd9^4q7K2JP~WBktNfoLB9;_E~F1dquYFTAuKZ zBc4}zIIpH%+S+J}*)0=B7hc)^XwLcF(6de(Rhz!v331Lxez8eypN&t7E5mCT@%@!E ztYojqmR-v$(*3)3%u06*<^2xzNcTs+*v|hRN`E=Zu8TPSz39b_C-(fde*6B1=d=EI z^V)w;*gyJCPpB83o&Pp!^4GV18hRFYJA!seXW51Kjm*cNeQo285p(8Sp1yG{TXoNv zE81mzSw^o&&_mLlHE5UjcA-Pw5${cY?~CVS9Ck)=K6FjJ(37=w^YZ^3zxmCIoV#|Q zOc&XG^Qk4T+h(y9ZxTTb(#)H$&TkFcrS|ULzmM}l+I!W(#aD&Z*7QKNgHIH*UuUt{RBH*VoG z4o6WtuJ&G??^-2%qN69&^8{^?pryFl<9h%f?e>o;JmFXYc-m!Is821`Db*-y&@P`1 zJ;BIHdm`9xOGg@9yIillhmTb)5!|(;J)t@)9cl0^;rYS)xfn+xc*2qPM7hss=qA{- zKBJ+JVpA(z{Xj#1#rWsdKBJ*)WM!1Tg=BQK&uHkQ7;Vw6z8hths(nVoyLOS#_lQC- z!l>sp^sABjUXl8F>04}}mtj*qgE)$Gwa=(UuJ`0jkF@&+UHn#Y=pY$2=zC{^Ug^7h zMth>%XEb!ki;?S_PNAD%jNHe8u83`Y8!z1v-*i&lL`O^VT?oHhYFo(V;tVA^0&f5AH^64N0F}f88zS4XVmmayYJSzTyd1X!(`gkKBJ-E zZj3|Uxe9%FV;tTq^j&J}JG7x2ZH$AXNLTxehCaMeLtQ*gk94)qs70$jqegpz*`-&E z))VDEqoD(FC31S`zVYiKXSDjhaOeRXGZNQT`j)r8M-+Mp$Bc3m>1vbRF+181pesJ7f%$r+R@q6LgsUmDo=-LyQkJwYsR*9{|0SWipxScG;8#o=e&y} z_E%FJWx_P{=bm7M)UY@T0(~uGCjr$|y+TiTY8P?vw-bz@C!}39h`no6>7_xt+$*kf zI>J^)nf4moMOH0Ec#W{5D*Hp7@E8a6Tz2E%UDEooE`>HXq&;DCAj0ORtmh(6J4&PI z31f2W$`RBf?Q)gweWXFV%%S(nW=(|6bD55jyT7}nI{=NMU7lUuE1M}1)FT}uPrr`O z8fA4!bM7^8ipFn}t8Pn!qeyp-gM^*bvgE2->@#ZB%W8(a@)`r(0mv3dk@gyloOO`2 z%T=ni(xC62P~QRV5$iK*rzOu1?-hvH!%dM(gQG~tIZqn&-S&s>$Vt1%orYzhtmib` zt~EUo9ldh(gI*auaGz1tbMm z5!55?HMsgndyRo=t$H;w4(hq=rd=z7vq{<$HU}bXm6Y{d&iNyo^o;-vZ^f_AyayjOOriJ%^7uff$v+H2^(gnv(1^+Vkq z83*-Tc2oTj!PzA337Z2EHqT`}7kR1%8bwbSlba7mP>;0BRjLNkpk3zBdu4eSVe?$3 zW8{_kp;5HU9qhfbnG!)g((YtP^+N>hatC+ziiDkTvJ@k))DOKvyWGLvD?67&&@Sm1 zd8K}cpk1yp@0FcuBB)2&YjE|E_8O`m{CmQBZ$Z5p83*-Tc2oTj!PzA337Z2EHqT`} z7kR1%8bwbSlba7mP>;0BRjMD-pk3zBdu4eSVe?$3W8{_kp;5HU9qhfbnG!)g((YtP z^+N>hatC+ziiDkTvJ@k))DOKvyWGLvD?67&&@Sm1d8K}cpk1yp@0FcuBB)2&YjE|E z_8J4#5A|nc9Mp5!P4zW4IFmpi!d zs;|FVdUsF+?UIg>SL%ld+T|MaUfHQ8!p^}m?KQaiNPCTe>WBI>G7jpw?56r5g0o55 z6E+7TY@W+{F7i|jG>V=uCO03BpdM+Lt5iRvLA%VM_sV8Xgw1oAj*(aDhepvZcd+-$ zW=aJ0NV}6E)ejN0%N^X=D-w3X$x@8GQa|(x?Q#bfUiIC#r+3vv&@Sm1d8K}cpk1yp z@0FcuBJ3P2(_VwCkF?iN{m{F2)@M}DAL`Y}IH>2co9c%M&L(M3*c^zkc`oa@$Wt}Y zD0;$}+$wPd^+>y1rTQTa+GP&CS2k-RY@W+>jJ#4mG>Ue)gS}TaQzEEG+MNvP`9lQl zatC+ziiDkTvJ@k))DOKvyWGLvD?67&&@Sm1d8K}cpk1yp@0FcuBB)2&YjE|E_8O`m zeRVMYhLD~=)T@zkP|syI)ejMzP12sQIS^s4^n@`L^I^|XmUj`W2v0We&YpmUj`0qv#1^a`WK`>XCN2 zO7%k;w96cNuPpB(Y@W+>jJ#4mG>Ue)gS}TaQzEEG+MNukeu$u5?%>W|k+2g^mSW_U z`k_~7mpj;dW#^Iz+9e$$uhb6_w97T-y|PnH1ocRJ4X!@YUSpv8pA1c`nm2@=E>CDB9%? z_FmaciJ%^7cQT~s4-vG>9o*R~5_ZDLQjEM(KlBRiatC{_>|7E-yQE{}mHHuqcDcs9 zS9Yq2pdM+j!PQ6FYYbFB)T@zkP|syI)ejMzP12sQIS^s4^n@|F`EUgF zNV{C6`XLS4We&YpmUj_0&t*DBUa21%MZ4U=-Yc6a5!55?PKH!JM9?mGaA&Vb*a;^~ zG4e|N&?~gd9qhfbb4dj4l8%vA>W2v0 z?Q#cuuWY77P>-}b8B+ZaLA%_+oxLJqC!8$B$Sd_juh1@cu=mQ&B@whsI!0cpA0lX% zYs`CPrW4IFmpSxa*{q4Mc`nm2 z@=E>CDB9%?_FmaciJ%^7cQT~=g++;bbXBUa22?g?71vy;pWFiJ)E5G4e|N5J9_KW8Nz})kIK_wAbM3BkeT? zsvqjr$T+CyvYYCM2+k&HPuLuYuz4=)xyVyB&?tJsnB06gf_kJ~u2TJw2JJG3-Yd(y z2%G0J9V4&Q4~?Q-?qKhg&6Ei0k#;9Tsvja~mpiz#S0wC&lcgAWrGDrY+T{-RUfH=M zf_6#A$Sd_j1nqK-d9UnL6G1)FUW2QTwAUD@eyCR?XCN2O7%k;w96cNuPpB(Y@W+>jJ#4mG>Ue)gS}TaQzEEG+MNuk zeu$u5?%>W|k+2g^mSW_U`k_~7mpj;dW#^Iz+9e$$uhb6_w97T-y|PnH1ocRJ4X!@Y zUSpv8pA1c`nm2@=E>CDB9%?_FmaciJ%^7cQT~4^n@|F`EUgFNV{C6`XLS4We&YpmUj_0&t*DBUa21%MZ4U=-Yc6a5!55? zPKH!JM9?mGaA&Vb*a;^~G4e|N&?~gd9qhfbb4dj4l8%vA>W2v09o*R~5_ZDLQjEM( zKlBRiatC{_>|7E-yQE{}mHHuqcDcs9S9Yq2pdM+j!PQ6FYp8zM_g*bO>Z8aws8{VX z`sljnHAQeXNrzu5EcF@HcZ5Z#L!Qx|DEArtX#WY3peKx}+Gli)&rgg5Vnm9IU&=Y38+Go@Vbrv)|($zkrYdyVh)SzAN`D&lh+0HGzQinv-BVFw? zY8vX>XtXDA7oKXAW{{rnl&JO@H4PGWipo;8&*;ay7psJJc}i6Kj7}MPQp^?YlCJg{ zH4SybG};s8KBL!!Uv81V^n@$F+Go@Vb;2|~($zkr&%aY>sIR5bUZdP+)OL}&R2uDx z{$ENhdVtz|Fjve%|M>8Gud&altqhK0Op)jg{|^828YH;JBGLD+qNAs+SK4J3;^1Jv zzt5<7MS?58&wK&KKBKnpXqS0QM7QFgEfUE*`h>8a7 z^0ce=8MR+xvz75s_(f9wc3>#M(aI+zhWMG zxJ80=XF|Vq9(uS%f^=ts*(L1>c7)ccAD*;hcGa0O^vjKUemoa=%l*3n6x6RN6+G!{b z^Qx%lp<8q6Gs-w@ln7eNvfphqs`cMzmd@wjqmhq%CEVkF*VEkdlHtxSJq%ApWB=HC z^}RXr+csJ^KXQisYM(xFce8!h+Rm=&6<*DD)t#+XTdU=lFSDf6Anl1aM^EcrB0DHQ zZD!`As%TN{Pd;Q ztvxmDPtB=ep6Ma!Ec>#PGk#;Xi+7s+Esveo4=Y2eV)HO8p zypNvH!`Smabw8yiq&>mTq#UI#rJ?72)S#a46sz8=q33<{N_}5L&-+M_j`u#Pe=Rjg zdxE`XIZAzIL(luDK|SA9SKV_%&->_=I_!p?_mLnSdbmwowmsyiT^c(dKO$ddfeE#Z z-n^puz~i+VN0Ij3f$0_XNc#@NtP?!dyvBZSE!^%o?bF8GCl7I6aTICaNtvEdk92(g zNZpz_if6FbSniLDw(q=urhM?73%gU4dGiEo6zd@M=xzV_a^>VGW<3(!1y}S@44vQO zoO2Y{nILg)8LkggC(L*1Z4=l4jE?o6mt(+P9$6$#Q6qR+MNoRO36Oz?Stw9i$!8*S*- z*tD*?_JqW{<&>)sebH4nbn%RF@L7a+sWZq-+mpt(S{C^F}t+O`|JLm zVKe^p_1INc&p5J0LLH7m2g&&7{lp7Ximtk$gJjdX>e?vM{gG!&7hQENa*ncVAIJVj z7hQEN4s|#(JtK7QTkVk>I!MOI873PnI7r>{!w#$){OmYbtcMR+U052PyA-K zqN}cXH4srmp7vDOgFMyLUn_LEj=RfiSXbRe{&%PIila#PD`=lnLw&+RU+k#i3F|HU z?ANEouDbF>{&E!Q{;s-P9C>Q&s%yC-Vb?|Ewrd}MYvb5eH}u<%Gf2Diwtv^oetgkY zSH8;@3H5LbJuds!u4!C*{spnCZs>#=*Dgnq?(eF*#hn+#uDTXEN7=QH#PS#;G^trfvhtcm?yb=O>DSnR568YJwx z@XEUCj%+_2yXuBc<1xFm%PQKxYajb#(N$OVT((H4D`Mz0-nXty`r}4P1 zIEr+C5=ZQ1~2aVUhH_QcRA%R?ehMipO|lz6Ju9h(-?>-BDb!(XTSWW)1Y16arF0=-SwsU zV^>|>i^vv7@s6XvtL}&?Lt5=Y_e9DF|#;&>+IY-%b5r_I4va4?B;u?LY zC)5j_{*Iiw{Awr8xxDI!daoKmyQHffZ$l5zm@C@l{am%Ht`XED-C2Wn)l<>#?bKCw z@6c6u>(o`(&JxB!J$2PxA#~M!D)z|bDZ`aPI?LXC>Y8h}S!~K=<;u=M<(;%A`s;Id zu1=w$%W<3!(%!2+qFWkv|0xa9p0GN2$SilnuDX_8(w?AKcFIV@_Monrh5qsKiqVqp zOz`AXZ`sf_G-iQ%{b$Kpzr8Vb)eT)k zyj$`b<*vGRzr#_alSa7kYnOVYt6g=?UykCvme=6(67N5$7m4nI^Inmz5Pd>LS6zFK zvb%8Qje1^#cI~-lKq6`InM}Q9L)YoJKd2YiZd-f(=?jalx}ocITqPVu+IvM$s7JbA zV~OR8uDbS&!%^xpYudg?E}!V=3H3ZdTO?>HuJ+hf_vJ(0k6m@`gkuHZY3F<7QiFE+ zZ0HGf)wRe;d!pP`*VZoAEAQc}U3G2Oa;JKt+*Q}kC7vI=pR0D&wG)mfktf#u%f|Jc zFZ{H%*wuUFQyN|MRqn}}f7-uRD}UZ%pVnmA4F8&?rPa0AQ^&Vod~Ch?7vI0o)jDIg z+6f2L>fhgdO;f)LtZV(buEU-FVhgrb+<&324S#ifd%p|TuWvf!^5&3hXLSTEW!a1W zoWF6zr~9_2ZT*+VvUjdu-~RTKo9hf;+7YyrWk+AyXbgYsfcAuA?sCNVO>6aqFPPN) zzYQ00be7%NTw`cBtJ=5iKmWCl_Qmnp`h$AtiI3yeTOQRNMtjnoC*MqhqwG5T4s1`B zz4OHJ?MvRBwRXdYv$Uq4xOIK>&A)5TaKOb~?=QPe%+C$WoZb~a|A^P&lnCF_TkQ9@ zOqGT*Y_Ei#NKL!eDAHNB%3{a0-<^HN>$+O2wKVFXcjFU%7xhTXa$(;zM3{!r|9?Vr zOTw=8=S3V#9W%bY<1J@2_h0N`7x_hZY*|G6`#+W9kT>SpJAL`tb<%H|jFxnk-FbGA zt2N$VWN8xSySySDJ~5eT&GzDxziw_2{@aypQlEYGNlpD?)(Q7)6up{uz>i&CgI=A{ z=lj%|?`U!q=`0&tTckbtwH12*@UzX@@1D9@{iAg*Y%X~7hh5Yo9X^A6a?SSdPCTV& zn^o6nKeODJ`Z*)cZ(cL*g)Y*bm}$bU?R_?!qjulES)21r+7q4PVBS2j+TstlzPMsg zbDc1g+-q)sAa8|&&ESE3uk7~5S54-Jbe7%z#wD$B&yDF>Y{(JqpU*e4{^5g{H803! ztx=D3mc4rPTdnJE*sbfrt@m*=NZJ#OoL+G@I}_aJqCub=RkJAD`j zJG1=QY1Rc8(fHam9ou`q`(}FFg2w_NPN0cLdKz z(&0Pwn><|K__>Mg^Va_J4Ns39T_5-2`Ej+=F4tI=ZFbWA^=qdb*S`LySsL4HIl4Y| z!a2?HJIqm|horOYrRyH7*ZvTQ^Ji{QgS02itKYtIob!sFa2;pa%s1B?3!nFY@l3Q= ze%bR?mtAYGa2NDPuDKuo(CGTRr=8zi_HqoC#@vIB zX#eHi9q-%z^=;~3ulw8PYy17zdBXEJ%Z}S(=f-9~JGR}u`LAju%&t7~aXdWeoyMrU z#>L3<<#($8c5rxt{QMuW8t|mH6Fkcnc;darzh)lSerMFU5hSSRy;2=loC&?>~dLdN1Z9}#D?d!h}#0!fb*S>h_ z(_ORfy_(bDDC%X|XAi&KSZ1bu+ShHl{WNMYCQr;TXsgC&zdg3S%!wm=NKnHv{lWC7 zf>$3Ov1@zGs5xqH@0;a34LFK)maTExPK}KgIo7SjBUkxPlX|54*OfAS%q^SMdzZPe z`RHQrG;NeI(TKdjN7Wv1WuJoUpGj-Xw}7k2H@ zwL zHWyiP(Qx;=`sbH6X8Ur#_PKNa-f3_Y=`8zTqh<0HwjJ5t=k|w(&EFnd-~NuF%`5JC zqj`3?uH8JedDh7Hy1Z8}|7H37sX?{&3I{LKSZ~PK`nGp1-fZ19TaBYgXW4((TP9y> zr;+V>zMg&$b45MUS$4&KzsR?}a=rFKAB=Yz%$p}x8!{%JZ~Ox7oesEb*m_&;SwD2n zY13+#{k3^!xc=b#`=-sj!t^fh)z`;tm0vMr&i2t`v&Q}#?pfdZ;H#!Bc;o-vDAHNB z!IES0|2u4f_RNnwdJlc4p4a%-a$Dq|+%{MHuRk5^G?+I}y!X~Y`D`P4Tg$$%@30Ri z?Oi`%q4uAa-Qj`ekKuaAem#GB=I@Vod9SwH|B!sfHE(b2_w1DVHdpRlAGyu@!(TXe zx*J70%NBX_pnTT#dt0wPch5caoqAs5g+qhJ+PAl!`CzisVBS2j&lkt%pRO`P>zkEl zSYf^0$JHnP{ecnT@5(goT7P%Vdo^;giTM&|e9`;yr;}@pgQG}?r-`8P*EMHo&HVfQ z@1gHDN_wPqu65`7xBk(n@V_p3Vg#>6hiY)!#C+YkH@yC)q0iJ$cx&(a@cU2bdUl?- zDuh|eveV|6n18nOYCT&o{cT-dy)?Re#MFB~a0D%dJN-o`=C^JiMFmH^h&r6Y}nw|;NV^a~S@{ zVaV>^SNY~9&7!h6|CsI(>o5OKBor-Yv&faQ`{Tg3)ppgm=%6 z*ed`0S97-8|NgOe?r<_JIpwNpXZ_^UCP#7qXW4{<56Rcq?Dp0Z6DK-Rj z{>^-~_Ev8%-MV3!vGwO)Tf8}Fk3l`O%d;}P&#=@M`G0!mYF}~hVlCPtK}%V-#Qq;P z?in|>J!*|nty@3ZzW&aCc5nVLY@Qz4<=sG*ZN29&@-uH)uf5B0f~YUEKKd z1KT4$f2x-eQiGQI<5)7g>_)ru4!_vze7C0w{dtzncE>N;2kx~)^XOrlx_cjv@{!|- zrS(8~^4j|O^P1=U{HHzCBb{Y?%`>!h_^!vchs>O{^t82gcsFX_&lc|??THs2JF_u) z%pUEo*B)^MN7=L5z4y%=-YI%LJlEE5i_f(#4vr$-pR19*hr3*H)_mkM&-r+LzC(^{ zuQ72pH|Hdng)G};&L``?9(P>($Kz*nx#B!~qI;&l)IXl>fcD!fJ>DAiS?5JZOa2i~Fo>+DDd+HbNvs!zO<=1L&UE8?6 zd;OQqaVM_UbM$$e*MFFG>Exdi}Lw?X4dERhzz3&qsdzU9Z&N-F}z$XaD%2MGfZ76AS%f+4{+I-QQY$ zzJuDUzp_#Nk59faZSez!_sp`!=Jm&q_{+2_E*S1&3g5av>z4Y>clWl|dS-lE_qh4* zmuT+&sE?diNhQ{r&y*Up%u~d(Ml8ISt0-iJLCDsDAz5 z?{96l*Z8*X+yAlcW7B?|VR#Qc^j_7MzNr4^-5zP(yY7MQXaBrjeXc!MZ0)nWKIbT&5?Qw7LL(Yu&L7+! zd(!$&g9Oi*ESq(upEtI=eti3st?q8s!@JoFoHD67ZmtD;?7gLpcb=t3?>g(f_u^gW zMc!MW_5SB`t#I)g$LD-MnxjZ(*$EdN(U|f1ZQ4_h%-Yo8>Ensp#$Vc6bc30v%{|`{ zIo~7WDAJ+g{BxGpgjH7R`uNG?9YGICXW94ntlU_7pMBfCKYiRq&ir_dYr?zD_Yc{y zIqsP8PJ^TPOdZ};JK~c1-n%W`UTpc1?e)&>s?RWW&F1gUTBC<6hI&~xbmhO-=R0wc z_TdX{(tc!-TK(iFPHWyZ*U~+tJ+armPt+%Gw@v%~-q~GtNqgd%^YZ#H7QenV=dTWT zUcFK4s(&}%kJF~FzP9r)%N~AehWf+rT;KZZ+K0EFUwpsXTQ}d`ocGtmdPva2@GAui zPp{4J>hD_5{^UqU?7qT;+Obz%(QKZ+wxhG`&~@gochCJmYuHEQ+XuZjw)W%ydYU_I zy=D*fyv7+946gUy`c&)2wGU{AcWdI``Pp!>HG4>VV%%k)G~Rz_$NYlhk7}L%*|zo3 zljf_<{^-Zef`BH=TX}x*ami6u5Ubwd2=ASjG=QW<%cJ=&! zOZ_rm;^Q%`S>D^Ve&Sa@c0D=k+s#KF*sZ?#O7C~Qckc{6USsV;*UCR?f7fVl@m*`p zA9kuwJNxynEMLlvBAsQge6e)?^`tys_Q+LR3l9nJ^}YAA+BV<(qe(rlG0S^jG)`S` z$NZ!F_IJ4=?TJ07e$}{W`@#7sOAKz)E9T7;6CU3=fAaZn8Vi22NNa~dd(?N_^PR4j zhrZNY|MNZT(@uJzYvxrybXf?WbIv$6-|djQ8n-NXS8JyScdLK0;h($qT6vxxMoT)& z)_iYNe*PkZ^H;CI zpMG?sNQb{)yUw2Z@c(|)SUbO=m%dZaN51`_vH9{l+|}4?(Yu@m^X7@e9-WvE+xE8l zi>Kzjdg5)ZcWKvAOSRk+r1$FRhbHDHj61vj&_`$W{wYLz^~&dTo%Za@E^_|_**o`y ze1`MSYdqIj*5!(NUSrION931Xxn1LfJ+^C6gL(6W-UHC{|K@X?c$2Byb8Yzl@ky9^ z;qMQI$dBGHum8B&ZM|oO$hQjb8vOgjmz&fxOU0A$Z_b{WKR9W0&xKb{@8#1rX;0j_ z*%A4>GhfoU^Rg@NS$5oB^`Fjif7fTDp6#M1oXsrzD#UTc63^7X+F-$ZWcPw~F72w_ z{&0MsL2)Q1(pfg|=p*t4zPq?F>6itEQG>K6@}+jqXWZ+{#zmjscF%)h51zK`J6*Tj z_j(sS;d;xm>xb-~-?iPBjZ;^+Vi*bPk7repU0L?X=8NaU#%+|Jam?4lNKlV-mc6{gM~%Td?UnDp_5SzF@t%oZEQ)$_e?Z+w41x1ocRVcRz0Wq%r+xM>mGOxMN$RUOefxuE~E|y@w|?PrEGp z{L70P4?n+8WBNS@IYN4y|MZVt<7Zgg(c$mJowI6w=KPB`Ze455wxa#!o}0Ty%{;V+ zc6kzozuWie7ma^xaX{n2*>-dUJtQ4|H|nXK^O3b*G&Y>}O-n0d(ub3}J{vQ45AE`l z$g*GVyG(xh;wLqh{O|C#=J}yNU(>byB8&IXL(*Bc&c8 z>-^)-AE|Hh^7$?8i8qh@UDvn`e`wMZo-5&*bAvtetABc9efd{Das>5AXW88IPRO4h zyIg&%iRZO=;!w|PY<|qSjZK%{r)!UkC$#m6!ogp>bl*R>TeF8V$V`WK)!sUb-+L~LB=$ZV@=Jg{_n049$Q${#C%RZcS=f=I;zTLd?=f^q?y(eQd z^|Ea6xBqOk-fA@$K5Q>X&=by0mhCrs@qGRDemDG{y*Fy>6NO#g-{QU(zFpDHAm=8_ zPJi(2#;Na4z4w8c_HhKW;59~`vVQ)*=A^Dc`H;5W?SEq3kB8T<{zVV%a&EHh($kj7 zkNLv`&7~I~=?HpAI(*k)|K0Oh_W7#o`|bYM(mV0TpFC*9E&u&V5AAX`!>&DROn%`$ zEA%Y<()?`_^pJFxt@eLM+Pi3^{?we)G6K2aLI(V%AY zAItY}6f<3X5*I#&Yw6QCYLMX5eep?L_!O?CPvfY;QKUmP2%oEk&(vD_Y)zjJUD^J_ zw3)73sE3|#Zi-LI!Y5=ceNsk(dZfeOHwd43h0nWM`rJ#O-Td;gf8KZRbu;(SF6Sov zN^m$bHEUH(ZN%38I+T|TicuyvLx)eTH>eVMqB&bKaxW5Yb zR(0KD>0Da*oJ+g@`2F+lPKNg=;X8NX&NAFp)^&HOySr&a&guGUpW<^IyZ51`@T+y< z9xmLu)^!J~dmMi9V+1V~r)W4q8#+m8i=Jq;+nri*QioHzq0?F?@}d(S==$?h|L)=_ z?LoVX$}&}hPzf5U2qdUSx~Mpz+Qh1(%5vaB?|02G`z$ru)mdV9QAHgLHL#&tNP>E# zi#ix;V625CXjf;V-9;7EIaKCc6@;&G!dR88hWDOYT$e@Z&{}2 zsPGKc(6f}Dmu~)eO4mQay9FG@n2M*n@MPD}6CMfbkuIJ&!}DfC&z*Xs@1hKcq&x%wd-4eTMKJLqqR1 zkf0vv;{B5FUP-R^O!O|tHJ5+fb;m}l)ku2{Jv)cz=DMDr_0;fVxLbN@{EXrEWcv3! zW6Cl;L58Qtx}G9QaLp$Jxb^d0n)TrmZ()&K)J)ijA4>d@8LhpEm zce~=dUT=oyfq#VOfju^=)ku4*zlyP&uFvn zx43WoNIxIUbXe`bStdX6Zx1x*SZ1Un=%M%Oy6rz|9P@`$?>#s?sZxV>IX78$;Nj;s z=6`Qo*SJe2Fp(Sq9a~$ZQuGjp}j*AIRpSy2>rSK*Jlgk$_Q{`Rv+dm%KAQYG(s`(Y# z7q(Hw@)b69bG=?$Q%5T%%7fUZn1>4V<`;WkPEl&>fLXV*MJP7@yqQw}{*tc!F)q|f z)$L#AzgoN6>c^tGd8Cf&dtY~CzlVO(qwM@UbS{&yd&V<@Dn_+bTT-p_Rcic{isPOuoh6w?AUln zU0)?^W$A$LR&+T66XPOP&i~X){-TSe)pk+yYK;oa5YNhU=(#%Gm5ekfpZNqfirCarHRX>?~L#>e! z#Zp+)yf#Q5^Lsuix8cQd;eiT_q|~ahWB&5OO1oqGgTe#jVome?C??Mwb;k6Wk6a(l z8SvYlCC?mnHeHpk9phCTjQ8bF<#|{NztlVzW%A5XXH1_74^&{JEP3XrGp5h9 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/bhand_description/xacro/bhand0.urdf.xacro b/bhand_description/xacro/bhand0.urdf.xacro new file mode 100644 index 0000000..79f781a --- /dev/null +++ b/bhand_description/xacro/bhand0.urdf.xacro @@ -0,0 +1,72 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/bhand_description/xacro/bhand_base.urdf.xacro b/bhand_description/xacro/bhand_base.urdf.xacro new file mode 100644 index 0000000..a397d3a --- /dev/null +++ b/bhand_description/xacro/bhand_base.urdf.xacro @@ -0,0 +1,45 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + true + Gazebo/Blue + + + + + + + + + + + + + + diff --git a/bhand_description/xacro/bhand_finger.urdf.xacro b/bhand_description/xacro/bhand_finger.urdf.xacro new file mode 100644 index 0000000..e8b7e88 --- /dev/null +++ b/bhand_description/xacro/bhand_finger.urdf.xacro @@ -0,0 +1,60 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + Gazebo/Grey + true + + + + + + + + + + + + + + + + + + + + + + + 1 + 1 + + + + + + diff --git a/plier_description/launch/display.launch b/plier_description/launch/display.launch new file mode 100644 index 0000000..a113ced --- /dev/null +++ b/plier_description/launch/display.launch @@ -0,0 +1,11 @@ + + + + + + + + + \ No newline at end of file diff --git a/plier_description/launch/gazebo.launch b/plier_description/launch/gazebo.launch new file mode 100644 index 0000000..c829339 --- /dev/null +++ b/plier_description/launch/gazebo.launch @@ -0,0 +1,7 @@ + + + + + + + \ No newline at end of file diff --git a/plier_description/launch/plier.launch b/plier_description/launch/plier.launch new file mode 100644 index 0000000..8376d88 --- /dev/null +++ b/plier_description/launch/plier.launch @@ -0,0 +1,4 @@ + + + + diff --git a/plier_description/launch/plier_sim.launch b/plier_description/launch/plier_sim.launch new file mode 100644 index 0000000..c9bf77f --- /dev/null +++ b/plier_description/launch/plier_sim.launch @@ -0,0 +1,6 @@ + + + + + + diff --git a/plier_description/manifest.xml b/plier_description/manifest.xml new file mode 100644 index 0000000..97a62e2 --- /dev/null +++ b/plier_description/manifest.xml @@ -0,0 +1,6 @@ + + plier_description + + Walter Fetter Lags + BSD + \ No newline at end of file diff --git a/plier_description/meshes/base_link.stl b/plier_description/meshes/base_link.stl new file mode 100644 index 0000000000000000000000000000000000000000..eab1cf1cdee1531dc3ea12c4cf0b3253468a3b7f GIT binary patch literal 381184 zcmb@v2b@*a^*w%7#DWS~BAO`Of`F)4=FPivZLu4BFW6g5Vkc3V_areEtk@MBU_r%# z1(|twuANw8@4XNcvBgA1QGRQmv-f%H&bu#s|DVr)J|Dx*?6uB1=bp0nIk!v{{r~&( z#A;F0>$MT_H;+}aCtkd4^33_aZ{4$f-Sp;b9&3H={)-1cK46rypWOP9L1GWxYV$#k zkqTqf-)j56D6Y<=-A+wPJ=yWOSyZe z-;`T+{<-$5JaBZi-993WR)t&MAmaD~EUVdF|!Q4Bc(Tu?;v%SXPbAOjC^^dMD z8CUEvTgpB7sI}tdclb?ht@96shA|%h)00yTC1o+nY_GB0W~U}c)%J24>@i!)op|ra z_`2_BbpCkM;{&3o8G}(~dkxILzM(zA=iLF&JgG*Vt$FNy+PTFLN5~Fud3PJ=yWOSwn}6?@EPG}h8u|GXI z*igPKMtM7Eq^2QbOUmlbKuMkTc0j{1pfQCRj56DogqC;NwPKIi(hgj=TD?D-F&JgG z*FX<;S)a4VZ0Qg5f2}^QnlTt>s2!bqs;aiSm82T6WL?7tXEhc z)B3vGjKL_gy#`k5%+_}Hm@Vrr*7>v^KbkQZWwzHq#K|m1vBzwQABb0JJq|WwFv@JN zA-S%`+A4d@mNTF*;}AsK*Em$DdT zw%0%=lWFc#WsljCmmtGQ>-m*2koycVl$6CNv%Ll~vP^ThDtpY9{0doLTF(=SAsLxd zm$DdTw%0&rnQ1OsWsljCelu}`Sg_aDTF3?*eT%51NJ9ZQ$)ajNVwTlOE=@6_u1 zC}Kp0lCl_Ow%5SUt4sH4RrZ)I`zY+lXg_ES?A4|kO3GrC*^{n65{=CF4 zt1eP-tr%tF&F@mrNtf+swX#{Odna0>xK@8S>5;(TD{AYC?uuv?{l&!PuCl9(xD@hp z#E-BaK%3|c;L7nktlC4{!5(HHGSH6Y#QX2L%KC#DjKT^|`>0R<`s*-C_?p<9_d9HE z`40mw5AEQVGs9LTzjxk$%$ln%R@5J~a`IJ=qGw+@FkD@W2D%5N*vGZncg-V1%eht- zuXJ}u(Rr!upT5%igBcuaIcJQbmo__Ll|{83>|q9H15q^Z(`UkH=Xrn}F6=q-Gwq_K z&nlcz%s}2nyQ0I--)j{c?OYb4cq~NG79X7!G}yxoWM{Oyo4L~1(1Xli6p!gBTK&*} zUuh$euL);ld<~;$iGx>Nb%}zj%M8vLqv+@+;^nYj@m#|=4re5M4Wnqqes`^6^MgIiz`8=GIFH=)Os9W?;_KIou~p?Y_$5daanjD6GMB z0{P18onh9phZ$Iv=sZzos{g5G_gsJZ;L&|Ia%Z|W@+H3hSo^Z|FPClLes5^`x0E((22h=sHzGl^oJPPc10!fKgHgBrwqHDD?b!ty z>|utD%0>-lFlub)8u3xTo>-v49%k6QY1Ci_qvo}biqD?Cet`yim|-)xQG*$bTJ(es z<6SR2t}`$~f3Sxcwyp$5=nrNvN`K!P7~M6ThZ(l=1x9xb$6%DUuN)XbgFVc!tR^sm z1~V9?{gl@LtD3Qg8J24`YA}OQI^GI2*uxBqoQ)dHV3f|A0uA;s!y#rFoRJVR|+)P z!wlprZXeaC!Hn)GM7z9(ySj3X&C{L1C#-_=Jt&4T#5NSPI}texG`f3?VR=_*hZI+p zK4%7_a1CpSoCO-}VTR>hjT+2g6vjdgk+VR9JXTDPnDb278!c8F`}yGZ=-nGDWN{&|nWUY|qfB z!3;)W%})_)3pCin4BNLgYA}OQh=VC&ZE+k79%dk3h4WIG8unAoxGYBL?>lp~0xd9{ zhZ%^w;k?w!mw)pNMrr$MjT-D>2J#1Y67s(pjM9E8&|nWUkOzhH(tJCZ!6+SX1sd#O z2J$&~THDwTW-vPb& zaHqA68q8pnuEzx$>|q9WNba<@QG*$b(zsHf!5(H{r{_*<8#S20DBfA-Mla(_oL;qQNmZikdMP zWwzINy2movgq`YwbH}I(%TT1@Q2P7MTsyizFb(H16kRKgQQD3! zv}2H=q%3WdLz(S0^y)ed_Lwaidev3K7&6ZdC1o+nY_FlC#A&d{Y|+p$rW(YE3?*eT z%51Npqh0!>${w>tLuY|%7(?c{p`5gAI#VwBllL!*JyV2|0Np;1CL zj3M*fP*N77%=Q`@)tm-<%odHgFaK>2BByE)BQlhf#VE6bhD2x4h}dJcwu4Tcp;5?y zUO<`cHPG@l#9F7p9<#MS=+xO58f#s-QWmaTK$-0|(1UG=wN8UQW{U=TmQJ0UF&JgG z*T6_j5Nn+Vd(0LMj8HnKHipbWLrGbTGTUolMkR=~PJ=yWiw0&Iol`esFv@JNft4Xa ztaTdfF@iz3u!7S$wJ|i-I&~?FQD%D$M4SY%)@iWEY|%g@qH}6v;95znb?QY{5B3RV+i1hC}J^TXXGbBZl)Bimp}JYiK*#&<=^U(n813HaV2pUPG_0 z(_oL;Qm*!mY8XRftz4_Jl*K5sy@rkwr@E>onM7wrJ>_kHvO5wX6&c3`UvlHFWiH4EC5U zQD%D$T}7P+d(0LMU4vDl8G}(~dku{SPJ=yWi-yJ$)i8#}T8SBMZ^P8J_FzVg@%cO_?`tJoA>|q90 z40lf5sKE?IU2**{(<45gRG`5gW?+4E=hTfF%wW{$o7PAV9lS$c!;M7tFaztnJEv~c zUWR-g~Mui^1{9q3=5Q*GrbfX3{7jF3diNm(4E8WX*WiUP7`5-@&pHRsUZ;S;9%g7PSqP&$>Yv+;EMUl- zHxDyx{~3C)>Q@J!DI0@PsBLT0b_5SIpci(QuJoY6Wibj@z1*}vf`=KnZf?ig*bXj> zQ5ZetrsFDjn1TLx``ShgE{jo^1?8smBY2pBaqRZBjT&4QqcEG}rt>^_n1T7|_O*=~ zTo$9SD#cCLtKeY<))lv}ZPehh7=_g}Zo2LU4>PbnhMi@8Tya^9LX?P`#*g4(2G;qo zv&?I7S&Txoi<`#5;9&;hmD|_mt`+7;HQ}-tg%}(+jpxC`47KYSfXqRs!DTTDxkTJF zF9{xIXq(E7?clN)g`6mE$giYg3455KeN&*p3`QZhiyQJpr@)0Q`tF?725W{~5|riFYrL>1elhxL6_#juN=9cGG2D zEAM(z(sJUdsrE-ID30wGgXQ;8v@PDR-CN&9W=|2r*Qyu3P$1tOkXkXrY(eP=b=pyM zz|${wm4+Ri{Lu5q8he<*Q5*L;&zRHo6yA&%4Q4RPY~PN5;N92$`u;gz6SD=yQ9Ft* z`O_xZ^3RP*-aX;elu_D)?n>tw+UKrT>?vaSTFE=S8|oYD%rIL})((Gl|MS(#*@)wI zOzuRj*uxB6G4$&8z*i}r!`CU~S}}uB_IqEeYwz7Hdwr$e$-~en8dp*i%M3i@QM~p0 zo_;}qJ$Bug;oI>pzALgSzAqxRVusm*(kS7sbQJA;+F{wjhtFv{AESgl%-~!iiniS9 z=q$zi`l7)MMw#u~p>xnN*kiWTO6Q~2>R;1N%HDYMvbG*e{8(cTGdTOeHz3ln*{|`2 zKj!%mW-!WZU#ng5EtzZZO&Mtid(4(vX=c#r8PlE{m+iU8qHQs1#U5sGzJm8ZR;XlH z;bPQk3NsjGw%0%u$fQQ{!ydDxR%*Mo5+{H+SF(2>9+7^E9%K(QR9kZ&t(C32l9AcE z8!{(j_*(VGyU2U`@0V0<<)mIK3(6Ss`zX3|tFhUi9d0_qnTFKFaw5+dg!i3$>$hImQ^fG?&>1DQveE7| zj4ddgE8320KiVgIYptHyt{5fkVFqVWQG~TBlQl~;n87HseLMOf2L9l`y;HT=Cp9r! zP{#1>kaf53bEC4eaIM(G3|&{W9U2FvR#j#&%6{)_^^IRevn`>aD`ze`OHC~A@{Gmn z?^H+Zv05?1w?o%mcdeLVwxD#~b=pxh^s;$fKOQnBYeRpqhZ&sPg*fOmn87HseLFNd zI|h5qmRf1t)mlAw`fXi@Z*hF~BxWspn8CSS6n!%HvaY@G{R9~$%wUw+zE-&hU z27AnwT4~0iwYqoS@UEZNKRw$U*NQ#N;A}98-srPv*LwKkf@m;Y4zhgv=Xx&tu4cq(9hG#PAyYl{99UEhy_Jf30SHzj$)! zW&32ip;qi+2IjwhTMh>+0}{}jI!VRTD^!I@#jr?X4^jc{t&E|;eHLGLAbAC zwr4!Q{FtQDIIoKP#X1!eu@uhqBD zZk2q0=78)1>Ot`^1Cc?_+ckdZe$ZVjE{jq2dtWQ8Rf%R95h8uKUt_kQ5UJ^2(J8N= zmORioylbw{G8{ut$Qk4=iK|JTAzw8@p6KE^dx{voR>&C=%NdwqwxFz^{Iz;!?s3UA z$!%Rjs0YQv4CE_vk43K)a_R&*wPhJ$WH8D!e60>TQ=fB2%aQ5HeJ9J|!gbT%cX)<; z?d@^>J{)`O>Pijm_r4vvKbPmHtLBli%odcg>lt!F8M4&Gd6=PBy5=>I^(B&pV@E%j z%VLz-z8%_wZBi@tm@Vb%m9BXPb`uHhCS?3L4>R;iYpoCo5}X>?ZXz%kWwzJQ9(1*0 zkJ(Zy?Ln;-c3uhXyrj>ahZ#D9wN}VQ6WQJ2S`Fc{7-hDv6?Tw`?I3mDxw6a_lremN z$UL8S=76Mzam5~H=$zMf$W9xpPa-QdGZ)HKrXe-abw2eBoHHbP z&QN7f5yQ7bBL$1t{_be&g?t+wr*Jg{K5|utk^QqTBE}F<0fb<757-hC^ zhsF9phvuSgB(leBVIY%{b5U)_YgbKA+y2|09E?6Ul$6D&9gOV((Kh~u&0RO z+wmZM6Ob8ZYda(((`)tZpGU;UZC6Q7!u&w3f`=KJk!d?LhqIOk2BWMbUn`ld{->H; zzT#)CPmWo~l{Nf}-?q+3{Pp2B8Cw1gXUGkVsYB+L{yo#KZk>~7FpAq$$BPDgm@(`1 z3kNUzem9M3cLt;QDmV?G$YTU=*)Pjsdj%xO*&Ng=5B$_`=%F$N81dV+G!w!6;iF8{5GiW?XaSwA#&2 zuUya$W-yA^d{-;fNPembdzi6V=OeY-mg`fX!3;)O^l5Addzdlnls9YNZ@ol;1~VAN zG1xc2{V&?V9%jVXe^qPm{i9|89_{;s8H}<>-PjKHFyp&37ft77pA={?gHfDu zW?b}iuk^0JJy)Q?3`XTM8K_i!>#GTSn6Xpu71Q~$(H=cGzK|7eisC*XgYb3R+ChTFx*PE`9PP}#d z0u5#`%5wO|cCd#TKYhP;+V`yG3pAL)DBhPy{p)?s9%lS??C|u8JMY$Ak>hB8FoRLH zLuzaXdzc|{7I9H`cd8+klV>JmKj=J+(%-v%VjWKm=V6B0bw<_mf(A33t?g?K?NFim zbC%-aa9CU61RGpurwy z=o(yS1Px{|O5;kM5j5Dt42>mqM$ljeqclF&89{?R%+Q!vX9NvqFiPWm+&Dkj!wik> zbw?jMAM#nCm{t4_Amq2O?LVVVK53~!9AY&V?`-g}LdT>uYQWdzgXwSjL{SK!X{K!Wtt_O&2iO!wjq|W$ZZ@ z!eA8EO7{$8V>{Tx46Ki3>^TcGn87Hl`SN6T0fRlvz&c;Xo^v4#Mj>{&=S3Ua!5(HH zUX`)utjEDH2bsYr#9(=1uYkcGW+3jy*mEv~!6@Vs?%CSLcCd#T$RA?tISVwH!6@WJ z@`QN-gFVbZ9u#BGxex}UklVTEkQ>{<9%dk)i?Qb{&|n6mkfX{|>;(+=FavpMj6LT< z7>q)$?VikTYzKRof&4ngp0hxM8H~c7L7tQ^V6cZ7*eAr;b1sCzDC~V=dA_}|9qeHS z_B%25oC{$v3j4wE?3Yd^_fL50-tFj^fqh#nXR(d7;<6Z}zwc3GXCTszpq3>{;6hSOjMqjaX_ z8BT*e%+R@#XE+UJFiPitp5Zju!wjACd4|(q2BUQ4%QKt?dzhhXSDxWCn87GrkMj(t z!5(Jl8k}c14Q4P(BT=5=G}yxojU{=8(_jXpG(P4TPJ=zn(3qHKI1OenN;8ABaelCe z85-O345z^iMrpp1XSjB-hZ&lq|uuHT6u=kU9C&7AWLr@cci;Y>ou?i$)Y-56p)b(4l;!uphM#J} z9%fY9W(~sJaO^r7%ru?JTm zmMbCUa{EF%VB}lQ3|zBVuEhVY6{BPgd0^|!2mNn`*3k8Vw#nK5vsNkE;ZWSOc?Nr= z?~NgSk9M>+)`}U7lK#HX{qQ) z-T!ZW&J4L`qS@GTE{jn-3-axd5iR{IWhu(+nv8))4H?nqVTS50guy6nQvriVoX$aq z;`Zg+!5(IC4VyC<1?^NyXlyxqn8DYuP{WM|Wjh;JA*_6P278#H8fjy#n87I2Q2MEW z!7Bhpp{yTn-tjfe*NQ#Nz$lcptA4Gjo>#bDITT8gHL=c6p=#27G)OIVREF`Eua&mY zp~Pbhlq9hv{N7kD8icYKrPojy&$Z8pukGo-rAMf8rLAR(X^>rxA}~^ARM|teL^zrA zbq!-ggeo(NY-oJ)=f8A)hWCEZnksw9Zk4`}KJlZ37!je$j3OHv#~=K9*WVU9%4x8N z?A$6*XKc0n>>-3I^ZXzi8vlG{`Rw2K?&37qL$*a~ZHF;_4Glt-WtL)&I275?_@>8( znfxc$ialhv3RC{SzgEPE2<6H*6fvM7ZIGIY27AbswVg)0G0={wgeo(NY-mVdNS}xX zd&q9h&p~6LKc*7OjSA@>X)Q6JA!ABLifFKhY&ULY1o>-4jEGQWUKz-ShRh9_Bcj0` zvN5hWFCj)mD2%H*O6>g)JwP&PnRmkoqk$rIRa?Xa>KMRxsK$#ck7 zD=Eub?#k6GQp;Vd1_q6lgxol#DMJ!IQFPyMxO#?blbP-LSWx-vKo_KcjB zW5kAru8B^AJ!IRus~X0TIY=m5cO6RCO4ZPn+G((dY>OYN(Tt(%yhD+Vc4&-p8tfsv zm2=eQ3`UXdH6(I64fc?o+vz!tLI!FjG2Gf=HZ;)kHmpF_j^JSit{df7%@~X#+xK}J zW|j4al_foBwu~#uCA2@#=Z>Lq&`>h20*Y*CU?e7(RZfFFWXt@J>|8aBp>fd4l{gqs zWJ3cpDv|$Wp0kH+ndg%4>O618U=-QVkTyuoM1wtK+a9OBmNq!A#+2rOVMBt z*%Ak7U)zkqD6wz-WD(g3*EQ0MK77obiI|5Os@Lk*UDc52EO9WD#VE4t*Q$%!A!SJ% z47+%}Ze_2b*Q$ZRD6*lUJ?I$hA=}24Y8XS~pq(w)xN;~RF=9hQ$8IL=U=P_gKUBjQ z8V6-uxw3S$I~3W_&>7`4*h99>^VnajW(=LR4n;OJbY*ZF>>=CME7dTD#z9#>#AEA~ zL+MK7e(&O-tZ+_)J!DH9l$B34bWO}O4$6Av%3>7RXos%UPJ=yUTl`RsW(B-ozpK78tN#$DMT+}`PFSfGX?+q>gx_xbkQOwXMU>3q))O%l? zJ6PtY=sAt5`(J19CwA`(Wp;keIJcnfHwh_AtZlQv^n+6*Cxx`6wB4fd+e+VfScffe|#A!6;crWVQuH&|nWU z?7nJX1Px{|3h_!#za*Y_n^EjxhTVe>jG(~`Mq$R%E*0?54)!p^?$_ruz>@Q;dRdH8 zZ5M-Gg@Oiqm|@R0G-@z|QF;v}!gae=>|usI2ND=kHPoz{FoRJ#778@j!wh?7rcr|# zjM6b(purwy*z-k=8q8pn&doS5LVvJ_8TKqzV1#SM3`Xf1Q=q{fX4rFUjT+2gl&+Np z8th?)J>%D?!3;*}nqQ#79%k6{kc}G5=#G-PlViwWOyn|~r#nNQ9nCSS-5J6*l&m8% zcN!VpJ;s2ZyrY||6y+rb`YV11N#$qF=>!6=Md+qe0(U4&da z*uxC0^YWfofd(@eg;^GMmZ2RYBT+4Qn1OgD?_ia3qojesDAlgVa}}y4>|qAtu6viP zQG*$b(rZ|2WUz-B$RFH$cmJEgC>;w08th>P@*ww)VxtB#7^P#nK!ZKZKtAW*=WNtq z2BUOtri~2tFavq1d-wH!GZ>|7Oo0Y_n1TG-y(iqL!3;*}T3MjM9%f*l;NGcj)L;gq zcyAa*zs8qaN8|g3XTNbp>*S}CDHJo@I|fp&?x~Q8%U4f7TJ(&r+iPR9t-;`EskhFYpDy zf%uZ3OkMUAF?_9_#kbq`)o-^k!)!ruoA3=fd=GGPzumJlP%F-mbm!%2#kGwh`N|Z& zHsxx?o+5^?m45HFfnjVxahsy(_xRrHRWEFk{T{XA+)(#w?%o&IHi{PDD}}xAwL-a8 z>?vaSTD{ZKFS9RyF~e*@ahsxOJ$xtZWU%f-tvD;z-JPoy*A`z3#W#MJ#J2~fR_rNa z_*$+0;wG7V?Y29^*n;9VMbR*PC+y_voUTcz74HXhKj>=3wT+^;@b%WA_s(w2 z_*!j@FGp7N%aP15TTtAlD7yWLld?ZzG|H^yosjMzU9GsbQ6yi*+X-J#mX@=ph~aCs zHNFsguYS#n8D@9W`QTmLXqO#kFb^4Q@vfBUdYT7l0XN3yRwm zMW>(hyX?<%y4sFIt+a1lt+dZwt+=*fT)A4Yr-6x^n zRyq${t#p34T5)Z|9CRA&DPs6q>1c0Y7+X->rYJglolUd93|u>@pjNtOxLWC2;%ddU z4eM1RJ;b3=Irp3yRwmMVG%gAbWQB*2z1lm9DQYo6vPP6$aNftnE&NJw*&( zD_un!7{(S9w<(HFo-wbh4c|SJYo)Qs)kCLX|Sh=;cLZTV`qlhg5ows(aKm4Z`}Fx`R;YWpO9E8*Dihf5D^PxIhejJR zOVOyZr-rc3V)$AiZ%>f7H!zGXC~lLBwTZ=A#J;fCN0bTQKjPX(5n@z=?A2+or-f!`F-R;a#=Dfy{#S!N50+vN69iS48GD!N+f)h$yy-0wpVc8LhLqln>arPr!~VQfKh zo7|o=u|21bIH#^7(bbA;8%Dd+U{4Xl*Gk7#1H;&Y;x@Vcd1Cu>ot>^$I%{36xVB+s z$mCkFr-w>(3LEfaiuGqs}?vaSTIqV#z%aI; zxJ~ZdC$V!MUG-h9G#bRh;M#_W<22Y)#PGG!wY`C1Y(a6Gq6lYXZFWYc5z^I4Bd4ns z*EU3Fr@@{ghOd>z!3Ku01;uT0=ZS50o~YS`tCeOMu2x*zkjXd=_7pLEtu$w7U>I9a z+$NX9rO5gm19@Bcri-1C3d3xlS!&kj80;}y7@7gPHo3FcxajPaQG7+BNV8X`!JZ<9 zZ@K1h4Gd!oim#i@Rr{%C6TbPl^SkOg@nNlF;!!=u4cz>oPg=!3_kwjhkN?+8&Nj6C zTg}#fV?phZzkXI0RPBmaYFliylw-HAH@Or46)@PtjHkxmR2%tOKgZ5%FoRLeYsDUB zto8E2wJlE?QlP;MM)4I1wW@Y+IoEK(g?-bB8+5rV5*RS58GD$4E87YE{Izl#%wW_v zrT*z9cTXtL(Eg}Ne<<78s@EyMceO(K@>9*&!wl7{GduwdjEc^EFSu=xl(qOaBhug2 z4tI6u8YB9NRa*wb_RWIUJpTMx4u%MW&6~e%kvCAH2=&Y^RDrhi+QQW4W0i&9+ zhZ(v`)HRfrXE3VaT7_Dn2g_JR-H1cql(CAsa?v-f(m&x^1r7Ev0~%$lqWM}u$IbIl z7NZ*aBWSRP8E8`(t7u*WEZ6eTw~XSkpvAj?T>JA3Jp=!wjvhW9Mtd3`TJc^9=SdL)%es zb(z7ahL)q%@{{j#?oFLtabusehZ#C=>b0sm31~2bQ98Q{G<3yr9?LAHCY+u5(oKUs z%+NVlpur4AaSiht>|ut^`2r1QFe=~j-TP0A*B(&G=4@FTT-5TLuh}wW;l4k>NQHs= zRk^ih3&UzCb`%){8dD4yQWm4k_8RLAJvck$u5aXIqRJk#rCeL>yaq8MLrGbTGTUpcFz|$I>Evdo!5*_+ zJN%ko_8P{Rvt@azpuq#C1o+nY_FlC#A&d{Y}XFWeSABbF?5XicI2`p9qox+D?_=KQ@J_| zv>nYDj56D|LuakiV2{~Scb(0tZ-+5tEisgo#VE7AhORzNgFR+TxwxVBNJf(P=QsY_Flwz-h3@Y|+ptp&HE?j56D6XjF3=>@iz3 zY=DMGlGUhXQyFhiN|bhhnyg3J2ak)24by$e@qytRX~~THPG@l#9C{I zLv?51y2&X{{aO_=7-hECKo7Pd)>?nKvczL3X$SgWPNV95?id zu*YoCz&MukGSx7K%nw6JS&TB@iz3u*S%VSA8uhWH8EXuYnaVL9F%bu9hVpLx~2~M>+9Qjb;o+ne8>OQYVPD zw(h#J#A7Je4u2Y@8phCA8yHyU<;=>V%=Q|HQ3+zL#Se#a?H~psk(`%l95e>{Lt<@U zFv@JNfyn9lLgSz-OFV{>cBtJdw%{D2+Jxay#>lm!ix_S%V<@^-Wv`*_=t4Ur)`k;7 zZIeTp?KSl3It})iE#+$8sD?2#*2=YVdrL-{?KO0iI1Tog?b@NIwZ0wA7&;PtJ96i{ zIzKYGR)!LFv!z^}E831`3`Uvl+o7}8X|Ts^(a<>``*s*Z))GTWS&TB-;Y{+?~{8SS~rRs5i6;JFLD<9mt*LFkg_a5#T-8_MTl3dho z)L;gq_S#_0@{;EaD9~UJGjQG9Szn_DGZ=Nxt!I~yTYKdK4fZet{qN2!8#S20s4btI zRledli=1+i{N<`9>|qARu{%`_8lHguUK^++*xK|1Px{| zYSNg+bKmy^2qhy zsxzuW5e9php>w6qaPaO7M&10o=gX_~T_kSo5B4xa=X{+JG?>At(a+sjzVyXDbw*Vv zQY-c_L)Wf4!@;{V7*$&Cfb!`_|EkWY3Pl*~VTP{3b%uj?XE5rQ+q~cUr|RH5!)dUG z85&FSjH+lbqZ?|>*T=iP6KcoUqgFVc^b(5WCfd(@eh0#;XjjN!+9%i8bT^5zQR#Gt;iJ>e; zVNBO@^CM`mhZz{hva>8`2QwIj*<8!b^Ps^VW?(+bzBWJ4T|1b;D6C3pZoLW`>|qAh z755}Zf4>L5D)HSO9@>UZri&4B!#M_xC>|DO^he|f`4?SCl&)>+!T6tdZkB418 zYl{zu#=ERHB0f4A+_B2LL*sWJAAx=C$CpiyH~+FdYuRwAm>G<+_~@Tc-2c4sady_Y zY}$`M=E}P9)KML$yfZYu?ITJcgdKqoHSr{wL#JAhPn6X>Wm_3gSzNTZ;3q#{;&l;60 zDT*Gx?9up@=h5y){L%sBLtDIIJ7eQ136i1nfI{Y{U?cZ2ct%foUEMt%A6l#W%v zSidBUt+u=&zIau<&D!JZnrX;9IJWoI9mk_q{Xg3v9{b*ejuX(1E$jMA$Zr+1C9mpnUZ@+OEp}tnVcDto>C>Xmv zbm0`PmCPAqocHeQEvtPnH2z`{(YWP~>FHg4D%lD54yrMOQMiVbArHTCzx1R9?b*z^ z7s}NQ9%j5bX<+FGT-}w=la}|HvR`@%7>j+DXE5sTQ+FsG_twxj9WIP754R zl@3qY^UF`qEj@{mvD(L@rO$(Q6is?_T6)N`mF(@kW=RhQ4>QKCbbe_EupgTx<7(4? zOiOh+}+o*x=7x#I?4{C(}`)Bbm~XWJb=wv#<;WjB^4VT2DKzJ92c zpXZAYdp=zqjH{|+I~lc1*W}WHU|ez8dfgaD4^Go*Z?|WsoqdJODAx`tiy3R|d`W5E zix^j5$~@og*LS4z-fGWQxMXCmEJl4g<-F4NX!%=Hg>nB@ccedpG5Oq)F?+t7ctmOE zH_!*?o-^-_`Utkrz=j$bM3`W^_ z^VjO_XYa0E`(-8j#S>X>rDn!Y)n!VP-WwW!eV%CiWsjw6H~&=0W|vz_To$ALyZh2D zt75L)x{@$H$i6LofcbI%{SVJ#&)yGLH+&8A?l-HC2s6sp>b?a}&s+dT*EbK%Vhv_2 zy3@&{ggplADBAg>@14f0-58AG=!17m`d6~@D%0W}uDZYTCya`Z*S(=*yG=KUWz}5z zwJ9CTVXd{(9bcd_G$&%Gkos`q>CS;w(0@uA7BF?$AL9341faL1vKjmVXRaRtVO<6Gi* zwOex@X6%c;m@)stSqF?1jk|Ad&&I4cBA&l}mSZr=&b9p2{rRm*_Lq+RTA%8(M9dy$ zya0`Pj~}w(O8rG+0T_GSykF~zz4Hu4^~NYn#;)A5`pUu>_1{X?aoF~?_VPYu_MC*# z{oHSRm(HI!BBvciHO!5V=HFdgd8LzXTDM!RMuG9&MxWF!uPmFZ z6*FGIT6NQ6mzH|{D63D$JC$ti5k1m#y2g~a9gNx)BmbGXlS>_w*8}6?L!U`sc(C2w zo8Wbq*GIE`9NZFL*VqSN*+AH_*kiVoYv*%bgBX#aq%206?KS4$TQURi zO&QT(kJ(bLolJTSW8hj1F_e_WD6_rBL-;PvNBAy|Xt2j@Dc4R|y@oM%M1L4c%3_q+ zUITAnXTLgQj@%iovd3&G*G`JPhB2Tq#86Teqs;aid*jPV@8Fv?qQM@srCd9|_8P_z z4MRy;j56D6$Ty=t#208pgFR+Txjb*MmM8=LG1yR27NgAe8pB_%WTR)Vl!^v>%odIO z9Nh1XO18$7Wzy0E$IUX7l*OpaF>4oj{l?O=$b+KjaWD@1pjZ0wljCQxXKmzDGsj+E zdTpN#LJfVb{`O%dJLxa~sr_gE)*YY>ih@9I(Gb}(Z%upevPb>;)uSwzv9*H^M?IwHR3PfMrFV3cJBzE)f9P{|(I z=<@RX*CwXyVaELThsKp9-!OYY?%=Y+=}aL$RaC z7(48_!4N}9S&TB^mXCfNx zFq`r;iADFv!z^nKEP`7yhbwyqs;aif0%zs{LW657g^%7Y%o6=rvAx^|1KDt18Jmt3O|24>J&-IuMQ0J|iVYU2*SW@pLfG`|hO@ zdk~*G5OvaDN9%Rd*zL-#;~Vd)B!{&3F0%$R5T7~_fzoAflzjJ`ledl^0OOJoeR2#& zAwEeoN{9Sb7;Dd3Cmvp_B=7(EqB46BpE?kA(&LAY>{hFOtM!ckG_#Vl?6`E!!wkfy z4n&~z-DhQQ&}&f7_%tvoTjUvxLVTKq*phy=n=pR!t24{P&>xeon<$Yhco1zyBZj0W z_8F1Wj-o-2{JFgGj+LZz?j<=7GZ1YyMs!GzTuwCbQ(beb_GGPNKF={2WuwIR`OeQ? zRQvdVN^;R26NKTOHWCjr5N%ozPtr^F7mb7dzGV9TgOz0MZ+qkzj6(b^A?l=EgV&PvjM=mhEW;9&-0RS6L&?RSRs zd9Nk5O*`(aBzLU3RF1(Y#HSJ>Pu`&s+un4Qw|Zm%RS zO+TWOJotg%gSr&K=T@%Y^aw)9h$=WS0` zl3B~Fk#ftKfis5taf*;G*(w>C{0z=2$>yUr$}t#)k~-`6SeD)IoX&ptV4iQVP0A>o zM9jjuL%LvdS1V$ib@|!laqm=;&zAjIS{^*izzIbM&K=T=W=qS@8S+he-W!$V>N#iU z7>vTHL?+8*Vs?mwZ59XF zW41656W!f2zg{5@7BU!Rw%0&(ZnJpK9qL8Yar`OEKg*Q*-|cYMt9%YYcyjp z%51NJ>@~4`mpx`nxyXIp{d2F;jKL_gy#})I#PW9bm@VZZJ9p0kcnxD9Z=Y%?DT`5N zdkyR+65D^U$80GVyA1a{gV!*IXc$V$VwBllqw}>&a{fiV)60ImutjnfbNb{&?%wt?ZF(Oim3XBV+9- zn*Hxe^3$$Y)+R^uL78b9R zTv?2=KKDKN@@eCer~dKZa=#CIwXug8l8wn3fX~R1HL$L~xO3d6-}u~EVw7ZKaw_68 zvJx1}KfiNa{pI+WJ(7*dd5L6Xtc|}Qcwi;DYQbsojFC&{Jj{@6OimDdMz-HRm1LFZ zf_UPBzsmiOFb^0d*_fOf_>AnKODjpg-)$NHXTt?G$wQD`bVx2DS%uv5kj%nL^7CWW zGb%}P<%x02wwL7?jFP-Z?$G$$XLrVTNRU zazDyveZNA>-?;R|_@JFHlQS7tD=CXn`Ic{gRwdctpvB_@Z`~#3D=Hb7+$)kSj7y55 z1Hkxeb@BLL<912e!wkvHuFyJv z>22gxEj&lY49VZ*UXjn?gmL17E3`hlWS+q&$;{+lkz{9hX5z<6a`&cd*RFrzZ=LLs z3{377NfyT1QS=q&`Rw;@ti95=Rn9C!t(YO%nA|J!8QJGxtoZL6YfpYy$}t!vnVH-x zlI#q7=T9ri{CnQ4P2A=tm$R8iGBCMUBv}}1N6}?qoZaze?XmT4lGEByD`vpnOSJ&)XyRm@N#P zs=MbC{fsgO&fBLLO3GrC*DHnGK+;f&*!x(b^!%$Kdqs;ai@&#JG z{}HjrY$+FaIo$K2Uc(roVJIn!QD%D$+?7f6K2F3Qv!z_zt#Qx2dJSXfJ(lpaDx=Ky z8o0ZZ=>4dOJ!VU}xa;Je-}M^Ckb8HAlCl_Ow%5R2vPAEzMeH$K%EjF?_w2COXvSca z*D@&d!E{BG-EKzY_Ea4mTh{UQ|>5+XS2bk%Dr@xPg?K1Zyjf2Pt_{>THg*OR1u;w_AmpO!KbY_vd#cne)0_b zBA|HR=AaI)47VFq^}v8$r`6Cgs-EXG0)tV!Z}V9EFId%#J|w^5D@5s$&wf_RjS{I?#tcUBzAdl89%g*p**BegY*&E>GZxZ*CSwmXUVLb+wDZeh1scp?lx0zk8th@luTLM5-o3~Xoq>TG z$xk(72BR#Z21eBpz+ewE)OO!r_SpZya43tYjT-FXa=-O4F!3;)OL=CkH{lOk)=o(z0!3;)m+|@?==49+)hQ^Wt4Q6yl z$@9XY9V+C%iDaHUqdEn#b|DPR`+$OWc)GQr9ptGqpeNZtfd-ewC|pDL{$OJ}*uxB5 zH_1K9CjD@niuhyu+9%i8b%ZRlLVK53~+P%-&sKFj)U>uhbYYQ}(!6?j4_g-qF z278!+`4}VC7SHog7NfAn#PYscqXv7JfprDXlXfkH!6>Yi?mgi~4fZet>tl>qTcE)V zMq$l&?>jeYu!k8~=VQd$0u5#`3ehf>_thFT*uxCOs~E919|x-vYnj0)#Nb%oS8LQ@ z4>Q!xGn_^N!=aE%xcBHAHQ2-DYMW{~hSOjMqmUED^1fP*fknmTSHZ&!?VCKqX>eJL zLT=~2YtX2{9%kqmE6`vDqmZMz?=v)Nu!k8sR|+(k!6@X~?mH8W8th?)&iORQaMy|% zjKZG5eJ>-&aQ(p^X6V{gpur4AVYlSI`_ZVu9%kqoT%f@WM)A%vipmoz*|eokN=JXX zTkEomj!b8cx}jqoJg2|GA|u1;DaJA7yO;hp+E_;6$G2_$;Mm0<8YH{X$}#2m$bVkC z?r&jViKq0A+~&^FV&4oKe`93ErJcLseS_Dp+2KL<^tx-ejZXzip3LKtqUgL|PHP^tq* zsVn>@X3u+%0RmBD7y0R&&GS>O}+jTzi(xaJkKEgF3(ArwjYTfotDP)@!s7! z*REe<4>R7BCm(^K$12A70q=(o5gKCG)f>)kRwr@@SQ505DIMh`ya-p#mk@oDk6 zdF|PKUo4YjFv>=cZ~4|gZC2hMZ@BF-_P6`jL%M-;@;pn zq8o!zXFYJp{lfT#W9-+%YaDRU!!7LDrG4dDEtrG-@dgKL;~kS;OV#ein@GdX-X_;_ zW}N-|-W^Z&8JS*!H#=}Ys@JqMUbK?!`JeAoBU^f8`kZ_JW1V$wO?UmQJv(UWwQ>wbJ%gt# zhGQh2jCVosJoT_!(_O&WqW4-Udrs?dX-C#$WV#C8`Cx7Q^`RXfOc$Hmo~?D@g)%=v z3z;z=&-fjK+4VQ~{>KwHJ(Z?udp2dkMXk(W)GBzc?=~>}v*(BIHzPeB^W)W-FO=V2 z`rMAEQQu|0bnA!HleKHcC+Bsni{JNlPm*77z>M@bFixEGLYY0LCyWxF3fveg!>4$1 z9e)kz%p21IZ?f+8oRB&UB}R6N2WDANzQEC&6s&kdcxZ6*#%cWmGdy89Z%^U zjNbH5l7G46wDgFd+q2{EUM$C8l#L##A^r;VVU^nS?<(0tTkX@z9%kG&{l!`15DiAV zXU`XV;j+$MFr$vWJs+bO#qlbNF8uJC_@0N`lhyC3q(Juj6ZO1VGmz&TD;j$?a7sM7Ejs3 z3?vj$eb3oz)>h@^aHniR5_K|zQBNFudCS-pM#g*Kt#91sd}Vrk4)ulh6+!nkc zZQ8!iCw+KF{Qg(%NmN@Z=V8XN?@cJ}fHwJess}0K$F8Mf_Vj#nT+=h|S&Wv;DiQlyjeB#u*1H$rZuRaxZ^)PB z>n?9$b8Yc=ux`4(vjq(Kt^CLs^<~u=bKiS?)`829j6Zj8VUJsWTKe~8@chS7v&+n2 zRK8YkU4L%+pAFiRUbj4vt1mO2oaELLeGB`1Funp~|6B76M)4KFd#TUONLw-5=U?zl znXk{JmCo;23)f2Cqt4gr=a*-sB`{8Jc}6m_a21(x;H%en3|e$#yr_Gp`q3$mrXRi3 zo*a1M5w^CwYsIKlvl~0^#w?KctMPZ@=0BM(^-z0q@x0?(+4FTex#MJ@F2Xz2rtR~R zZ(o?1PMh1FEOYUt7IEAhWX9<`UDEMMkCE~2?w#rvZo4J@-M`wCgT}0ra#@V(IrY4b zHE|XEJJoyKaZCCKFh1I2os>PRU35gpS4)qK@4-9OToS(MuluXEay@9w@ar@@S) z<_zrkGe&##q^wt0AsT#)HF5s!J#vgZ%8xPM^8F9GwKf=kll4CnALz7kB_3vs9k)!! zSA9mtpSgFccYJlR+B-ktX{U?V?_dU_W^T3gtSvF7Z*lKb@AcegrH?V%H$3LS7WQ<$ zRK33kQ1VVSmlQ?E4jk7y9*iZ+vs&20jGiAIc=uvpAL!VZ?CCWIbz?9pzqWsIOC`JW zw%yXV-mP}>{!FrNlko)O-~-*ax+;a@ohqw=-d!7>wd8g0}~1mF(V~*NeAY{NNg2AIXT3|CS^x&e!S?FwWm`y?D|}2j?`H zA(=Ar-;!j@_$!rnR2+dG64MWn#e1T**+5e z#sB>e$6$}yvP$42MD9DgwGv-jXu@EW*hqs;ai zf5YGZIA6a>&K|Qx1LsU~-&r+`@xgU(4>6RK#VE7A#vb_lABXEV$=PGJXyCj|?mL&o z#$PjU!eEryUSk#f{f|ESO>*{_E#>0ePwqRbhA}?A?(M0DlCl_Ow$~VqzyGnjev_O% zW{U>SFXg_oY8XSVm7%08Mw#t3mdD@!SXRGD&K|Qx1Lv@E-&r+`@e$f#C@G6kW_u0! zyBWXJZ<4deY|-F(`<`>ZSlL* z<2ozZaU&K_+h;Bo%PAwy5#1Zoa(;-@!VWn@)LM1=9{l~TmF(y-IetzgUjJD83?5v>|%%yEE2G*I(k?GG8A#Ma9`@ z$EP?+&DZLXd-2_!ep{qBw=QAh%GHV)a*B#`(hh%;`UfzUTWpK;?OXEN}q#DM+dNssQQWm4k_8Pj1It})iEgHJIs)jMJ?%JAIld>3Pw%5>TkfGsK_Lwai z8YNW27>FOXwmS_*ne8<+syPkzm@OI_6H~E6927=mC@G6kW_t~d&Q60pW=pvmwN=9y za;*#{WiiTZuc29n(_oL;qMe$WT%iqs;ai zhdlg5dh=6m1*)>gY|+S{i%#qFXnN`^?OEH#=h$xB-Qi(W{*)6@EqM%4?YeWHmlN4o za?U;Q1`pzulMm0H+4JgDYIYBLLh&Ooh3`Dg=qnc#Mp)6(~Udf4V zX*u^!HKJOgQ7y+{6k?a0%a;1Ocd8N95{+s#_8>;Z64egI8$7J-qFSO+EoBcg5U*m1 zYW@u#M72btT8_aeM50)t+CSYp)re||Mzs`ccq~y(-f+RHE%(4WZpM2os_j-g{H^$1 zD~U$6l*>Ylk~@j_jm0}ZT-zu@R7*6fQ`kFe+awM72bt znlW5`nSppE_X}rD+Fy2eh-!&OwH$*{d_`PTOEjw0`1&A5#S+yv#Cz2FS|O?>8r5u+ zxLPp-@hX<6Hp#tHji{DHh-!nTEs!4lm@OLl zIoOQBD6_o=^29{)M42D#FyZ-Z&AT73`VbTHA=!I;a!Szj!t zgG=CB2Kjd2bTHA=!JLN~IK_+Qbns{QP8?1L6AX|lP6u-gM&)aT)4@bf2aVzC%M6_R z#d11$uKTWmv|LXItp^>0QG7+*>0qL#gJr%xIO~h$bnsTZ6PK?QP6rb`9n5Jk1LuCR zoDTMI@5JGBFwxV&RxXQCoT)_-&N31^%V3YOY1V2F>a1;}Ip{ph&^ccgw%d8h%Fw`I zl-Yii=<4Gb>@i!))wN4CjG;R(_dKPP#VE7AhOWC#gFR-8hOWV?VGP}Qx#vQqEJm5_ zH8g(6XpGonwrFT9Q4M40&P&$zvXsRrv%Q8!HK)NIvqeK=Vl1}Xc}e7KU@*#Tuc6V| zG1z0al&i5_HH@JB= zHJULPWwzJ2cKO-yt#~tD`kXyxi$?yg{`zOU5Ko-ao*caR=HWR2DT`5jw_i$@H-zM; znr*u6$nr~1jBXVrGZ=-nOYSt(87SXtu!k8B-?3Ucy6*#ZM$ljeqp$|c zorXFiXt0MF2b71U_w_%c&IlUJU=(7B+-ayYL<2w7j6KZQ;?VWeHSg$KXLv$42BQ!Y z-4nlI4pu#-nz4r&M}D?p`ui*Y)e#s$gBgs{-)nRRyt{_;Fk?(QI{oINyXuVY8qUKg zy&~mMtDwOiX3T$oWctIk+tnFCgBgs{eyTHq278$C%W*@}rB|I)X9NvqFiOW;oe?zH z!;I@+T`67p&FAWjpur4A=}fCLf(Cn-amR1)j9J_KIwNQ>gHgI-#Et#I9%jT3y;(c# z{JwQY&|n6mbRDZRLOa;QjE6UwRy$&&fptdEU@wy{wXU!O1X9Nvq zFiIm)0fRlv7<|(|J8!sugM~1(egp=iFgN9Nr+C%|4>K?y}g#4fZet`<-%b9~Cs1!6=PH1sd#O z2Jc>_c=uD4`N52CsIYsDqV(yh@#*XM=cz3&O*r;QoN`1F$5*la@4-loVW{p5ltdXo zGX|r~_9YGJeR9`L7yi+m0kFqx8B3gTM3FJ(ez59PLrGbTGTUpseb?W*9{=-iod$c% z77fmvqNo{zQD%FM^u;B!Ll4~BX|Ts^(claa{h^GxA6z}vP*N77%=Q{bKeBdq#C3_& zV2|0N!I^9nHDfT!Y_DF zWK6NgY|-GIMHCqWeLlocQWm4k_8O%F{*XO(!Ts*cl09aN2Jeufs2PJ%W_yhbUph6r z_@y1327AmF4c_VDou4KQMw#t3-h8T(UG@18H%r-LwrKEen{jO4OxnR7vqghXbny2k z>Ws)xQWm4k_8PNp*d#k-&-I)Jd(0LMKADOlVnl|LvKVEy*Vy!_RkE#b-N9+F$86Ey z6E^&%zd9o_l$6CNv%SWsuRiZerXS)o*kiV6Ai~iJq%l52pBqZbVwBllW0ygbyS91h z1gF6svqghXJfnyhk)fn4Mw#t3p5J^(*Y0*+(WdPXjo>j`uT?lBckOTtv}1~)q%5>4pv?9fxVmlH z9}#=Z77bi=%9ffj7-hECz$j_caV0(I$`X&+qJhyvS)Va5uBIAF7>qL8Yhbh|IzJ-z zm@OKZ1(dxuV=&5WuYp;c=scGh<;oI|*`k5jOj&p{2BXaO8d!Z2U9V(iaAk?dY|+4~ zM7xP*3`UvlHL!{%y6(yf=gJa~*`k5fm3BqV7>qL8YakjV8b4&Ec4djjY|%iJpxvD@ zBu_MyFc@XF*FaQDG!91WFqL8Yar`OEKg*Q z*`k4LkWO)oA$@KrDT`5Ndkti-iRHWOFm|-<=vHh=ZMS z@7I?VMVlY=NvGI|aPEGs{oXNzlyvtPJ($Tz=J9D`qh2|1owZ;BpjI`)?%@1Qblz1X&UYV2Bb{liM@hC?K**1SM>V zC?Kn{FNWm`in1@49R#w7>(jNIs#DdcYr3B{JlSB0c6M(qcrWxA_m)JSDqpM(CsD%6*M|r`!Fxd~=U-l{ zr-di-b)^y|P_sG8*vEzvs-+`Fv@yu`!2IFfnes{4Vyrt}V`gygIe8rkTnv^fQG#v% zk1;b0SSYH44H zC3ocjk+W8Lui#O<)~8Jgl_){2&Tdp>P`gT~mX^us4|*zXLBu8QEjyn|+s5k#LM2Kd za&mb9y>+F8YFTf0JtnoG5+x7;x_pLS8%n5_`h03b{SMyc-kQ+ z#Xgn0mugv!^s%9SuCotpN1sp2p%Nv+?2|mzppByOUaF-%G_|1;C3Id{JfT|M{WwsA zCF+FZlIsoq;?krXzy?dLQH)XUO+K|2U%M(%0@0bvHR!dWglg$X6w1JV50)xX0#T;R zndr5lglhGSaD(1bT2~sMiQ$NQRX_y2M0_$S)vA;P+Cu}|d))zW_K z3=DcRgQas`_OB9h_EW|eJZ_|YH2N`HZ+FQeGO`{m-gCFi4tL7 zBNBtuWI6cHa4*%;8lg`3lh&0Ix?>Tv`R|laEv;#sb9eKiV#3Q)S|{TB3H{AU{gp~R z%?#%)y*ji0a(i_9fOX%l^tS=^OhEnBKm1C}@3*Mi4~=f@yW{$`N|ey^2(xUhd}6)9 zuSd5hO)e8cwe)uaQI5IqRws{)Ze0As8MR83(326f?ESx3P>p>5wtR{Dkc3bz{guHi zTjjw8)ngzYtPZJFqJ;jkAii*$eQt4jJ-R*d&ZBGnbw54%OMk;J%c|QJ6&L?ybmOPv z_Ni5(gq}2p^DI|cvE2XD8|6=ZbmxRntzRa;4S4-A?^b`meyDxU4Kr$ec0Fq{Eywph zvU#=lbE6w4zB;Q`i4uAmCVp@E3)4qF^V;b4=jNQ85UQoWmY8KP-ZQS)>WJrBb00XN zR*4dNUMJ3n+j08H2# zHU9jwE<(;1)wap9d1#O6Xpc79L+f4JLw{2-%YOImMa8GTG}NBA&OWtDl+Y9GvTXD7 zrj<*7aj5Z)e~d{8)zV*KM87(`SzdeP7VS~%PpVZ5-*3jV`%>bO`wlMG_|$T(IVU_& zsYD4q$1lqcJ7-$?!t6C#D=jm&RzkJ(S0A(NhWigLe{;*|#!H7jP^mUp7`kf0;PTu3Krv@*@Xr)LMVFol712 zbWGIq8gZV?Nhg=*u6OK|^Pd>xxf1aVL;dPEwJ{mQuRz=iLM2M*>5Ex5=7f{W)t(*Q zUi1FJrV^^9zmbezYC8Cs^6=k}Zv5%CGYXX`p=Uzk4ATV%m;btBbo=xZ9!Ln)(qC21 zvaeh)t^Dk|YvxCPU~H)pCG^zFEW7xDgUgAnVdP^vdY=5)Yh^5UQoW^_*qP z?lFC2v#-CDzcT0KQYA|0iK|(*==O2N%%`8r*Zuhk387m0ThCec%bTW;Z2ZpX#yhj| z<+}X3v=VyuYnC1T-e%R|FOO;b@zq%gp<4Ru(D-fHb*7KJcJ@$vS$wOg5+(FRTFmFO z->p7%!%*X_t7asGYUyuFXW2pX7gTG^y{$E6!6Btel+ZJCvux&R?^drpa7XKtx6Vii z)zV*}&a&6$EU3QyxuNzE?L$hHDDltaRN(Oox2RX#WvFq+*6SyPYUyuQqs>1#v3_s6 zq4u?t%Tgsu=qbd=VY&6tdgmR68bABPNTGyk=`UVq+3*`P>-9(fI^TVTw+odhq30xL zS?kV2>pRCilwbS4Dj`%$e-|6));>40{_Pnxm~p4gmaUpVWedO^Kgqdo4a zrV^^9zl)9UU1zv=wb@Y%Hz-unO@x!DF*0~!@Y?^`pi)9lo7P{_&a&n3RK>E>+oLyq zioeGge~DWO{gNF%_@|lmPD4YD=ihp(QbM&f*2al)cN|)8diX=FFMgm(qHrbj%x(O7 zHi)f3z5O!2iDlXF}pc zImB*PzBs!5*PF%_Dp5kuWzDj=KRLQy^1jiH9d0`}AyjMKorebg`RIh^Om}kRYaiRW zzT(88_RROMSgJ&cSLU8Iu>Ef**vXNZi$Pfuu$;M~b9`{7Fa)JyL>)Hv;~MTKhVskbTdk98;2k717b`O(c% zB}(Yozc?xV{bTDNJwCee!uit@Lbc9+dECJ2&rN8)_j8^Bao+I{R6qXoa`|zHvs9u) zdXn$+OO36Uzh#a5-{($C2-W)c;Iac(E}YQ(i#yNqgix)&@4EEVRq^{c*SQlgms~hFvhnjaszeDrKNISR4P$IPx#ETKse&^}YjZG2#DWO`& z?R)Y3En#DtJ9GI*3(hFM`QGUEB1Fn6Q9{oe&9Xc9d!X3$*3pgq5Sb~VS_fup4}TQ> z>bd*buTEWRZ25)F)@&76hp0peJpmP8Z_Ik2_{J}nYb}SKsDx_G{^sQ2WBzAC^QLEM zW7LF6CMTHWowdBiZ4j+ZFWSaY3fHPLvxm-A7qx|!$u2?2oa#n3hytwkt<+&iH zuC`*S5z9Y!JG!wJB1|Pz>&$;o9DWo&ILVzbe%AVL7h6@M+aJcBpGuU_ z)2)$V`r)cr{!tC)Q9P-9m_O)61BPwB?*m~8)4bK_zNC&O6o_lKQ>Mu-azV6N>pSSE&BU9emt#L8p zMU^O#o`=5jC*H1ZZVk0JM5L^QYCUu1xPgD61y^>z67#^{N2=#ed?^3u{6lM%D4}P$ z<1D1*->$y5@2~S;yg4%=RO{FCb{IJ9cZhv(u6vgK;we_Oq4sH5xhSDptG#l@z%Sr~tK+{d&xPLyc!&+@e;A5_(cTe$%^sNd4Qd z4z+KXyP#4+wN6~|?13F%gXgSc2lD0__0U~+wBC2YyOm0m(6jur?4ElLsW%zAt#wmt zK|-k3rcYcwF!nbSnoGIU*mt;cMt#$dh8lmo?%hfyO6ac&;1_jpPU`lT54Ee!rjID0 zS{j{a*^=0$UH0LzjibhFUa3Th^dy9R5V!y2$mjB%e?G2ILbWu8&ob_VV?Vs$Uby}e zyZ-WfdS)i~+Og+eaKBw8O6af7XBqeNv9DinPhSbu($hDQdyaPocz00py@5)U`1cbN zM(`G5c#b;}i0>uvexl^N2_;lZ&*WL>8HNuP93`b z{Yy2TzI$BtN9?z&LHp}>a1@BoZzGG2BwT@aiVFYhe2F`P*4)Og8-m_GE$D$G? z^qkx*;Gx`|z;s>tBxkz|-hc^It6HxOlfNJR} z#3{iy0C*En^DTf%l+crovy5*5@Ft+ybw%j9|ZiV2nF&iEjY#CZOh90F@}A z=P%>e((ncVZvtw*1yDk@zVPb_BX|=q@Kv0piQmD(8vwissQDH^B}!Zj0z2#O#7%sU zgWY-T>(|`VS1p{l8Bdr_3GU}(U%%#_zDkt9=}>a2JoodluU~UdUkTOv_-`hRVE2At zYnIP)z2 zMnsnJ{XE{&SA0jWgleTv#rG0;KT-4Dgi4gqUtq{GzL&uJiHh$glu#|L5oF(CR>Ll2 z$sI_Yy>wR7Q>e3yJDk|*EV;|65+!zi1TzlK2Yd+U17;a_QL&p^awk;@)zaS{Vf^iO zY)kIesziy8!q2f6JIr4ebig2Xg-h-TE1_EY3nf{`9cS!3m)vz$i4y;Y4eUq{KjzLb z<*qh%w@dD9E1_EYnj#e-S0i z_yz!P0!qFGP>B*(zy{tB46lN-U$cyF8Su8Dwus6>f(;DdO_Gt9Gpvy5+j z@b;(Rn;#`qOMi6*ztn^`OL)Un@a>XHlz8{~2_tw{HGjyRzxxc{UR|@!^yV^ngQbLO z>8ON$b>G;=DerAoyok4CDp6t=j9qx=X6Fd=z1`n#A6N0+of4|0W0#BDTNbyMi29ny z=9s@Xexn9acoR7-!(YX(Mk3;j=Op7>SoZZB1$1mf!^ z#_jjwSDRei-mtj6REZLLqPdIP+ZMMcglZvjZZd8^%KZi?;`WBc?WJnzIqNBbxIMSH zy-v%Fh z&i;HBJLibo&${15`jJpA#M({9?N7SjGTr3`WHb7>y;6x1dcG`v&+E?7jT;fSe+Vlt zB~%Nsc9U`Y@^1eMaeK?+_F5%M=&83ZZf{xKUMZnkh_#!H+yD7GSCEL?+ZMOiDp3NF zY&^Hv#qAA?+Y>^y5IHv)x8H!}fyD1rEznIyy8 zx!)#7+}^Oby;4H8^t5pox3?^AuT-K0;_D{k_LJQ&rXy}|S=^ows-d@dqSv|j$K*y;QiYa)e5u9>wh?X z9={OcH#z&}Gx6ozzh{Rp3Boo1zauIV^c0nZYkrlGes2I9j)0AIf)?+kTH)H;cxvj0 z>y3Z6tFxh!a7`Qf1xA)Fj!>;|?QP)xH7I98CE=Pj((hOnN2pe~_BK#YHEWo4rIK(> z8~QB}@~Mqrdju`sOSO1C^9S?BCpM~Q_SkD}l_+6%%4sj!sMsD#s8+a6>Z+D<d0&))-zA%k#Sy9%uDuPEx?~O0hDyRUZJ>wB*UN!0|8UlM zFV*7p9_QT9@ekT4;2(2UqJ-IN`MNS2h51LkmuiLUq^?R7V^AgGn)kJOGaFV{BtpsE zxT{*>+S{-;cQ#ZKu4%*C-)smGTF}{0t#IvaSWk2|R1&UfBaGm_u4av$Ro3@yQ#^Lr z!}<2RFWGuz?%A&1f44yhY zqC|PpyTcDX^r>OeS$5wN2b44Sd8+vS7mpoQLba|r>#gCByl+P%-Wau6`M>zP@YQ+4 zU;gZf`^$SB^WMlX|ME#Ldi>$xi9fx`h#Q~Twfq*m>MuV(H&=-gY8&(5ZPUt?A0Jcx z^5Q2GLbYDM?Umu}cR$T+EI>I9uyUwGiL@NlCdHDobd<6jtW8oZ2k+0j`MUZn%CHN{ za?U$(wy{p<1jb){3{mnq>{Mc2%N;);jXrQ4Y3ZcRAR` zY{l*};rBSuL)cT;OZ3^5VEV(PRpF_WP%S*I^927?D0w9%j}j$N3j?9vT6sO>C+Z`AY= z`iBy#g&sQ4>AUFdRp{+1Q6en|wCmteDBVC90pJ_1*RUM8{{TI~_Y(L2s|5WIObr`AjUaAG($bWzPS8e7*Pp|1CoTIw6e)rRp$Me2@iILM^yl=cp zcpV74)70dtDw{u|b=9(`9q|5PC9kC9PNIa>!hp8{-(c-lHh-|L9HClP>qb}$);538 zKb*u`(9zbiM!+{}`iRXR>cR2#M zdznYMa+s%?4fsY)AF=s^-q}NFEx7rkrjOYC5ed~Y|2G>p`ncLvi4x`?MzHnRirwX~ z5w7P6F~a##w6^(!qo^yb5;mgdzL&r^I8xU(e?&sHKEM5!I5W7l58hy%bQ@=bn*Nb$ zt>LtI-yVW9PL26vo=QHyeTSgOvM zecltrtxFD$yYT}Xw^#Z7wfT2f+P%5!e>QGke)AmnTRGvH{~vMt_yg<1zx9~glTk^y z=1FYzs++WTnmi}}=D|FbZE=KZh3m6cqz&A^0_9eBxK9hx1|{K|_r=q-V6)+$N(q(p zBm7x$D0PL>I~z)bYigl3TBsGXp@d5M5#Gl4Miy0jjoZiBP$FDYYvRIRwN~F`J+q;N zO8ODr#uVi9U5GFIIf^O~uBr9Q`yXq)@y!WlLkX4iBfO2ZVB-g7Ly2(h%CYj_THCC% zs@YItqDcA?-bT5_#CrB8{YmLcgllTObwt+Q=dcybh7v02M|c}M!N!o;P$FDY>*)_H z)5c%3p@d5M5#9#wUxRY(p+vZ*7Ru1Z9n6LjD(Odf8>pumrFS-z2-nm?TeMLV&YQDL z36=CCybZK>jaGCvlnB?ZW!YT=Sj zOX*FI8)=<5{-Z`b^p%UNe=WSOx(_y*+bwGGFKsA&`#B3+&rJG|5$}Kgy6U%}?g7F3 zQiw4dMEkX|=eK4(Jf%5y?xgnBkDS{&_QomAlV*Orec%IEwcfgJ3g(aE zLl0JG?YUEZ(L*m(HgdXOQTf^T=C)Qm;*;&w4;X0Pxy_ZW`$s0X-<&r9Vx2V?R;Nte zy8h3WuU9Hr`|R1R|6IIr`|c&V$Lls+W0eu=Sns>$iWq<)@naAAd^g&zG*>{>RKuHPgPk1`><`;f)_73y_)vDu_}57sQH`l4Z+Cxn^4 z{jc%uSKpY~`qmDcH?O>E-S+X19MjtJ6_$ML__~_2`)bv1wm+y=i4uFAI=(&cfUmUP z_$-O>=;Z_VpHLlq%Qm%+06H>o1ZBDWShChH?yElev*oJ;&N{Hxd$Bh8{2YnYHohA? zu&$na^kda|pGcod2_469($vK-S4V&MsOr|{UP(Dr>%*(9-#+k~!Pb7C;}<+HzxYVC z%wLbWlkGBsU^WD~jnl`R^Z-x4hADmy+ zqqeM7qJ-8P+kEHx&*$A;9sTGF6-P~uCmcC#R&&1wX0w|8X4qcC+to|YdA?frn5Qe1 z96D{I_8w=1sj*mR&NiP5qC#*H$;o`e3aRC4Rr{m`J0=}eSmi<{MSCexbEvTgshZ2kS&msWRPvQ4cLCC(bVW_yE2@3UEL7bAY$ zMW|L<@_~CctdICyRn2;5&7>SkOnwsn@zV!g%Vyd7AdUucb{C;q+D=)v%j(u+EDQZB*+zASsvh!eU9)zY@Xd1R=o z2T@nkQM)QpBCV@&Af5ohHdjKmv^DXiH{#Go5Lq%#)Ywp?Nv$`0$8y*k)t9C|UfqGZ zQi&4ntwy!^*GGMy0kJy>`iBy#rS*p2653+L`irlQs#&`#QR2ygrP}<AV}w$ihx@7+0`xU!2-E%gFK0JuMWg#JMvpdCK1t%TiuZN+Lf zoXS)YbB+t8b#NRH8&$R~LX-7Q~iaglcKqV0RF{K_8)iaBQWI zxc2aSJ+2LGC&b$0&lq`D!w5wG(Dj+F=(MI0Wndh+AL9wf5|t>yxr3vIZ;x9+`~n2W zDvl_;U*L;41Y--2L!D4|+f)7TwEU2z2B=%W%P(z@cf&hfpw zx2u-+{Kc=fHQv>F!+egJc^c;1AEB;PqC~p>xERC^AlM#CsFv1SmhFpqb`s{>b5K_* zQ9{>nINt}vW+2!eN~o6BTb3P*dG?E#Z#mbhLs%q4nM4u!g!6 zYpJuwZd7sw#}(HlQ}=FirNy<>0gvq!*XPSUwHHQFu28vB#VWPrI+m-fudTXQldDp$ zJC9pw&lo4Zy2_p)ZvXaC)!`StTy0$JRWfd7lssq3j3!qPjMwkIbVl4e@$WgWD<)K9 z&bzDHbn?MvSZ)1ogPBdPJ-DJcZPS?von?Re%SzRCOE0J%c>cgr@2f;u<9Hif7jS)m zwLwCtR#+iteN0WOc+yU9PaogNCs>av0tsXvm zuaYZju5DksU`CTW6x^xUxH+R4Vr^f$+{fU42KF*al_t#!1EF zN`#ovdI`pLi$xPcwL%o-pGqSALbXDq&-K50sQ@3L!^ zDp5j5ZJgMP2!LyJtj`ldwX{aCp9q5c0Eih%l_(Kn2|s^uy~$N1R*(syT4^sK!Idha zzEUMhglN#)kVrovR7?FPiS$dAC=u2S-iEC15<<1q|C7~SsS+i^I?>y3u`Wu_k}IKF zI`Uy{fO=wF&Gt}<5@Dt9Z7||vdu5i9;9eZ!_EIHEgm~WD;0_LVa=HoC(q4&of*`nCgq2sR5+%Zl z%-i5T2KO^q4kc7edu5h!uY`LhSZ$XoQ6j9uy$!C-xkm3MR7-nhmT~>heE>d{N|XpY zFW!b*Z=&=pxe}_Sy)w(Vrsdj}wW|^(!rqy;!BrPmU)_XiX|Kfk0|ZxiSlyK>Q9`3Z zcog16ZSuF%tGn(>3DwfI5B9I{zH5thkF9Q(s;!^fttes1hC=uR4`!x=CQMsFnoz#R- zE$x+fO9p~(lCk?ysziyfE8=Z%FOhqS-Gpjsugo&O*XH|e?0A(bQ6lVwc^ljx<33q8 zp<3E2ai$XpzIDeN_fjQFgxybXgL^*Q`(ZhhP%Z71$m;{aTmaUtN|Xru*WQM_n@9-N z(q5Uo%}7>7N`!Y)-o`7(JzTB(^_*`M6GFApHO`;+y1SZn`Rdgciw;cIYD$E6Y~IGU z+umPYFfyjPYwwg$EnQ#XRC%A{RWrM-U);vLj5LO`JhB>z9D^ze*CZ^btnIVggvf#x zBS_T>*FL+=vPIliTVb`u`-W@M>AE%$D97xeB{?N6CHVhi&YiOn?$u3L&Rxqtm1XJm z5ULffeaZLoc`_sh!&C7|!Zq#bN-t*CI6@`;2wx7%_i^o^M7XAwuKKb}36=CCyba4+ zayFC**VNLrA^gMVMma(y{RnTv@~?V`KvPTChB0Hy5i03NcpH{S)=5rt&p^|=tw_$mfJw%{gIqZ!9{U*zl(3NRF!rQQXQC|+ZSD>k-BOmq?eNL() zRML;|Ho_=MKUX4LQ!9*op1_P#gd8u-8I6z?hOxcDxPe&~m~k46S$tjwX0^g*HNGEg za8|agut;OJYcK-w1m@bp=32hN$~ni9P#QC8gYkqX5CIex0q`A5&KZ-0(ufRlMhBii zTvAwE!YsX<^B)PNasQk%w$-!A%GPV7dN zwi}fYs-^Yj-s2SZ9;e28oCe?HFqadfX(Qw+Vl~m=dmNw3i9F7N`JBw(w+kF#JtCv!QKP%Vs&4Zbhr_=uvPL(L3^Da)5 z+nb}$>Moa43DruUYH_og&SW~;xm~rwcGZ}_8|Minu-le%hsV!q*oP}@=Pn^sOUD?u zvt8KEb~2VIfgSIhyR1HY2fOEm?VcxuYU#*_8RyYw3VYL#jMPdXa>}{7@P3Xr4TZgF zNC?%^ao%O`lp%Wu5o?3dH}8eWGH0~UYwW7$++X(Pz+0J8G9aQv3B-&!*CYO^uqRX4 zo=g(SX!N3O~@P%Uj6mtRtb{1TNYk=7O7N0pMj6Z?;9X=~z4Ktz_d8x343dq5UQnK;Ico7xEW0hXtrBTn;Z1dEZ>pIO7YWtUw#hR1Mk(2! z4S1Dn4~&5gt|Hk67~|LbbG}-J7`5-o!EcGq$Y~m^)(mu!nr<+9fmGnBAs?YH3Zo+}bka)~ZB_ zw5~9&my)?0d%J3B&v(1EeOKEW0cgFs_aCLb|6m?+TvaQfaaWe%9ZPBNSQ0|DwBFo1 z$kN_HGIKe$loA@F;(XD2HZ1KuXF{l!)|<;=DJ_SkQi&28&u1BOSW3%bNeI=_evDst zT=U$58E(vOLrk0VEf2HX5PRl)zsc;j5SRFOsfgJN`v$8-WS{fBDYM%Ur{~P(VRl=H zGJJLdGN}q?R56zJHbJItoSY9(iW6tk&9%;0y5kV#cAql(#7Dp3Nfm7KX!KAQ@w zmBPM0O9<5pD@$(!nN$Tcs+diMm^MeO*k(2r)(AQCqnJ$)$jWZ?ItgAae&pbk8Tj?n;B%fXp3K z8oy1x^n!xPTo&)mV_kG}6BZ?I(kAae(mP%Z2jG?<~{a|f|2 zQQ9{@MOg8&|6o_5!7Lc&4hDbpy&Wsm!oD~x)hD#)r~ZNUe_`KqG8f0~m+)Rns28}r z*TV8%6GF8@H0YlSqe5YMuZe$zNRMSo35gS#h2-Ky-b;xPGkTB0Ob}wxgix&zMfs&?=>sA4Xs+bN=T zCBh8nZD9AYv~T+oLbcSJk%2w1P00*5X1A$t>u8|1vkaMSB{STZ-KG*HbX;*?pOyCY zSwg6m)*&*45Hr{pZp@}~u^LORM2J582#3{U$$T|tw<)1oX)nPF)e)BCqjyZR6WKbfk`n(Oq zx`lnskr1k-BcJt$vkxgBBF zi4y62j{UKc`D)C+QbM(~SGuoE9bvgqE()g&CBh28#|+rPDeW6Y=3hlZwX|2d?;uP2 z4w5-uZXHD%N`w`ew}E|(!oJi?2-VVF>AnUm>}x<~x4C^0+E5~_+r15}%?tbbEFn}& zd!_rrt*|fLm~-cLwrE3%uvg=4V7*z`7gY(NTG}h!S6hXBwZ&{hx8p?{N`&1uZv(5Y z!oDj?2-VVF>Aqbm?AxVMB}!;?o@K~vE12QN>^3D-OV>X5-Pd)GEtuiP>^7Askw*H+ zY%7@I#_TqYST!QoUYTXcY%7@I#_TqgD3M0U^4>WiR7-nhvUX-}lv@e2-jxV%uzlQ) zUDU$96HW-#(q4%jdJuL-3Uj>NUIuL_QQ13hZv%UYg?%lX5UQoUGRyE@yReg6nBC^~ zuV_Pw@SfY-!2VcaUw|frYH6>`GQ4ds>^vD}>A5{i+E60A8TU4@=Tq2MjR~Pz+AFgR zIRFJS+$?v{?K;zj65(CCw;}H)m~9vd)zV(+G8)4>`ec==M0h{!Z6LF)V1^sB+w@+l zm99CF*;X*ajoED~Q6jwO_BN2&Rxrbj*={xMpmKT(z8eUhyQhzJzLp>v-B*$(%Uaznp$C<;B6?Ol757@fn2qcxl6R6M7X9_SnqfnN~okC;cf8THs)Z_h7#eL zT46=zZ789VeuTGyT(y$9WVE3~xTaQE8+sc`sH7j^ZSdSS=ETv465*O!VU6o;D4~*m zgtx(S+n5bV8%l(0YK7Ikx1oee`Vrm+&uwFlB5f!UuBjDv6TA&2RML;|Hh69ub1i8@ ziE!=8k-QmIBJ7dSdOyP3;JIzgGIiyUdj*-n>GA?PPi;0Z)I-&AscoO^#U-={{tPht5!QDR>f=a%mi@8t4*YUKMAmhTfK zO4wJ%dCd3Wx5x$0ZquhyEzBkH%+xHiFRBWj-G0yApD3|! zR~*52B3uQ;e4iTmK85A`L_)Q+MqIv6jeMWN@_k}mDPiA|T<@-eIO6W-B@_q0n>*@v1Zqs|I zR{B&tw+$Jlg=LuXY`X^Q$4)|MScYlqO1wdd8KxC7Obg2}jS?kzZW}U88!^L_-}aR} zyA8e(M*zOn2qObVP@aHkV+qe~LxyQ#8K&`G%%0*~6U#7-wq1rP&u1ujb{pUHgy&U4 z$1#^-S|P)^7Cym&^^z zFpYO|8KxC7OiRl!jS?mJo{0OsF~hV%hG}UTrjbxB?F%l$v_ghyX&I)mmndPUVl-lg zDbLF&d3KxLOSN<+ieI?(%xXH5X-&s(Moa9fF;^}2Q6;du!?Sm6R0+V>Lsj=tQz zi%>1?WASXNlBe|`Vs+;?^InK7-FeZx#%^?r`{ceHcIJR1RH6i8Mt7pMe=7Up(6yk( zA{xDD+r%$&OJ<9xL<#Hx@-!=JLHp|0wYd_irETM~+xS&{$!rmoD52%^1m92a>^3D- zOWP)%o>cPmB$X(U)|H*M;M!aX)za2<*=_vR(#44y8)`JE^%lQHE_m{nN|eAZF3)bW z+O_YU3;Kr=s-^W7&jWC^s}d#fCZ)}{DZXFXnFBq9YH7W>>^7dsQS$6Il_-Igo;xqx z_e49BqvY9bN~o54K|I^g^>+9`8?W|@5(?pja@)zX@dXD7JYRf!T>zIggx520FG(=NNM=G$sHyUn$& z5@}u8IV`1|-R20@(zbEgZ9Lo1`3J^Uo{j0+13N749CEe+c0$~_=e|Ac8(!xhx<1nt zoz`^x#=YSDp%Nu9ceF7ESbNxa^o3=&#dV)*X-&s-CJN3UDp5kq=d#;szVWl{w%8j~ zOKaL?x7EyP;OL_gCDOXG(|US(yJ~6AU;JuY<6W({_;r85v)fdngsvG}b{kI+aP6Ul zYH7W>>^7dTQSj_Gl_;TWIG5d4^Ia#~LkZQ=dUM%rJfW%JT&of#bS>(#+jv4#!TDSX z)zW_KvfCZ&-Gl zi|u>{1kY_l{#9Z5S3LJPxBM%f{+wI>mD@YnvY{SB`4S6DZ!?F!| z!hFNB4PC75YuC=9=UxWi%0vmjVG0DlVd9rbG24*mw--FS&CYLcShk^C<65>M&u?$U zY{LrKhJ|GtMhU+V;;NVg*8lNo<9Yfe&u-(FS-~f;UlnUQ#M-_+?AHoPp53MrCA1FX zsg8`o6GF8@Y-c`*^RJlu$`i9xD@1y1gOrdsu~3N;A!hU~XeWPhHb@B73Nev?Dv9)& z-4=hNCPezYZ%Wt+W}H8mtL9b>yq6LozVc6H=e;s!NC?#mQHFmiJMWb-LpX`8L5UI} zX7Dx;Bl3)2#)%1`T48?lHtdXF#)-@$b5S29N`x52+ptsXT**}uW=m@6om_Ss&%kzs zN|XrmuD4+)LAw@ILbbxY;>%$t{JDOm5+%Zn<8AP3Dt=YPo~VRsg&EG4~CNp zb4rv5Gn}`i`i~MwX|2d>^A-`8F##xtLENe(}ogZC(PTh z-#6$XR7-oM%WmVZrSXkBbJg5iZ`x2I?0$M1c4ogThZ3r#z0zg3@i*LD?W#nHuz&4s z$QyTNx4Ad#d@9w_UYWejNLEEkgm+Wk2G4Cnb{pR)CWLCGYaE{2hU~V&vfJY7M~U!` z&D-F)ZOCpbEW0fds)aYNaeWoD+e$mTjpw4c-%GSyj0X4K!nKe3EW52_CWlJGH3`dA zYs9nLnBCSxs8+a+XSXr)tbhrgdB)R7a^5#w^GPhH%zm-ZGSB!6t310c5~>xh{eGh5 z!#Nu&3D>k?xp8?syNwxiBtkx%dn(lm*YWH&X16&aJQeR7uK6U0ulYT%m18fT59bJ# z^do#ZELY9dt`gyzT39FWJK@f+J2D^65i03NcpH|h) zIU7oZYieOd#_!MV7d@3wNk78duv|4~Ly2%rEvyas9ew9lLzxff2$l3Byba4$>mdS7 zEtY|I@E)avO8ODrhUKa`8%l(0YOyU?6W)drD(Odf8^an8{mMT%= z@b#`5-r>Wm^dVHD1Z)on+u@1$@4-?D)%r^HvDWU{$NJb%i4r#Zq=d7f5+!b*TDI;u z<7ciG;!_RssgzJHn-e=Wpv^yNU7<_^p?+X5*1FgA|4iFM36w8SN6G`ZoO@;CDf8z#L+3ae<;{ci4v3cJH2)9wm0>uT_se@BBwq!aG#u-d|v!J z5BEhp=gtc3Er*s6WpZctQA=yYis1g0)|C=?T6b1pv@z(plu#{w!qkRJlt9Vd35L;z zVS}X-s z9M3jbszeF1-G@*uT|q9MP>B-yjxAP{dnzSV%W8cfmSfO!aZGg2Yo6+^&6^vMAOI@* zhto2Ta#~9JyZe7euk9hs=TjRr6Gl--sMg}2O1%@U=}ti9v!k8jIF>$@N|Zo5xieE^ z$p=F@lu#|ydfww7t{mD1)^}Z*dfLMtZLm~{5}e&QXT_)LOQ;s3jfcjrHolioi4u%S zc3rsFdjB_}TI$XAK<;0$9L~>`FnjL*FP=~>_4ytm4`T_41|u6jJIa?oxYHT^OCBXk z;0YTiUa|7LSn@$w!r#GC@1d-9{LLacfs<_b>LuNT`<9TT19Cs^g>0cCP0;!u}EGK_^kd=EM#$ z=#i9AEt`WoV@V`bq6Ee+_svGE-S|{0QG!0snvX=Zp@eE->~dduL?YT?zhwA!q}C+-ic+wyROp6{CB1O^*$=?sch7LM2MrI-%3A3`>b_Esh$!?Ljn1 zl=$pRPmE{HCxm+{B~(j$4|T#H_f)Z8DZ#Ok?bB;R@1-4E$ER8Z$OCyf>RF2TzV56ve674-Hp%Nu*1W(H`$fr_5wX{Z38!A!4 zB97FCD~A%QrS%qV@Troo&z632?bgWe&vxI(gptpmjT;#dDpBH~+rQSrU;Da7i7>+P zUSa&;wbC7ZK9x$82qRJNQz@ZZv#+{-__s6l{^3(~Buc>l+V{+RWt~WPpo>r~vpvvDpfANQ8PVqP3rDm|3uWw64wWboX4GCA zN~qT2TTmrRgxR^*h7zi!y~nD_{cDhC_H({#^Iq0t+_klAtJj7~lrS5P_BZ#IV!v|t zQZ0MhJ~nL32v3r;?)W625qCSL5l+aNkeJX2PcQ5o3w};Fp`RQ^evR|b(23c~IC^78==gwn)h~1EVN+PaC|Kja}~AMxs30@FrkGB}$mrI@*-ozfwZAP;VUJ`qGgFZEknhUf2KAjiTHO?IC*ne6Sy( zS{4m-Y(zpOO6a)a?;dPe?Yh|#e#f0Vcg?x{4-Z^AK9<}t_N$IW35>ao@6MYvHzDw3 zDWO{0vVEV*wYd^z&;9?!6RM@{pAs5bSnq4_*{z3mYS*yAS|v(YKX!C#LkZQ=St2D= zqJ()@9~(-jmic^240iWj>)}1UGJPuZ52vMs`AVOE~Y|IT>yq9W)Yj0!AO_r)(TQJ?(P)WF^4c%4E zvOv&A(Bi#RD_naUi$-l$0vMtn*%~6|TJvv_;9@NE<2%*R+B5j_*I+ zSmFrU2wJ?CYK3cW1AVGw|D_F;glpPBzm4ysvn&v>!Ex7F=e<;m*OOPix-;(5Mib*M zN6{!z!tP}AhuLVtMnb4oxK8TI%~2`|*U}z2uVY;mu)%Sc z1j@m2*S$aEy;Lh)dmA<~I2$Sn*R)|HhS>-NZ3HdeOSQtax4}Nep2GG}Nw}sB%Gl4s zHUHbcAA}8;<;iod!p;pnJ82r~(x zT4+s1eH{YY{1Y>_oJ0xUpZ}da)nGTFTIg?#`clH#P%W04W#N4nPpCwRKkadS>xy&# zG2Hu9N~jh*jd5a!KpFU_lZ(T9DRIyVx3+fK`u((*+R%HcmU&u-h&EKBg!xK`h&Gf^E%W~l5pAI4 zZr*0Sqa1ng4;zD9Nqc~DUK{6gCGdoKkJt7Ps)eU@u}@+HWr?{4&bkt~f6kgn2xmj@ zrCK(+_93)>Y=p~s-^JIJN|fNJfPUs^JPZop{)uuZp;{ajI1l%hLnTUZRDdURh-gEJ zZY|CRy*BuCL88R5%bmYAy!gKmss-DOgZmIFQ3Cb`l5+T}LR~4LTGoOc8?of7g}NFD zZO}tR8!Ax(t(mhg_tupXs%8DH51|qztXKXQLbc2X`w%Ko!hGew5UOSV--odKwpb@t z4tH%e;;yY?-M?ava1UWM{a*;xvc8ZKX!qDloJ0xh3n_u;N(t4{bz&@sv!N0tW~?yh z8qRXPy+jGsLOJN?eF&8(0ekfGln5n{_fjpiM~v-aIdBn2A9pV$P;VTsQX4&lYN7pO z%$VBHzGSmO&iYw=zfy@3^j@}TZ|y3fS{!-UQ+f%ND8Z43E&6{Gs>N}#v%2e)-RB_( zi4q(^uh{mIIlVUYUaDnJJKRgCLuAMB~l5*sQ};-QB=HC&$buGv_aKi!yj%Y)8_5~?+AnRn(dcxxlG@mCPn z8le&;uAehJ|K~f6%GoQkZ0()KG%j1}5obdQ)!OrbBgS2N=cZ=kogK$CE-^wSO6;=X z^l{tozNFb0ztfm@KSH%&dupc~|JiX&`|{3HMTruyH?>oa7xSmvKkSq|5~@YN?6k)l zAm$pOTBxgm&;}`i790t^L?uel-;-W45_*Xes>M;E(|0*41RE+*f}=v{$63Zv0i#3c ziSb^l#ZjT-gB%qwIygeLI4T6cO9_q&;YfVSHn1Q{dhfpo+ zJ@!=A6CI%vC9GGP4UP&J9eN1WGQTk!92GD+I6}3|SKNJ5!o1cIDpA5b*q(}`0^B*Y5}6H-3h?zFLbYskH5(ii0-;(qKDzs+gpJhBhDwyMQQMx1 zqXJ_^-`m}&@2snq%@X!hHsd%#B}&-rV>UP{V07pqRLkaCv%ygTqk|(kr z6)-yV5UTb1THjt19&I)_D!|trp%Nt?|IZd{!HdlXM}>ZbYT;=a`jq zu*cZPY;aV-=+Hx`7HXX_oY~;0fYHGbs)f2@+~(RKB`oT5gi4e^YcjIz^b$svJ%nnZ zzcJpmr?TkP5h_svy^^u7+2E+a6@~T0crVq0r!j6f8ypq5q9CDK@D;}D?!GBuk-j5T zq69pcs|kB5jtXI9P(ro%M3niF0izFBEY5~Xl;G3RrtiD-ajqzA^ojRUE!HgS(c2)w z6$J^^Vr{Y}c;A%3NX^xqBUGXU+nepS1S z!BK%Lif%%+=uPx0Z-b)(R}>^vq6EE(p5Se8RN#uDn@}x|3QKK!dM9RRaz#NxB}#Bq z`0$#icVdPnR}|fZYT46T?88xkD++lkCsD%eS?t46fh&q`Lba^c2Yg*|RCwJ8l_+8L zHsI^ZT5yCmlu#{eO(QOR=Az=sE3auT`PPw1dt5nx@76(I`PlHY4W$c%qx}WVE4#YUy~4bA&< z*xqa(Z{r#CkW0{0*yc*87Dt87T>HNuhCuMCRH6iXB>S1SaocWBHHOc+yoXRNjSO&N zFNn4gDp6ule#O;WOxVY4+_~FR?S6!6;c2-yV6)nHL9{wg6(vf*-aw}u@V^oIp_M!m zs)ah_K7-kS|BcWONvK2#)Z0L(J>Y*8{m|MY-b=O67r4?l8}Pr1erUZUN|ZqR4|Mt! z{I8-{brY(EKFyWB*?|8=LM2L|ALkwafd5s&2bEAQ+@C9bo7I$1i4wSfPJi+J3jSBo z4_OW+R15XQb-USs|5fxu5-L#w^_0_JybbtYML+B&R159Rb-USs|5fxu5-L#w?VZzK zybbtYML)E0H{MIN&~Le-x7iu~SJ4k?LnTU}-{$leZv*~U(GR-`)zVdXmcg4U`XLFG zC;|V=x8Lq7B*YKAH{q-w6Fs#$9(W)w21+Y{36U=!dkS5+!V$HyiN3HvO=h zP%Yh6ck>`;HAkpKiPM)jbsYW0+T72aJ%nm;9HAfjHi!Q;=!f=HQKAIL5&Da_!8nwD z*iEPw$3uFXx4}4+en>(kN^m@+zjzyrL+OXs9`RnP#c`e9=4~(zr61CUN|fNZPJi(> z7>ClUx(U_d{6uf_HW-HnLM2LYexkovd-zz?*-%2YaDT2v&CfY&(hvDmDp3OWXS{1R z7>Cjiy9w1oJ#k%YHW-J}4@sy*3Dgtgb{nr4htdzb3DrV-bNyj97>CjiNvK2#v^Uou zW`l7k{m{nUcrVpLzvU{`<`2f9^h4TEi4y3yTp^ha#-a4XZbG$mE$ZgM0`p*))#Cb9 z3HV=Y>iws8=D`BhFxqWMo zrze_?J%4a(!N1GmsgzJH^DeWYgi4g){rTU%9Q)ykPQ{bah7zh}qlDSmAH+!@SXU}h zg7w65c^fODW?w-KcN3~*qn+7U1;k4r*ybuxg6+-r@iyA%A)BJ7bQ7v&qqf<&69juB zpGqZ4ut&0=c^gwU*s!^1>wonSs->&2ESnDE4G?@Pl_+u5atB;<^-JG28=G&i;YdG1 zwKyu!cYMFv6NEfflqdmv1D$ff|0*eYBvgx|8@G_WO5pxE{l)hy_+LdoG(V5`QZ3YztnT1{75$LqP>B+#r=0%cZNUF3 z`e8SrT4--s-NFAV`XO6TB}$;ZbNY+70spJ$huwr~q2J2t4!y9VAM&YGq6GSFPJi(> z(9#j4C^;J9tw?Kjc%XL<#s`{`I%_81HS6pdWSS&4U~> z+`UxG#w)V{|EuVSEQd;zuyMs~!2c@xVK<>#Htw1Y_+LdoWDBZ92^$~H2K=w0A9fR} zW%GyGfd6qea8IQYC2X8G8}L8QI6Z`F=_<_4gPhgeQ>jFWv8$gxj{f5N75tAgXAhxT zHfvis;D4N*!&Aj|pAsBL=r7&|<4`GiBvi|y53|8IlzwQn8`phGa6F{HcpHpE>4)8f zYFQLzHW-J}53QHPb)OO(*Xb|b2IElrVK<>#@B&%gF%G34l2C~f=*Nr`%?9T{dX>b9 z?s-)UJ|n9;B~+pW?$3DFY%mU`ADW-Xd#M&iC0X4u4y7Nm94b))^~AW{Y%mU`A9fR} z#khyw=Ep0>q4Yzxph}cLdvpC^<1XV+`e8SrT8!W5ZQcfYVL?CSQ>jD=^jofw%m#XT zK|ky!R7+Q3Sq5(^Fb{@VEw1~Nfd93QIOmMcJXp{VSq{CIYT45c`*QH9=!f!DPNIa_ z8}@y7%PYs1@7wm1#bM8GQL1F)jW29XS$5j+vg@4Kv|2D?YY;1eI243Rl-Truvs;rF zKJ4f$d;Nk{%D-%PPVx0FLba?lTmGp?ylI3=l-TYIr?ifmwNi^uh&PHaf3UoGjeDF8 zB~;6LrP&~Hp%E%kVvn=;Z#{I>r_IKw6<#m+m*r4GwamNBh7u}Kg7@ct`*K`_CwdT1 zMjJ|~mW>i-g9OV$LM2MDo>(q#gKfbY?j}^rMmw{?ws^w`l_A3zV;20ewn zL+v<$(WH^uumKwK%%b+q@0< zUqwH(+Kmz=P;UdB_CT9gq0RMPs>M;7zT<76%_E@_CD8tPr(ePUD(Q*wUaG~}hQ8x% z!2cql5+%@&^NxSOqpIM8N~jj@FRMExRH6j#pVMD_zk>hO^eXleB~%ObB&$1=Iua^T z0`-*BU%U;pMIFXOB~%OTEvq~DUmeCol_-Js&gn1S2K=w4AKFMA@18w3G~~X{^D)G|7!XneNgYET8t_?t2=m8O+WObPe-Bz{4c-eD_QJH!8K`k|D=Nt7^q1KtMwucjY%6RKskZZ_b5HT_U(*GZJHdNUi=<`qk>_fjqE z3%U0X67)k7DpA7PKlkNePoy7q6RKr>+H8=ZACgds64sB+hIv#Ep<3pfW;C}I9+ zHsF61{g6+kglgHSWHv~!EF@H-gpDg^!^XrOLbYtHG#hLS`XOzoL7E)t0+-|<2wDt+h80jJuwohg+48-JI0}bP>B+ppXe{% z2IoL}mH9`!mukVAWp$^7N|eC;8Sk16#-a2o+E7BZFe=IF4rPdhN|Zo7F>W^-s9CNJ zoDC&Z3uC3M?ih!LF;OK-puM^NuyL1hDE-hz>Ub~Jg3rk6j&Ugc&}M@uQ3CyzD9^I#-YOIKkyD+&bW!4coDI_o|q;D4=YSDx9K2TS@P%c1vDEi1>cpFbFf(hsE^ zPNIa_8}|L`h~N4JA~|TC?S!ibUH8l_bQO=d@0}be$HT5E&4wu2&8(@tU)t#CD=( zz0z!u_z{RpP;!+h@#3TtTGw5+i`m$uT)yPrZbG%pyUd0XDp7*>=YRWh+=(YT4NpcJ zN~o5N5@zEkAkG587F3B6tS6Ss+i0O?S3nJ4&_$@0jdo^(ZNWC74V5Ut_GbHd8|)$M zTit|e*{E$clu(Hh?2+te-bT?lrwR9DRUw#)tB}%;f*iy4ky>wp3#z?TC zglchApzrv;`{~9xkx+>eus6^t2mG%Jb)|%Aade~acpIpzNT@^!)Z0L(J>Y+pv|zlK zYH^gN?|2(%^GK*f3ABIS=~wW-ie6}fN2K=w4 zAJPYvKy5}Xw70D8(0X+k6IG%F+B>JecpKZBBpjHsBjI z{g5SBLbVuGc2;*J=!d?SbRIeNG15(_mf5!1nKtN$@>EWugxMSD)D``( zn@}yQb+ci0L)uWndWq9A zFEAS<=!Z6|v9~*k64sB+hIv%oO{kXnrrA(JB}$k-nhp40ML(30!QD%>Y*aEE@V|2^&|;2K=w0AKE;~@ygvxwQO`X8#X378!A!4#z(VZBXtjJ$;<>7Z+dITds;xN2o*zj_dRnvw@j_ zUS&No-b=OM1+uzh97@7^dz2`_`HBAGZEy~xS9KGr#d$V(bCxNg5+!hd#=B;NaVY)J z{5;-EwcszlKV->Ok`O*3HyeyY>4!EC#(SYQ8QnWAjFqywL+f#E5Ju4`Q3CDF z^+#uHFX>f$D!rF#Vg8WS9r{!xRH6j>Emufp13kT@AJT>rs->&2EF*z=FwAOk-KPZn zuXV}q&+5#Bw9)kasue~YTGpB^|5Ot} zya?huu%QwqHrnEn*1)x&Z1D-R?A&S1^38KcmEDADS+6u3=YjY$h_hfrB}y#$;CEVk zo%Ut3@ufr7F8TM&E<&};yUd0XDp7*>=YRWhyn!b=2T#VQQbM(ClrS5wgE$|=X&_Xh z1nY_A@;07C%}zoMv#yj-EgS93#zGM5fnYCDi4tsYwvV^LKE=MpUZR9**{E$c*r!O) zhDwxRk7PgdHvYKI?B?E${d)-2(p6ZN-3{W)AXrx_QR2qx6SD`dy~S+&d7arKBv@BU zs1`>B`i}3r6$n1n1-=|nq6F*>bjpFcs-)zRP%Vyb^c`;lb>#@F-6&B4^)}FH5BOh2 zKeQH%glcj8rMGz-@V|s@m{KhdW!2doYN12e#m~M5+zVi zIsL`kfdAF>L)MiNs)hEJ)gAn=rXR8eRiXsiJEy;R8|YIt{m@40crVpLzm?S;3Hl*z zs6+|$+noO5ZJ?*u^uumKwOmvgS9kEHnttfVtIoPl3HV?By{&d0?`@EvANqdPAymtr z)@Elu75$Jts1ha2-at}Um6XHXOSP=l&4$%gCAHf_SiPAI_+L#wlooV^YFS^%y??;} zYWkt{5+_l@+CTT@fdAF>!)`*g%nQs0{I8}TN^f@(C9EHt4fCkl=0W<0BUH(n?KBkjqT2cN|dm1-fY1CIOFsXs->$iHxF`Fb9JQ> zC5}4m)N%9|->=|*oH<=xDWO_6Yg;+sf1I6bn+M~%PYI4A^e}J3VunzTNT`;@5}mqY z%n)ifuKSeWcu0ToHW-J}53L0wp;{IbnGMFF^h4_*1nP-#yV+nIN733ySke!Dzv`?MRm+}s*w+=GihgMGAWP^ZN|?Q2->;^xdsw-_ZG*+{%|3z}X6-7WS~l95jo*NH z90c23B}(WC+F8avwHx}@o?V1$*{E$cCVn%z0~eAezakC6Ck7ol1l73e#@?_LXnPi5tZ5+!&lH~q!8 zIqIsSA9fR}#nFx4=54_L9AWJdB}(vgar%q50spJ$huwr~ag?UFc^mM*>bIR<5+zEY z{rO7*W&{3L|3A9EJA99#`hKJ-AVqo!EtEh)385v~cW3FLsz881LITDJA)y7SK>?AX z(rZEhF$HOYR3ZDmyL2QJ0Sh1~2tR3Gl%RkJiobJq?rhG)kALKOK2PpF@9gfhJ9q9q zm-Em@VvA5M?lzolp$&}Pn)8rzP$i1MIF>3Hm{E0{gNjfs{Jxy-6rmDDVE#!p56r)s z^N@2;5vqmnB&R#fznb&VR-aa)2z;lu-iULUe>LZ!t#BLH#Y&!nl>w9p+!nd1$*qD^Y~9raOm`UUMFD4(e~I7Olz!r#sB1 zn)8rzP$h~W`}>Q3`?^)_A%gReb5IegWo_H;%%|c!l=o;Pim>*Ehxvi|$8S|Fj8HB6 zhSmlVoQKjMjYJXl-K-7Fznb%KVT5YgxXQx(!2GK@4`q}z5=B`5XW>0C|7y-d8Ho)- zwQNjV8<>9_yS43uoH_r6uyJf{*o>-eA8Zk-WpmToP=rbpVe`@2!2GK@4{aahn$i50 zYT0^aZSWm94`ucFFNCct)&}NZ#d&D^AlIt~p<1@?S{s;u73ZO>qW^`k_0ihknBqLN zeUK}4gHSEoKdcSRzl!rvc7y*y*g9`*VE%E(scj$Rj?*AiOHX0VKFD3I=|Pn!;@(-u zugCck#uertcg~t~P!XzSySBXt<{x+G_#W-KPZ4NO>ilr6;;gbaZxO0x)`zu0JCq3P zkM`WB2(E{mFYP|)IS&^`sFvA8)&}iR&O@=58i^t>VpuW6+MpfEd1xcClyTK+VHU{g zj(Z2^q3wgMM1L0}pLU|P!99?(igQqZOSLd(wu-hAMWDZV{;+kIb|~ke z?Sm~swJ>MobVoas^U!vKR-y>3^E@G08yM*Y=b`O`Ekd>Q6y_XeQ-OW3XZv7#?o$Nj zpH#0Sg7eV!!4{!f_8xP?{=ui>Je2onB#N;1=7#z4=3WQ-Ij=nCAN|>cdY47-$?o54 zg{GFe)>Yr?rD@q`ORwKKYRBzx6Zh8ZXZlswyuU&0eEDy)>eVG0grc`TxtD#X|LTT# z>Kj-3PhY*!KY}*$J^r5YA8XJn`tA!~&3?b>GKN^>wHy6!fO-%J{ysH{Q1oIqexC7P zc&fGVMDOCs9tMK%z^5TX(fob36A*lBzCGVutGz3l@4$Bnh~9Q<7JoecY(I14_Vt7% zHtW2*;w9PCr-$Y%&f2u|JI;S7m$sap!R<`n#%{yxyF+9I_#5LKYy}_ONvxft*!8)({?+x3f_cx3Do z{)G(=E^c|`=Ltf!uKwA~Y~<(RX`TDUCwKcrR~u4vS6jE{+wm>=hVP8OB3o+m=A9pZ zYgqD5&KQqtN48E8s-<7VxuYiR z?l1ny`~I{G$J9&z`i$)C{u_6Gv(t9@w@&$9_LpfJcRn7sU7n8JB?g@2FZtdw#Wx1; zRjWi1Kf3JvY}7S_I>(M+4_^8AANYOFTfVsez7YvRwe*XCJ!$QW{Ouvsn2zinQ;b67V2ivFF;M{J8W-hHUQKXR|G-}J&GYn3SC%hONF zUbugwPXE6WF{N6;58mTZfBGR46NGBryXb`M=3)Jt`S09R^v6%oA15u;ANr*gjf&7m zWqz$wp7tXjm{6-k5xNoqF=H+Nr$Zj_i~oIMf>5pWskS`lKELFi8~W*6POABB_{RJ` zyL{Te^UnL@vNQMEHoxY&jXI}1cVf2F+kEpC``3QvL2LSF_dK#zi6X|F)xR_Qh;L-? z?@C1fZB{IXKYE&+jee` ziM9XZ^ZoqAo25^s2wlfu^6NG9l`N1ZgqgFUK+puOE*Z*gwV)C3ze7)FC zwMrDB-;I6#_2MrVKj2Sz{!bNGO|BUE?KKY5pV21xO4w|S7$3s=6bc<=|hWI zhfenoe0kjjp;|f?oV$IGt%}+EyyBmk_myOnC}RGqTXfc$bXAt!KMZX=*ne_PHWdOZ&#T=clb-eE-Tn z`!moVDp7>KpK~u5;DT21h)9mve@w(8i1Ci_g&~wDi@w*YkjWY3Ih_ z%jWpP{JJVp1V=i*W9W~4fEWe@dr%RorC-`P_65H%`$Hv)(Dw@n_Ts__)zUBR+^P6h z%i~*}if^S7MWo;AQXswz#7+w#R7?BDInE8v5zY^;t(+rGe_##dykH-2<>7n@{qYy9 zJZoYF;{4F_nV#tMOT)^*I`Syi6RssHQ3Ur6t{R~~?f~KmAh=#BLbdcuBO4Ga&+o9F zaQ{$=BJ};hFABtOfM9>*?9BUMzr7vbN+pU&&mUI;u@?~R4@Ib!em7Lh#y-0#_S*~btyH22J;OP777*J2 z!TwN$YUy`#?j-E9`(wZ5UaJyCr03e>fEWqH!edvpxR=Lq?A*yXLrue3>iiYAEO>(B ziR-FihvYnI@ho-3ugA3K^W|O~gH@C#RGw6EN-cPf> zMgwv8_rL9ryW&kh#E&UxH`7X^c(sWF22uiJ$O

k=~K}H zrzH+6yrA!b7WYNJ9h1{er&a!^2M=k_&eQ!^ya(-2+M}>V3tFhOL7#klbWSe_ZO|Xx zH71WECVbtqzy6B92{!MJPktpqs21&M+P@#I#IH-6owhsdb{{^;Nm*UZNU-f_6`LCW{6nY3&dF9}oz7l#sMx1(3drsgl!OB>ERB@?#ZyLT7$Q}9I1v+bWR9h=ib zK~Keyd~6VTCYL8w-=?Lr$|6}UQJWk~uXT6*k*6d`t^SBWB`&1jhBklOs_Psug#*&<4+&Ja=-mt3(lThYM}c^Fa>?ydMcd zwREj?ZiP8F_`BiH7&LXsLRU^*Yqf3Xt~+eHf9bnJi-*6wZlMxI=&J1;&*nU%<9wbV zR7<}I{E0x&4*;8?P>CX}#$f>14; zH;JWRs6-L*%n;g;(_Mm4EuH_#>8?n)m?r?aQgL|AptrxX}bW}P=-!6T;@b4BXQAD)J!+uVW8vSHAr6vf~(oyLg z5%k5uZZA}#h-lA;Ht4~jCud=VYU!wSj$R^qi*WKPRHBG@A`5NMk3oM1-$N0qrK8e0 z`by|C!D+iti6Y`DJhZ{HInU?|BUDRArE@(0(+|L>Qi&p>=Owh!oHz0Id~-#pmX1p2 zc&6pqmS0yTiip0m&<0OkJbf*UP%RymIDY`a6CO@?g-R5m)*xmS?xME(@CW|B`%;8z z>DdSVE8KT&ztKtlj=_5+ry@n9mgP&|`KrHco&We<{&--a=K($M=%{pVv0XRzx8m+# zkJ}~`Dp5pw{*aS!f>13TmC4z;P>CYq9dtMq(ThrNDmGhC5niiu+RqmWAu|Pj8H8dmCo_Dowx3|aW7P& zi0J(cZP4dK-w)qI5vrx5(mBQeFcyGcS0##w{_D_&+)X41)zVR!+-4-FB1OczsnEvT zCqL~sIy&QxVuDbu^o;YDF%S5uSFh!_|NF$`tfq)~#}?YyefLNGrM(sWeTSq7)zb5o za}#I$xH{#)$;CI<`&M<*w~xr~>uu7xiK99(h-ynIFZ#GOMr<9^Y}-vY! zFL(IY7M<daf`szed#d+c`sSj_jEP^`4oMcJ2zoK?O*cC*gm zUl^0WIPu%%*VY}>dEwzPZGZ5q!>9lGe81ry+*CSefq=l=~K7p3|yYx zkG*=c{6{BDDYo19rKAV-sTA$pE*rSwzG;UPPp-F5McVn8OPO>IlO)S*WX{P&d0b~ zZsdoVN)&++lW|KBwa_0K$JH|z^IKtD)i$miMn=YQ#jzCs z<`~0R$T+Sxx{F>MjH}wl)qN^agg$LEu4)@s!xW)f7(E%s)noJcbuq3g8&|_sqKNc8 zFs>>aS0%<(#&PxI(}!_fWgJ&q^oF)8Lzw3nSCx&c1cCl<)(>i-2Q!YVSB~Xq$GEC& zTqQlIPo?N)T-7$Nx++lwMoh+WWN&+3=yEYj6Z z$Fy_f=hXh0@kcdliAwrHgl{$GsagJ^A5Hl$L_|~T56`V!es|yg%^Hlz0YRvwFGOhL zvUm3Mr@VS<(}p7A-_$zoH_y)f!eZ-M8;Vd#Ux?7gBWU9!YeNz7Z)$xq@T$4XUa+>c zp$L`qg$QlTf8e~lJnHo3JroiDrq;FZY&~n=-Pf`<6rqy75N#VhYr`ob{%!9ue8GF5 zjTV95Z6$pnLK}GV%D$CTMEsjt_zJ@p^oJr;(ibAMfgY@^&z&OT-_$~HW(&rZB2>~B zBD8^#SlQThiim$x3!_qO21Tf(FGOeqGpe!~jR=V-;i z{_(VZXvJ{0()OVhLpz20AgvhuLi2ZvsDSW>$Y}c*BI8pTqWRl7?oZsOX!}Gh{x0_? z?mD!6xIc0I3bqgJ9@sw>Z6B2=g8LJ9pkVuOe}er}(e_b}%RSu|IS2mdEgL;$uzhS?d5o*!Dp5rG9yYE###Lia)2^oNW8kp(ib9pEAAcK5f(;7G_|-tad!x9C_*KDAwnD61G%%Y z4MoJisl|PkyIg2P5i02m5!&Eh&K;UiM+Mnt^v!j=71vM}PxrT;!FX(I<>rXu)v)H3wkqzzct?hKXmg$QlfoBM?k z5lt=o3f6`qRMHnBv|&Biw4sRjH?^!c<9;4SNrO;HUx?6#jl};#L^QQ*R9YK~P)T2i z(1y*ZrVT~Jzp176igPw=J!Wm=kBOFyB6RI){XR7<8MBtU=Eb4kr^`0Xa%%o={XRs{ zQ^a<<<|(4zr^}H+O9^c@f46?0ntPP_eVX4gFHYCa=d@Y6?fKkepQ`PA-bxf<9-VG` zKBwQOw)1(5P%ZP9bldYe{XUKD1G|TQpRS$Ho4@URPQOpLJ)hI>L)(Yv^HvhkM8JM) z+iv|nw0(F!ZxO0x-kolHKBwQO<{qUIMWpXxexI6ql=*$Sc0Q-yr)%f)ra!{CGQUsF zJxUR=*QjM4mTr4Kr{AaM9;H2~Po?PA??c;%r|q_NMVLpY+n&$q_o=x@DMGcrbp;SJ&oGY$b{?k50GsC(`dzn?JEdsFwLlx~)HvexEq5 z==bSzWSAGH8Dr+F>9+nv`h6OkS|y6WcWc{j{XUINtq9dJ?@qV%C(`f3aYcV3JwlB{ z5$SuF--qKWqdg5PxoiGJS_ED5C-QV>^W6MC99Ibfz1eD+hou{AYV-SWTqQlIPo?PA z@6*`SDp7=abh@oSk$xYJE1uxmCsD2Rsq6$TU{UZmm0qhPpM6xtE4YPn1gl_ z{x3vCQ_D`p_H`AZlD-h34Li{{Z73rCO)Wd!TN{c{NneQ2hIuBMHWU&6rj~grtPMq| zq%TBh!#pfa8;Xd3Q|rUqub2(1!`e`UO8P>yZP2&Ww4sRjx4j4bR}0!`5%}F!(ibAM zfj6g*EWSsJh-hlzE6@+O;9Io_mGp%OZJ-C~>x=!-{#Ha&3%yByqP3w2mGp%OZD1tQ zXW6u&i1;_PFe;lhKiG+iP)T2i(1v+Zn>G{?|E88&AC2FK-dfID`h8lvL=oo2ZT7^* zi&LB5hhCg6QRcuoDZ;=e7BLc)Dw} z_**z_ce(4>`Mk^Zt399Byq~c1c`H!_PTpPaK<)Xw=KX}7&s&6Q;auD0`re+;YxDb@ z!TpIljh)Y%zwLb9<=)bs&ujDh@O<7%BAN*9vkTq>exKU>K0Ked2-V^)#NDVppV#L1 z;rYCkC?b6ioX>0X`|z~gwX8qN)}P36Rq&K*Bct*4#J|m-$gxni{zQ%| z`hDn6Y$b}Y?`H2|;I;2tOv_r`_P`oxT4=D=|O!eMYrRMexHs?6k#K#Z2gHG zSM>WN2-QlTiYqAZz0B{^zOAm0+O~7Fd$?M&&sEYFBCMj^JGdh(jEHDzaew0O5WcP= zRMHnBw81@)I~&_jMEsjt+-JGVg*FtSlD-h34esUK)7ge1;@{Mwy};c%w4n%<^o0m* z&?bR3Lk|o6KJ9PCzo|vL=UbcoZG+H8MBEg-IIU!1#CxaweS@Tp9uV{twFv$lwG2Hx zX(M{0_*9LgFGOg=-n^3cXb|ytsbycm+E9c_`a*;@tOuJm6cPWXmi4CX&Wcb;Ux?6# zjl`x6MZ~|UWuwyCP=reQLWDMKMm23HBK}P+wLTiZ4`(gCwT;~q?Gi=s%og`V=PtbQ zq~hY4XL|NWy~b9ZuMVD>oxk!y`90IO>a6*#>#_-p9+b!bKXnpgCdS@;QgO%SXZoeT z@!35pQN-Nqw(69{b=l7rVLZd>H=R_Bo^hr>_pYf4LbYx~d#j?oncra>+M*q?Tp<2HJ;;DD9%|1AtZA{wa^kUa( zb9&RKpTCVt6tVRcTXlZ){*3ImA2JH*yp2yUX1_nDSAFXbcPm1*wgln=AhtZ8Z5)F( zuD)_kZ`?QkaJNbn@%|Zjs?Vlp55LVeu0|WP-k#I**vT>GWy_R z#`Wplo!qfB_jtdmhjiXt{K{;FC)tJ~RD!*>z4?p(|KUAsi1n_Mn3u5W9te1Ht1|T{*dg%Be!jHm&ng?O~T3X z^B)~p{O6K;eYV%HD&=H|c~{I{)p_IGaT7oFFMo1%zTfd_8~VF{4-l((n#-p;G|GsVhgMV+>nKk{O?B++d%}1TOap(Dcj?1QG zjPd&Nn4!hB$KTQW)v&>}N)&Pa%^P+G?sIVV{hzUoHx3zE9DU{;y_?a7B2+7Vs*n1O zE1sKve6`6rFIOK=8PGXy-u~H!$8DE?dFuh4HP1RAdvuTO@-JMlNoR{iCTAmie5&4> zzn06fwTvfX+p~JRm!;L&OJYul{v*icl^6B8bdp>!^hPYO|Azi&p!%ch{n$E0riB9lHlUabmIm z760zt{eQ<+y87rU@!6muolTa%8k8K2bo#>Z3B{vdIo_ZB@&n08)X|qBmb-mYvEQLP z`U`Kptx}01bUk)%`JYcJ)*rc}KkMccp<4R1i0uFCs>M5(Z4A06#F-jKt) z(b~liCp?}n_RxrABq~BVV88JgD>VKhMhkx$IDUt6gv2 zq*!Is1M@!&FA{bb<$XyJ=giusID67c{+mA>T&qM8DLc%d(~9Dwm;Ramc~MlEm)2D) zU454A_~On*p2?pbvq`NIMWn1MtMuEw_+;+Zev#)_O%ST3D<85sUKv%KGHAS?*ZD`K z>!51sSOAC6{L#gY|J>H!dCo`4C{ctm#h?Nh5P$u6TmR8Q2-VWH64?W9k1V>Yty2AD zO;nke6;4Nnt{8ZaZyr!wan_fr#cus#trA7(R|m_@kH-`@Jg{nY<=9V>)kn2<>TKFM z{H-&x#lFu`a_Ogs7RL>Er+1|POQjM;Xg?v&^5_Z0Zx>mz+Tx-Y6NGA=`M~C#)3^Fz zHfSn$oHZYxSgbkz`Q9q;K2fPe5!z44653~SvBy{D_xAm6nIKf_t>XuGhJ5AX?38^N zXZg=R99#V3eb zP%U^xB>rlz!zLBex^?xHlRxUIL=oDvuq0$-IrD-^ z#mhTCT&=j#y*-sELU&ZKiyd@u@$XrS*Js}Fqa=<@wbYVz?yGxEEoR*RTJP(>TF0v` zsy5@8gSP6-`PTI8_0@Tr7`ELZ#f-;${*%3L^KtLvsVLfT%y-qCdguQ1!ih!y&;QkX zYJ+3F{;pd3&+d=2!Fkta?|q$ZJP5=}i~PIy%!bE$l_)~bBFM*Ckkjyp^0seKIGURJSV_2)uBf?cpzu2azyd=uYOf+a>aXzL=oCg&ixzl zaL+zGrTXlcmwmMKe!lbA*0S7T+p+ndXKvEjp*J}jRx!t94ItjFrd0F4{jyg{v@D5; zHr$_xn3XpxWUHVCwF^7Xg%c19bDP_4K> zK6C*QE8p^|-+rI#@`(qIO|pcPJ0YHAE?$Lf3)Sn}7sXox{orT%7n*-M@6$~?bNBv1 zw(DQUqZ(K+q8OR^C!Fbm?f(fbuYxb^FP)jO6* z5UQoT4ahjWVpMU$2bp)s98rlPR-c1xkrSq6ch6={!*!n?SZuo4rvAON7fBGRrR)xf zNO|QO#mKLp;Llp_$%Kz8|# zC_?8Z_VaBg7Z-njw4b`<>;$1&>FRTQaa1w&XNUR!_vj3-5=Er5_RAN4qd4jOf&O39 z{+J+COIJSUM&16YzjMTO`924XEp+_o$WQat_C9{K;^M5E(p~M2|C~^q_x)#jpMP?eSBWBY z?vs-qCUT}H#&Ow}mf4KgbVx=YK_rCn8I9 zQ_me!3}5=Ey~nq@EkUT(o^Ni^Ieg0tvx`pUT5{+LM-=|wauc1N)(~v7^8jb1B>dkMXRf@ ziYh|2bhiVW)e8F;hkw3GwZgnF6)I6gx_|s~3&fsxvDcoM?wqQnd$4mwzaxqdpZ-;K z@ZSHIcmZ{cr53;uOCMSMXTrSd+-2@fEC5C5=m9s?N|TE}AN)Y|xBn{>glge7OJe9B z`1izO)o(st?fApDbCoDUM-R@NgC-XvuPv+FKln$2P%Ye&NiM(>+a6i0booQoEr&1d zRiX$TJ@ESsn_Qgy<~`Mw|5z#pj=a$BzwMd;|k4d3yTi%l1~r5bwj_6b6@a5upm znkFL#R>s9g6<2*Yr~3I8og`OA5vhIk#P4zb`24Zz!Qc9h{+4P*k6ySjd0>STi)9ww ztvYJdhzfT%Z8SITirT2_)0SPk)9-5GiH?`ht+0{D74Y+PN z8I2Ee{W{;M`ZesvS58{Hv%+d?WEV}KUv%GkgkSHC{k!9Um|m{Z8T-d-77>b`@xwJb zOH7?HJRou)mVRUZ&Y=t1m`jABXXdMS{_)advjSpoJk>u=SSM#2_9UgW(V(r3xdCzM zn@1Hp-*kPo+3_PP-1c-B=|C?hZkO7)`F&nkuQPAdDp`2*j}Pgezjyz*?xByJ9@}W% zHs*%2J>`4GP5u+l`guz(S*Km-Q zYrfgZ=XJKbx$W}?p<34e&HuxzHgi<*>m6qJ_rCU8WvhNkPyG2OuiIJTrB%zR4{RGx zVI}?h&aJcD9>u<=oZ}Z?dD+@dTa82!HWJG)5;y;%@0v*&bE$E=1dNZp4m*ikH?M?>D|?n_4A`urpQ3+Y?ko*!qjb2HOnr zUwL$7f>15(P52W>ZCo7o%4zRV~R7@y1{QhaMkD|YrdkQZAC447vkJk4mzfI=gAxVO)o81 zsYDTJ8#f_?=ffvw`TZVUu2h6-*-C9sWqn>rpEvhI@wCl;w)SkjviGR?9x72p+!>Ph zsQ4a=P%T|6VYi3(sQ4Z#QAFHvLIlL=*B)HVx%HCj%w^iK+q{Ri7p-od)-s;FxZ>CdwO!3dVkIN7 zktia1DZwYW0Bon9%T>lKfVu27vkaQQo%_$`JNwtM*U|#e^;P#*oz377nznRt z$X{O1zjaUh=FO_Fh^24n*Lix|>2pI5t_s9>AP!mxp<22sIrq!%*Neq&-o#J*!m`Qg zqX>P!|BX;B8)LTamavwdUt~AG_(ADfqKNcc%?09jK&-wHLbY@y3f9s`ukYWXC1Vy+ zW4)-oqu&kp&g(8)OdPygemuUFN)+*zL)PpZ{q*y*!q@#6h`oVee<(t=^t(B?&AB6s zftQZY55(71i6X9fqF?8hxzEoEd(;(k-LlLT_-wpSiKRmVAcl~qnRq?GB{s+Nvpu#3U6eD(GHyR373=g>SXirQ>`2Rw_}1eG#+5*&hc1!TwN$YUy`_=MLZM zfc4MmO~$uUi6YeMckWgo)(3+9p$OH|FYVl(u)^0lah;xw-R5kdE2n-p=T^ZypZb^A zdz|MgQAD~XE)K*lK*-o_dQG+TyS4MYl9AZ-lp=I5`QHfD((eWany@ldoaZW0gq|#% z>jLq@BD+R0L$S^;G6<)y#PyC7T1VL6{TaUBAW@Q#~4;FHvTFNP$BFsYW z!9p%nqKK6L$}HqAEaU{CTJeMwp31Dg3RYhc_a*x7htx12o?6rkT6cP7b z-X}P>_MB10&vuznUA5C|UT-j>{lL4B*#AFzfQaj6jVivs(~Ro1Jzn!FQAFH1!@a?d zuoI72>xL>DxT=pf6>mmjpPvHm@Ms5x`;S#&C%*mU4b_q_E$3CDh-gKH^SRhpnIcpx z+E)Q_9_*`c-+GBZb(vS=%};szf}5X`_c+#G$tQGfC{7d8ahh0riC4W!;>kj8e#&t3 zV{h*H=8A}C4r>uA$}ke;lp053BT+;=e}s{^>l?qwhadLu z&NDB3H_nfe^B|rY`L~_IOY+5oeJ_j>FQcUSR{DMPt2_4-_%gnF)Ajzd<3=R?p@?W@ zgi-PYR-Zq@E_v&~6rozSj?E3DWF8Q20Pz?Qsue96{%(r+6%ea0x|`2{P>CYq?i`-# zVeB|#v7ZlL2%%csi3Z%Z?CkJVB@lyv_%jeHQ3Us>q4%#aJG4Q>!PwOnMyOU?!9yE- zsx5%vQ>j+m2j$I&2ZX(OC2!tH6cN|<@KpS|=#T2x3*NjzsFwA47TRDBz7B-+U?WjP z+)F|mHcBcPB@IHgbX{pzhKehLu5h}drcZVEvU?N{pL|YLue@xb5=H3h>fG01xBuj( zO{)HjqzKhY`$G{bQAD%=!pd;lIU|c-UNXMNHWZ;+I(o35191Zo%LAbjMbPegZ1%FV zLmNc=_LA}W!U)x}wrxi7sip%VPt`~iVeQQgZP=Upg%PTit_+G$i6V5ZgxC4a-HYtR zbN!eV+Wu(v3DvSavDsJJ(>8re$&RClblsIxYN2~-Vhx0~JqvGczNHGjrMR{?5=E$G zfK@b{AZb}92-VWwY)`4QEDMz=BHE~7H?VWme<4&$d$T>O@oZ42L=ikQoO#_+vqKwp zn&9a!L8zAYW_x1Eiws&`l);HQ^);0<2O-++QF^&gZCc^LbbFvowK_M zo{9>UC?ej41PhrrCh!69#w0nF77v#r9oRrY3{=Oc1JN5isR*Q`yFjuN_@HIef3`r$eS! zDp7<*x|Iiimx#AtKDv1Q(><%D#-|9?vY44NT>M$o}STE3Sj|8(Z8#IbsJsmBqv5h=;3HqKJ6j z2_E5zAs#MAJY0fMt++b}U-($W!*xeq*W2^Jv9-k~m8=^aXAy7y;&~_B_E|h!g?PBy zVs1*-KepJ9@`1~S#(21r^`xD<@`K%rw|}rqwfk3BuPsupkto8VQ_2T!B4U>@`xTen z^!4hYpD&RhRLi2?%20KB*DFR9o%vZc7)*jHQG`X=l>5HIC~u30s}K*DAXLlZ;mT0c z+v4FW#KTo8QH0J-BC36p_x_r4SEy!FdC#N2dQVL8z9l zd^n{d9&YnJuj>stpv~H9Zg}G!&N~(zZ=gn-vRd)|MKJ<)69#sY)e^(C^m9!{vyFOAxAM z@kQmUj_Z}h!+FHRRVq=0_J11>mm?l7L8z9+7nNf-Wp<6l!=c9EqP0pCq2suXhx3Ss zOAxB1yImU(=MfKAt3(m${;?_|$seev_=gtSIaMp3Aj1u>#lv~T!}WCE)-k60Jmz4C zhx3SsODq6I=;&$V;XLBu5`=15)SGdCT0ERbJX}vDiqO&1#>08U!zBpSvZy!XFtvC% zk9fFBC5q6|)5gPj#KR>B)v~C!hH14sdTW?m+juyS zc(_U>iqO&1#>08U!zBpSvKY38Q@V|Z^N5EdhfvElt%%gVvUoU;c(|@2R4aO*Lv(`W zJ6FheE-X8*WF<_?^D3vGJ38h&m%C3IgE?sV&OPKi$6J|_e&c8@(VuL2mnAERw%N-) zWG^QO)rvb@@F83Fa*pif=r1Yh!HzZ@ec_h1S6;pg+pz5A9NEi-N)!=oMtarT?ByKU z%LziY(x|6RjW1sUr!ZO?%j^{Re*&}<|t3(meh7b22mc8tey&N<8OJ?m@ z4p#ZMFB}}Rm&-Mp?0(B$&XK+BEql3tAb?% zmV1vlIJZ3Ea+QYBVbX1rij|MpvHJbbZu2Tpgk>3*-vmpAbC$haA$!@YL=n-3V>VZt zAzdLuI_7zmlqkaTQcG5JMV--*-CrTQKS8KgJQatkh?ei%L%wtL;*^{RIzMzwqX&`i zJZRkGy~7?Fk&InMSSEAHioV#@ez{@sn=|J1PMx$vf>15XQ7xC5!m)cL@}2u{b71fM z;YFcZmc3m52~~AdgylO|$agMOq6o`NE?J)!Ye~p=?jhefL8z8xwc6@q`OZD$I~OWZ zgk>_9tl|sLUC4K?knfxzR7+RBHs85IzO&bLP_?xGo%<28mv{L4w$+j6eB@Q42+L$H zLv`TEKn(n3+vZ4kg zqgpQVZ+>0Ncg~UT>{X%&?I+YeJ8D94#TS15XQ7vCtoNfH)v5CcdW1r9e z`0f*4C5q5~a_%$aJO5_6`T1+#DHDWhS&nLX!4}LIv3%zo`OaP?iqM`#1YO8?&XMn& zAXH0NyEflBN4~RHi6V66YxA9RWi?w}fGv^lyxuSF^>=NynOBJ-v}eH@fqdt?cP;%T_brzo zRLgRdt&+eb~ZmeZ*^VeezMQHdhd58HA&Rp4|= z5UQn?LCfisgVX6Al_)~}$t@QWnF`5(*?Mc^-~6KSO9w6_V^3-jD(MRmdeGRD$gy>X zBI4iF(sN?Vo|J<`0DD}5IooeXA*P_1Wy;1~!D zW;3o|yx^>25AwEzGl}yq{!LCHVyCy6JplHyisu|Mn4v0rNlSI@C9)i~+e@Bpc-yD50DjR=uI`b=j0|Sl zhW;+t%SxWOL$(vx%X0bw$Y2KcvXZA>-q(P=tmLVlw>@AlD{0LJ1~agi<@5uP!AvEJ z0DD=<6Mo200DDB|G z1ACdLAAk&IDp3U3%SxW`gLe?@Wu7c%WH3{NYUvlj{l{I8dHMm!U}jYpI`r>=y{yT$ z;q9AM#As@#;#~Xst)47qWH3{SBJ};x#DUE(Sxy$SyTM?ltB}3^M%*bG-2-VW3bq?%hJ)Y{xV5Z|oN4t(U=fGapBa0as%v7QXRG=<-5}(lI zrGmYzM;0?Om?=WFz+P7JBo-LVz+ToPiy0ZrR10;nOPS< zZhXnp_er58nqsVg{YJ@bYM?Bce zJXy@hV5Sm9Xg@gz_A*ZvGcuSdLbb^0&a-=9d}4hI3j>20*vl$LZIQt&?tMHJMH`O3=`&84Su#4}!-4dLgS{+g)D{`c^moR&i=6j(sDFMv z5NLx8W{Oa)xIczFFR+*O$YMqYvoB9Ssbmz*pD!KTo>+JX8BZC3!3^wW6{EJuU^e#N zi%Ld@9P#ThIoQieMktWM?49vfl#IOLu$NVg+9HFQB2??%5!aNA z&06IZ-baDGtYXv_8O&6o2%TwI;YRIKk;RM*W{Oa)^)L8I$=IwBr*dTgds#&mGcuT| zL=igE;FJ0O=!z_6WH3{NYNe|W*vl%in32IuC5lLAE!fK{vY3&%d0rs*U zSSfy{u#uOkgkrds&ZBTVya(glc{3l<$>{&02mvwgL9Cicwo+FjI*lbmYU{ zoj1Ej7Be!KDMGb=blLeOW3#Rr#v4VjmsMmjBZHYr6rpny>+aI$6Mg}w8adcdz zyBgTbaz<^D!AvEJ(2r!2|{~u$SdzF(ZSSN)(|p*g3G5 zTycSEef<8@9JGcuSdLbbqNRx%1EFqnb8 z%rk0>3}z}(g!Vt8qnCXxCyN;w%oL$oU@t2f1rr#|z+UDVwM7Oql_)~TF``~hThx=q zj0|RqP%YiNoCABACyN;w%v7R?bpHT*nJ0@G8O#)+TDk{22lg`0s4X&>>AtNaM)!I6 z$R^D5jM^fDnMxF)W5GGFmwB?7k-{!6{-(`z05OeiwtHeQG|{K?B{RZy^k$D zSTySU@F`X}5c_n32Iu5vpZ1+&Zkm}4f$K=?P<%SvXZ1a2y@mvxwv zgFKcREVeV5@j@*{gS~7n^JM~pxj4+QAAK*vl&N zS&+d@C5pgFFI#ZO0`{_sd=})5QiN)yql7Glah~hN$$*6|zK2Q_5qF&M9$+u?WHCDv3}(@{ zza(+`h3J!|Wcae=*tYK6nej1YPd>}5T&n9%~zHBt9hotuby0pk!^ z%*Z;V5=DT$Y&bKq0}B+`%X-W~C$o_vR106ET~U$GdGjU}SGS=uEPRgpmmLvL2ba$Y7Qt7HH`>b`I=iD2Em-OSLBP z6~zA3?*{g=JbtT%`k+PN{pKzhyI?QNV}B?j)za?<_Od*FD?U~1DMjG@#0m#{SswdC z5vi7bH?WuG{8nTz)1Fd<>kxS_{53xL8kICui0=t#GyOF@xLnG5ykD zFU!ed#(A!i1d*)mU@yzbxL{+q?E_sO^}99m+{cwcC5q6!43@h3*BpMGkr$IU4$FbI&}*DT~hwP5d-w2<%I za$yAdea%8H^tTiN+qa~JJY^X9mdNjG7IK16t$0ETPesmJv-*m-FVS}&cQxJu#QqNq z8?x6HDp5q-cSFt(*vmXw%*bFCtqk6IMEikvA+i4hM+(@>JXy@hV5Sm9#GNzT8-Tsc zlgo=dUeTuF%}DHXG7UvLDBOR5z08xJiriExQAD(&!uee6t4tB97455l0DD2eX0VIe}jR?Pc860v8h4%PO*%k*7!{iimb_xcMP(TYPgxs1}~Kv5>=?i@nSD zXeH6c<+J0R8Y?`!2bo*V_9@WM%^83rBc2U7V$e^G1rT~rPAr8=6cJA^p$Ew>Zs&8( zkLFx!w>`~SmbX0^Z_Oz+j6^x5awN8rcw!|YojD|(aH#4muy+&z#{*ZB2){jQezEiu<6wxgf~fCU4$K6cN|<@Kj`z z4uHZGeX%kPLEwXYcLbddZqzIKLBJT5HWdM6wPQEav#!RW!s3kY(O zk&jHrRf^cYKP|P;2H4AbeIa0-wOVLfW)#@Vdh%2vS%5%$&8aA~L8iC(t@O843*RtX zFiI4m5=H1*=^WV0Dzcc7!AudVrTa?aTS|5uMWpMloKg$jQ`H*K-fVnJ-h4}3+naMO zzlkE$GH{Ok*LH$T5UQ2-CONk4lv=1n5z$5sy8&6C?QD=BQmqBO*__ql*#P5efh0w& z+n=88&<44X?KF`fI4Yx-_NH^>Tb8Gi@v{Jd_8MP!XoHNvW>fP$T7+t8Z-SEp2(#Oh zy;c$UZtebvY*}!(oA)C@sFv>Yh+A6V>q{&EMWlPJcyW^W670^6N5}T_<}4E4oK-f= zPn}qnicmWko^9NJnD-+=s8-sWtgK>p6NO3?5l>6OLMDT``2Z3`s9;?VxQdkJlj$Ga~CPS~xM_NH^JLL*Nl<7WW^?KQVGp$)QG+j)@h(IQk!dlSr& z@GaTxQes~zLanIg#-wLACJ92d)V6aD>}5T&n32IuC5lKbGFJ1nc(@ApwM~u`8O#tx zkTDa5c_p}s%@_|C7|dAB)8gSOM1^F`5@I$G;^DHG(|{?z+{Yv3k+sp zFY{zEBZHYr6oE*$jJZpJ!3^wWo-Af$FjItTA!a6Hu2jffVl_{Thbs{e*Hrbi9Gr|f zILwv74R*$OxG8g(QN?PW77y1`3F6^eg!YqjU@xo4VnznDxO>sN9M3rPK;vFDV?117 zFk>}Oi-)UJqKJ6j2@Gbe=4tV82|~5v*(dnhS0`p46z>>iqM&cJ%98*o-Af$FjItTA%-nuJX~Nf1ACb#iy0ZrRH6u-X<)fIYqTee85ztJ zp<3zc1NJgc7Be!KsYDU!tOa|SCyN;w%oL$oy7D;(_OhHTW@Iqa@uMSO$D4CtFU!ed zMg}vLC_-le*sLzUHYbZ28O#)+T8LrG7!Ma1%vjCS;^AtQC<5_C8ROvsgBh!NT0C5W zP%Xr;WsHXl3}&q6Y4LEiN)(|ZAK6a7o}H7$j0|RqP%T8gWsHXl3}#?2^JFn2gPBSc zp>wl|hwJqV@o>qGqvI;w)mY8b;^8WlC_+bm6A#z3c(??iT8J;o7!Ma1%)nmOBa0as z%v7QXox#ZA{Nhi0WHBRynIcpR@kJTq;R1sh*vl%in32IuC5q7R*2Kg0EFLaFs21Xj zGRDIN1~XRkw0O8mC5q7gZ{p#477v#oR15J%8ROvsgBh!NT0C5>5=H1ZZsOr8i-$`P zs-?SK6AxEeJY203MWp)&*vl%in32Iu5vrwoa1#$#Sv*`%_iY_xy3aT9aFxZwB^H1p zbSyOSaFxZwB?#3*3|q!{IDZHT%{64=vZjt;VO%VOAxBXYMzXTyW|kI!D^ls4_B!~5vhH}YMvGk z*HwgSMGthiQAED8w|wUU*?AfBoylN^Jg}_FXxuMoFG&y?r_0}jO^u}WiQiT(nRdggB@)+`ofX5moa-eFqk2G zxo6qSg-R3=ZN|W0hV12@WiKZP)k>cV*~^t>FZ2GRi8kW>K(vr~(||0ojM>Y9!3^2U zm1Qq`l_(;v41vK6*~^t>FDD4q(l63vFISem+=+cl|7YxT-bWxSEhBHu_>CE7iR|Ud zvX{L|6ru0eWG`2iz09ng=FGvY9pqqT%w8sg8FG{}X5I$|Gh{FKEPL6jL=ni;%g9m? zcn!c_)+37<8O)H+mysiZtP02m%$TuE1~cRdXXIxH3}#?2^JFn2gPBScfh^;UtPz31 z4B5-xvX{L|6cKH>z}$iiX>S?Q%=2o_wUj6Vd8rw5_ydC(virSd_a_L|il^ehV1|6> z-1432#c57OoCi8TbWDT!Yuw{GSRUM>%7@b6_w7ds$8vGcuSdLbZ^inlaxw zFqnb8EGLT@8O&4**~=O8o&N*|vlM}RXK(q=g-R5GyyT4e&Vj)U`OdlJJ0}R$N>?A` zJLi_~T&P45$Yjo#?;IG+knij*-#J03macqFzO%P{XRqs^YH9yF2lg^g7Be!KsYDUT zWX_oH92m^NUgpVSMg}uQsFseHCf~WTeCK3M)ZWxJrpb4%EZ@0Mi6XS0ntbQV@|}~_ zN41cnnlaxwFqk3Vxo7##UL}gqe!^3IVabXtW~YL|OcAPu9Mz2Z&Vj)U>}5T&n32Iu zC5q5~Lgn7&=J&{AMg}uQs1|ZmGv+%71~cS4_blJpt3(mnPffma&+?rUglg$(*W^3* zEZ^CyL=n33HTljx%Xdx?s+F#y$ak(R-#OW%wEuO@Z}Och%Xdz814U>*p@Pd2cUELE zBZHa#mTDnKIU`ru8^<$y0PJNISSHKcW8Mu4P3QGcuSdLbZ^ioRN9#nTweX z2==myEM{adQ;8z9XPbQI%JQ9aMW_~Xlr!c#KQ@oqfXH{QEZ;d-i6XRTn|$ZW@|_ce zY9U8CW4`l7cQG3f`OcN)JLf7U7v2-Q-{z&UU_^^DW$9+fCU{mIB5yngXo*ppgst$xw?r2`j|B2>~BBJeGNJ*g7* zq}Hb!(bUp&qH|zR>KS`drV>S{SG{3Rs*F8pu4<`umLkBO)HC*^ZB(L&boBvyS&wX1 zWH3{NYNcNn>}5T&S&_j^C5q71&N*;w^^9XHL8zAYEc*P7U-TH2Vm0-;y!YUJ4RRQ| zj7s6(h(_u14kSdRAnL4Q^qJMp?DBSucWKB2>EfKzRE9yu4S&h%${^~jvg-1z64PoS z>a5FHGDe=I2t=J#R$ZQz{@UMC1ftHmj4KO~XNWrMS#|jYp<4D%_Ed;EtF2->YiD+G z8Y+2qLViIP=bWZOA~I6CxRWZw{U9Q|Yet{3ijqncfsB+c?9_&3x2c_3Gy2SGXLfP6 zX{tsd52TAzOUcMHM5=driydzD5p`BG`pjx)wh~1kN27~#PQzObPtg{~)Qmo30OCo~LE0fDHqn$c%gJCkpl@f3$l7k-6|=Rs?)shrnT$g3HBX0HszDFamXV3WT_D;>;P2KR?>V~s&7Dq6~|t zJ;+!x>A`0GP=xiStqh1E<0y&sQri_rwRDwe=Xp~jSJx|>=dr48`%AEQm))agESXip zY$b|FS5d@8)r=)$jF-NlYNh?52$d)TQT<)U0)>?t(ONZQ$=HS>R4W}R|Z9> zL=n33HI*=H#*$ej%ywl^E!*LmU81RkSu;=3Dq*(!ha%Ed)Ye_kbys)DWN%OQTEvjm z$W!!I3A5d66`}ilQwg(XESc46Y!RxZy@~9BX-n6PC9?{W?f6jy@{qfX1qy3BqP1$q zk}Zr-E$z*w5@wCOpIFzj9Y2ad3{dx+wGJ8(+CU6h%~&$4gxMlgOMA1agjq9|OrEM4 zKZ>yShKDu~LsnaLdDZ~sn>Ps6(%x(;Vb)f`KG``Hk?wnboyy$B!Zq zL)N|MiZKI18;BvR7)!P=LbbFvn@X4!W69*Hn(?CuYj1dH12JS3W62gqsFwC-Qwg(T zESY@W##&N@eYfVk(^SH&kbU2?N|@}A2BBJZl4&fprV?hwSTd`G+1hZ5NY7D-A*;!) zMqV}WYjl;qq-j^fS-*W^|suNpX=yYMfR#;4xJ3BRc^gBY?d*-!$n8e+(5a;uS7 zO(lprYZ2N{@GT7RUhOCRojxzA7fm5v}w;FlX6roy(A?uP4E%2&= zQ>`Yq8hO=Jq6oy0brGRb23|G9kk#Z?Bd?kwR0}a=UBrKtfmaPNWHq_f$g8FjMd(a( z4xDN=xz)(4rU=zS3|W_aXn|J^oN6_>)yS)+5=H1ta}JzpHM!NutELFmN>?9ns@3FH zBd?lD6p_waaH`ehRwJ*PB2-IPK6p8A|FpUj+-l@i)A6GtU&kAE&f{0B$*o3SHI*nr z$254=&gfT@TaCPGicl@Ykafw27I@VVLspYpjl60qQ3PVhx`@pw1Fsrl$ZB${kylL- zs)ZP`F8R;`uNq>=YI3WQS4|~~(2X2XCbt@S)pW$*o3SHI*nrXRveNRIACYMqV{Vs1{<#x`@pw1Fsr5)oOC9kylM6iqP-YRKl#u ztwvroMW_~H$hwHlDFd$>V#shR>c>i$UL}gq{%_ zHM!NutELh~=s0dFVb}+rV?gNZZ-0%sYDU!{sB(4n%rvSRa1m&=^hN` z;eJQdQ;vswqOX5JT1_A6np5Lkw9>ZZ-0%sYDSv7MeTySZFF?*5ppS(96hylRS2EyR#9{;LeUYKS4L$*o3SHI*nLwXYCER+C$eylRS2t<)Ee7_yqN zWL62Y%g6_-gxTdCx>dsL^3J}kgjq3`%qn5FUSK_QAcm~Vn3lE@X2n=CtAyDiRLgca z^9Un`tY$2kRl?+rLgSA%8?NzFBZjQYh={flX3bbKtAyD~6p@~`5kpopmdq+)wg}Zq zp9(Q#HDk%F5+-jm8gIW@$j!Y0V#vC@fp05e){G^yN|>!g5vgwpF=RDk$*dA)i%>0F zSIk3?7_u6bFe%nz3Y73A2?b0x@J=-WRr&Fl)w=StZOa?**+AW|xr` zRtdAqJHoaSX3bbKtAyD~5Ovlf5JT4Gopf6Xvt}%rRl;l~iZB~43-{-UA*&fnW|c5` zu5BcWKnz)zF+Xi3%$l)eRtd93sFt0Iv$hgu%~-PaLM2RkahiFc^CKPYh#{*POJ^kl`z4e^G?qyVYU)Qq&G_qOJw(Yt+u@StZOCp<3xGiWst*v1C>Wv)!X~WTd+RV#sRL&Zw*s zX1g0GLi?$ygjq9|%qn5F2-QLiS(ou&A&v|&WHn>StP*A`QAFD3h#{*POJK$$>dbS9a^o0oVaENTHSs##XC?ft%Ej_(9^*L+S2V`wPl_)~r zsj1Idvp!&r+JGui1hNxoKbE03AR^mp)(2#5Kt-rl`mNX>jBsOgo357D9~pbiekn`7 zZY^Io;}_LgWKWodZ)N?_AXL&9BE$~b*X10HU$^CyPsSK4ckrl=heUFteqo11j^6~zIdGvO&C_^PoIUZAGekhKcx?#$4Z#mhW>8!a)(No<^#xC2{U@qnD-y=amX5AmTVa+VIq%= zK7gE+Fjb<6cyAP#Zp{afvl6BvR4aWd^8t8P!i@J^WL1c_WaMWs%c%^NFp)<_AAn~i zOqD1idItlKu=xNyD`6@^we*W1&nx%IVgsG~1MAdiebfQpqcRiX&BB~X?9=aXty!(=5)MW~iOEizgEx++if zJ)G!k9X~qSb-X!u7Ebi6hRI5pDp7=;)yq%`6IC#4R>Nc^Ohu@cox;jc2@_Q?YgWT# zB}~<_^Lfcim?^?e^c5>%szecX@-9OqOk{=eMBig2Ohu?xy876OzQ;!50B&!Xzv{LwY5VX_jYN)%yd^)gh#L>0`M)i7BJ zQxU4ABeXrydsf2K`K-OE^B?aKPV}CYFjb-m{p!xyiQcmkrXp0!PGM!Jgo&&$p6GK{ z!c>VO^s76EDws8^VX_jYB2>#xVWm~Ve0*ZPCaPhw5~fNNq5Xs#-hC$5tcJ--n2Jy> zJB5{@5+<_3c%si)2~#DC(0+2xPV_lW^a(<>bnR+S^f@bGszedGcC{z^oRu&Yp<3yh zXeWBlN|?GLYj5fb?wpDxBy&D`6@^wd_P+hDw-rqW7$XsS-u#j@q8+n@X69P%S;Tfmt;~ zZ1oVaRq3fgt$w>J%mVY5MQnLQY*o=dr`;ZX)3o6%&LIoTUly^|L&R34zpJ*W-Hc~} z`3tOHHQB$&{G}2_sI`n(oPNjFWd9=bmm*ZlVl=YA`~}vpn(SX>{!)n|)anN-*ULxO zWd9=bmm*Y4&mwKaR*i_QGM?zQ`lC!g&?!fw0ll_a# zU-7nw_F%j#qGf3}e_3GuvWTq;5nGi?6cO)n0`r$eY*mQZN)W0QZ-D~ymql##5U~|4 znT+;%yd|R@Z8zgtVE(d*tsWw_YLzG=-pU2$FN@gfAz~{*s8+o53d~<%{i?|RMdmMy zddbNA74INsFp=pWr6t%tY0sL+oFEW3rL=ow%1?yK$_AfGjDMGb$MdmLZKk*)zBVWfG+^17k ztI7UF<}Z~fLT7<giMf{iJLdd_3P<26 zW{wFncjM^8}m8&cg&~^ zZ;mRMz4uTJla(;_ZDY1Q+dvh}E~`j}N|=`K>{$s@{nYw>)GyxVn5=}U2-UKDoHA6xL>0`6)i7BJQzeQ>-@}*?DptZ&tJn}3-&`%6HZ!cpN|-89 zM9f_Z{UMp&2|~5h4nnkgU|Z<15~e6)RyXLbbFv;ZF?A6csCBszecb z(o3=$6NGA|qr~QU#d)sZC+6yNp2tjo{*B!kJQJ*j$x4{|6&0;3Dp;VvGr?+@tc0l& zMWk&AKSQYq)k;@t>vJ!CUh))gPgwFyZtay}l-PTCzK2Q_VQrV;d~WaI`5ynDuJZu1 zn%Lra=&-mfy>|pbiXwGy?#)n@j#NdO^p1d(r7sFn1u23^2Ppyqq6pk%GayYVqNpfc z0R^N90)kKAos&#*{{iIt-t&HY&M%W>CX+Lhng2loy|AyOofa{@49+F&C~5FrL;}Ad z(bref%iwI7oC#C4UFSNmJp49A^CcJROU{PLnK03Uglcc5o9U0TVDg@7gY&*3fnKT| zo9-L{?0xlmACt%Wsx6s3R#Pq1bo(pNNby>tV?jc-O4I#5sP^z0oCy<;gJ_ z#As68g($a5yl=i9K!n>aT98oJ7j^Hh(i~uwf&hVDc;D#lO!tbjVe-8~3li%3qVC=0 z`rvGsTpviF7v4A07NL8^*)Ta1CR&ids9)143#R03m|P!7pcme0O;bD8d9S|LcB32> zVQ+``%~wKToe8h)I(2{q_I#SA)E1ojz+<5o-ZxEC&$$6D(WxmU@LlrX1bX3pqYN%? z&tUL#jus?vWI;-vL~u4t&V-2sdf|vn(@4E6%qnIorygg#v{)%X<(YJTtIYP6t6-)w z*mK|Q;w_as69|=E-lmw^%k<}*2@)!A zyyfT4SZ>on5o>EzD21t zJA_hcwp{%yl|fRf+?lK$ZLz|a$~b1RDwEP*wp<-Al@(E{+?kG+7h8}}`3@~tp-JVO zl&t)P$3icq5UmJOFEd!hOy$nxyy2G0oyqyuox8yLYTTAx-6)kIPpaIRzJ*oaJc8BP zyzA36l{M74ay%A#v2Gj3jqa7J9H8EH_!c^MlOsyLT9vm?U5CmWE-6~#%vmN!Nh)`y z>9rWvpNrL?%E%^JNe3;gkmnJsKgSW1TZ5!tX7H$<70g%zkjI@WcP8iBa-J^M(TlZ2 zm7U8`FhdKg33>#zM3du2wvd1Xm`2UdY#`vLgj;$DibE>gLICiay2@H$_=T` ziqy+E=cH7bFnuE6^?b9{{5Eo1BB_^gUQ6j@!URizNP2lSzo*>igVf77cjjY+23~X> zoR?6QLF#3kpVK)j^kU^Tei!m_gM`Wf>Rq{iEF@Uy|9;XGGTI#T<1CG{fXZ5td#4$p20torjdG?%_?Rp z6Q*xLf^`C8&!EcHC|Sn~uMoWo2I>O|v>>7K`Kg|o)XO;Mq*DeG0WWAhP9{vwYbl*f zm|zJKEmm{v<-QF_y^M2bK1OKI$GoU)zfIHKB?8VWW&wiA;~eX%3|4w$O)|b$cr5e^ z_6$g%1qtl=oJ^PoWx|vy6Q=34EA(PTPwy?^WWqFf#LWt3Xh9;_i>jQ(PQQz9NPM?r zZ917SZJu9Z1v9iDf$w=I6J`pJB3Z!<3G@oorbg;zDXe0~%3o+fLgn*QQ3k1(an8xd zh=3Q=rlyg48RxZ>tVf0|BS4gHy_!cFZX`qMWt=n+DdETmo* zp-h-IE12Q2&(6Q&=-ArTx$sZ5xX70i^*w#5o&O5NJxJ?AP1ljSOy zsZ5xX70i_GxyAccRL&2J_iC&Bah9uKrZQnlRxrckDm`qAcdx6AW0tF6M(SlLtYXFr zW@te|DVkfZf*Glo8LVQ)3T8;4m&$!-xe8{aUS_b087r8f1qr3hZn+9(q+VvQiWw`I zA%R{>FWzz$%v2^!UJs`$b##k&7Ak#mi}x<6JXn^iV5Tx*N>(sK3ldmQnnvnnHmjJi zf*Fp_FfLIUl`L1mOl889tYC%~BrqnT_qm%1Q?h~?66l2^GE)9>Ghs?rFvI=|N2w~~ znB^*%sZ5xX70l3r1ilj~bC#P4Q?h~?66l5RVA54*gw)2 z6E_p4WCb&oZO>u_GnMttVg)mmz0z_O%t*b=U==e~FhdIxDleVoDwvUanZYV%tYC%& zdZ~PumaAY!>SYG2n6ZKxT98or^(g62YgI)XNN3F=GWYB+v_cK26*F(&7lKn6ZKxwjXTy*xoda)XO5QV#W$)Xh8zo zG<_3(e^G>0%viw;3G`C=E-hEVOl889tYC%~BvfWW%T+K_nJ^_Qm?42)Dto2nDwwHE zn35ID(1HZEe42;b|51ch%viw;3G`C=E-hEVjMU2vRxx7*GqfOq&!(RVQ?h~?zHzW! z1>b5a6Q*PZGqfOqE#J?CDOte`3G`B#1ua*>jMU3gSjCJL%+P`aKEX6Ent62!tC+EZ z84~EFG7DO+f*Glo*{ov53T9|Q0`Hrj2~)Cy84~EFG7DO+f|<&MDOte`El6Pf`nYcd(xcQ?h~?zPGW(;CtTBgeh6U3@u1tTktbsN>(sK0=-neOUqR-Q<*R&E101L z32X~~CQQi+W=Noy%6DnG3T7%3rep;(v><_P!Ow&#S-}hm^iugQEmy%zWx|xKV1^bX zur2tRFeNLPA%R{h-=*a$n5j&dk`>I*f&{h&T059}9cRLntYC%&da3M{maAZ?Q<*SL-s`0@VVbU}gm~B+x5(R-|5L@D65HFvEF#ije)U0Hj`K z@=h^76Q;pCm|4LLElA)D5`BaG@J)kvFtdUg66l3@#L0wd@D65HFvD*J_;rEQ%S_&x z=4Zk*cn32pn4tv;ygnxrrok#^tYF3(%e)VVM=7LUX7WBPl?l`2eae0&%n0vbW(6}= zpYSY5kb0TPyY>7`m=Vf^DODy+llSzgOqeF`2vnIcP2MZ)XTr286Q)#|FntT@o%sZ* zmzliN*w2J%^A2WKFhdIxti8?q8eFvnQZKW4mozJwp#=$2FEe>>s-Fqd<{kd5V1@*G zv8Ffg6!SA-rtqF;RxraBhtCJLP$v^+3agl@Oql+2fCQTg&xDymnJ}fwgy|FL zMe1cH?^E?NVWvSZas=b07E(1HZ1mzlhq+0TS&^PXo`Fhc^pu;+6!VcL`lQ?h~? zsW|%mAbMf_JDD(T%7iIZCQQHeAwlY8ChunUGhy142~(;}m_C7C*kYVam@l27mz0Bl&s(vQS2=94j1v9iDfp^`> zglVvfnaYIe9}B%mz0Bl&s(vQS2xY>QDifw}K?3W^$%Gl9Oqfz-!t@FBBK0zp_o@1s zFeAL@nH9{?f<&;+Nxdw>d!A{(bAUiE?CqRPm=Vf^DOte`El7}Vqu=v6nJ^=i2~)Cy z84~Cf>_thv%-}uGtYC(HIMyci`A#NGgZDhMf*D$nz?yY3VH%VPQ>sju{+k88NWIMD zeae0&OoLU-R3=Q{f<&;+NxjTq6*H9y(I5KrfZ=(sC8dR3=Qx3T9|Q0_S1I5KrfYr(Q*~cNWF~nK}uFILkki(|Db84UdH(#B`cUAfnM~SbKY>v)!0(mHn|3q zaSqx0&HJlycG%D8=@4jn65*V6*krj zW34cZcj*jG-tEt|<{il;Sm}*&nex5T(SiisLq`eDRWM^UIo3Vn>p%j%yuZ8G!77EU zR>*`Gi>jyACIE~UI6d=2kQaQ z$U^54y{llx3e9SaW3zTMkA7Ie%=_BM>KEAO(>`HRFjsQ`fim#8-YmDPV8#mOY7Rhp zGikhc!TXNG>;EZ|)p-uURWM@(b2SGb(Sn5c-N@aczzXJS4j@3FSMaP@!CcJ&*xq+8 z-ihLUCF30`6glZU2jD80v4Xjp1F+G8gf~0rDwwf?xtaqA5a@+>#F+!I)f|AMV9x6W zdBwOl@58%YD7Mpi4!~6~OGOIiY7W3g3leyJ&K!WP<^WQtm(h6+fO{E=OLU$CU>L#tLRgpckI4rm-Hm8qrH^KiJx_g=!k9mql2`j1|n#f&}Z4^N8M6 zFeCM{2&^xf;<+v>?HHg5?D{9>6Goy6jm`~1v4bji$-BOkLXmPe?XGCwS z5q+Rq*l{z0776GgdG| z0=-y|oJaJof*Glo*{ov53T9|Q0&CV8(c5Z7pMnH>(I{N!5xuKm_5taUs}X$)T9Ck+ zbw>2I8qo&`^kO}79?`oBW~@i9M)WCYK?2{X&WK*B5&d=~&{T&E2dPHmjJif*BI%MQb!n)-7@s%t*b=W)(A5FhdIx zII^IXXy}YkL?ha|rH_0kytYGGSo8b7|`%1=fG<_L2SuMs@FynlatYXFrW@tge z`zq(|;pKdjtYXFrW=NoyH{nBXs6mk{JNWIKv z6*E>aLjt`x-z005xe8{aUS_k387r8f1qoUQVzM@pt6;|YCRxRd70i%8FIr_~vhtX# zV8;0-S;dSM%+P`aK54Wbu5B}$Rm@ny3<>n&e3Ps^<|>$xdYR2CW~^X_79{XVBbA%C z+uE#R#tLRgpjWW>A@wqwRm@ny3@u0mpITBcvsuNA70i%8FYNg=jnvChSjCJL%&`4n z%g6SnX{273!YXF0V1^bXuuYSi)tp5stYXFrW=NnH=bL1$GFQQj^G&jf87r8f1qoUK zW3nogt6;|YCRxRd70i%8FU~i~%44pA8Rwg16*E>aLkkkv@@aJU{YNRRV#W$)NT3(z zn`EsrSHX^yFN?5>87r8f1qpnDY1T2r>Ikctv4R;A=tV1FOjd<* z70gJz%wQEWRxm>g5_sR76 zuq`+%wv077`|^sd0D)edZ<4jjTm>`EH_0kytYC%~B(U{3E4GYsW&84qtpI^uoNtn~ z%3K9A&Ns;_W~^X_79_CsI4ib{x`};x#a4hoFU~i~T4k<+8Rwg16*E>aLkkkvdYlzo z#*TV@dBs+MKrhZW$y#Nuf*I$VWEC@3FhdIx*cO}>TZUS(6(G=y^G&kyn5$sM`6gM# zj1|n#fjuUAoVhvHB21+61At2E#6*B{_XAgbF~vly(~rT zF(Ga8#Ub9W!YT#cejNVo?d);2UP!&n+mA!v4&MKWchRsH(%#M&atYcc6j8f`q_-1AmEqIgejJw|^)j2)jab>p+qcPA>+R>{-`^>*8Hd8A&Zv-+2-U`G3$ZMEMyFi(y52j|5#jrQZDsQow+El6P5nnvnn zDXe0~3T8;47wyN5e|)t z%r_!xXILQiLBiW_jIhwh&?wNxjTqMJrabLIS;T6c*TJ8aOL_M`3xI2D|$uT9Cjom9xv#P`gY6 z1bSg@I?5CVtC+EZ8CsCQkzQa|V}L-fU@KvjLhm`p`$NyUvkRY}b8n|V|E5pig;p7? z{>92)co&hz9+hV353Dj+{fm{q(1Jv;4A5sVkwC9tPtA&TQ0I=q29M(D44s|jJSL~| zbl!37wh~rh^R5FeNKn~2t46rvb5>#Vt^*15!oHFsnFA|qRxu;J3==I#cx!~+yG!b2 zHmjJ8BLy>RyZ&`xdH8LLvfT`wXtRnLE101L32LFvu6S2Nh}6q$wWpd}yQ4tDvmfY1 z?O11J3U>|w_Pz#sYHCY5YfJDf1+`FT@2lHifkq0qMBjo0wMw0JG~Dll2|KFUY7cLK zKrcK)nr|=E#l9-avL**VQT`PoLC=b#=;F?Pz~1lxfnLEYXZ=zy0`PXlbNlf$Ah^~% z%?Y;#X%BBi?cojdiTHlSr8kw)fnLSYG2n6ZKxT963dD^f2rSlx(~jgUYu?1?mu zb}xJTgdd50V(|{%H)mJ8x5r%uEippVKKO{$7TkM9JMX5s%~3)~QA!Bh68$;|5YY3{Tp#I7u!ALJ?Cga0!J2_M(SlYtC+EZ84~E_snNKto!4Et z|B~gy!pS$5-mt9Tl{hKbWO_2PV|2h z==FTY#w!}ON&f_b{%U@=;@#qWEIOu1lyfF@Mo}vN31@{CB50-%zBvk#!2)_&@&y zLG@y;sGe*2U4(&MmSB}R* zFV#YyPzG9%Q0+KYhJRK_pcmGSa;A=i`x0(#d}gZ7buNd0a|_|4`F9t~@Gac(Jc6G; zE;B$lW#F;UOSRBo84f|m^jozebU3R}pbR=Qr|tT!8VPlV4y`W1`A?8QFLg(rPzG9% zpmwG6Gx_*gA%R}h*7S3qcX4{x;8~#s3GRh%cGwsslKIM!KrgJ>U>RsZLX{V+4?=^j z1ii5SoigZ*_+PTbdRDdRw2UX#xkI1@3Dw&@p7_b44te3q^c4l zG|!8Vg>@_xHzsFvuIffnyKm!VpyD&xNh^zweY zWvD00DFZFuZ!SYUX{rp5;CAJC@v+d$`|XyYdIqNqw0OU{46pCv-+o{67=d2iZ@&!g z;T!@j-fwjsPM_$P@kD~o%J=eq`}fMAr^-7kzkl_-__%aOc!U(YR}P{2E1y6w@3&h9 z)u5o3;*^0F?>Co0_0OY;Se-wSKripNTLvGW%i*?*7VkHg!PmfLy7%h82=wxPyJhfw zqL$)3gJ|)7^Kt1(<8hmM&OJi)S5E1CEcEhzyJc{FQ`_>MbLUu(64Yau+q&0U?q0`# z5$MIgV{yA8?34X+P-~A_kWgpk)pA}lX-+WwE|Ei4tBGAkG?Ute1u2TkDyx&}gYR9UK|02-K z`|Xy&ZHlhmDFZFuZ!SYUkE#rhQ2muZe}P`!Z?_C?Q&jIx8EEl-a~WQQ!@v2SdjFE; z?E)1`oLfn1vweF+8Xr0z8t^c$^LtB{QhJ>+g`MA?H~%+Tq6G>2(~0`dV!2{Ovdbk) zv>@@n3$N?XmBSB`Rar1`0rTQt8TgkA-C-hs_PCCCET+9@1c6pQY+rM)9ku1@IM6W(~_4M=2 z7(v&-|AGX1^}U`u9Qt!ijBo)W(1OIAmYKsFc20>A$u1Hk(5wEeBH@#ZbH)h2474C| z@bg^ZPMw~O5q=p+px5;GN`y~c$`j>#s1EP^Ct0Eei9i0AKOFw5Ta56_Kmxr+94sDQ zK6!TN@iNeYg!&yL{4$&ib>9<+Ow+Q2XH8kAbLm@e#Dz07n&$jIKKj0X z`=i6oZ~w}v9BNl!K|0YNT^;rNbreCB+%;}-3~o{B;OMVs%Oh<8PsAdufAv>-uk!F;S;Ib|S$ zUaAL=-Q8qzr+@z2z_B1fZNYr3T|GvimwFRDp$xPjL2bc&tX(-}Ac0=gN}{n=vZifM z`>p1~1z(Bhb@tVH5$`uYcjd#S%myP1hxzZ6x9{+K_Km4S#Qs07N6~@=o}s2)Y_-g8 za(j>{Jo0!V66m#{WPh{L+j&(PUlP$$5okf8?e!t%mQ#5Y(Y@?hTdeCQj=h#EiWVfW zZZz#d$l=Jv*E9519b z?fEsC<;7{OMT?v5Luf(bn+zYDr*b@{%7`c8!4nAd3ZB)xk=5jz6J8M2D%^1pe6ys?cdeHAJI4nhv>>q|*HLq8rN13o(`plu_Xz}g;WcU6$)DTF z?n$YfcIEXSd?pPFJY`)u^|5nY@9%Ek{^gx!vdYlx;!|@&6fH<}&8u03n;cYUmHbQ# z`9Vrn@zuxz0Rp}7j%eD>w<0oa!E&N|(Q}DtK_YY0`{tk#hgBKJiMUkYaRR;YzLA1i z%dxUxl{rqlLGN>mV*|c&?>ArVn4Kl8-{aOKx=)mGVXXY)tzW|0j~Pw0AVJZG6^mpV zogOP+uAe3)_0Vx4B+%=vdQ`^lJW;od#zb^}$tBQ&L?~AY>(17ZifEhkrtDU2v2EGM zqZIX7UOZU+%Y4>Htvj21T#CD_SPWOQ&k(tkR)(EAT|5yjNc5Rl#JW8*r$f_Di;kmZ z+n2N3ZAupl5a@+xsA&bd4Us!Oo@vjEcC*le#6Yu%_1zEIR2e^Q9VN5%FJWiSem#l= zdIhiikr`6jNJXw7tGoHtU`D<~hg3J3?#ja`%>&IBbtzF(ZT)BpR&B zZJGVYsI$68#L6cS=!N%<)-zmeAlK(9=!`jOY+!n01MfH22c9jdi$yyt}Z7{Jz^?QM62WJ-xLw$#lH%NTeb3$7{0bmb5bKl(#}? zL8AEDOxB$xn^YMe64CJq1bX3p)3i5lMD15v^ye#2_QpM9hr>h$F^Op{j z1$TcKLJJZvZY^nEdbY4St2}4M*>j#ipckI4roDbMwQ=pY(XvkKvZ16GI)*M}Dd8OJ z;H_sur;^>@IF6<~yg809yZ3Oc9M$WMC|Z!9-%*d|_r8|=AB69Pcf>g>+dC_?;Bo0} zqu$w)uJg^*_MhrHkU%fIZ<>}!SMCvb<#18q@Wqa=?gE?r?}mpd!hJK_ac3yHI1TI0nw{pIuaDg>alp2B4hy(vQMB_@T_Q5 zB)m}(jdA?h8X6Di-lz!A))`F*7)|)sfdq{#^w{`=Ml1qGEIxr=cukr{BS-^Akh(Xv zq_LsyjT&ie2=hL1rA`~a(s(fcZ)u}wL4rnJdTcz{zU*0}DvdeoK3E(e&s~US=ITquv`_bC-P<)tD^;p;B_RAA7Ga| znj~cTZszf!?L!UT&J}*?V9&^vLg_7! ziZX561nL9J2oj&}KWERV(@jhp-X;+(NK}1lPN;RIJmGsadQurX+ikFyZXO^e^=}YG z0=@8TNh9U(c>6$jm{@t}tNJB1d`%N1_5VnHNbmERK^CFBgBt=lWo=wX@AvukpO z#hC?E#@LJ%?Q$hYi6Kc7s-Xpmv&DZ;{4G9bxNF*lL_{BcVprHTK)e$%bS$G+WOis+ z={(^F)q~~HQ`_K2yZiQ@V%47AIvy8^TVKu%U1*mle7Ovt)u}BvQa-OdMzkBh-$Vkv zux>Oh^|wFTg%R}*ffxm`y&j~ECf+=pBiu9x zpViI0?}l}{@>eo0ilPMxyd#>nEh#1C((hwLfx@qakU+1Ub!sGLcsEBlO9?Jx(0cb? z4H{RwI$Dsxd#Gs{hwL&gEa)q$Ce6~f=u4u{f0rk`F4KZY)})2eTI=(KPvlq-Iau}g z?H^Lx9rz+&dHkeD@Wm(hucEn{ctXhC9Jx_6?l zCg%>%>CWxy@ca*rBTo$$1qNOUA%R{KF4l1!r_ZPC}*lY6*GH>Ow!Esbs$ zj^-PeGkoCUqi0p_NKs?^kx^p8jr!ZL3?%mD`F(q*Y&pZz)9~Hx)+3Ek_Uvd8-!w>| z7q&`GI}j~utonYGIQHqxM6@6=``D80>9*wv-_FZr)Eqr8GOW>9(V)}3ZAhS3u(fyZ zebIO)Z&xwoCoPOMh}TrV%j)P;ZSsb@{KEaN{Z(4ytsh2G;80& z;d0A9hr)2_^xBhcN3`axeBpsz`0j3M5GM}xe?|0eyD)?nB!bs*79rkg^?jf|@VNc=r!vQfiiTgG#b0Gwo+>GJKBy&RwhaLS zy|67%ZrR1<#Er}mQ6%(RV!wU)!e1WR8(P|#BC>z-ht14($cf0h<_S02d@STfWVtIB z6orp85GOez0}B#AJt!1jK4)FXjmQqYP*4>7zJYl5bdW%==OTr}|K?sBawD?)2Xlzr z>6>vxmh6qmI3mL@;NIWeyL+Q(Rq^0_B{7O3GPEFpXG>b%m(vKXOIs1&FGWWJy=opV z8ZNhCVaSchzW*j(+%DEi9F8BWqXmiJb)-68RpcvMNwn+RCh@27xxzF4y%^%CXzi9KqVml=;Th$B2yx`h>$J;>Z>a`Sam@-}|V5 z&JiHZx4#}1ue?%TblSUHM*_Xx9+WHGZq=m_$8(xiI4`xrrwfVRhM}VciET@>ho7sH zM(2o=u6$BYk?rZDMw3&MtIchiC0yiYF+I&Iy&`)vB!s)IETD5ViL|DzE!tUJP5Y;@ zrSpVpXh9<9+N|LXEfaJ%dW~P)T736zW^rZzTOlOSD|lA()(jFAi>)v&b(M*AS7i>D z%46spdEKZPA8vf>S)F4MGn_db9#}``cuv#K(RExee$@E0Z}2*%m5C3(bET}#5gDE# z?Qt*nhG_Th7slMdL!xL25SN|`=bBtWcO$Z4Wjl+^C$Af4r%n$cu@}7dcgzwVIG`TdEc0wZc!91NCdB=MX^5O@QD3J_Y84566m#ZW_);2*3$ag!u&o@B%;B{ z{l-5T<8-tjf%lCRFhgTSg-;fzaJ1Aj92b6O)7v^nWP3}*h5u?XPUrY)(ED*=(XqMi zMr5xLQIm+BM4(sO+nK`qzZ|Y}Ocf;ZJ{T+7=J`wiwEv|LT9BCbcP8p32J4@VgNUr3G`}mKT|j^zPs*5WFI{p9Ns)L z5iLk)H{-%-KB%v|5!uJ9lSKYWZyJ-k&fA6rdf`(*5x`HQM6F^)?PEV`VXQ&Crhodz zg@@mopt})S^|d2KongAso+2`|Akn&YTzLA@S9CWb%kkP+v3%sr$Z?9ukU+1FmokNG zJpYF7Mr2R5?JW}1eq*Qa_`UAU2=d!2bGt0z8}?G2-{Cz*#D%}QF+q1Dvfn@NEBgHN zrM)TZ1|7ZZ7vsbGw=K{)o(mG^e;p{gu3K%7__48$79=+GekyF9nyYgJsA>NYac=Eu z`>pST1bW@g`c(LzvvYJe>br7jtXMzr2W!aCsZqSbHy&mRN4AdAIqJhZqG?m_jTRfH zY4-TG6%)~d1fDJFOpF;NE}bcDFUc4r(Cfj&xbT&4r|E9g_ui6W;>hpg>@MvVhR}jU z@H+k)(NFBoyUc$5R%092z@VIzQq^nlEm$;Vv zy*-3x)%vxVsUMz|!Qxo0eB1Z*S}$j`I8M0v_cVQe{8JXkbCg}9%s>&pd!2n_@8u9$ zLIbDh?=DZUIBvru(fj+H#mE{D*9#Kvw@^h=u)thtT2T@8PBp!jjeI(zr8 zK?1$fM5gHPUrDgssIT*|!J_(K^PKhV-nT8T16+IT{oTF0zjmN;fw*ihq^J)qNZ{FO z+RMF%i-Zl`?FuvxhXi^}STRY@d@j4?Mty513>78POtD*1)Q1)%g4dCbGE;wXY6i=lhpT&`vzV3rs%;KvlZX~1qK9VdQ!Ayj+*!5xsauMRBNJpo z-v&`6(CbqB`FioZsVt7?G_6gV>SFD^igIy>3Dt`CUalWWch}@NszuA7PXWJ%#g`sn@l&4X!sMerWd3=0wMiD*LvT9C-LW~n}W zZp~dY2nFOpX(=#gKCS)}mr_?U!VMF+-wgLE?I@wfg?7H%vE9ymzyjm=yPdoG@v6 z2nqCB(e@)K~s)-`04OmR9A z=#})r8olI;H%)iuF8z$WV*TvK^3%RD5iLl(|Jf$JLai&NJImQG{QzV9sU$gtqP`xV z9MKDl((>i{u-`juM2eNPP`T>YOFsxO17byA|%kO^vf7=Fx|*~}2}`URe~p!&Qw(>r*JZuchbK*r4Y$?)UH^61Ns}YJ9QS_Er=>n^ zx{+n_s3lfSB0i6_Q+JjO2-M$5(Nf&_YP_~C>e|LaN9jr#8Y-6v9T_E?!f zbA4z*B6uBd6l!AimLufHw;S8IKL%I5G@pM=*NUAo-KcN-kdfwiT1~}^q|kzd_uGw2 zy42PUYyC+10nPP2iC`~0Lru%n_F&5Ntz%^Cw%-Tp1CKlL8XmYiplR`MAdz`6JEs9b13YoILrI$+6+#A5WWomYy^@HvH=EAIxdm zY15tSOMGzNs{i{~`2xj>XhGsozu(P-0Vhp&u5U^1->lk1?1=^m^x6@3!F;CgNz;w` zjNZ+|AN=FqUAkI-MI+UX>Fsv%{_fu0m-?2n3(XrP>rvE)79{X&N!jR|Pa^{|jFtOo zt`7xq9In+F9x>4V>Bc&tX?i(u?(AQVAAQ8NdIz8*yRm4a+wOO0M-9=*B%^%FO zXHJ=J)Hf~ZS$kB!QS$FM+9aX{iH(~Mn`6$OHr=Ri@%eY{RQG7@Yo7*DB+%{p#EREP?+<;K{rBp=aw*L~q6LW>Uzw)<=Wi+^OS)Rm zu9|M7+)oi166lrC|66m-&eNtFk&V51&)(X*qfCBlzljzk@Q%>F-Gl~q?K>l6EBYpk z1bXEdaoB8du-zix!f$7=B^V> zB=lcy7Rq?nd0Xz7zS?Y7@-G$pyi=%(YT%2%2#Xd7S{bR>B?kMkmH@O;~`;lKhHP?^6?8J%K-ZU-4vCJ}O zzt-}`=pj+GAo0wWP3F@zuc$cD`ui7q%bjkrGsTHWpjWT5Tg|gAFRD1PYufyB>{d6RUR2DZ4CwS$;)d!_k67@Lo-R z`Zf90-E^|}xLJCMIEx$lX6a}_V(NGA zn}2+m#&W;c&i=Qt%$F*!e0k8N5EAIs?BfMy(H9@8sIOm@TC(2$QnD$&Qj3Cb!t0M0cQSL;LKrd{Sv`X){ z+VaSur)2^~OPz`?GFyFf-z-Vvv$@AUFozCEWpRYGG&0k?HZ6mtzNO~sDqkLQ(O!O3 z3*+6za}N@0yI5Y+lKb-QtL>S)VCpbt}P|R(pQrYRj3XIXi>pMr7-Vs7gdzBG7`w zx(QQEIU~VxXYLjeF@uP7^o17*^m@JUR5RoBES4L??fE=%#$60O+ z_xxM^<@{7pd+}=vLuf%FcpXiX-jJ1ko?}XHHQ6|fc;Xc{( zro8#;LT7FXEl7C3-6-S1xz}aMdAIB}G!OSAg1ztzX}!S;_p1{V z&GMh+wA>i3>!BpM@2P?I0Gi)L0==;HkY4!QA@cr|_w1(h^)=tCnXOJcX6PKZ4eR%m zRW9Q^oujZC!{e;7G>7cQa8=$IB=ZgV$hmTwL-cojK4~|od*w@Wjh5AK3+fErwpjU>4@z(U$7U^z$b-4IwIc;5D zd+)RlOtc^oyp9Ii0J*)?X8R09WJsXbiMOA!RxX~WyOHHGx>qkxe9vC6=5h!vNZ@^= zm1o9iS^8WqJHAhw#Pd1htX(UUb&k9)^^CLX-JC0i!y9Bb41l075jUw<^VuTvC`1bSi3YTD(KW97A^bSY&iW;k&vleK$lf9LDu zXLmALhg%HRzohR&Ip)P##X2=tUq;KV87nW|Xc5^$5g8Kb6`wE8YF+kq^$l|BiLo;8 ztc)q?DYC>X|KA^(tdm3gIp2iwny4j4#>&g<7DW#6tQy=OB+9pqv%bv!iuxveq~;ho zxc#-1yR^Cu3G|vyMGci(g5}e0aBx z1bR)*9%r5Dm#n)H*;Tr`nTMuJxfC{Zv><_ZTGR5594#9(PB4C`KA{@kMIfu zn>*i!X*E@rk@8Nsp7HRr$<@$;M2BISt+|J4IA3Dv{ZVq5JTzj0k!IMCC=%$Ec2#C; zZ+=64eXWy;W>+>|G=8C|FU{NW){OzBoo~PY#3fki))jER*S(rCi`8mw3H4pAM6JP6 z)SGX7n<>-wL6@Gg7EY_+d_`W?J+rm@a82hca=io3KHIW$rY}#0LrV!aG7wZK)peyEG?_{WR~>?85}>(xKeW zcfh`F^H{(2I~L+tWK)I&Yu)k!>YMPqbXDY_R8_ zCC_FpC59!>($SJ*cP{HhmJ1<{6Y)r-VotfI?PYoP zT24`(z9J)mUgrj6vzj!EQ(uvrH|ZhEbUR^;Em?mX*2m>~S**`57t?FCq1kh2V>F9H zL{B1`=c~UBEl6P5npP=&SNVc@(V*3E0Rp{VZIab`d3QGFt2O0t`{*@Uu}nJg`>*|@j^lOP$Yz}~i03G>#2QTAmfiX%CAIU77VCyq2o-NAa~~)m`q4ZbT98QGm(v=m z{TbrONzy*kaa%m`VdEYL82)U{fVegQ6E~6SeU(#b^XYukQ?<4d#1RYkoQGVn!b#pW#-X* zR`siULL7zRktpx$uu8JfjH+T<&*u}-g2ch?`K+#o_lENKa=s`It|VvAtSYvpsTd&8 z3-5@gt=pGX4%pF1Orsc%R%uzDvI(ula&}Aemp>zQK5P8{4usqouG=TMxgWGl3Q)aNn&%sQ(KR z=tZhJ)?;ctP8n!H0(UhB%RmCXNL9yrvRV&Xkib3T!7`9QFH+L6o~+h`79?nw80@2u zm69xxKri+8Cur}W1qrXk_%*1C@yl?Ig6AjSO7BiK{bpY7O74&L0XV&4KR*wDRqXoqzA46(iC0YmSRN#H6iT<vWc88A=s}kaTsMvDsja!W!|Qi{8FHWV%?a(qf}aZ;^=sZU(1HZ6f!4HLRK})N zMm;YQO}B)a`>vF=Ht)c(wo?Jo=o5a>m3I7b=J zjmX{^n_nb+omcK?mqFl)1YFzj(Xn6k!37VQ?sYUJ;@DStWw?C?ffgiiErq6K?pjRL zs!>R;x_{F^0=@8iw5GjS;yID+Kpt6Z@G%3wBIB3ifAU_@f9p+OO`SK+*I$(vt4frX z|K?p|palv1mQE|MiI7CR@Cbok!SA&#$0Uf#Wpm29%kqfsDcg0u!f}(IXIycST<8b= zxfMH{ziZmnt#M-6(H!!t<^=^>kib9o&+v^-M zjWg3Cvh8zO1$yDSt{_qV&>o{%g(`AkpF9FBNZ@KZ`U>!1pRw}Yit_5M`~d>Jur1Kc z1huOn)UI|?yFv>RxW-S@imo_njF%PU=|>3k!WOD&)t{SbEI!aqzO&@0f$LClMJq+G zdMtYV{=#nKr!$S^GwClHXh8y3Y|>oDfrG}DVRhyBH|_@r^uqOiv`TNri{eByznoP+ zWCYf_cABDhU!P!c{}Eg-x+w88BlK!}xqreo11)KQIPsvKKID}=4y|cJW^XZ473n0! z>g53fy>P86&1KA5V^loQOLkp9#6SxY6vI0TG;U8lY0s-N|B|#a|9gK&@aqeHU7|BI zy=$V`4s$2fWG9JHsdsxMo%`IGD1AN?SK-@+&t9TDA# z*!2j3Uif8;-Z+KR$w3DS$}f96eTnJy?YPPUzjZ6eTuU#+QE@{gox ze_a2cz3Oyfxv616?yr0c68HsM)51%y+DBg~B1exX79h}zo@O)lHdwX$ie1YnCj0Mn z`gY%f#3NtBXP>tddX<)cyi|aD2A@DLTz5db2R=GxSNgfU{J3&HffoF7j7OrUmWYN# ztR@02NZ>bUP5Zge*LII1FUT9|f&_X|Uunkr-Oc?E*kd|BE7x1axKH#gNZ^-oP5Uvr z&;B^{f}CC3=|z14z3@vs<-5yLLaul&i=1#OqrmkgxN?Nv^JXjpXgN5KOkXmGtRBtE z5rA(&BDlWfTKfdKBU4T}`IkHa0==;HkmkUyc=_V>T(a~8=dI?qD=Pv z%q5?Dgg`HB`Lqu*TvhH|m|dnV^{s(x$8hBt#dc;aPW*azNm=T>f^y=niyZa&79?=h z8-0}-Sx63?R6wR#s&QoL6X=C2hiGp`gG%zt%TLQK9Tpk5DhyYGQ8Z}A;>15Lw3PSz z{%dbK^j3gCFK-sl?RV#_ctcLU`ElgSv>Oeat;P9Wim$C$6uyCo1w_0+1X_>?&Op}r zk@A108xv`lZhT;-2xo_aM5_s}$~v108Mk+*7Wl0IzckQT#EOlI&X0dp{Pc1?QV)G?s zh`2nii!qJ}v><_Bvq($tXkEE!ab+VVn==yjkA+?|3b$f&09I0Md1_>JBiSx2&T*@>ca7ZN7Z21q68K$} z>U?DlIk)T>BWIaloue1FH%;4mu&TURdcRSF?iJn>ye9nSO^R7l6QwbKr?GKB4uKXV zXg11>%|?B*KT&S{=af;@&KMxj3%|r`TGzdG<+m;VXY{G`je+YgaMc6Nep<1a)TT#Y zl)GO$Wn_Nm51tqGElA+{2~C^Wpq4B!{jgEt&D1>i>J#XNYY;T8#r5X0^23`(+2q9r zt}nrrBQ&dO#b%vz_HH0wIFlfDZ%hgh=!L6cC~hy;z<%@HK4MpyPmB$qq=5<>*A5gj zGu6l+cIO%1Ct@BEw@QCvpaqGbqQjDGeeHBj28e^=?Z9^f{8kVoO7|^iH=NN{e6jnk zftnnsol$mgezWNG9AS4(=KV%%Q!<_FAi9U{8mI_^dNO6QER25IAdezeHC&sbo$Vk> z8Fvk|Ac0yoq`0V;wTph+R@~1KB+x5(R^!?gv-4ePE|S`27HB~N^;tBnEnRsRy7E`( z%8@`Xyd$J~x;aD2l99E=*EvcGRD@al-mK`$d9s9gOdeE+sUK~UQcBbpKW;80(1HYi z8tPXk!J##+TJa9Lb%$~<17&t3bxe1oH>D8ermx!2= zub@B+5~#zYX&vuvOu5vmvG}b)o&bSfsQW|r>V=-hz-o=e#LNi-6|7J(i^>jp_f69d zBxg5n%xx-))Xv6b_!cBkt&7x?R_%*S>(E5h@0}|^pcg8F(H{3j6C%A!Hx$`U=ND)} z4Jj;}_7$y~5UF0Kp*VLkf1nH`P#sFs(o||3sqy7YqWat-0V3#yb>6(iQ;}-l)E8Ik z6mq_Ad#wQp)RWS*ZyL4JQ>c|3q*j701HFQ+YB7(8JfovDMcNR1~8pIOILsL3Ob@UCJ082DTBk8fyYANCeAxGha#L!v?R2=c}g; z5a@+kftof)Rx_r)+(F!1bHzXl5_nCt$33Z~F}7ttG2-MB1GV%}KaYA>J=X8OGjWQs zd3}Ge=F=eo0=?)sK4l3V6uVzEB3qCgOgg%um$$i!o9`PpC<+S zb|f(G0qtHUVj2+(A0g1|)edi%>q+y>eSbVh#7rWV5P=pXFjE5UM9Oy5{<>y|#|ZSQ zKW?GS42#sGSCY%6aMeZ9fsKiJ12YfnHZ=zt8*m ze^Y0*i->hZaDAW`W)BDwrxsO}4}UJ{5NJUH^AJ$h1tPR#CFz^gBm)WbTG!^Dx$4+n zbyj=^AB*_>^%f#X*k*Ww77u4BefSvB2#YbBi(T9Cj@37XcL zh-PW-TT>q)(CeLOVXM!>!BO}5Xhp=>RQIj-i9iby!Q2D&-g#5z9977k`v`$v9}O#D zW&AVVbjx5Oo`?^LK(B$21tCa$IJ&P~_xd!4KnoI>Pl5VfBEBPn+Z7V%RbzE7Yj(qS z>a3VJLj?B>=v5uEM+Av)W_6Ndx9qdIXFv-Qm>q$>r4sQG5!{O+fnHyCinrb!KU6bJZVfR?v zUrwOwKmxtypZY7>=ADA-i%GGDBkcA>Y#;(HNMHsAp6eT7cO!!PcC=uI0z4A!uWkQt zO5=|QI|N#gz+4BK)=UxeA2}=Z`Z}pZw0?;q>N-{u(U8jEUKA}zUX{0;Pto`|kg=iG}TfnL zGOg?;yIghJu1}y>@JpOksh+5PH$g_nPd0Fc0IsH^XA@Q@EP9QUDU&nEJMT^mtWH28 zxaKbN=^A2GtY`3#ghmo~ zPz2~_l^`vov_r+TL(?PisU~xr=o9D_Tiv(#@Y z%56#~Ze(%dUEhKPu1}>o%N7kp#aK-36X-?pydI16DGC=Hg>$5jUYN}xNYL0oz}Ub) z77{d0fb0=8{t({y1CNDXG%nF&qaqsP2ycvoUYN}xNYFS+c;hIvAc1)yoUxkl#%f5Q z7mfP#*a(uwgTfmRq8Dab2of~r6yBH3sqvin63$tJZ37TgxV4lH07800;!kNo3ytxcK z7JA`qi!)zhz@qmd_ZfJjW3%rh)LfnLE`oImx(a?|~b#vA?j z8aVTh-zjkPO6q$X>dUNuo;QY__&G32MFPJ-kotE`LuTBXRxEfgNT3&v!ZmFl5ow5+ zLCrRmP3H_w7x+YCT4v7tSD2?3(Ys zy^)BwsSLCr(fo_|&EkKgRo^C_YxK2!>fy`ctw#v-!nrd|tEh-%BG7`w+JCy5O}oXb zGMZMLWsiQQof!KFfnLGcL4$~qM7&1?T9BX_Pxva+v}6mr@wc7C&!>U}df`_m+Rd@O znVof4C-I;!t$T&DoI{&Qdi zi3F~`(6o!~NM~YMR>^G_kA+@1LMA0>A`THTod~obF)#5S^U%}{YE|*b4ll}D+SD*<6)TuX6`kG1d6T2=v0a8q(_{q8<@^chQ1Gm2Ek#YkM=OGUh$(Dvdlj zA0yBU=e0ELeIiN|F`LRj3lhhV=CPh{-#hAlQGDrm54r8~RcqEG1bX58oTf3cng}if zElA)x5c>LBw}(9c{M1PN?jV6)xZ;LX{&#hkZ++OYDQ9rZnpJNxVf%MmiB7tjFHLXeh4aSbNugJM{myZ(Yg(GBIZAiodBBoFoXhGtymo9~#HFK#l zRy4gDsgbSwV+4BP+yH&mC&D0t-ydi}qSxyML)rAastlgX*nhXjV+4B9kzj`9YVMDp z2Ew->LBFH1GL|*HngVBqgzrUn1ZJZq69HH5TkyDaP0`rB`ng>ndr|D}`UHAW&B99A z3q;J1)u3-dg6hVM)p^tW8|oza z3w{W!_(d;VZA>{|Ca*8aJSQ~@9G;FvUC@%SAAvR z7jRq?fTJZ^-~Ppm#*)dM#TQ>Wk)=P5LIS_O(_YJpvy9=f=+!6C3rBsl7nz8$u?X28 zK_Wr1uO5r3DQ-77ZdXybPoNi$cb&N1AylOAkDZaA7+#N!4Q}VXZ+sRTP51V#JZRrrr1}QQlaw*LbLB3#>Lo0@p**>YeN5WQjUAj1lF71bX4fThk5_QId#} zM4$zUndyEpcdpv3_6b*_+|Ix4j2Dj*=!GM1O{=Pi;Zz1%kZ9C;pLy?xL#m818#2lt z-YqH~CD02;-kLT_5qwr?L84%%b>_Wgzo|0DW%=Dc{>Agobs&LWIP%uC!HP(xGSGs= zqy^K=Eg#=gWt_kJg`NFgL_A8M7mmDXT&sxDR0dj*I2`|q`QSiWwXUzy+3~h4SWi4k zpcjt3X&(y_JBb)dWuOI#+3m8Km*>Q(GA<+*vupg_MP@cbbSMj}YjEt3oNWb-kM@-G($3-7z?tz&+X}l_9_ct|Uz0cM@ zMxYmt?&%8_5w(fnmWUQ4*1nnEN_V-gD&zeU4djk{Z#+hz7mn^phn|Q-L~sv>79`HB z&uo>Cdl+@^m0gOosTQPvj6g3O-P8Oo5l4s^LuH@^iJKp0v62h6Q)OJVo69q`ezy3^ zkw7mT-P8D-h{kn(w%#NHEl9jyF~O>MV^*Sj9g$y~$tm}iMII&43wMvuieDo35y5qi z79?;#1x0-?(v|Oh7@7QfkU%for$hS(qfO-21Mxl-< zf7dS(xX)A5a-X#9o}I$-nGR0d^$GMsRV7W!{{Og~}YSc_>n%LL!wT8B)X_8Q!GP{E`Treed3{kV=^)GDRvOA}@*hul4M;p8ebR zoWuQmUaj}8-}hP1JneJ#ee{*!{=3VToi0DJ}uFUQBUIYo6gVXWcPOE{pK3)whfhxSE zaGa2c58@Ta-ishXYe_m@qwa5aytg!7)hvN3yrrPeWf1XZymH!m5hQ3$Ovh_2tSAKHo*eG4T$--ishXYr7lo8AhL2;vFCFGAw~AyrrNwO%ZWSypyr_B1q64 z#f|qqWuLV7+QqviOP~sGDIBLe5eLOPGJ7wA1nsrpjVI3>+|(=me7~^Tsb&vn2~^>G zX6P?;f4HBQYSJk5$2Cg4fd+}>J5p|~Sy8@w_XXZFRlWs*-)X_`H_&^$9{ErCZ4aO9 z4LQ^7sqJ?qkVt;VWOG@Y%u(?!+!Cn5n-Ds465+)=efzBqBxn!s#%F_`Uro-u8lNUC zfhxQSp*sK~D&iB1y?a4|&LVDn#@YD$iHuB~XPoA@p`*BI*-yBhBsTL4wXy zZhTgou+PTKM|2*PvzooFK^5MF&|M!9pA*4*QS=}|XG1qWb53}sw)Z}rYvq(`Z);G6 zHzD+wl!;gqpM>q*3len3b>p*hNz?tkjdVVjv$G{og*PGehFBst#3y=t_kskS)!q0G zVD*okyteVJfhACdHzD->S|SdPZzk;B3lena0PiEabyS(R&$#88+m14K8J0j5zA=yP z`kw0TJv^>5^XIz8iFfHCf$u+aoQG%aojK*E67Py8-4oxaI^l;~Qa`^{Eq%?2v&yko z(i{GWIEjc+M4$(WCGXaBmmRX(Wtw&wtA=J8OzDzGpbC2>z3ZL``un%u6`Hk<7WI7Nrl476-iBm@3=svmT8;Mc#vE`X%ty|;~ zsKQ=Jf187d*NEV{LJtxbz5cM5mInaYdu4J40 z__RS1WA2Pj-Z}eB%p*{R@4utBY!Y!X5nK-RAW^dZPxsW8O(aI^{yn_K3)|%psKOl} zy$gwmH;A~5VxR|!vwBoZ?{&%Jsb~!TR^ZH}`}D0X zl~oB;;SP}AJWRy5M2w~w=s{xUeNKAKiY*f3{()V+6$4KWsuHNe9iZbpLc~HMxINH= zM5jA`bKmdL(~rv0>aat--`C%pN1zIKfb@2JB6bnMwTm7kZvXsScWsTUCC2kdxAIPX zD##;Hg*!m{`_4oRB7#ef9wa{e*IKv!mKhQwwR~T%>#5)55val)pyPN%bRmN0cJv_e zVxL#tL1#QCG2Z-gcjmU1HNvU{s_?yWbf*sldXQN9*OTtS>y}H58~$3CIqaf_CI%9y zqBkDF`}(p#pa+S%o2I)@?Dv_(m^k5u%u(g7O$;PZg|{uV-xY%A67(SP>Bb@MhR5k| zteLfTb*l4-z9v z_Dn6CRb686z0dWVdgT$Q!rKv1o! z1gh}1#c@^;u{`dH_N`n@Xub+`zCr?3H1pYah|&8QfItrtG?9Pjk)o2HPUJ-i>E4d(CNE<8LwO;`d|bdrI0Iz2{2r})HTJxI`5#E;K7CwJxI_Q*N@N6H6B|YydIynZCa?JlRkVp zp*9h4qPHF-P8ofpAKw8qobgC-SbS?>2~^RI1$;W884(@hn+fYdg6#0f{yrH_enWFE8-;ypbL@=!? zyt$>%Ob`LNvhPAd0`Ic;_xA6~c(}8`oy<%756kU;Kx^3{8zurh^dNzItyoW?5=2$i zt3wV;#>g^(=K(x_yk2izYV@tuk^}|IdbpA;ysM%A>X0YR>9_t{hxn&1{(ecc3zvME z7?>`eql(8s4-$CNGZ83#{>gespo((nY7Qf9^xv$9D*&!IQVzM9h?%U19wcy0jP;x= zBv4hbt_Zb+sYN7kZ7&$Z5U9d-GDJ4wk|oC+;(C>gfgU8J{pF^J7#jl#RN;D+jDa&J z&eYVhIqHdSqF-?+ZgcBF0@spc3?xv6IZP7hK?2vr;smM+mORVlz?lKZJf0JhG0=mA zlrK4IO$;PZh35nlgVg+!9Ot-0mKu>8uSgvc=s^Pa@Ufm_Ab~2(VUj=(5_lFVPN1rI z$+0I&Jk$Gd-A%?o4-(Qgao^2GT-HMZRk-dZW8h3pG3@M2y$5b_V#f3<>p_Czr3$Y& zm=>yN^?_R)ijj@tWIbGE@ScJFc`FY6E^Ah2^&mlZ@`feLX%rx=3Ue4~qyL(9(3TL> zrQE_zQOqO>R245dwiLD??rP!)Tn_Xg@zsSNx1ky-&`Xd&Rn=XM#>sk=EBkCq>PP!7 zJdaX6=Zbow^&lZVCeD>WNdi?gZs2*8$~gv&b6$nbIzh9jecFR`oF^vGg9Od<@H{GJ zk_4&>=88bG4%+7&v|icgDzw76w38{k1F#+>Xl{omKUi{13sqPnaVe_S6%vCIPq1Pp zS-YshdW-cO1A7VeG5f?7+doO52Z_A>E@N4afds0sAKMs)Ko1hE(jB=a$jEv~psL{b z$TER@Lt3NkGY@Hx!mFCyK_Wr>D|jly+2I^;3``4E(ihB5Ez+`_2~^P@&OT8pNSGMt zL4x*-@XRYppZ-fRkU*9E{vUcf614Y)XLki+n6ywudu= zx^dND} z-3#0ivldIPuI%42{9kz{{A=$eJ`$*!GxtSz-z(=!u6iF{9)5F8r*OYtr@N@?{Mll6 zpJ1LzH%XKe@r4lRL1NPZuelRj+$*{Ixy6a$q-&dmA8dNwM*>y<{_q2L`qD9ytD%pb z8SZ+uR@m^Ctc$8Q>wMr|`o`5J-6U}d5xa#z4-#+fTIYV&v?{cqjVziukIYBK-&aP^_-pw3s*Q^y{<-Cf#xV2a1b=3(32jgtnZczmq6;Cpx3 zq*@YV%FuD)O&d=OYQA%Zj~*nFF^+hV-qpAL<)C%lG8YL{b#D2s+h=G~iE%U$V}w8t z5?CgB?o8!aP@o*0U)=6?y|gs1O!Uo{-8Y1%HF|2!!t>|nFz-l+o#Psb2%dq85Jn{_ z<+$E#t}sMKo1f!D@m?ohVyuaLjqMY^GU8`7WH`EMU~8=Cfy_)yfS572QB`d1r zN>*o&*K<_K>TJ?Y60!p@1bUE=oq^;^b{QV;GLS&k;HkH^pVV%WDo1UeXilhw zR6Mrxh;k*+qc#(iQjT^wajwc~?_+YMDxLvQMY+w z?R`wTNrF}bkM=$~x7)OkpjE=By^rLIRveG^K4!(iv`|GWkxzRc$rY`&9_@Y1T1)Gz zPkSF-k$u|xm^GYMQJ?lc5`)%SkM=%htwj&5yOv1CptaVcy^pT7HZ4@qD(chTM`F-g zOW(YY2=pLM|+<(vXilSM?&nB-TRoist93JQVV9! zXmb_F-iLEyR8rFg2x$*PU|L8>t-E&b!|h@AqDY`h>dm!#A8rrbi*kFIw4|nuog}0^ z41pdbq&*~8(i6=t90^oO50zX=Zx3bf!@b(1CB5C)NkT@HA<%<_j5NuWj9PPIK>}4W znk82AWR;Ly$%+%o-iKEfla{PF#!eElsu==3NXTj@xssLB z+!`Q(Dp^q_SF$>XviIRt*rX+^v$2ze>;Mdb9wcOEAi1Kw5AQO}4GR*eO5U*0-iLQG zA>S3Drw|d1bJ;C1kwrpn+56br9ZuQ&WC;ixUh;`sea5`DJOj`y!RJ~tw;%ug2kwF) zOXaL41pSi@(SrnyWgiGc*F(yzbfZkt@5BuotSAVFi3Zw-=!iGc*Fj{NVF z?l~QAOA;mqdXS)z#`h&j!o)xVRg}IP(}6RQW=wkiGdy@ zXcX`rS&}d@kU$l+cZ%97NthVuL4x`;-xMYZ69WlUU9fpn8|rgO!o)xi61Y1jA$7s% zf7uWTRB^w}D+f{85Iso9*o9|Ynhzn5w;xYK|<_Qq8t>)%+xkIswB5DVPl{N z3CXRS9|H+gNv+3(je#B{q^4tn%D_Li1&s$)(tBbeYk;_4n5U7$-5EC{A zdXSKw9}_kP5~z~VT!26i5;B7Sfk2haV+9EGAR#l+KM++_)JqExTm|YuLU$bb{R#@=^rz<+q6(ceSvoX1!ABF32J|M zR)jH-KozIYzWmxn4-(Xm;mHriKmt`zoN)~FsLe63Pt$vyg`je@R~4s)Dz&2++!kEJ90NUSa}4a$ zjst|FDozVkYDY1+PjTPk80b-(V_=_l93UK3aayQiyXF2bwoSw+|IZJ9&P5Lrl9G%M zi9!87T01l?RH+@skdkMZK#$tc9zNT)uJQ<}H=|NJiXkoNaSZgR&FM!aNkuGr-drDqZl$Xm>B3$ zn`6j~Au);(s8TzMA#V$KwM%YI6+g$8dryMxaXVC>X2MMj|zb8Td`?TsVQi_9Tz(AnAR%ML&{4H&3?xuRpD;Dw46`w8u9)QS0#?n-{ml|&WX%ku9_opf(A`-gS0)DYN}vk+F>B0EmSa#k%qPh?Ey_FJs+e3+?=j!z zNyH$`^hE1Hf=Isiv1N*5U|Oi6QDAGtsO3Lq_OTu$sOR&YQ!<9h6{dwMthZzg>LuoT z6I?>-SN23Fzh9DHa`YfUEoq()CWtK86%wezT2JN*JxEZg`8KLR$&o-6woNjIw1><2 z6_v3iC9@JG3G^T#@eEy@Ko!<{l0XjBs*-pbA?ySq}6dA)~863?xv6?N5K9;+<}pbN3(baWpCi?{|Ez z(d)Onb9g4=Z^)`0jSnIMCD5Zb6FQos@7ES1P^EShqZ+-mcMW|?PjY4F5>;`!Qa+PI z$5CS9-IM33iqk@s+EI)NEsqKPJKCEV=uw+v=-7r;iGcZ1t=;tD#42 zPFLrcD25Uf?w;IERh$;8)Q)24O2c)99Du>jrSvAq4Hph^*k?#){BT%Jw6hnH6iGd!qIfnEeiJ=7bt9Gj5 zv{0pX6hnHuiGd!qIY#n3X2l3pscmEMs5LRrqqdZTN3)cJViY7OS5~FAtt*elpq9g^ zq~w;M8nNG&H)GHcG6pSyDz&2+)Pf$3L2VC{7JF31<)HRA=PS19{kug7RH+@spq}W_ z7&LtsJ!*5h)I<3+A>%^{8H4t8hbpzB7&Hbw9!>O7FgAUnt%u_^*#1SPRZlNm{@Vxs zH0N`liLnFM`P;XC>N7Fyvfuq$5BkQY_b2w+T6w{UF5&+}xvM%8>KlKSle_s+#>rgL!%l94KwpR`-pK;vam<5oXoSe5U24IrY0 z5cGLk`wcK8j@@hD^p5#0-LLu#qcJ#oUAM60uNuLt%}YZhP$l1El1~*+{o>GYWaHk! z!go?3dXTty%D(A61~hdWq&UX<>$`<>7uN_DjVnzMsFH75NsI}fbP9jI_Q2rcdwPfH zL1Npr`=!?%T*K|R>QahP_nyPUHaFD`HdpJFAW-$u~gzXW5&?(q2ubLmv6h-txau1pZh(XVUAXLsnZZ^f(1XOt-Fv0W zUmEXDAHp$i`>B06_^Eq>xu=#U2vnW_?Oy34x{h=gzrw_gXCEB)>2iB;{l?M|J*S^u zCw=GaGu)lMhE>Vc+h-pV&UyU$;H_T05;2gt^1eE0@BCBT(S5l+vIia#zB~TL;Gs8r zCJ0o~C#B)LeHYa~G@Sq6>w`n?>KUR32|ryoogRIR`^E^4(fo)*!UJdA81#Q4NuUb* z8@j*elbY;e$m>IywbEcOBj`<>7(YLvIX89uO^wsh%rN}= zIhBjHbPrG7S(+eF)pPHAQ>XW6nvQ0Meg}M7er{#=aB{cOkmmE8&gWx}dO25eN%J)K z68zk=;|vYCKxEVp)rf%sxMD@8Iq6 z;jm!sfSw_G&Kp~|V#ewt%u1b%aqOjsdS`dIE~t5JG6oV2@2^wQ=E75Cb-uFAA>Jty zZw#idND`=`dBuMB#BuJr>JZP}er-^CZm$qkozJdQv2?#P%!-^O-W-0g*Z#gK!K7c! z8fDW$V&|5jP z(KnpTN}s9LykhdsH&Z;KCSKgMV#(rs?Hz1xWp)7eyGux9U*50ckIHJY);hO!_4@6u9;8MkbA>AW9+Ttz)v>eJ zbH@R}nt{DTRGs|Lz7^lDZemvFByrv;9lXW&l?H33o81zBU(J*piG_RaTk+J~ma;mJ z{kWT#+gT%cy`|YLSprqqr>VDJ(8W9L?4yGpelzk^Bdh#$W;Gw$?#y_UmzhUh^8zjsM* zw66JX=JY4&FCqp#L-ZhV$l`^5`y;>iqjhlaFF(q>ymcRM>Epw2Hp*)#sT#sji-;xyg|R0Bw`@(^}(zBCR@JnpS_xQmQ9+~@-7&^J#)Z} zB!MdY{;1>3J@}W*eGRL5;Wipk@Lg0So?ZC1KXJq7el*S}`!&63@Bfl{oOT&Vph~{G z=11QWdSJ=y%@p}!K-AjoX%*upz(Ye`~6A#v9=v;FoT@9=py z;5hw{U!HmJ!6x2$G-@#|RN-i*%iYtS3aUTb(mV0k-eGR_J?_*VH7mF`P>u52b4)vb zd+vj7+h%)IL_4z1b>;*wztF~8Go&;`4-!;9en*b+# z6ITA^uQGMje&w8C@R+vVb$676=s|+Y$8XY+7;PR5g7F?DKB-iCfI9?KrP(_$XMrZ6EK4 z4Q7V3c}Eq^$NWAasok2_e-NB`X?^eJXr{IvBz|oCq`R{IHkql{m#htbJa}Jk(L6I# zTLM*B(~k4uo^J>5KGe`V;=iWv+O|dFirtU9gSTyynR@h~6~X1yf*(-}Vp^z5wqUN@ z347o8d*<%Zy+XPja`krTlm|a{oi?BOaDtSQZ)&_`sc3 z?Q=hxuX;Dx8T>#*>pn>WRlko}?Y=$g3qLv=jHO<(>xNq1S=39gH(+ZfiRs_h46AqE zo+*2`Bt#DqG=uZIm!ur`5b;;1?U~+H2vlMD9Os)Ce<|N^W%saYwd6Sp&m43|mW%Jm zUb&}lX20vZge&LJ-(Ut068NoF$GMw`Mnt?>g+LYE_4#zyC--o-6469rph{K%m)E5v zQTOFJnG*)LHMv3$5;7kfnr=Uc=ugB7$`ul*I_b-K{^NscNUmBDah$|J74=H{z2qcu z+x$;5>t3yIa)llw@Y~Y#H%5r~mqNT5pgL=s~X5sQi7_COC3$@a(+@v_7~ z0#!7E?f2{HZ<$h?ua#bc9we~+Y19slK3BVnaz*#i6?7k+le=lQ&E0hJ4SXnMmR5q*i^xdhWf)v6a7S6q1EVe%A!W2A}THb<45&wS2RlKA$J z4qoH>HyHvwNXV^$q3N$}60sK%oGT34-(08PS(?~4-zy6`RS76su+PP zn)%Z4yxZowZsAR5{9HL`S80e(_3*hW&GYsxl8&?XvL0c{QLk5?PA6gXAVG6JJbk5g zke^~?dHp~FRq}gTKZJ0A&~?eCE3{cr%^DTz8ii@0iq;i=!)Lrkg}O$e2Z>}|(Ha%P z8fDW$6|Fw}tXSHE)~Ha|DD)tKZR0q!TMBizgwNHaC%U{2N`H%YOQG(T(1V1WEDY^9 zv|9>ww}b?$XjkLLyI0yRg|J()?~#==j!8F3&~7Qv-4c3`kaMl%iuTlj?x~SL745a% zc&AVM_CWXTsFL%iNjFK**&xuf0eX;-dkx7Ioj(FSe;|P>neEcis@Cv7D=K@@bDUnM zl!o{;3_sf-^O(e#yXou7&2M%O=lp4BIO9P=W;=-?vuMcc2d0H8nO!9Yt(-hlo6{Y7 zkVuw8Rs$0Q2~^1{Au;H57wG8@JxE}^@l#U!9TTtVODCrW&svdnOvC|NT7<_qRDq*n*?EEpa%(V?+efW@gE3ON$gyH4D=u&@&188mDFJY z0zF7bz5N4$ss?+W(1vRzzZ~d6;<(d>w&rsEJ%K99t?9e@1bUF5cxDv*J%K8!b+gu5 zf_e!5WJB~ILG@J`y35qcr35sV`YDY2XTiE=r7ZU?LYICkAeY4g^ zIV?t?O6@2Hl_BKPbB@rXHm6HvgZWAct}9h>TBu?>UY&&qYIXd-cIZJuQp!c;P=f0U z2~??_s4HGOvglDeDu=0Qi6M1mRvT4C<%m^M)3T~b3z`_{QJZ6wt(yh&l@ijgxSdT} zs8TyB2e$>6p4$UGYD+n|PfIzJ;JQ+kl*6hhhsL&b#qY8(G0>wn$Ds6KzT#e3h(MLv zQ4A`B$ED|TphxYf9Pu1OpH2`$`jv?ul_OSBUx3qu5E<%M^U%Y#&Vv$9Mz9jnuWVYV zQae#s9+bn(0IGuakQh=|d4$xiQK=opkQOuqder6^9G}Y-+22tw`A&KX&1&`xaNKE| zX6vk`b`*n%K!_}Q)aG=P^CJ+BsyHoFscq|u=PT}4S@fvQF>uySzMD!_oEEComU2+3 zIcFRLJ!(hgz*UV)Erg@0s2s71>nuLk3X$1^`W1TE*40u{%1L`fG0ZHA1gg|d)Rk#- z^r#K(Au+gSxo>e#P*qfpcrPM#DD#!HpdrwsHpghZ>}GSCka9%5B#%Iq+R`3TPc#I2 z)RuB^57oLVLQt-(N^M(LJo{*_j7myw2~MA>s2r>=M4(D-DF@9yR9~hA(W7=$4%~%P zFDXb+``f)b+wr+ph=BT4JM?gRY7}545_O;LfXKn z)Rwv`GW)2CW9W<#m4ins=ZOCCE}imSYRR9snm&5c1vT9<)gChTl0Wx!?>TL0e4@`9 zfC%&;F{WAzck-7)a7*TugD7r~I4x9B`Z+FR zey-4i1f}nDxe|nlfds0kHv9$`KVG<(SPv3Z9)G|8EJzYkjyNq;N$gzFTp14%67L@f zR7o8cAkc$^)SI85D*H=D)9waudf1)*)%Mw|tDEi5INT7<_o9oLG5fJqf z>p_Cso6BX1Y=oG8WeHSK`gV?yAtJs4CwVwOq)AuBaEVUq&BPLL#wVPjZ^dOHYGM4-#BY{jVDx6Qt%J)30n=sFK*JqPa32BqUx;L?PmG7!RtX4r3x4A+~n& z2&uQiW5LHz?cJj-?vD8zQpmN1Tlqo6)5^SrAXtQUCV(1C-L?=tLadJ1IgwoM0 z%4c&v4fAjLhgCYiDv`{g5)@-L5~xx;N{M!s_QZl7wK?zDHugMda-}Lx3sq`IF{ljo z{t7*6a||jE^h71Nu2jWop^EKz2OxyGzd{cZl2R^e4<)#+kU*8%iMrzU&Z0-{s2n&m zNbQ;)qN=DIu}bPtR!(U_69YYJbBrIyy#_O!64I~Cyu>k3rFK*fBJBMYdeoM3nDsoW zDGS`O$^-<>>+!h{Rcc2uxD1>#9_Q#$J1R%K?=ttIhTytVRaA~x z#dQ{+oh3%5I^AEPhi%;(N=h(aahq^mA%QBj6Ln?U96f47dq@nat2{#L&8XClVn_=b z0zGPTjIYQ4$DCNA_E19ll|37vN^Kj1=PMHfJ!(ri?7qwPU61QZRZ)AyyEDq6A#7dQ z+bHy?%`vFnU=N35P*t23s??5Ra2dD-d1XeA+EF>;omzC?E^W^J%0!RK5v!;#*b}lP z0_s=o(8IRw4J9QRACjv;`jt%!Rca^dDui;RpyVc9sS$}Gb(Ke;O6@2Hmzu{2$3TzT zTvs|{u+2LC$%ak#8=Ry6nOwbCXLin?QQhpE?tJ6dB`2P7ulc>I`QL1a9wcrlIXHLO zfJS!TrBsqY)ouHCYu)9p*#%;t2MJD-*ORE^8i8|#1ga>vWrfSZzhy6{_3nx$?j=wE zVQkLPJ4=H6`;rhnNKAXQxx4w$Lzg6SmE~L^fhvieBq-b2@Q&9WD=WXJnc3sqw*Pap zDTN%TE9EeDTy7>X-RcK4aIYP3f>9NZfgU8r%-@;%VfJ&$7^WOZpo)7A_n<_{O*znm zMC-vzQ_X+enj}mNBv4hnd@AeiGc*Fu+}X>Ms#A)9!EVfr9E6y zO68XvJxI`4N$KcH#y|p9QX>Uopa+R*`>#)(Q2yRO5U7%tH9bF>EA$}IF{tfcyZDX* zF_1tNj+JB#?%mb?jK&(Nd>w<7QjTjSzjo1s1jX}<=E|mpDyl;}^CfeI9wew1az$&` zriCh;A5DyG6e&5*^}d8li(}sAiYT7p;@JQR>bpyH#xMk_`6o%BifWeU_FSTNvrM1| z2^uT8#E2p_|0D@iNgXC*7y?x^YI8ap6erMw1kEeC#C(10r(%fm&w&qg( znaF%PyTbjrR=8v8ncj6{Yx-wBcwg?|dlzMny7Z6S;a@Dw&Aus$w{iZA+*kK8aof<@ z70;}%6~24RnI>22L1Jn4=iHPnmARL%XX1qq{z%_7y;)f8@_`8gRhUD^`DkOy%55Xd z!mxK&LulTSSbD~%xkc?h$W6bPV|+=(v@6QOUa2YssFEe`MkT-G^IGBSwLu7SX5G=u|K+cPmzR(%W=iD^L~wNN zKS&HdtEoT!ldqS2{}RWzX8Q2-Nmo@1j{bT=fneP;0Msw9D`WXUIH(&?$IS7v^$bD4K!-P-=!P47sZ@L*J0s;d;& z=;JkN`B$7fBXy+diGLos)<5`~Fth5i%RTf+4h_LJwPq^nyDwa{*57{0TbU=08=gm~ zYT(iu{)eq+rYioA%Q5QJbo%c1S7v7ImCV&C*ERH~-`Op7*urEE>BQ2eUd59WyJc=_ zHD2q=p~x8rU+`auLV)Zs*<=*)i2JlQ%`}p`}F?mqS~Y-dWTC=Je1`oimw! zQ4IAUaryGb{>8`aC|mvl$7na{=JbYC=gj?mlLV@8R-(@i{@mTYaY0}2l!N|ITUVO}sgp8I(X(vIP(CQ!_o|$QIty{RfyB+G_Il3 z8R*owZyWE}Kl_HKb~4QmT9Tp z_5MgL8nH0fhvsvts}!|Cj@tlt{f_et5q*hx<;Q6$^dLd4nWFa3ar-+?^=7UY`dz|x zPprrxfhyefJI<99>X9;?cpw-T$eb8dw2hsa|h$KERT1)V}<2Vlyai0+AL4wwK zmv#WDXb13TuhHJAW1h-9xa!&*5~#u&ah%CiyHlxlM^~v`Bxp@^Y2{2sE9cEb+*Y7H zP=#&dIN!EE+3P>2p*Qb?=_#CLaQ4C6I?jqFJ-z??v4_`SulIcPAVGVr6z$$GwXspUO;#hKnw4KA$I(=X3UG@tVv<+6>rb)0i|we>a+?Zfw? zSyZXbt51^XSHF>0ZOuvE$9w$CM-LLT4^GhzITh`YN6<_?lxFJTG*csiDxAR`C$;m< z;GDOHbFLgbDe8?EmqYF7tmciZ8$9sv1Vf-lZ6-FZ?=XjNEZC;kiwp5>hr07r#c3r~ zc&kQ4hGT5|->CMSGrj#lf>JU!AvT5~C`LOZP^ETM4k~#@N}ffJ+MF)7tf?y{993~z zs8TzMvGdM0UiJI>nl?v|+8hJh$#MLB+k}1pG=xL#%%>u=FHxHb+;KQgw>bmCR;!zP zSH0Gw0zF9J{(=6+$enG%H}CE1b=u)^zq0oUNKg*#J*?wQe4tjiY3Z4Hy`&HkwMVgj zrRlPY>d@TQM#Q+e1Hwz*Z0_B;vPT8x7h~YAhWgcE?ZSCS_wnv-@NyY?kihae&Z7JJ zhc!xDdgtC>kswf&+%0|A{^W1~%|4B5OyJeo?wygK83XQpPMbD7YzSu>NT3RH z=s1^9IaYL7ojJdJ5YLIWgh=2?hDIq7Qwk8MN|xN|b#?giv(1Qe?SRJSH&>O;?MvattMS)og>Sx6BfReZ z0lcTS9whMY#BnYkFgTn~``uX$k_4)-Z5*dw)3d`xm(>XO-?@*E9whK~hu$wr#1llk z{YR2ORkF?3F5Ma|J?EmZX~z#M^mdTvC7DZnw(;K2ac-fyYDjhUXqCFcT1ei>G-&3A ztLQZGWbcQ|(1S!W#xLp8aQ&*1@YZva1gh{R%yB;5*(jXX<)pCj_-0Gcg9Mg|PN~_3 zVejHP^ESh}IYvXw)IAj=Js7PD*b1F%XB&N{5(Qccs6vL4b6d742t!YxE$lM60=|(t^8(~YJieqTYI?lTn-CU9B);XvZ z-3VI`5_qrWI0r4exuVO>or80aHaEhSKvnXF<-GFl{-gzcL%9*=5oMl1aZdCG5@%F; z!}$NY`=1iA{<=0EdT`ceT2nH2$S&O>hjNE(JxJhfq`5q_`p4_zeOR`8+{hHq z;s1X7sMG_O9&T)@H@O3d)DfXI%EUvBTcmn6IxWXGt_-oBW1t6#FRGnY*0nTi=;8#b zk}FQkWIgm$AO9|Jv@F4aO#>&@oL#6SX7 zRO@`3V0N;WAS3IcYG=*Cxsm%-H#J(EKo1hL&YG0#-*er|`Q<hkcfdth; zs%Tx=v`{563bY`4kf63nX=_F$i2j>3E2s7bRN?4K63O~G0`B*!)RkcTjxF@WMDpGz zj*=u$MeVdi=a^W}?SUR7@SdqSfhua*oX%ZI0zF6+@4HB#irPP?Jti3gJxJhKVZ#1h zOLIH;*e!EYcb)Q_o>Fzcn~Qgrg@}6V7aF4O(i>BK)`Y zKjcIC42$F{%Pf1aL@1^FnongsM2Uwo~C4GDqc* z;COrOSXiJvG%Ze7Ra!poJ^3-PXK=k~AET7=dx@zl^>DgKG~Z*t;<++uF`+89Ii=`k z0(yy!p|y*|ln6UzT2yAk@PuO4o&z zGwvl!WVzNbEg`i1Q=dJ!B)4ff#7GcBt~cY(s1^^8?7VVVg40q}-_>h#6Z#b)I8!E9 znil5@iO=`lkh7y!OP)ul3d_VP$A1MJJ!~Vv@eceRO3tW_p*5;1rt|8`64-)|yzu3c zS+lGaCxw5T>#2@8Tmh`J8U0|`|zt!qhs4E3-I39j{*$3P55O*v>5&Fw!v>U}V;n2}bP(6l%P z61raH=L!i`{e3yGx5La}#yO9){1`mWbqpe*Gtu7@s^VN}jpP&Rk-VE554Lp<{(C}I zOlZB)CkI~dm!X#xoBk`Gh|e`{^@J&*ehY%rWjp#k5rGm(Po(1eUHn9|iBXV1mD*8^ zPs;WQyRAD-b7ej^%^p>84E(e)eKJ#sN$)%JRK*0U)Q)0s`b=>d(4#iTz)u^~b7vta zMmtq;TBuSxiox~7^~EvJqc+FD&nG)hF#=U=ubf%YE)gSh|5@kELk|)XPd?c%F>D)a zTBuSxQCA+6qYO%J(v=#KZzxDzdE6eD7OK>aVn_>`80b+O`jx~`0@@?RX-WGVmD*7Z z>ANNdder6^$?r53BT%Kbjlm;|V`R~zwv+?DA4M^ga8xDbuqw)-v7;DNa*t}*#6XYQ z9E0kOza$_;J!*5h(*6=d31|;9hoegED2DVz69YYJM|qFu zc`mQL7v=Ahrx$%g1bg3G`$Eun=^5UA4I4@=k>=s|+(OlNRO-u#mdkwBH+yyV9~ z4-yj3%=yU}NT5pZgYsjb2MMXSlqDokHbeqddJ|@eY=mS(^dKSaUmyk&RaJa1YGc@3 zv7sI$a0VB#`6oJ6D1j=9ZJsCO$3PDf6wl7!$rwnWit5ljr^t_i9weyV>+Bpo;pmxkJv6fgU8NAH!-OQL;1v@%XT5p-OLu^JAa~35k~+ z=OzXcsG>Q>JO#>+fgU8J-s1U+i(+CRfhw9S&9kEX80bMl+CPp#=|?e;Ko!o%^!JK3 zo|aiZbX?fz3}>#6C_bM*bMIZ|=>q3OZT`I>0wy>PdemkD`*ciDjJB%cv{0pX6rRK;nbO6@4d=xeVE$Mu@UJ2D47YI6+i)AZS> zA_S_`j$%}1GT}i3I(i%fJ!*3d?9+}@j6jvzQH+(|J3*_@hnX1YQJZ66pQgVjT!cWC z+EEP7KQ)DkfgZIbhI!`6cBC&tSQXLsDXGa-M$3U7wWY4ilhG&!m7^d*CATWIZF_jy z9_Ue<)1|gCPf4Q~)E)&1RH+@spkCr>ze11NoG$e-^DH%rQH(&9+EEPZ?VgMe?z<)} z_NdM2(kL*`qoNqa2vn&Z#h_8^$vEc`WuI-S&FRu;HqX_f7{v%wsU5|j*~gRlif0D< zj81J%mu4mNd@zbpj6jvzQ4F1_xlf`;ZBAEb*Cg_@V=%E`Zt72Q90yz%Fm|u)gmB!X*6OMCXP5MjC^qx5MV7hGUb1KKVxzFzQ z#Rye#N@_>tSa#jypzpC`O$_y5x@_|kA${8CIK>E6aSXMi7%Q)voY5HS!F1Wy=OTYk zsET8#9TDf(EcI@ax>66O%eFojp}!j1XZQSKgsM1(+EI*F{l1)@af%U~Lsn@yERlV1k5cc1+NBC~{M0(Ct73$zI3=|sV%@EigCP<_J(w=r+^3^* zjHmHYj8GNFP&$Px0a91$!F1Wy=c7{b`+!7?4v4IQRT;Q~OIF?Hw#$eSJv1 zAw?y(PnYy55YdUJOHTH{%Nm4-E>fl+-pr_NAvU3VZ+j zLx3Jkmu-EH=Qz2)4q8x*P!*@7b`*np3ZFl?w_6XUtF}J1WUV2xg$P#Z?_)x8mGEG? zY;(!^xvDA0LB$AFaSXLNN49o(PP86Omu+qveiHxpgsM0twIkw>FaKBBtnEY-Lp_)- z+xqO@aem)*(EMVAsyK$)QH&nb7H3{Occh7-9!!_*_(}DnyAC?27@;bTp>`Bw#w^e4 zzO;jhp&m?^ZGAHS_k^lAhT0MF;Ph*~ulF5e+FU)DF5CLNp7vL}7R)b3sET8#orqz^ zhk7twjmMu9bXLfh=9?-n+cU@nu=Sk+`zJKRG{mhv&X9@ZL`_EN3dA(SR zNF6&KXDjC2%RW$_llHx5yd&K>|A_58Z4`eO>3=0YxGY`9JLp0|E37K9^=?^*a_vTU z+g~-BIMVlSePjE43{;RP^(5FqzZm6hQ)3{3uDOppI*3w7Dr6y0F%%o=aC!ARW5p|d zJ_Zt*`6C?k)n{9>lpL>xuFuz%BogOMwQ0$<>Wen`Z^P;T$GSq|(!<_XK_BigB}>U= z4AHjeDygq=5S1RrWg$@U+PmK2`fG38|1nocJm{FqQCCYZ4#^S&bA>MKJ!*T%(ms0o zU4W!9E&iqwt)|p-L~j`$958!QAxC=a$nF7yRvd7Y$;a3`;PV8!WW4M#P(h-UzB)~` z$FXDIWr=|Vy0Cm|t}3-2;K+N4eT@UKOgUc+as0i@H>XVt zOAJ&#MTox<();WL_QS4Xx`<}6wY05{DywxpnQTP*yO2=ZtKmeeTWo$70u?0s9v^Hw z)A5)+Zc3Xh1S&{O$UENFc;*s&fhq?LYOYX0LZyCQk(QL zJxdEBfv$JsnAN{hvUcy?m%Q&{?V4*Jv|cN{MLSulecJNLKUyR6r)W=}CmNAf2~?1f z>E516SxWvXLb%Mv9oGNoyR>r0Ph}x;P2Fu>czuVqa@}Rao%9{n>ruP3(ZQ{ZaZPO2 zo_)7#D^mT$1$`;S<+QL4OHjy42w^^J1Y=$H4|9q)-^vipWHG@is`-Hrc z2|}jD-^EqLm9rB^H49x9Y-xkx8A8*l+n`>qjjScZEC%*9JMQJJ$pGYR|^BCXx?sj z8eqKa1m+!yjQz3NqH9(87|hxpNJy86@hEDbR_p${PY|L;#i}oB?N%zY(|%~ytxxn4 zsbnQC6w>Y9$w{9eWOP9kP428s@;PS^X_?!9F9#BPEkW8BECmOgq%_TcS78kM7+JFoBAXC7_vLpT$P%$4CmWn*cN?OKHg;kNij zm5s&UBx{2!$S1FeIVRd=;dqA1y>M^iUn@6jUp;l+Kjf91F>Xbi*RRZrQDPu5eUi8F zPZ#YZR(Cn0A6Tgp=#pg;_bVsSYv#{%LCqly^NwZ8JX_W1KX;e*-9$eZ@i6*1ZPU9K zLj?(umb11qhAE#Xd;OpG*$C+x7vO6gSu;h;8S3MTk=D2>%lD`uLj|w9cTaU=?R=?P zziTZVb0Q&|4+pSvu-7pOV*PBc!WcLQP}o zH&(65Z_e>S$fh=t>{N0miV9v=q;b>|GG|E)yL0TEo|TX;xmt3rEJeQ3s!U)z*K9ON zMa~~`X7IXP(^$WsP5XV}6UV3}Bx25ZcIO|H85NlmNy}NuS#n#$aOQq&K{i6Vs!gwH zym!;8Wz2VTjlots2D1)V51UaDF(fgeRSjeM^Hi3Pzn<{4WF@4l-tFqf&FxdQHBr@EF}zzhWPz`%T2R63&fVf`Tyrr+ySA^Hi*OrS zlg)1(Xh8)Dk(T!oXRhkpEzK&mZNjm3bmku*R=*# zF;ImLKWM=%iaXYG@=Am}xKmCWa%-x2TKX6z1`_8- z7d9R)w@j-Ndxy^@Z>yHnHWY|6r!O6=5a<#)l&e}oR{vd4t9mQkoGW&mgOCam#fIlJ z#(qCnJ04Mo$B2q}Wk33;vw2yqNQFR`h#}X$gycJY)xIjTp}GFR@eV>NNaV`*+^{Ze ziuUxU>U^~{s>1>Mkm|nXHjz;Zfi4k4u9gXz|ITjDf7;tzSC3-oiYoue&}CMfcKco) z$2##NQKIAz_Sv;^o0IoPJ7P!$iK~T98h$7;SlfFona{hd|3v#_@9U3i0PyI}b5}brokT{dE!%*u+TdifnbsnQgX0&a{KbHbS{!j^Yi5PN4&U0lv zY<)DdMqub0Cm|Iia_n7eFm4Xg#uOAWlG2JBH=KyoZoN98*q<3{4UxkC_;-t<`ni z12!;%gZ4jBwYEjC;k$$EFfmK)&C-X&=ow zJ|uxI5ko#%5K_ABp@5_Ns?*ROPC_b3bhm$Dxbf_zeMIZlJVv+Q?*^qETRF_Q16i&4Dr>VNo3&!oE#m3UCUWT9d$qnF!|p9Br1$MR*^CMj zxDQXr^KAoJLWf*>yYpwvs33uF2M95|>&(W?dZk@op4);75+P^zrrl26ti3zdf#1(p zH*U&*Vto?6}mRpSEgO&OhR7>JIgru?APZ zV3pzqnU;5nv&NU)>mZPBwZbE8$&s+1Wx<%%~uNt8+q%4UDJ#!UwQ< zC3h2OYP&7dzeYp|aA)6}d|MHQt?8N^j5D^nw;tkigYB zAw8bN)5?FD*v#QyCS3)M^hk@^%zb48Wu=d6c$Mf}*n{5Q z>c##HX>LIU30$2MQYvi{_1Wph+D>e*5a=@ZnrzrGaJyD9UpJnsSAMzZ)H65rJN2TJ z-4E>TxYj15@Ak=b%YS>)NA}^$ni>f;#==V;bosLN)LK;~(1p(ogp{k8lLov0Mj!v# zUwJk_0?R~*`}{KOmp9E>%Rh3Pv4>+HQ+s=I{bYuRMC zGGAfasI$-83(Z*FwZ)nH$sT4@kic3eBxX@Jwr$1(df~+&g+SL@x2e{d&-mWb@e?_7t>s33v0P6(|L%C;4?(S0GQ3W2UyBW7FoyxE~eCRXJ!X4d|eJu0__ z_I~GKK?Mn{bwYN(4`usf2h&D*@0gK5SH`);)%KXwyQU7GozLn6(q0@2{}cg+11|n^))Nf zO-P^%-!2leGIR{nnpL2NhW*T_Ac1vA$cDDjY~s6>`d8yKO-P_ieQW9Uats^XaD|@m zIM$2`5^8(kS`-O%;Tn~YJ~e*P$6xiObG{zWaCMJQ6O|H5SzAwV*K*ve&7X>Y;>3ZlK`f+HNz;ml$LW+Mx2^uq=4pq1%wa6C z$jvrlPrSCox1;fkIaceXHt|}E%mRFsQ8XZi^|lVzS)o%pp8dd69sN7@u+^VL!ZLu|a zT2?C`Gl>&EVKK~lzoPD6nYaY@hk25>lCyR(s)J!-4?%^cH1<7p@IaSjUUAklL~Q`=lyqWyB6raVUC)n@G8!#=dCe{qFCS1IMR z;X!+UHep94`rX_Ndbi(D+qw=3_9I)?`r}DJr1{)lsSEpSePg<4)*Ffn5_k%c@5$V2 z#ojIMN~`=;kRgFCHCKge@bM8kSr6H9T*oniCz3F?e9w{-eK^sX6R02|pGBQ-_47tV zvsKd;>Wj_K6#`v&j+Cz~?~h{>{WJ9Impf5Z@Z2ND<~v^AquBIe9<+U}1xoEAfhQ>W z_^3XdRrtOTJ=cD%LZAz4nviQ3$FqRB$$<$C{pf&N2d#%nZqW))i%5Gl;*j;g`xRR0 zQ78P#~YnRH_TzveY}^&kvq03=#Bm}3oCo}}Hq@4?4;ctRg` zKF=f54tj?ofv(8C%dNMzCux4iZ}VKWxRjsutv|usY)?y8IjOl}{*BGrf!R^ETQ7_I z7b~2ky?E5e=5=jr>g;_#Xz7EFaH4d(vMfiFVdk(UjTkCOEW5eT&#QEjHtKwLo~x}M zmDz}Peatz#2Pg!(a#viN7VVd$6}$2+Cvs0pq2Hw~FkiOxV@rNXFtjeY&7@6vzSiusb)>T2j_)~fC!Ifeg*VaL`m8k{ zpE#1Cg2ened@np{vsR&!c+WYpV_CY&y2xDP$_Rx(mzpcDHF5M>VuCro&0vNK5@+Jq z83yt_pkqOkc#JbQH_{8c7MX9g9iR~C!W!YZS{lQ;`LEG-?99;d1RdTv@oXF)A4?+H z%m?2E6d2i#qJjk8g9*_$#;`GWJ8PxtoYIj%7oM`>=Qr<}nP=30O_$48W7VrPw?0W3 zti5TLN4bZOEOXwvs`?PES?)$gzPD7V2dnUVev|3OTZ#(a^)ZKp+^9K-tsiFyG#^M; z2z1@^C~9NdhG=>EPv$YkjE!Vfs(5LurUg?}kia_Rd-~I2SW^5sEui}u9SL;d=|=uE z!D_H-??TMx0`(d8YP`4OxFMwHJwG<{dy_fFUPBolNZ@ED|Ob4<`oYcC75QUJ~5)S6bMks(F0( z{tAJvh?J6sEh%wY&<_CyzO#Mdl3xDJPSfp~(G1@~;X5zG)7}1q+Yi<{4LQV#Ii0%D zAI|-1Dsx~QLj?&nhI>#3t$6N|>Fv?)6arm+7Z<(Tx^Kt7Z1CGe#lM zg*}wdq9t$ZjV6C4`|-8)d!^cd9!*`mVouM}tucfi86n9^Q6Wzx2m=^X2cy zC?g69d^671C12jti;kFP&YdG%A<%_u2|}7&Kd)CiVKhDB&z|`7i(>`nV?xRw389|% z#+%~yM<_Ej5;$%M39EmaE^OP%a;XaA<%_)YC;aTu&{>3QcYVIR%NIlfun$svO{~YYKteEx&*zZNT3T>9Q*{t z`a$f$_9)Yd#z&Q110-wVHpb|lcHo`_#@f;$CxC*phId&1aH8QywO=1JwQ zhQziL`E1kg_-WVncH{TKFXwh=^*7$vj^`x|uZ1qW2lKNZ-e$J*cyaw&wdxENB#d*` zSQp*$(^~BNlE-NA4PP_lOwW%JVn6YM|nlEd99o3duRuW zyF<92gssVAj09%K8@)mYOxQ*=|NNg>dMt;wH+uf3x~S8Ubu zybWcjAc1wr_kBv7r1efs()&#hQwVfnYZCI!n)dY9&a3pL_6UXw5?R_~+-d!gTTgv) zlNg0S7q&kk$6rUV(=Zl0j1AmKL5*Y@&)n|8u2 zAFthMuR>XcZg#zs-#djs7q$(5x(hY2#DM4e+gM+Q3KCnIU9~oB;jT@JTEj75Q9pSaP(&_5zuk`r;4pazqVcQULp;24f zeSJ~7_3cRyRpQ?D=62X$;maTgf(jj?U` z3cxLl_3rsd@3`U^MFk1Bnf|sFoln}|T<^zg_sNb>Hm>w*eg1*h3V|+c8$#Y^1~RXu zm1(7r887fGq=VS(^ z9M&U(EOckXNQFQbzJcIx;>zsTk3X43+ddqvoW;RCWIP8%h*!EV&DCf*UDju~a^43C zb!U6im@hsXo!3-f8c73gb!4a@fi=y~m;8B*F1RzCmU!MrA<%_AhPQdKmUPy(XfNkW{T;dkdvUD@19IUQddq9W4{!gZ?08DmsZQ+C4 z5)VqVz&5R%1e_3(E^%FXM#mZBamQD*ZQGvN2z1G`vmD26O{DIt$2tg9WLjKTo?&vv zICjg8u6-PxjX;-7J7d&LE2Yz3yY%B1Vi@k8;%+T|5yOAKqVIN^yTLv^A^Lk|4;gn- z9~Ox>oO_b29cVb5kJ`}sGpPBLRqrz(oS}jQ#^yU-tMjnk!!GIRtP{iCY}^aSD-kj| zS29QW73WHoqJ6eL`ow zJFQoa?Zq%BxVNO{>S&|mbk?ZD`h!7XO39JHeJwuDU)ku7bq?qSiw;!?bgBE)L%Mcl zy~|wGlQY~I?ndCd2`nFf!~3)ytD5^a{j^&VhAw>np%P(ho3p{ae$`*cmR0Hs34HfL z$eOSCo@L_`dhl3Zg+LeX!xB>c%mmi2Q3<`|gr;`<-Wi|h@JWxKLfRX_ju&34N6zh_ zyj{ZgMm++TSqJ7y)>g)z;P=|h2P4_R6YKO|O@E-MAffK!e7$@atLwW_-+5}cLZAz4 zo$q*Etwv8>sYWaRJWd%=IEvI>V)o5J*C$P-nX5-DZH@$f|HbR-=_ERLavJ@;TYrT> z*MPX0hC!`&X~pLF@ZR3PYYv+4tH<=qy1kTd$?z*Nl~~fmgEpU1h@CClo}q#Se*eXH zSn5oogAyvTK_vne0$q!mE-=hb+^cn1UV^vB%EKOXMT9?#4XdSmONL*Gsf2N^J6%xs zTXtx18HNfH`280lwKv4m;$L=PHI}`jNT93ErX_~MeXLsNly`h(8Pv;z{uCC)qCzg} za<!#uCt9)w}0$uo38h_I;+=G^k z8^ErgJfnPlh6I+0@B7Ru#!BAwq3_GIQf5)?ed;*BQh>1iB{tG`Q(Gyc776SNe0OkD zS@vzG19WrX*9w8Ig6UytLx=9v8Z{AL-nUD9NB=Hel;y8lm7#(JwiEv<<+2x>o3A9> z`8KaYpsQ8$+G#_+-J@w9dHHWAxJSRGU#zgOeK&7VRFJ@WnMukAv zqltOb4jxI>+T`-&tBe*G-_V_Bx-hT)4Jax|VEYpiUBHWf{L+HmDY;Td0$sR%AY@*H z?(D&Y9MsDrlj1Cct%ma$A&)nF%RGW&Xobgx7%E6$trN00J(M+QKZW{CzoN`==(-p& z*Se+P4(;-|2D}BU(dKOOA7|)y1OK3?Ac3_`NNTQ7R^XpQbZEXU3W2VCqo-LLHA~U7 zX-)VT?Bm&-Y3=i|q4SqhRFJ?rB&0HbW}Y?nFWPc*bA>?H#ryGA&mMcU(w%Ga7Oaxe zj9qwFmd!r$Oh*L?wLN?--B>rxgQe{ARS0z9DwCf=Y8lOZi_XxmbnsB_QP?(kx8r>` zehj;FM*>~=+bMjdzcic~PRG&NbN|s%K>}-?kbq55?CrmRG~RhCekTN1xzB65W_q7tYe zF?8{0o2-$~6X?QrQVE{-54n1k^OiM?w}Z$P##0GYRKmkn;^_3+g8n=q>PNc7mE><+ zWFT~SZ2T&>1)( zoN%Jfw9#XNT3VbNhMH0;$O?* z7~3N6SZ{(5>#OW_g$fcFPt6q)=n}aVtG?_pP(gxU$?!2(a^4luL{7wWhPXq@wCE*r zEg{lkrgqNlSqXH>wDVr;>g^Umpd!=ax^j);jN$6-*$8yWv@?dQx0^)_RAgFQmpdJ6 z6lV-ED~Q=4D}gSVcE)hcC5~K)-Y1{QWLmgz_2H;1#~nw+kS-A&T{7*=m1|CP#6U%+ xMGSQ%BkwpOhIEN*p-ZNnG2|Ub5U9wsh#~&}aYg33e>mz&y2Q26CDYCr{{xzGG9dr} literal 0 HcmV?d00001 diff --git a/plier_description/meshes/link2.stl b/plier_description/meshes/link2.stl new file mode 100644 index 0000000000000000000000000000000000000000..6f9535037a15be1b7872fc84898c7ea69e63fbce GIT binary patch literal 20784 zcmb`PcUV+M+r~$l1uGU5EKv|dMH4m30(-_@AQqxnL1T}KSkZ_eDi#vOiVbWL6fi~+ z72Msk=R~nZqei2t#u_Xbee>QS#{PJ1K_Zipk$b)0K=AyCyvMWr zi(X^V28y1Qqe2T3+=m!3ZzoX2YZCobnh+KwxWBh%_f=h}!v2?iM6H=_zLQ(qmJ{AL zqP4s~-j=J^7MXb4*u}cAH>2Gg&2R2Ov>@^JKF1!!zQO*NTaFeaCa#$tC^GVP0#zl) z6{qG>{_p<64()gk-m2$o;khbVW-<749sjcvJQA+r7EwM|bi^#^HxjmbOA@EHC)jFQ zx#EV|?m_sNonWw878kg^ii*?v!>+c^tuv}vWCAT1iE&tjjc8I-wgiDbXt#Pc)zm$8 zB!99GtQUz^-@G*NjNHtwU&03xs5-pul#N)tpkWCDb8^~!hApZ~n;-ozvx~&htSL5n zY45*FWEZ1C)!TE0@#fW7XNx_1l=uHKS4b3;d*4Q1YU5L)YJG3MA&TU}=> zlOUgWpW4cCUq1^R_o%h4oU~wlxE9`M*b1 zg0RuPTR$z~1EXT)S1M5!KIZE4TK3w`+s}y!^RrZ*ML}cv&4joEaDtbM=M^)yL-rvo zZz9Be^>%{O!iR{~)_YPrP{qq)MxB(q-?Hk!6LV>z&&74B>$WGhYun+!W;LwGCKHd4 zm)-NjOr;4?7gsebdTN=|#8PTzDBTVbI}&Z`G*nNOU;BorupL6h{k^^A!opQZ6qMiCAM1OJ^6Do+1rz&`coVHe&&h@RrAp4}Fyqdn~-QS@wS zAHq_S5YhfSAyk}R(q^|B+v&v{q7oLaLgIBhj`nKr%kBm`_ZHQ*#j9(L6C%^%bACM% z@+P9>l`3dEG5lfz-I!b5%6-hfIycZWd5&e<+#EiZY;$7qYROi%&pt>zcGnHYp1agP zdml0%TT)=i9=20$75KIJ{^KIU#hx3~e)Xf+xI*GhK6t%`!tsGSW}LCi$ZB1JK#Pc~ zc$Tn5WuJG^$D0VQ614qpfW*076$7){EmYTsoHPYCJ8r0OCQIe2x3>c=NSvH_$S@@2 z3)Ny;!1^40q%PcJh;`j(n=M6|_W{-<6KFxgtx=BQ;PG6w@y^;Ma)s?kHh2f-WDHj? zSNioJMkxD03lj701_f@|5TJVBoOkf;1ghSiU9=$4Y-!)XNxQ13-5M@pV;6IU1gfxS zWdd{J@XkJiYusM-uX%C*G7>SnNbLULpkbV{N6pROQ6jrYpbD=7IjZ|-aty!5<*FO< z2O2~V^1EfD#rqA5uI8vC-mO_;l%NF(^ey{90##a9v!Tn#-RjFuLreHT3lj3!72%-A%Gkare0O`l7vv5c+|{1FDhSMpZYEHajue^@5QK&`o2$nbhKc-*U$Tz9dOdK`vyKkdu`Z0nIMK&^{Pb@1 z^Y(nT)b;BOAII9iXsI8K)zN|k`X*%8<^-QwDLb{_hfOI(hzP&#;$!Z*Vz+vC6Zi4B zK?|QP4pG_$&sjQJuwJ>JB1H4hoZYzM`5jh+ zPXaA@eTZwKZ^y>wlmF~e`}|QRh!FpBReY*fR15rJB@-3AGh?)={Zin zQE*;C3lh96R?CF!O=#;olT6by-99fx2$hn`=Bwu>wfX8Y%*UD=LB1zHiq+kt!WFb& zy}T^ejD*~3MSabwbMy(zE*eV`LM7&7`_rBAR<2jCV<)Xot#kDE_xCWZZBR{(Ta#|C z)^M_^Nu!49gp3Wg=MV8rMaVzb7iRc$+M;~(!8F^hJG&#`Ngw$7f*QKl-hrRS|8*1DQ zb}W<$RPkJi-X!E$l^W^ayy$6k`_fJb3ljYk3QR69hN(|Bu3$dm&c&s7JN&t^V{4f} z6^;eggOhK04asoOVs6Jvqn$@0@)nlsVKP+z$I{>@jro}J&J(YGC*3rkA@Mp|klrX?_H-RBNbs`QXCmZ4^A+AzKFHF-k4-5>2$j5(y8E<~QhC4z z%gKxJ(w%eSl21%Swq&VoBFY5e8kLYHJr^oUQ62SalbO=$6$#w^B;@3Q3(D-&7OZE7M4$?H zRS7BM-+>ORctury@TF)$0(VsjSvVq`-W~o}JsVJoq6LYjJ+>ISpU6_Lov^T|vTl#2 z9u_C-_LQp%5~#vGSwenjA4Bi1tz@lzaHWD4Byb;=U4sYX=+c|jtc^P~P|$(|K8q6a zrJg`*?x=1Zf9-rQ5~yP1%C-k!f1*!LcUB(u*k?U(E{oIz*B zEw+~3JYT`skv<>1-q6Zrms+La0Y)5evruUe-&{L2YMRszj9rfEu)mYC=w_0(Yx;DG z79?Glh%p20+fk5 zA&yG^-OBn`--l7OAc1Q;LafaeC{O=-NAG?#NFq=*x!Wq!?6f@9HztKe)!gc+96KGL zpRL+LS|{QPP$qI#Iw%<QJ;GfonUq%Gj2uWQO+B*So$@kU*7B=33LC5his* z6DJnc^9V!{jI*PD_C+IP%x-9^Zj$V4SMV~U=3wx6_yLqhh^pq7Ku zV*g})tMzkXv2LJp_S$<)V-g9g_1uaNm|FgNhq6Zx` zFH}ESd$SP#C;;>O=r(1HYJo!x6) zB52&hW14%#oiYKv)?#{+;l1wr)by)i%*O<`9yH*?3VPkusR~-KUd$mOP2-2q7c(Ae zt9JH~2vl7!N;Fg&dO+>ccNgoy=KH!+{e`DK>C^)wT9A=+qCulHM_ZIAaeq6G=LKQ^q7qcfv@ zwB;aWv|bpr+=^#d#A=d%=Y`)>5u%LmqRdQLuQUjsq+ec;YWl=4TTPwhWr;03 zXByz1t(J>!Y>}U~eIl}r7g}yo0`jNoXhA~W9h_KaMbOZeTa?J&(*l-;!NHld$G~H>Pt*XwA*wdXl(yBD8oUBx7JW?W1g&83v@klUrpB1ERo#vy5 zep}ygaCf$PFTb*7=J3pb>8rEV=cB7z(nk3hDjr&=R%`Yxi|Xoxw)FJ$E=pWZa~&;6 z{P5$(fF&!l)n}&aEUGmQEoswUeU!-P))IlL^-Ip@?VXyfZgj50h*kY3(!$7H#(~75 zoxhiA7)o}kneNZbkDXHu-Cky^YnDATM^8UuXdS;^ZGDA*^E0{DSUPys1>^T;E^25& z!n59RL)X*U>ZLn;FZ_N&EcK2)6I^>qm^S~j0>h2SovL^ANwd$-`wi=w>{P#Mf2V|x zWHkb*K7%|G!vN_4A^sb^SJ@)0F)Zfhuet+kqsb>F9`7 z+R7v6H9R$ir>Sl{jS75TF40o<`W5Em;^8P7+Oe({JS*seOrZnoyJ|IC zZIB35;gv>6=RHm7(4xg!yY8)YJfDUq-ApfA2Yy;=j1bbg?p`G&DP3Fp({LS6g5jC65oXO0bak<1&ga!w zRKtgVr?l0#XmcwM(b0kgo~9$@0)3(^j7`ij59M+*|TC(HKXqMelJV|T57jbs8+r9Fw|LEz3E0!c9J1Z>ADoofI1=3SLcEk+tQU8O3E6I8dl??b)szC6Kow@1 zkYDf2qQ@_tvaV^~MZ=j4*9kaR5>hWbo<<)_wQ4V(TG4`pe4e5DiW$`Xlk?UlDRZP* z6jcS0{R0i|=PaF)KVu_tQFJ{0<>Y+pqbg-Iv><`!CkV;YX3!SbKDX}bK3^hG^;c&a zSm)!aYG}9*^RYH5o@S2hXPpq|sG$W3Jk>$SfcrD(;iVs0r#Dz25vbZy=o_eL0qUL` zx7pc`8tL)$$5D-}6%`9vLjVu3`UYFWIm2q z<7xYvSJlR6oHVo`f#+w~yxVIgtvyM#6ww6|fvO7O4-8dv7pTce-C3^2{TNS|H=3y? z?Q+!6f&`wpAmqab&9q*7hj`1GM_K+_`&=-~8(_%+I)X;(ij!;6b zdxX&OzXWQXU1~{pXH>aPsTX+8`#VdW`}y?ZXRYW+NQ zBv5tO|FWU)u>ke!@jaN22YVuEb{SXeh#4<6v><^al#mh5p|t#jj%v9gPaO$VRgT(Y z7<%v{^{ey!m=Dv_Ncvmh;NZazUTA1R0!JvD;rfNrh|D14vf7?H5~$ktXs%(%`wP?- z1C}u#L0yJY%gUL?(G8zzXhA|AyXVqF=?_ld8QWd0ts{Xdd;(y*2Fv@?qP!QzpvPsU zl|B;kD*T;+-D!_8zDm@wIud~@d@fQyinq| z)z@}RA1o25!nFiDi?h#@`maA>P0Q>dtum0n@kU7Ku$Ri`1#7LhYeY%}s^q(K-{+pR z?_*URbu&b|J0pSPjcqz#eW~2pP(FC9IZ`4}C9g8}cB@Mr+Jqbb_%K9TGa!NEjgW+Q z3C*f+GVUB6ArYv;br3sSyRt5IIaWrQ@_RQOEl9{?_p`}_4zadWPPz_~2vp%yI6Fu7 zM-967PCsQ~XbQ=9{tzSiKmyMl5VCE>LS;pz50w}3QzQaam_v3&O>MhnL#W>^UylyJcJHxZ@%1m&7LrRBy3ct^UB3J*Cz#1kpi9%W7Gjn(04)1qpdh ztaza-{p?hEZA?-=#zcfJ_iMY2U6CY14P_n02(RyDSr=tZ4+{+@QV$@~j+aqq;uNfmH0#)+$G24Bs zqFi>>{@ONKiVFSVE*@+7wlJlu!&I$8(`h3;w1uAxbMe^ zbO&Xqcf3C0i%nMC(-phJe3ui?!?F`XvHvKf^H6=j@5`;YLyL6Rsq0KfZt$SCM_FG|p zSE-$7xUL;gEx)wjJ~qx*l#J>6<#V+(j09tsqx$Q82j$k`7`^Yr1Pv`n;3-`~-Wi&x z+*vzT-`8%pM4;;Td#g>qX6CCYx2-Iy3XzUV(|{3r|Ad>;iC;XKD-)Yy9Texw{q%?9 zE9huJ0#E4@vhue?#gn$zS7&-k1gchjpKNOT^*(iDT?cl3M0+?Xhn~Hsk8yloI`NBV zd1Ydui=$HEX+7PepsS7+B=F2F+lSk=KsoO1tmh2uBN3>=am-FGS94azt+}iXY&c4~ zqL9E-x`ebpg(IJ>+hgm{-=jnHtM1RGv5WmLkHnTv&y}S|!t}ZM zDH>Xkz-OWbH#tYAt$0u6okz>m1Xh8zA z&Q3J`=0VFXmr79d1Fh|U4LVwoko&_u*OMNq zXwq)|-bNx&g>yb3NosXUzZ#)w!9Aq89SNMZ3F$V)pN=`@q|F{+kO)-aorsW}CxdCv z2M&7OJDJj4f_)>;3|<$z)1^yl>Zx_ZHMAgsS!d5`%ZAWtv+ilF$BmQ-RK2h+GNf1A zuZ|wcPk$~N)Ps)y@^5W*nZp`dkie`HGQ=x_E~#(T@`vr02vm)!l58m3bgx?Y-f89| z(<_87PTH-F+vK351qr!7jz5f`{S4Eza;<;UkU$l#CD>k{M>x$7ZLS40DXXIe3Hk0k z>rfnB<5XR1IPx=zKo$Nrhmcl3#LzbDMrm7vnrUc30&~c|qkkSpKRJKTT5$Z7 z6$w<~uX)&<7(Rn8^6=7bl^>y@1qsYLA@6^{c34`bTjv!1Wkmv2^2&18(OGmu=zeR; zhMpQ)kdRk>ahK-ML)ivvly9~b2~^>#mYv>dUzh)Kc`pAAq4;i7{Js``Ics|-hyAyG zC5e*1SQfPST=pT}+`v`hjShCg{sxgZ`FL%S3HzHu{+-}$5|M~^T$Cozf&?qS`bD7t=ppF?{wi7 zq2fOH+fVrad6}IrVQNlI9JEy;P$kNCA3P!+S;nPiEGm0l+#<@nUX~+xBM{4z!dstl z>5Fus;smNhS@>wF6%$@)5#{1`ym|u>AuKAbI4Wt`E%_*s2vmu(-3QAPC-_M8 zMvEwmc8E6+*~S%*N@L?nB6w6nCCYXm#Vyy_xUxkhM!Qgn{t$0GvW+XAU7d|9iQw54 zDp9ukDDFX>jVoJrxr$qaiu>R_E8f<```k8481aRdP;mlPqAYyaMj|KD(IU#l?SMCC z@!sRT$VaIl?YUcvfT$C>BT)L z%|1e9Z^!F5jq%y-_4~-)lq+nL-A4(+HfL}P&jNqjS1|!s6cRiVG5hfR@c-KhoD-1{ z^I&nkK-fnN|GZ>7Ue|?f5?LrspalsYq39>shZy0-Q5l3vTwSGoprxb_kp + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + Gazebo/Yellow + + + + + Gazebo/White + + + + + Gazebo/Grey + + + diff --git a/stack.xml b/stack.xml new file mode 100644 index 0000000..c3783ed --- /dev/null +++ b/stack.xml @@ -0,0 +1,9 @@ + + UFRGS WAM + Maintained by Walter Fetter Lages + GNU + + http://ros.org/wiki/ufrgs_wam + + + diff --git a/wam_control_gazebo/CMakeLists.txt b/wam_control_gazebo/CMakeLists.txt new file mode 100644 index 0000000..97ce471 --- /dev/null +++ b/wam_control_gazebo/CMakeLists.txt @@ -0,0 +1,33 @@ +cmake_minimum_required(VERSION 2.4.6) +include($ENV{ROS_ROOT}/core/rosbuild/rosbuild.cmake) + +# Set the build type. Options are: +# Coverage : w/ debug symbols, w/o optimization, w/ code-coverage +# Debug : w/ debug symbols, w/o optimization +# Release : w/o debug symbols, w/ optimization +# RelWithDebInfo : w/ debug symbols, w/ optimization +# MinSizeRel : w/o debug symbols, w/ optimization, stripped binaries +#set(ROS_BUILD_TYPE RelWithDebInfo) + +rosbuild_init() + +#set the default path for built executables to the "bin" directory +set(EXECUTABLE_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/bin) +#set the default path for built libraries to the "lib" directory +set(LIBRARY_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/lib) + +#uncomment if you have defined messages +#rosbuild_genmsg() +#uncomment if you have defined services +#rosbuild_gensrv() + +#common commands for building c++ executables and libraries +#rosbuild_add_library(${PROJECT_NAME} src/example.cpp) +#target_link_libraries(${PROJECT_NAME} another_library) +#rosbuild_add_boost_directories() +#rosbuild_link_boost(${PROJECT_NAME} thread) +#rosbuild_add_executable(example examples/example.cpp) +#target_link_libraries(example ${PROJECT_NAME}) + +# Build RobotSim Interface +rosbuild_add_library(wam_control_gazebo src/robot_sim_wam.cpp) diff --git a/wam_control_gazebo/Makefile b/wam_control_gazebo/Makefile new file mode 100644 index 0000000..b75b928 --- /dev/null +++ b/wam_control_gazebo/Makefile @@ -0,0 +1 @@ +include $(shell rospack find mk)/cmake.mk \ No newline at end of file diff --git a/wam_control_gazebo/mainpage.dox b/wam_control_gazebo/mainpage.dox new file mode 100644 index 0000000..590fcdc --- /dev/null +++ b/wam_control_gazebo/mainpage.dox @@ -0,0 +1,14 @@ +/** +\mainpage +\htmlinclude manifest.html + +\b twil_control_gazebo + + + +--> + + +*/ diff --git a/wam_control_gazebo/manifest.xml b/wam_control_gazebo/manifest.xml new file mode 100644 index 0000000..b8569ea --- /dev/null +++ b/wam_control_gazebo/manifest.xml @@ -0,0 +1,23 @@ + + + + wam_control_gazebo + + + Walter Fetter Lages + GPL + + http://ros.org/wiki/wam_control_gazebo + + + + + + + + + + + + + diff --git a/wam_control_gazebo/robot_sim_plugins.xml b/wam_control_gazebo/robot_sim_plugins.xml new file mode 100644 index 0000000..d52e012 --- /dev/null +++ b/wam_control_gazebo/robot_sim_plugins.xml @@ -0,0 +1,12 @@ + + + + + A ROS/Gazebo interface for Barrett WAM, exporting a joint_state_interface and a + joint_effort_interface. + + + diff --git a/wam_control_gazebo/src/robot_sim_wam.cpp b/wam_control_gazebo/src/robot_sim_wam.cpp new file mode 100644 index 0000000..5eead8e --- /dev/null +++ b/wam_control_gazebo/src/robot_sim_wam.cpp @@ -0,0 +1,102 @@ +#include + +#include +#include + +#include + +#include + +#include +#include +#include + +namespace wam_control_gazebo +{ + + class RobotSimWam:public ros_control_gazebo::RobotSim + { + + unsigned int n_dof_; + + hardware_interface::JointStateInterface js_interface_; + hardware_interface::EffortJointInterface ej_interface_; + + std::vector joint_name_; + std::vector joint_position_; + std::vector joint_velocity_; + std::vector joint_effort_; + std::vector joint_effort_command_; + + std::vector sim_joints_; + + public: + + RobotSimWam(void):n_dof_(7),joint_name_(n_dof_),joint_position_(n_dof_), + joint_velocity_(n_dof_),joint_effort_(n_dof_),joint_effort_command_(n_dof_) + { + + joint_name_[0]="wam_joint_1"; + joint_name_[1]="wam_joint_2"; + joint_name_[2]="wam_joint_3"; + joint_name_[3]="wam_joint_4"; + joint_name_[4]="wam_joint_5"; + joint_name_[5]="wam_joint_6"; + joint_name_[6]="wam_joint_7"; + + for(unsigned int j=0;j < n_dof_;j++) + { + joint_position_[j]=0.0; + joint_velocity_[j]=0.0; + joint_effort_[j]=0.0; + + joint_effort_command_[j] = 0.0; + + js_interface_.registerJoint(joint_name_[j],&joint_position_[j],&joint_velocity_[j],&joint_effort_[j]); + ej_interface_.registerJoint(js_interface_.getJointStateHandle(joint_name_[j]),&joint_effort_command_[j]); + } + + registerInterface(&js_interface_); + registerInterface(&ej_interface_); + } + + + bool initSim(ros::NodeHandle nh,gazebo::physics::ModelPtr model) + { + for(unsigned int j=0;j < n_dof_;j++) + { + ROS_INFO_STREAM("Getting pointer to gazebo joint: " << joint_name_[j]); + gazebo::physics::JointPtr joint=model->GetJoint(joint_name_[j]); + if(joint) sim_joints_.push_back(joint); + else + { + ROS_ERROR_STREAM("This robot has a joint named \"" << joint_name_[j] + <<"\" which is not in the gazebo model."); + return false; + } + } + return true; + } + + void readSim(ros::Time time,ros::Duration period) + { + for(unsigned int j=0; j < n_dof_;j++) + { +// joint_position_[j]+=angles::shortest_angular_distance +// (joint_position_[j],sim_joints_[j]->GetAngle(0).GetAsRadian()); + joint_position_[j]=sim_joints_[j]->GetAngle(0).GetAsRadian(); + joint_velocity_[j]=sim_joints_[j]->GetVelocity(0); +// joint_effort_[j]=sim_joints_[j]->GetForce(0u); + joint_effort_[j]=joint_effort_command_[j]; + } + } + + void writeSim(ros::Time time,ros::Duration period) + { + for(unsigned int j=0;j < n_dof_;j++) sim_joints_[j]->SetForce(0,joint_effort_command_[j]); + } + + }; +} + +PLUGINLIB_DECLARE_CLASS(wam_control_gazebo,RobotSimWam,wam_control_gazebo::RobotSimWam,ros_control_gazebo::RobotSim) diff --git a/wam_controllers/CMakeLists.txt b/wam_controllers/CMakeLists.txt new file mode 100644 index 0000000..95ad1f8 --- /dev/null +++ b/wam_controllers/CMakeLists.txt @@ -0,0 +1,30 @@ +cmake_minimum_required(VERSION 2.4.6) +include($ENV{ROS_ROOT}/core/rosbuild/rosbuild.cmake) + +# Set the build type. Options are: +# Coverage : w/ debug symbols, w/o optimization, w/ code-coverage +# Debug : w/ debug symbols, w/o optimization +# Release : w/o debug symbols, w/ optimization +# RelWithDebInfo : w/ debug symbols, w/ optimization +# MinSizeRel : w/o debug symbols, w/ optimization, stripped binaries +#set(ROS_BUILD_TYPE RelWithDebInfo) + +rosbuild_init() + +#set the default path for built executables to the "bin" directory +set(EXECUTABLE_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/bin) +#set the default path for built libraries to the "lib" directory +set(LIBRARY_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/lib) + +#uncomment if you have defined messages +#rosbuild_genmsg() +#uncomment if you have defined services +#rosbuild_gensrv() + +#common commands for building c++ executables and libraries +rosbuild_add_library(${PROJECT_NAME} src/computed_torque_controller.cpp) +#target_link_libraries(${PROJECT_NAME} another_library) +#rosbuild_add_boost_directories() +#rosbuild_link_boost(${PROJECT_NAME} thread) +#rosbuild_add_executable(example examples/example.cpp) +#target_link_libraries(example ${PROJECT_NAME}) diff --git a/wam_controllers/Makefile b/wam_controllers/Makefile new file mode 100644 index 0000000..b75b928 --- /dev/null +++ b/wam_controllers/Makefile @@ -0,0 +1 @@ +include $(shell rospack find mk)/cmake.mk \ No newline at end of file diff --git a/wam_controllers/README b/wam_controllers/README new file mode 100644 index 0000000..b29cdbe --- /dev/null +++ b/wam_controllers/README @@ -0,0 +1,10 @@ +To publish reference: + +rostopic pub /wam/computed_torque_controller/command trajectory_msgs/JointTrajectoryPoint "[0.01, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]" "[0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]" "[0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]" "[0.0, 0.0]" + +Arguments are positions, velocities, accelerations, time from start in +seconds and nanoseconds. + +Set starting position: + +rosservice call /gazebo/set_model_configuration wam joint ['wam_joint_1','wam_joint_2','wam_joint_3','wam_joint_4','wam_joint_5','wam_joint_6','wam_joint_7'] [0.0,0.75,0.0,1.5,0.0,0.9,0.0] \ No newline at end of file diff --git a/wam_controllers/config/computed_torque_control.yaml b/wam_controllers/config/computed_torque_control.yaml new file mode 100644 index 0000000..a1e546f --- /dev/null +++ b/wam_controllers/config/computed_torque_control.yaml @@ -0,0 +1,16 @@ +wam: + + joint_state_controller: + type: joint_state_controller/JointStateController + publish_rate: 100 + + computed_torque_controller: + type: wam_controllers/ComputedTorqueController + joints: + - wam_joint_1 + - wam_joint_2 + - wam_joint_3 + - wam_joint_4 + - wam_joint_5 + - wam_joint_6 + - wam_joint_7 diff --git a/wam_controllers/doc/urdf2kdl.txt b/wam_controllers/doc/urdf2kdl.txt new file mode 100644 index 0000000..0f5af05 --- /dev/null +++ b/wam_controllers/doc/urdf2kdl.txt @@ -0,0 +1,9 @@ +KDL specifies the inertia in the reference frame of the link, the URDF + specifies the inertia in the inertia reference frame. + +A KDL segment is an ideal rigid body to which one single Joint is connected +and one single tip frame. It contains: + +- a Joint located at the root frame of the Segment. +- a Frame describing the pose between the end of the Joint and the tip +frame of the Segment. diff --git a/wam_controllers/include/wam_controllers/computed_torque_controller.h b/wam_controllers/include/wam_controllers/computed_torque_controller.h new file mode 100644 index 0000000..60a09ea --- /dev/null +++ b/wam_controllers/include/wam_controllers/computed_torque_controller.h @@ -0,0 +1,61 @@ +#ifndef WAM_CONTROLLERS_COMPUTED_TORQUE_CONTROLLER_H +#define WAM_CONTROLLERS_COMPUTED_TORQUE_CONTROLLER_H + +#include +#include +#include + +#include +#include +#include +#include +#include + +#include + +#include +#include +#include + + +namespace wam_controllers +{ + class ComputedTorqueController: public controller_interface::Controller + { + public: + ComputedTorqueController(void); + ~ComputedTorqueController(void); + + bool init(hardware_interface::EffortJointInterface *robot, ros::NodeHandle &n); + void starting(const ros::Time& time); + void update(const ros::Time& time); + + private: + ros::NodeHandle node_; + ros::Time last_time_; + hardware_interface::EffortJointInterface *robot_; + std::vector joints_; + + void commandCB(const trajectory_msgs::JointTrajectoryPoint::ConstPtr &referencePoint); + ros::Subscriber sub_command_; + + KDL::ChainIdSolver_RNE *idsolver; + + KDL::JntArray q; + KDL::JntArray dq; + KDL::JntArray ddq; + + KDL::JntArray qr; + KDL::JntArray dqr; + KDL::JntArray ddqr; + + KDL::JntArray torque; + + KDL::Wrenches fext; + + Eigen::MatrixXd Kp; + Eigen::MatrixXd Kd; + + }; +} +#endif diff --git a/wam_controllers/launch/computed_torque.launch b/wam_controllers/launch/computed_torque.launch new file mode 100644 index 0000000..2da9e12 --- /dev/null +++ b/wam_controllers/launch/computed_torque.launch @@ -0,0 +1,14 @@ + + + + + + + + + + + + + diff --git a/wam_controllers/launch/computed_torque_table.launch b/wam_controllers/launch/computed_torque_table.launch new file mode 100644 index 0000000..3975bd5 --- /dev/null +++ b/wam_controllers/launch/computed_torque_table.launch @@ -0,0 +1,14 @@ + + + + + + + + + + + + + diff --git a/wam_controllers/mainpage.dox b/wam_controllers/mainpage.dox new file mode 100644 index 0000000..deb448e --- /dev/null +++ b/wam_controllers/mainpage.dox @@ -0,0 +1,14 @@ +/** +\mainpage +\htmlinclude manifest.html + +\b twil_controllers + + + +--> + + +*/ diff --git a/wam_controllers/manifest.xml b/wam_controllers/manifest.xml new file mode 100644 index 0000000..2fd288c --- /dev/null +++ b/wam_controllers/manifest.xml @@ -0,0 +1,25 @@ + + + + wam_controllers + + + Walter Fetter Lages + GPL + + http://ros.org/wiki/wam_controllers + + + + + + + + + + + + + + + diff --git a/wam_controllers/src/computed_torque_controller.cpp b/wam_controllers/src/computed_torque_controller.cpp new file mode 100644 index 0000000..407a982 --- /dev/null +++ b/wam_controllers/src/computed_torque_controller.cpp @@ -0,0 +1,173 @@ +#include +#include + +#include +#include +#include + +#define Ts 5.0 +#define Xi 1.0 +#define Wn (4.0/Ts/Xi) + + +namespace wam_controllers +{ + ComputedTorqueController::ComputedTorqueController(void): + q(0),dq(0),ddq(0),qr(0),dqr(0),ddqr(0),torque(0),fext(0) + { + } + + ComputedTorqueController::~ComputedTorqueController(void) + { + sub_command_.shutdown(); + } + + bool ComputedTorqueController::init(hardware_interface::EffortJointInterface *robot, ros::NodeHandle &n) + { + node_=n; + robot_=robot; + + XmlRpc::XmlRpcValue joint_names; + if(!node_.getParam("joints",joint_names)) + { + ROS_ERROR("No 'joints' parameter in controller. (namespace: %s)",node_.getNamespace().c_str()); + return false; + } + + if(joint_names.getType() != XmlRpc::XmlRpcValue::TypeArray) + { + ROS_ERROR("The 'joints' parameter is not a struct. (namespace: %s)",node_.getNamespace().c_str()); + return false; + } + + for(int i=0; i < joint_names.size();i++) + { + XmlRpc::XmlRpcValue &name_value=joint_names[i]; + if(name_value.getType() != XmlRpc::XmlRpcValue::TypeString) + { + ROS_ERROR("Array of joint names should contain only strings. (namespace: %s)",node_.getNamespace().c_str()); + return false; + } + + hardware_interface::JointHandle j=robot->getJointHandle((std::string)name_value); + joints_.push_back(j); + } + sub_command_ = node_.subscribe("command",1000,&ComputedTorqueController::commandCB, this); + + std::string robot_desc_string; + if(!node_.getParam("/robot_description",robot_desc_string)) + { + ROS_ERROR("Could not find '/robot_description'."); + return false; + } + + KDL::Tree tree; + if (!kdl_parser::treeFromString(robot_desc_string,tree)) + { + ROS_ERROR("Failed to construct KDL tree."); + return false; + } + + KDL::Chain chain; + if (!tree.getChain("wam_origin","wam_tool_plate",chain)) + { + ROS_ERROR("Failed to get chain from KDL tree."); + return false; + } + + // Get gravity from gazebo or set values if not simulating + KDL::Vector g; + node_.param("/gazebo/gravity_x",g[0],0.0); + node_.param("/gazebo/gravity_y",g[1],0.0); + node_.param("/gazebo/gravity_z",g[2],-9.8); + + if((idsolver=new KDL::ChainIdSolver_RNE(chain,g)) == NULL) + { + ROS_ERROR("Failed to create ChainIDSolver_RNE."); + return false; + } + + // set vectors to the right size + q.resize(chain.getNrOfJoints()); + dq.resize(chain.getNrOfJoints()); + ddq.resize(chain.getNrOfJoints()); + qr.resize(chain.getNrOfJoints()); + dqr.resize(chain.getNrOfJoints()); + ddqr.resize(chain.getNrOfJoints()); + torque.resize(chain.getNrOfJoints()); + + fext.resize(chain.getNrOfSegments()); + + Kp.resize(chain.getNrOfJoints(),chain.getNrOfJoints()); + Kd.resize(chain.getNrOfJoints(),chain.getNrOfJoints()); + + return true; + } + + void ComputedTorqueController::starting(const ros::Time& time) + { + last_time_=time; + Kp.setZero(); + Kd.setZero(); + for(unsigned int i=0; i < joints_.size();i++) + { + q(i)=joints_[i].getPosition(); + dq(i)=joints_[i].getVelocity(); + Kp(i,i)=Wn*Wn; + Kd(i,i)=2.0*Xi*Wn; + } + qr=q; + dqr=dq; + SetToZero(ddqr); + } + + void ComputedTorqueController::update(const ros::Time& time) + { + ros::Duration dt=time-last_time_; + last_time_=time; + + for(unsigned int i=0;i < joints_.size();i++) + { + q(i)=joints_[i].getPosition(); + dq(i)=joints_[i].getVelocity(); + } + + for(unsigned int i=0;i < fext.size();i++) fext[i].Zero(); + + ddq.data=ddqr.data+Kp*(qr.data-q.data)+Kd*(dqr.data-dq.data); + +/* std::cout << "time=" << time.toSec() << std::endl; + + for(unsigned int i=0;i < joints_.size();i++) + { + std::cout << "q[" << i << "]=" << q(i) + << "\tqr[" << i << "]=" << qr(i) << std::endl; + + std::cout << "dq[" << i << "]=" << dq(i) + << "\tdqr[" << i << "]=" << dqr(i) << std::endl; + + + std::cout << "ddq[" << i << "]=" << ddq(i) + << "\tddqr[" << i << "]=" << ddqr(i) << std::endl; + } +*/ + // Compute linearization. + if(idsolver->CartToJnt(q,dq,ddq,fext,torque) < 0) ROS_ERROR("KDL inverse dynamics solver failed."); + +// for(unsigned int i=0;i < joints_.size();i++) std::cout << "torque[" << i << "]=" << torque(i) << std::endl; + + // Apply torques + for(unsigned int i=0;i < joints_.size();i++) joints_[i].setCommand(torque(i)); + } + + void ComputedTorqueController::commandCB(const trajectory_msgs::JointTrajectoryPoint::ConstPtr &referencePoint) + { + for(unsigned int i=0;i < qr.rows();i++) + { + qr(i)=referencePoint->positions[i]; + dqr(i)=referencePoint->velocities[i]; + ddqr(i)=referencePoint->accelerations[i]; + } + } +} +PLUGINLIB_DECLARE_CLASS(wam_controllers,ComputedTorqueController,wam_controllers::ComputedTorqueController,controller_interface::ControllerBase) diff --git a/wam_controllers/wam_controllers_plugins.xml b/wam_controllers/wam_controllers_plugins.xml new file mode 100644 index 0000000..4be4031 --- /dev/null +++ b/wam_controllers/wam_controllers_plugins.xml @@ -0,0 +1,11 @@ + + + + + The ComputedTorqueControllers linearizes the Barrett WAM dynamic + model. The linearized inputs are joint accelerations. It expects a + EffortJointInterface type of hardware interface. + + + + diff --git a/wam_description/CMakeLists.txt b/wam_description/CMakeLists.txt new file mode 100644 index 0000000..f8f1c9c --- /dev/null +++ b/wam_description/CMakeLists.txt @@ -0,0 +1,30 @@ +cmake_minimum_required(VERSION 2.4.6) +include($ENV{ROS_ROOT}/core/rosbuild/rosbuild.cmake) + +# Set the build type. Options are: +# Coverage : w/ debug symbols, w/o optimization, w/ code-coverage +# Debug : w/ debug symbols, w/o optimization +# Release : w/o debug symbols, w/ optimization +# RelWithDebInfo : w/ debug symbols, w/ optimization +# MinSizeRel : w/o debug symbols, w/ optimization, stripped binaries +#set(ROS_BUILD_TYPE RelWithDebInfo) + +rosbuild_init() + +#set the default path for built executables to the "bin" directory +set(EXECUTABLE_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/bin) +#set the default path for built libraries to the "lib" directory +set(LIBRARY_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/lib) + +#uncomment if you have defined messages +#rosbuild_genmsg() +#uncomment if you have defined services +#rosbuild_gensrv() + +#common commands for building c++ executables and libraries +#rosbuild_add_library(${PROJECT_NAME} src/example.cpp) +#target_link_libraries(${PROJECT_NAME} another_library) +#rosbuild_add_boost_directories() +#rosbuild_link_boost(${PROJECT_NAME} thread) +#rosbuild_add_executable(example examples/example.cpp) +#target_link_libraries(example ${PROJECT_NAME}) diff --git a/wam_description/Makefile b/wam_description/Makefile new file mode 100644 index 0000000..b75b928 --- /dev/null +++ b/wam_description/Makefile @@ -0,0 +1 @@ +include $(shell rospack find mk)/cmake.mk \ No newline at end of file diff --git a/wam_description/launch/wam.launch b/wam_description/launch/wam.launch new file mode 100644 index 0000000..e13ade7 --- /dev/null +++ b/wam_description/launch/wam.launch @@ -0,0 +1,4 @@ + + + + diff --git a/wam_description/launch/wam_bhand.launch b/wam_description/launch/wam_bhand.launch new file mode 100644 index 0000000..5302c4b --- /dev/null +++ b/wam_description/launch/wam_bhand.launch @@ -0,0 +1,4 @@ + + + + diff --git a/wam_description/launch/wam_bhand_sim.launch b/wam_description/launch/wam_bhand_sim.launch new file mode 100644 index 0000000..60b4beb --- /dev/null +++ b/wam_description/launch/wam_bhand_sim.launch @@ -0,0 +1,11 @@ + + + + + + + + + + + diff --git a/wam_description/launch/wam_sim.launch b/wam_description/launch/wam_sim.launch new file mode 100644 index 0000000..b22b8d0 --- /dev/null +++ b/wam_description/launch/wam_sim.launch @@ -0,0 +1,11 @@ + + + + + + + + + + + diff --git a/wam_description/launch/wam_table.launch b/wam_description/launch/wam_table.launch new file mode 100644 index 0000000..fb882a6 --- /dev/null +++ b/wam_description/launch/wam_table.launch @@ -0,0 +1,4 @@ + + + + diff --git a/wam_description/launch/wam_table_sim.launch b/wam_description/launch/wam_table_sim.launch new file mode 100644 index 0000000..05648af --- /dev/null +++ b/wam_description/launch/wam_table_sim.launch @@ -0,0 +1,11 @@ + + + + + + + + + + + diff --git a/wam_description/manifest.xml b/wam_description/manifest.xml new file mode 100644 index 0000000..44032f1 --- /dev/null +++ b/wam_description/manifest.xml @@ -0,0 +1,14 @@ + + + + wam_description + + + Walter Fetter Lages + GNU + + http://ros.org/wiki/wam_description + + + + diff --git a/wam_description/meshes/wam1.stl b/wam_description/meshes/wam1.stl new file mode 100644 index 0000000000000000000000000000000000000000..3c8a5a4432d7e1790b35f4a6f4483004a66225a7 GIT binary patch literal 58484 zcmb__d7Mwx|NpV?yDT9?$j%HimU-WMEiv}2C1elT_gyn~Nl2D#B}yW~7~9Of2ZMx9 zgk-CbGASj6qVjva&V8Tjd8YdQ_4D{VKHbN>&-3+sz0UGF%RR5xeYSC2#Q)EK3o{GR zW$x^cgh-Iz4fwWpTvDRdh8xbs5GWunW^Ytmi~z1(=0`vU*{a`GM_J~{ZZ6!h<} zw~tu-%aef>mEkwkWHq}|H*B=&)9`nXjrPc6@ z3D$wvrmDJ%xRPLKD8%6}o5)F%Z|tr;tgO>`=~UH%11^}Q5G};8TvH+_Q@72Q(VaqGx3 z!zLjXJY814*rL>~eWIyh2kMS!A?iK;`WEIG^k$nR)E)T{EyRVCTH6?rx&ALnSSs7H zTrO*PYnQ2^5F6jT_FX7 zlG#g8s}ZtcJ=SXXteuw0v3PqEZ`s@9_x@FVl5^)qQY4SsHM7l9h!$eSp*S!9hkfhs zEj-Dv1LdM5s@+g?`>A2)_TWP6QA==1}PUU{vchBoXeHVT~ zxi|{Qj;o`cJq7me8C`z~k8_JX8G9crg`-)BXwv4Zj3w%yB<+v`5hzKBTqmYD1E1S! z4gLFwg}YKGZVS*ZX@6R?UwIjd6t=TXR7k;|K{hpUnMxYcd;z(kx?!` zYqTz#AlEJWEAhmZ?~^r0dOq#vg_sk`>Guh(^m^VO>a4BD8v{-tlTnU#}PuXEJlfha%f4ubgo@~!W#X7#yq!8 z#F1&PX?f&x{ah~H;>~!YuCNrMg&>4g{O*#c81azga$T`pEQQ<(@vj_+KuJOj>UGXr zP3>{iZx2_u2g;>740?}hL67a=7UWX8&C?^aB;O8gIkF=HC2?8(Pqn$*anUjN-_|~l z+GF{yqcNSry@d7E?5I1nc_2xM&eI3WIzOk{n{xcR{p8prx9yD+!KzQoW%Q%oUiPg4 zvP9B8JI`bFj8#T@^drPT;`s8XRC{a2Cu(U~J3px7@w4VYw6Z#Zd*jMcpVnf1bty!k zBwbJZ-+$JXMx!Jl`s6+6U7bAGSzf+;;#*{SKC+y(dgqC4uGsaNss(<2xbrjhcg>OD zbUzf8SY*hS;1?`~XpQi-YX9CI_lJZFN>+Nl^c+3{IS`F}Lah5a)oVC?uyd>C3p-IR z)~Kn~=_#q+l|KeKhp)V1*)un)Ht*T~P6$gOTHEo+a$P^DA);vwC&tNjTPJ$!Ur)7~ ze6(5B=$dP@4G!df#6eF9ELU@&T$Cil{3(OwlerGs@6K&%SdKlzv}5RrN%Htlan^e) zB8|R_nwSW!7xyb{1LVM3e^fp_;+?cl)F{$DpT`G3Yea(6>W|NAaVhSvTc1A7GiQK6 zv=H%$&3UeMl72k&kMW`9q9h@f-zX!0eYU2P_(GCb=#%U2z0?iX?lZQBa?w5^zH%DL za$W`Jqdi?~rAKHD5v}bI39MP&W*giuFMgpc7*9)4b}n`Z~wno>qTY#z=Qx*X%a82O>tDt?9Ptk=@2#qH0%q z4_CWuXXIADU@1h?>a}*7H=$x*r`f4>dyxZeG7;(RDBCHc;=oe;tnCYGmmU&iYW)rF z;pBfuXh{Jgff07!wXU}&r{X}Hkk3TSUGuKHezjjGi2iRxldbFB8%bFd2crKQv8Lb# zcVk2*g+TOwBhYe0n~2oOgXO)v2krUa&xzt+bS?6;?ituCg&^T>A#i=Re2vG!V##Xd#-?{LzW#kIiMvCn5*RMSmRZmBKsFcw<3<0>t(f1trek&s&`zhHxto~v^u&zUs6^= ztX(7Q3lXD3zmNObMYM^SMu>f5)+hZ*b+vW*FV^xhZ-&In*Ih)Lh!+TP|M{7IH!78MG8akU`CRQ3)yk5d^~`D3 zZguy(N&atpEk z&nnLPHnGl-Hb1&mU)f;g`t7=2msolYZ`z^sQvc`gwqX?(v*#9~=p6`3l+Lo9%zqdk-y2WVb=h^we+4DP&cFm_&PG)9r`L|A8Q-e61?I{jOF0ZGXLs=>J9>>9f`<_>RA( zM)ZFpXyt9`-2|fl6~T%bEr@6n@zL4R-Url6R#bo4*ni-T#cXpnoBky*$45s#OVPaq zOCef_ZC{o4x)8_Hb6W1jo`L%vL@W8>|1&wTSN=BwcPXf$sa4%YE#-i!C7cWA<3qS> z?BD-)H>$=0YxtcTJSV!3=JQh{)4Wzk>eUI)gX)*?%o&tIv=BYA4Ut*e?zj7N?htC) zI=feBhrjBhm8I8uTmg&M*CwLlh%_(mxetri}wb!AMif;U$A2d_)LyJ zuZ)+?whgoA7x*+8twpqnm`hrHaesO()@tRzn{NM1D?<&sed}UPn~1iA_~TBE7;cYz zIsb5%mz*DJ+w2Dy(I#RmA+|60H1SqC%MooNXs;%-?Ofx&HatfZt=qkoFZuf@tRJj( zA!t`5#~jGuEudWyt!upxdK7TOJ0YqozdcZr5UHfq_wCMa5ARr1sqn5SK%gWcXpiI3 z9w#O}0$UR`G)FD6qwd%?CW2P4UY_QWF3%rW3S0KS5y*$=|3;u(?D-~w*3s^%mp3S_ zuoRA)|3;uqh&Bp1!Sl>%pp(Z#>2$AF@CzTkPsV2`jh(JC> zn_6`%QDb*a@>%KECAi`cqUy?>(Q^xat?uI>0{Kj>%9p+#^>W)=%8pSPBdrTvvnxAL zF0OEdI1m?`6mxj+KM=@=Xwwd=Me9i6G}Rs`7gx?g6uV(X+b4fk9Ed;-5&hpBC>QrW zCW3mLRq>!dKCl$-KNTXu$0bNapoWMxIcVfqLnlpBmZMzU@0uKlKt4p99ON^C^DC4~ zekC|NGdakA*kgA1{tEdJZ6c5Z(I#Tnjq&oGCx?06=@bV&GI}^d1in&;H*)rsC;F#( zSLqCZ_WJJM0 z(I(=H-ow1#u8)_ePJXiY?B_MzVLh^YJIHd>1pSH--{wg3{)*}=>!!4cMFjF8T8Obl zUw3OHyeLo8&I=JJ7yXJ5GrlTqzi?@?{HAcLy&YzKUHhA^`IJ^z3cZBdL3*@-f?GZTD_^RxR)Rw zqJ@DpIckDlLWlx%Ci5b-`Gx5R z>LLR95G_QNl3kqJS+dG4)i)*6+S%$?V}U!Gb`U5Ry@U{N-6-SSf3~KaL2vu0_gQ*; zARnTIIOjBSDti^=JE_@sFoMtF_#GsoO+@WQEuBGCOUN#?$3d+SZ6b#C8|~+1`V1L&UWgXrIofU0 ziEv{0L^#k2OCeg%wfg?66-zlT=q9_-=HkS?Fh9_{TdW6t# z!?oAuziUYbLhvuSFMXlxKn|4T>*N2wI z|5ggoCI=$0rqL!LUYju^I`zHJVz|yy=)~*XgTmf!nxn8ralRs-n7M78+U?${%Lsn& zd^tIzLaaTR9Ye0M6^BiX|&h# z7WKvibpyhkky{}UZ6aC~pB>%h^;7?-T|ULrXcJ-g{d~vj9ls|r$0a(a{({S-(7Ox*yb!GKkYn@x;_Y$lHlS8iSwDbAyHx+{JdszEd)5!$2Afin~jn;YV ziY@qCYepd^ zC4Q2~USZphO?Y-TI5Yw!(b*Ec)i3?p+@zn=aiCmWqY5#K5YM$0(SlZFbP8-mXI`1| zw10*iXlNq7r`rj+nkVlp=bs^4eM-$w37;VcXcIwa$hN!S(^|jyXUM^g6goo=&?cfj zt>NZ;TQn&japcc<)_p2|PAF~Yd6(X$yZYvcxmub|>nrXj$;82>^qLw=AzFyM#8G5u zlcdLqqi&-s?xxJkLjx**?IItdg?N<^R?*G1_+|~Bm?PRmutr;QwPeqrR%CkJ#%mva zQ<@R_@3a&Cv!v5DvW2s}T$7YGnLl@*sXZ%{Fz2{oIcmtWbF{jd@IC#vZ|v7@fvU?= z2DCe%5V{sj%kNOhFXk?)eVhJ^9O==zriIAAX1o2w^ z>W?G#tzm;4uU?H1av%aFQB=yyxvcL_$2%jd_Xy!HC>Lv;PKs{M@HW>N=e%`(X3Er- zx81^%mW6I*J8rzq!1oliZvVMu%1h_sodwr3TZlkDlOrjzoIG%_u@g0ViaWDP25SNihmoCK1Az8mjo_YC}+x%nN2|q)p z6Cf9Ntn?1D$3<^?oBncK4H=6F2|{DUQYjc_39q*$87@##cexJPDra;%a7Z(I*>2v>Bnscr6_tiKnpQ9bAQD#>R};{Sa-GM$Y44RPU4YrN8G4cG$El z3eYB^B}LYZr3jnJAFocN$UzNzcsv8dW5cBMm%bdM2cc< zlJB6sU|`8wv?>bjY;!5y2K=n=i_`rpLI^@E8}-X}{fpL0BT$lxGPOC%bPYubu~s@x zn9pSNjc9(>QJX=V>uA~F7c7NnAxa!iwYznu`l|T2Re#TBA5m;}C_UdJjtqxGd`9i; zU$ZzVCf6qGZ;I8ud}w9}(a5K?N?=6XwqenH0;Odk+C;RV2-DdVgEg&6+)mU4>&LXi zw>^lK4eAH^OvH0kvmAvT`DGu21KS4q$nOq&$$7K)e*3|@pHA*2`h@B(f_f9Mt?yN0v z+(HD#24g(05cBff^&V!d?EJX8pz`h9!#Rt`r(>h}{g+j9&??L1X#VMO?^2&;&iO*W z*$KlZy4=Gr=bm7cLNwhLS&1Z77ij9_O^NKm|lsI57sPl&6 zXfUm@VUvldvU{r6=-dd$tJcZT3ehGa*OIZ`yT_s(*}amHRi#6b$tlY6KeidQK=%M5 zCwdE?tmWK0U&Xn0BAaTDljqkOr4UW$4EM6h8!=10`cqmOwTn4q%(|LzVXHSd`B|sa z_%G~Cr=C_E8)h%Eu%=DK?9&n6!WTz4by_a9Q7c572p)rXo7Qta+)&fVK+~hhzcY8N$4>W2QbITx_av{yG<0d;3 zoTm9-w2=dCG7;I9jJ4NO3%b;Tn49L**l0E8x$l}MZqYQBOqOd4;UU zAfo9mPAI|_eMdN(rYto$&?XZ>9?k&|r{+}NrJzqVwJMyoh*NBG$VrIZZ1-sUhMEmT z-NuIHh!*051?`=3+LwUtn2pBdXuJ4~eREhtXUnz>PKhBC6-R^o6D+JZ6ES}2RD1K) z5zeazIvQFb+C;Q^?2H|krMFXQQg6G%+I4E?Tv#Nlg*KUXY`p!xy?M%Tr|F(!#(a)w z6A{rlQqAWjPt1+!U;Z7J$6(E@nT-q*=<|8Z@;`qkj0k=&ujh808E7AM=yjDvXPxKm zc&*^;%I`+RHZc4ydQ>4Y_IXli_0wb-g9zmNZ>`ea8teP^24gIgi{8$+Lfe4|X`5Xkr6TBUrMS#hj+b&Z8` z(RZ14AObZ+v=C1hNmFlR3Vj%}>&2?o>hTJo=hn>@%0<6oav%cv5G_R6`49N*t}{EL zslkDAam*`@1l=C@_GD4sCwuob7M8-%WoVUv2-FbKbPu3)HD&qZ_Tgwmpj;e}rdHp+ zHP#>J)UU7O^g^^z$Ay*}TJb)M;+%|IX@ zqJ=2@TXipC)>xGi0qDbU(UbXvuov(@?wZAP~S!uOl!6FMw;ph_Ln*t5J zICr%3O3{7>0&PMx-E=xv#d~(>Uv`5AU7Q!14o>-yEMJ(q-a@%JRw%dO;Y2ri@HnUS zy|FeTP(wshgu?UH>|YWyI2i|ac3x^aIHWmHF7|wX)V_3RoYV49f{h5|L$naL>t410 zY+J(luu3K8`@)qiZb7aql#BhCR+Vu(teBp}v0luI7E~PE zOHeNMd?6Mch_(;r8teSEsoweL_itBI7&ipHI92km8%578>)iOm^L<{j!0gB*x95z~jgBp=Xj`%Btw7oMcf;datF+|T1zx?fQaq01Zo4y8xytT94- zH?Xy=5M9VwJN!vQtMuqc2yaxpeBy_hR{n;`kq7DS;K!7$hxh%=fm&&8>D-49@7$Yd z?LOQ*5fOZM5Td06w11v>{KLG_pQf{ewPLyZ(%B@$iwh^pl3k};)4Ijk$bpt4T5095 zRyQ9{j-*mXRJ^u>Z&_&#h1f^u)0;`727bObo%#UZW69*wiFk9~DJYJ~`X z-bC4mxSi;ny6HIQ262=e_1^Z_#MiASFIQE+U@1fk@gpIw5u#MH<57$#M~J>dD|qSA zk1YR#5OWAI@A9`XXa}NAj@nNRaaMNUU@yNJ>mdTI#aMJ9au;gkM11mvef-$p-V65@ zSQm#@vnSWB=wT_0MHk}a*MptJTp!pMiaQ1eB2YsiZvD~2d9YF1*V?Q$IIt9=DSBYu z$M*IguiHO0ZY}$^oNr~DQq4}dP|-t8_~xOGmKS2vpuA2>qwnpm*CP!C+JtDzllkWy z>(I2%?W(y4$d4*7u~L62Y0nv2(?hu!i!MZ|0SWe<+SlwIe|9xE5P_1|`%wP25ue%a z@|WaaCzB$(MAfucjIH9KT#R0)lkJFCto7YKx8Eu}KxXPR&#K$2nk{Nq@=z|K>GXWs zIxE+nWA>WgUy`AWovoRlRJT`&${wOk#I9yztY3dUW9M!?Kvrv0)Owz@N*G+(L$ry= z)#_Mi{H%+1;hOyoI}mLmDttcMEwJ;n-G2N4S*cA?S974XRBu7{G>XA$bu49Em;(`5 zZ-^G+*%cpq1#e!rhcsv{t(NoMOw>!}P%lBbn465&aMpA$!>DU^|EXOK#O_Y>+@@61 zKh>&aplNpQv);{h@vOamSbteJV`o>_E^;7R2zS6pH)FMv_N#qgG7xAJqJ^kirIGBM z{DpnwwZFYO_ZGMpXbjG!F^IZj#xxgS~mS z@(ix_i71!6M3A9Ph(;q{lv}#(wuda3VQ7U2@-cxV<#%OM@>f?1?%7U$$<^KxH*Ee7j`d-ZAHxMAQmP;cUla_R-xB zo@MmB&Cfdb3eG;%<}`mWEXbI3>$uvJXTwwFkwmv^LYsvhUfy zLo~k{=tqd>CQo$UY&+dL|8p~*or8H0(WX|EgU;a`bpJc?N))cC(%Yf!qZ@7Xeq}1X zXL)5+oUtN91WHn?B`29y8N2*dh6Ssoz;d*S&idXO;EbWXwci%5XQM3U(3&tpOQL%K z^!Al&_cXnIUGwJk!3}zn)oFh^F}|%u$^<&|2g( zImS}$9w?W|&Puh599YvPVhi0ISlF&s46Uuz$u`^3bKd(FpK`Muo$1-s>TE<)uR!rk z_6Zs%71jy&LmD3oUo|a9v=C1nj#GD?`33~)&ZRV;$_n<7_85zHxp5xWFMnZ`>8)_1D`>oNZG;T+|(+b^xsE) z_xC(`oby|UD8I|&14|)Vh?>N~b;Vy4K;5~N_7aGuo6A&JV`vP%KwQXyHkpWbsU-WW zlD@xETJdavXj7{zktLl)H>x>flTRAw4C%Gv`HEXsh#d90I#>4;v+tMv%Q!Va1fC$! z{`{L3&eXd_otnk-8J-#uxVxt{^`ZUtm6u|j%A$aACWG~ceL;woW6L>@f0WJrl*>Ivj~j}9=(O4Xc})RtPpP4XR*1keAjPIaXvX<`qFpTl{$a+X`3_UCJgUJ9WmI5YTmEFwe<*?|bu1ktpT znV&a$|{E88JY*KsVAL*>RJKLVOyn!8)d$yH}5DA<2hfqV4V=QsZA`bSZnuE{Vu$2Bg zpPf-$>Vi(r)I8apuiq|WaQqv>Ke>DUn|4nAU0Iw(wWy`}_1-=W%BgLzwJtx_YnSNav2wgwK7odgMb+)5?n7@7KVoY8qXN_(y*VW19 zbu5&NqA;j{Kv?S*Qt)V9HPZ{aLTYm4?o)e8R8;5hzKB(#INl#orn4J^T77 zXWV;nDLKjVipS?!C>KYt5S8s`y^p51aH>}L+y`Ad{<>GiGUt&LNZy`G($qtl-2$V#T zNM}1b1#+|xouOWmw?;R`!Mz0K;^^XNr?YnRaC@LEM4%)gR_`g}%%grag8CKyf^u;* z3-NYLPx&T=p6b*cjKNi&?bVs zk7Vz|4Wq|k`1CxGtN-qg^IorYkdqE)b<)#y60^44miQ zd!xGjZq14wp6}ra8-2rVxOCSQEaybzZfqd%q!7^*Gy1lW-<>Y$%!(>0&lH~TcA8q< zUiiaP9?HcNJt6LFTC*Y0L3^-{iPCcZof6MoDK((~yC{QdA3;ZYR>J<0gy7pp&zDV?!$}g=jhv4z0Gv zl&|PKo4tX7K;7|_o4!|cK3iybzR^yWNh`di)rz`{azxsr&sFlU6rNcNQQ?oNbtmU3 z=%hI9WkS`W*3P_<_TbYd0woD?ZE`E;mC}3dL&NWQSi8u9lIXr@r#&g7q6#>d4z!mj z3pK$LXu4n0^aD4;4-K3rZ&xt-E|$W6OtG&K>)hFob#yM?$Rj_d@v&k9%~1vDT@jq` zW3Qw;MdLnl+ueN1X?@?3Nn4A$x|bjVC6R9*`;4qRb%(uq$~Zh_k)AIHil+u|;x6W6gjF@?(J{ zimsXevQz1=ZElsa6D;g~WUZy^Em!M#R*rHt)GA7d=U45sD(oHY*w4;4+8j$En(o8h zkG3oJ9PT`EVyTDvA|IkD>UZ#JyU_R{PQyCSvu6nOMYM@{xl5`Ybz+cnGAe?bI4>%aS+dfdy~t+%trD~`jdMXe!sBGrmam-;87 z%#fp2VvV8BciVS(Rbx6^Z_KM{XRrU1rx7d{M;e_P5XWlbIKB03t$*WS1WKZB9NzP+ zXU}$Unt6E)UxKZMZ6id{{i$}YmV=$_qiR~SkIYfMA>o@*AzfE!2S3x-HqS>n-wdhk zTyFNKfxsCV(L!7vx6OK<>==5lbm-@01+8IJR}Gw^A>`Aw;B$=l& zQdlFj_Q`U@&Od>&K;P|WSL)qW*^z&8H4E1ds3ExX>%UON*}k=abLQ9TilgU^=Pg_Zp@y`_nHg_y zojuGMME^xi5N#r!Y8PW?UEIYvGy1;W^T31x-?U5ngdA#XQp&ynNbiwZiHH~#B#Lcg^y5EvkTVm@Q2;?&@UsiOvTSCM; zz56t2Ix-5n3>hj$T7Rtr3 zN%yH6J*PP4HJoQ4P(wu1cbA&}l+u&hepW%LN zN;{gJFVZZ{vNQtuOb)UVe!7 z-=Y@$ICYug;1)!=ICs$vQ|f`-6Hij@A_Dmkt$L!xJ+Tb+#H2N6L%JuTT%5J(9FBS* z_eAQE1_JpIP47QQe?6ks49(=PmS{wwTwHO`i5JOcj()_22-FbKv`(ZR$nEiGlb?+B z70RV?ZmAiS{IMFfs;+p{;u;S55KTEtx}jbOafmh%g@zn;_tLukAg$Xg z#&mY|x*gFb;zRP(yl#KD_EXV_z*6Y7DSDvRB=5{KZJfimav1ws+{>a(LVWbtUUxIu z(c;VbhE^ySH54M-y}!K)A9r+0H=W|uI9J4d|5~Jdq(eoc77$J64Ba!k2g=7eKff0t zOXMl)im8$Isi!L$yJC~04P|2MkUdI$R|az|VID8c??e$JcN5+3iVb%5%YBAc$Y*kl z&KUAaPaW@!U-g8S6=OYkpBC=eY?%o|2@8mw%H|f**McvJW;8_^aCgS^+v)tPw6`WQ%i7Whi5u;^1iu)*HRsruMjd;Y#%Hl%)Xc9oqwQdQm=r zt21_8oD%0m42zI!^Axp~#Yfut<0^T0)?;!EC62h9$9H6;e0?YjIWRYw5Lfr?uTy^U zU?W%-4Ie(|1-C@7FJiSSP6OmZZLmrLZ;W1oDG}F(XIQ_fqQ| zG!V##Xo?O0Uz?pjE{}JX&g|ie33z*5*NDM#a)diHDYk9Q`nFJ&OG6tGIy#Os^HN zhVU4yQN&mWA)0aswU}i+HJo-u*{3n48|@D_aZ_ZfA^P^4Ts~M za#wGM5P^IqN8(5M_6{Pg4i1?UiwKm9dl4bpZgXR&%XlZgWNoY5rq}AQR{QEbX6%q~ zXF+$J<6={$5aQSQH4FsunHcX~C{z_;QmDEd; zhzBoy6kGc5cxS|@k75yl8X}rv`|gytekH9QpZrP)#~sSWeTfkBt3PRFNu|Eqb+&;( zK1BPo2hW`6e{Q=Iy*`c)?8lD~{Dg9`6!tL_fp#DQB~g6s;(Xg!t1J)O8CoF%C7B#p zqo@h?F%yC8h(Jju0)Iid*kfp~M)P@p@>j_l>&K!O#hNzlc=^wgvRPycc{4)gT((L@ z&q_(~b1nzDyC`pQkfBS6zcWWm)-9ZK+0yxtIop@cnrvqNqMXa}^SO(5gmW$j95g!{ zXq{<{INsjwMO+^y_e@nemo1&|6*a*uV01U?k0ai%!v@J|w#vC2a3F&Dv?RKvH#wJk z{dBy{T3h8@4t_zoln*(`I!5<0ZqBeb)EFoC`8k)ZE0dO`gmW$jr7*8It$luM8KRua z^01$CIY6K$CdcN;a?X*1jpYzO=dxWnb#O{J=W>uQoU$7SdBo`r*3Dn+N<(|e8Gg>? z06{sI13ptL%DL=N&SkH+pL5yn5cyYfIOlR8mv$L8e}B@?Zd`eD8|U4tMPvy-=W>9c zHC4c8YDGDh9m=`P_vkr;vXT|fxg5x)?8d=&>Q&BVhjK2{8HI_U^<2QGCHY#t5z)e- zoXgJludAHP_SqqsLgAdtfn3UN9DLbc|a%o z>gQbWb1vII?HUyd=UfitQg&l&d6_pu{KX(4diHJZ?9BOu)5FiX93W_K81R`|<#;T+ zOF5UF0ohc}Wo!IllI7=I4&+kaV(a43B_aOC5ak@`anYXBroZz{b(M2DK+t(Wz-MYz zs#zXc`ST9W+^j0+vXxqCRw$fvIgpDZnBMlK9`=g$>A>$P(7QW|jUpcDY-tw5u}fb~KdrI|VkwST z*WXj1FHX^$@Y3{tqFR^U1_JpI&3&Bz`BCefosMPkE*0hKzjN+J^0z;w+Wn^wR=yXt zLWF+y-%T(rpV;y{Fc=2BSGkF@&qr@lseXasYZ2%cxzcK(O;!_V;T zBKRsvI5yl3$I)9~(>HinE+h1}OAt-@;V7Cs>z$eI2vI`CpKAn1kmFZSG+M>cE3Hn3 zBiy)W=-58gO7|W=CN7C$;&!J)aNGnVF8h)9flYMwx^SXXs_S%jpdWc}*r7QPO}>3# zYo}*)A-TuTIpFt1${N9?P{T)Btr+%_^Gfgi-cNq+gaCmxjlGB7t5ME@Y*be*i>l~; zGpV>2j_wcSa{Q?NdJLVzkyi7M#Cg>=zZ!*Fp(gx%Fd~!c zJwfz<7cuv+iXI4EuBv{)Qi%2=6mF7M)O8d1h9M%fwfgV=dHZd$V>cm=b(_x7{ec}= z%H(MK)DYRZ`v&jXAN?3!Z8=(tUu~jyUWFUUF-N}eb{c{E_2-FJE^ks*y2g^@$ec(O&xXK3**ny=GOs5@~yP8^6pK19<^*_9vLWp7^h zEI+#6DoMR$t{>eW$i;6-(VC(Dbo-}uz+fx07Fh{!=Bt)bOUdc!EX9}#F1qA3QeawBI`@)zF4`6{~K;xWk4{ir*B z;Yx@O1M)gW8h`Ko@V$!ee}te+7`he^O<#VmF~qsta)bBDbU*Kh_6#VOyoB}0C%!oH zMJK-7ZtuhSD!M=5Km>UuOG~2L36zcGEcvVV3+;&_zhr4|iE{bx+S@5F>ikFu_p6*7 z-5`AlArae z4`-i88G*tv?rL5N&*27I&(w6Mh$6igmCxk87LN303&YX<2Ko_#qWdL9_q!MU=>A|H zaol9vxL<`ZMVvxB7*ZD0NaA3bO5m&m7 zb&h0x+WVRE0dRf>z4pOUh^F{KKSEk?6gJ1A<|E5>G&!%Y_}R3h1;q!a7RltD2}c&Q z(rA+dtwlbQ<0#3V_;@C-3~_NJo94ipHWB41Vx2~lNDfE$vmH9RpEcoU zQ>&(Bn%cXHXYvk)BfXh}qx-QGpS^0d5XgbLb1BV-Xd!Bo{+q}Sm+axFKh1$QnTU$v z3<7(?83c5DaD1(tL@b0|D!fX4%S`Qn~C6@9A83C4n1mVL1 ztkph0x?gFfvu$XPL2(mg#~eb`2uDb3gy#6C9T6mZCn0ofcr0<~XmTwVy|xhVl2)4u zQ6-&LI7e}$rj|svcPR3nqWiroq#ehJvQ`}3k8;tY(zk0!HY1n|Wg!A3(Yl>t^@kGT zI&rWpn>c!gqx-d|MsG(M->HrU5rXRsWuYc0i8DdxkgU}v(u(7DwH+uI{i6^IVj6lI z3Gqcbtq_5d=)13!J7E(c3Q-Mk{IRY@l#Ae405a`^8-1Xzuqbby5`Wi9snut6m}}5P~xzAUo>LG2FU``W%#D z!>gW-1LaabRtVOR-jc=ibY`D-y*YjiZ?GT4F{pdKe|{B?)mN(kjyNhithzcQ!&3U$ z=XhA4qm!H^gUs7fMg3YCM_2d4QNID7M*KGi|AM8EoAUL&*1@TIIIA4}o{IVnIQ|Xc zbL{@9qeIdCvIj-?bBwdDMU<=2z8xRdX=%UsdxV@ePQ?jZc^6mr*7|Y6!8rp(o?6Aln~f?%FAOnF;489py5^V3Rzqw@w&t?q^6gaf%0!yD8a-PwMB zq3xEbEMF?3;)DYPN1SO5O|2FlF6_+CRzZH^#|Z~@g?uK*ymm+2;=LQn%wLsP@tn6O zMtb3>-{1ra&zUGoL51mFh3?n9)^k;4ad4`JXIbX?)ps2?xwjjalLM;xG1XdkEX8+H zH8kYnERUUt=4rlTVv_b^m_|=jqJEgta zO)g(i7NIy{WJhc9yo|o?crIJYbNNQgjT9%mqFPaFV~$9VCv-ikfP9tWgz*>D z1kbW)l@a%WweUs*xz3Lh4*C+7!hTFy5X-Hz^5yL)f4QULgstrxs(TzKj0o(NbS^sX zBWuOYr(|x56XqLjx@{4`QIuK|a@3-@v zcC9b+A)0O*&VO0Hac-M+oxW;>2rOmx-N@ggy}x=4mmi;0QNKYS#ZrhCqSc_)Uas*& zWQJH3_3LWCi#^;#OnW}nYkOjl9CA@b{krVixlTBeK%-4WGJPqHzL>_dK?27Z=-EI& zGulLiqqb!G{v?wozZmXE;Y$5^zmrfo$iaiMfdc##z%U2>CQHmLTs$jQ%rT@*T)S_aePh=@2N1P9XEoa);4dMeZe9F4wMpWO+O)=^Pd0ca#qR-!9?!z@AUvd|4}G z^)E`w*;Pv#@1t-oK{VxI>D5IZEpo@Zp3>3aK)HGp_}*v2H|^w!omu4IlEV!ImZEiu zTEqE>aMmGJyZRTdUH#0Z5FO+x`p2l%2u7O-idgq3VqHEpT1BiYKiI&JSP#a$IcjH( z+vZaIxg7kUw7O5rUNjtk9-vLcuu0opia(cS9>f|5ETwx4Ye?A^7Icycd9uqKYg85} zr3vRk`Zqg##QFRq<)nMFy+M?l3fInv;7C^XV=RfH&(255$A{LIIhy}z;V-&=ST09r z^31?BBEszNx4Fu(rF}c1O$7ONn|=FO-%~4&us;v9VuYR( zX;$-dC&;WVQxmlvJhriv$uZWyd#<$72)08%YxJYKN*J}we(Uj3vf2I9M(uJO9GBvV zY_qOAxtKqb0d^ zIi}v!s?_y(j?R=HhNCl;EQ%AxQi!JAb|V!zDLXiR`zS;yc@#o1zCq75lv}yUB#-f3rEO0=F9HJmZ+!2(p8-BA8m$Zlq#(R)}U#sPbh<&XtgANX$Oql#SPId!S9>PL+q$@m{AA>P8+GUW z6`BvxbO*9^{S@|abIH@8zE}#mDQlgm?k%PAv(xXAa#}ktuL11NE^*f8RcTD$_K+r$mNt52Ui)KlYwiOXEjqR znm=4Ue{gJ%l11|emO``;(b>GpCM0;`eG^Mrqhp6 z%e-|oJ6rzjta=}>qiE&~R!F8+T_|4$&(8B{cIG%JWe4Rc!cvGe%FwS1F6!r!B5)EbY>{+gT$_>iVh^Mu< z%0#pfODLaZpXn{+e98lfC)g+#M>E|*qP(2Xwk&5`lxq?Z$cJd(!|lk~TK>?qxN)YB za?$fqb{NXbnQPT}`)$h0$(}*K1wcMT)7w7EXW5JFSV(r@TL6@cvnXX^JJ!&Cj5t;k z2O^LU(W*Uc-5&Th1LfkZO?{X0a?Yc=3Q=7l0{IY4XZn-@GZXcayM8YTPJ~e|uCImI zN_ja)mu#Q%EwwqGAtN86DIRCf7$<9n7d_6!iU^d8D{}fe@bjs*K9iwcV{lrlOX(H) zqg6Pa``B>q6CiLEPP^3Lq*#c*+V!?a9aRHtuqm8!h3_13$tT57F8p#6z&s*h^RNoZrQAj?EXMybO`LgQ%AH(a7G7? zua%t90Xa}EYN#?g*p$&haz=+*=ZaX8&SW^F1C~NG#VFRyY*nZbCznx1htd??Uwmq$ zcakzX;5jU!g&0mJMLc#hP;@_@2;oT)KkG;w%cm)$18RkQCdYG+h3tp% z<7MBqPk1>F6|vr>lcKVe(E-t>9bfj2vex#Emj|3KF2|4QlOjZ$2r?mo?V$h2;kAoe zXX&JfcXWt05t*+|w-?X=1Kx%*7*S)l}qiNiL)wow@!>QF`p$r&B+Gz$4l z4vX4+c-~^W@=}{)WIA$C1Q&gBXjzD3%;?MSd-v~(UOZUtU7c#2K%!i1O(CAEnm5lM*gFB~=9xRW=95fJU6Qb$+2H!S{DX@aRbJ(q~i|2+Y7u%n1 z2%T!VlQKF;&gg&$Jf}o7eJ3tzV~8?3s5aNKxNY?__c81-+;)O9I!Kk#0ZuuQ579n? z`z<{s=wFxvPd4@6nJ>s|Aggw$5sf`jmrCD{g?P2h_LOP2;$_Wqsfm34se3z~g(6>& zH9}dA2rQ+a{oc;{hwTuk36|2&z8&ElDYC?PQ!6}sLk)%4OHuI@Wh(1^T|f5WyaMVB znWOvvO~XJdR!r6I#P|Zrmk5fy*P3uC)RqdXe?9^^5P_1Yy(u3+h2imX-^`*RM5MPv z*E*g1%#L&^OMxtVe{U?VAQ6F*Xw_G)nnlt5^8Wl?v3MecnwWO1rHI@(s;eD$d#Q+A z&5mdj0hWsvBQvVn1}z6F_&*y%JWpBjl;Sn;OFN9V~_DaOL{#A<#lB zh1@E4f+b&JJQC*(u45bahMv0mR3 zFTZ>8x>37`HW9773(E3AA0A6WcC@44;@5U@jd1n?dMlGVHuQmvmz_J-F!twI3ej|D zyHNi6lsiFsFU^Tfe=?y@BTU5hpI!?cPKlSX-Kwa}1bUZ>XcN)60p+0E7cY-LUtQ&W z&T&9LbvCe-S!}P(ZYa=#%%LcXhHK`%2%C4iH#MKl_oa=tZ?1{0o-S&;PgO z|AzJvL;9TYdT#C~R}NI)^bTs5zRK;_?v%`ySy!l4{XLug+ATIagryK|c(?>aXsuWi zMAPlh0(s?(dA7{$f6Y9&3w-6Rv2G-_dD{kKER!SZ)Z#?;)B}zV-_c?1I;GW`B3X@6 zh^Be)!@1t5ilgL!2=#69z;e9(YjXUT2g=k*qs`q325^_Z4O2&=fU-x8jYmgoJ zyRWfKt;W1^d?(vccxHtwV!aS!SWZy1{#ciu0w zi#aX~z8%w}?Hh_i)NO2VAUEC1cy+eYYMB!igBGG(ltf?Dd9IrG>dp+bLhfwbLw>DN zwLRQ|1Ga9qOgokx{$U4e)%@CLiN$YZRa*7TvCb%kXu4|sWh9zo%7S8oz0g!GYYAfhMtc3?r^A+`SX)1m&V6%AIhoiv8q> zzr2x77xjHLebaj1mzgbY^EI!ou}nLjyL(>EwGA7+x+CpGHdX56`L#wVMEm`4;-PU; z9!#*&TD*;Ia@4`36+Ws9<%dRmp*Fnf_v3eof??&Cx&Y4A9? z=H6Hvtwp|naFBF=6^<5SDdeWi6u(usU!FBqcAL;ieX&sAR{!y>u@?8;2IPHAt@>T8 zn8X~hyDLS{7(P*zx=i<^uoR-{=5m3C_S5cYnOwA=QCE0#9no}twWf~Z*tei?H0q0` zkegP0OLy2G9PJ~Yvlkn7yjJjaRnrl%4J=cuC)edrp5bt-%)1uUdBeAMT4SRWqPgAp zpI^Jkj&e~FeaUR;8+Mi3BV@5vrPS9Q^?m&Q<=?S*KChWIvt@F8dc3Fd48N2-Q+w_! z>r|;*^RpVI5KTM!mj~J%z8NbQ_0DEkj`#mfj(Zo%Da!|R-@g;}#Zt&kUvcf8YJYHM zki0i(C9fI$xB{BVXhv2V@~mcR)h=Sa8iUWq%!qFC(PpbUdxLAULs$yYlD`*91_%0Af83N@jbIvBE(<#oeRBu}6!Sb7@9=C8MgL1W2tS!arpQtZCPOBoHJCMmn1Zs$Ay5mJ( zonF6VpI4gVQt1~u+JH z#!IJK9jK;zUPvIsuoIJ<&`)vhdn+Q@a>c=Qg?xynGyM%Q&Z;5>WX~I?33EXSaR5_CTjck;$Q{WO>a$wpl2b-_Wq-Yi92xj*E-O+DXTv<<{<%46P7>lIX;% zbA2x}aePM{9g0j&(Htmue&gIObNF`fn7Z4vp8Rk_O+zb0pd^Y)xtC4uq`G>H>gv<6 z(Jr?j*A>d8dQ%*J3x2(LtjBh2Cp%CUB2bd*B@%jx;!wQ=@8JFll{=Y>6yMp58#uvZGPMvQaf6DQg) zzMg8KCqo2EqPV*(MdXCZAz3VTvyH1%)X>yw@MCAZdRcnQS(AF(xZXvyiLh_K?;V&j zTrS#u%nNLczG&kL5^EYYq`QM}obi%}Hm^gY zPp^)U>-KjvEJw77Sn{qz2UmUA$52DM_Zl1F<>)&?&YrT=umjO1g2zXW z`IY3p^fGmGeO4Yf6+#{h&B=9K0R(9?$b;@DD<0+YagmnU)i1^%>?dTibWNMeGHm(40OrVCeyNiu>(&iPD@02)T zFrXG=a8Qty-^%FBF*N$6@CX9WRb&Ch*tO8?Tw>kbohRIknIf-n2(O~6cI=Nyv6E- z-+2X@15qw!EmV1(?WKnw?g-~~4)OpZ0&@@wL7CF+COMDS4rfXa@(v;bGYSf^oDerI nTuHj;=Wh>k^dSQC0}9ca5YK0iiq7f3uQlpQ=a{?rF2p)zP0yxp3{4)eAoBmb6ws(*K6JDUTg1t)>?b*eNOx{ zZL9r%{s|6Z?4!u>;;-##8^?W%8xLKPa8MSDlUKZb3HdxPGo6Ph%Ow_ zx1I9VJRQC`Fw$yn6e5$cOvQ1Z`A|}bW-RXeG;yMRP|oPX$&PR9Ks6t=i@j&GS)qQL zAqnpp|2L~p3ek)extu0G==)k!)!1YQ=Nb7B&Dh9ZNuuf0Hb$$AJ4f#x~#A)2vHmAZ*?A?r zZe%vU-O_mXXsCujO^n^>+gOw+pXIBb+Dt>>D4!JFrU(T^cK;Kjj+#} zd2gw9bL{-YX?7Y**?HQz0?~*#NDQ{}PbW(M1LnSWRcl_Wk-uf=IT4 z?48B$8ZQrg$^3J08CxO-ooJ(tg5se6ao5#|6IsghL|X0WEutB_9$b_kzWAy=@`9QReaP4xfLeEhOttEN04nIDoU+#r< zv7*hH3U;ZP`;BHS)}$C^%gjHSBAo8WofT`gNY6LzAG>8_ekCEo@a3#Aav*bmb>@*`Ql(+NWvtOFFVv)X?xA%=WYhZm;RAh|Pl@8%d>~p!P(J7D&Q8d=K>3{Vwz8x;RWDR! zD9>wBRipcXtE8ZRoRWHy@*zqgTGb`I`_wi*S(i{oRvgXUTEyc+w5l0+;>qWt^QmUQ z`9QRe7?bz&W;q|(V{2*a3Z>9m^5SwDFTV4&?8m9TqB=@hvWV(WsTb5{XoyD zrdCpyDOaHsqE(&9qpYClaa1Sb=prAY^|g!kq7-s7wkUEu|K!}@jTyB6kn2|dmHQ0; zZ&khORu$$4N+DWR`g~R&Rq5MkJMtk~?QuBmiUNBaWfhI6ti08@`FBO0wH}Au8<>6$ zljcK1_&IE;Ngpd56Xc-Xi{iV6dmL5iBL_+$+T&0=FRCn+y(8WIhi5yENZ|kD!W7NnLWQa8HV= zGY`$!n|&MevX!!o|4_Y~wz-kL?QToor&J*$pYBKWNsFhaERAufrp8!{XdSW8t&qj` zwRJVCa1?X|RmfKIjz0`pA-_=eh|g+S-cH)8DrBGZ{F+-KgCFkrx;uKR$dpvNTOoT= zRGoQf#xC`_Wmzw@Ff!V{ChA27*&8a~^;J!N$wWSVta{fh%YQ8$ocl`SIBh-j3ek+s znRC^g{8cM+4pqpf>csnc#Wb|1pQ2h6`1G-Q_K~HQwST^E$D-ldd>~p!fK?2w!cou> zHxjBjtEN3_)};!$#DI9CN7IJ(rQ@nXHl*iu-3r+o1((4e88W9{tf8d*6|yHq)tQH8 zEaJPf_LUo{IeSNBXrqgK`dEPyBTt} zn>ZYL#CS5gydAf`hlzapSPgBk)Y))qzVGk{!?pQ9w2qJ_1w2Qqa1`!Am~}+T{(dp} zR3U$Mu7a66aldcE?Uu5dG-Z63JpkPge}yclLXM!yQhB)At&lx$5ly+aaamDhVDa2q zb>pV3i;O`4G+6`|Hxhs~?oG&K~}9qwLmn z-MTa^A?A#%^u4jdQD7`RJ6&9=9_;*ay@K!L3!!G8Dx(dFz#b5ysZ&&SoM^c^%(*z} z$1p^o6mm0mzSaQo;{M}S)%WvaE;kJ|x0e~?lN@LXt}({`8QFnk@z`+l z)rNO+??s>{#ySU$7em4}o0*477|4zssEM&JinbBqyaq2fz>3+wzNDE}|FW_QEx~7= zv7;+`h{lgHo^idL57`lcni!iLR#$Y$Ysnujay1wK1@&T-VC>Y@@13Wz6Zw|D<&7?H zY%_{~QN@;?qZGzq#-^^XC9d3hhHuQP?n4elpeDvvzF5(j_H;V0{`-^0+0XCBlpY?g zI8ZNUIL2;oU+?@iWEdZLxs4BXAp$iq*82Mj*85@U{MxvxMweZG=AL}ld_FY(CQgNVOtZEqha8X%4{bWa;+M`|WguPpR zMen#XhzQigSepsQtq;Nn@J*$|4P-|IYGQ2vudVskxEj3IMk}WK){=J4lkVC@ORz3w z>~!f!zT~e6-s+)Wp~?+3B2>54NVjIZ!Wl zxmCQ1p?D=Gx$(-=g$Rl+?`0LQjN*6P8AJp{ z3{Mlq_6f(G_reE=PN6DZdF+Uwc;#uLwflQ(vFD{4qUXmdUYX95?%G95;^6d*Mz?gN zSn*ecXgyEGD~}x!6k|M1j7_5|GUXmkBHpAu8}cFAMMTYbBW%e%2$b^wR@|B&nWz`f=yj{s z{Fugz3`)*Us*~*W9_CuLyhcqQN+FuDYZ2pleNWQdZHqybmob96_Bl zg^)KO5UnGE&!_R<8w5vJ-j=NSf#aql_BBnEr^w>vua`$qM@Vtd3Ap|3k5TeO+1`3F z%GNzkT_4Ne9@07IiIS4C2PN9m=LV;lJp&Di+c>(q0eANP6$dW&csF=2dx^TdCqL=UE?7Olcj z&=D|$%zyf3(`l%W;-j*#FU3dQk58&}6L}q<%V|t8kz${eG8S#~C?--QQ=_|$at8XOBSx){6}2mNj^0oC1Fb@|jsVXy@jMF8pmaYde~4MV z;*2gbe}LyGg=o$5O!OA{5bfF&c+T-eiE^!)kA+m#=p2-t#g^#cobr^NDGRIlkmrCX zg=of#S56R*-I^TThw2hUpihX_t)i+=Su%~PKB|_~Z+Q}{b5MOHW^W#oy_f1Ms-u)u zPg4DfQi#?#jHSWvS$-VN~@Y2l}KVsCpGqmj{O}rCQX_u1=28 z668}Avgqv$-uS6oAuB)RsV?#%nz4>_qp{S6Mq7R|k}W*1MZM^ss*uI1N;#WlO-=Q# z;J`bklIrwRG9=VHcKYo+AgM8LRO?q-b~N zA>YskBKfxA9qa?0i`h95RZX-6&)69271LFOkI0JYobn*w7dpuPweDQs#Kdz3B2W`! z-^Gs-6OK=}pT0Ch^8*p6iLqAs`Hm5C-44m}rU8>HX&RdsW(N2-L*bZ&A&}(4wFFdM#+Id5#>YiLu3VhB%3Rf40wu zrSfSr;(b?-CfjinGEB4tPqXNhto}@=|GtCf>6s%nKM;YM7|Y$Yz<#N9qIGRYn#Q5) z{pa+I?q%#*V15>oXqB_mc-EA7qx`XCdo5W-&$D;NhUZ3%ojG#WJV)ntd)|4XX5VRV z)sQD+Z&f&{A#_dM8&`8`pB$%d4#c0I?|UJ4;J*;Mrv0}r*k!t8h%5V-7`li5Sfy*K zHFt>h@YtX2@ie-~j<(~u5nZgw&$rGzaorB0Rnp_gF{60N9(JwolT4Jt^A@_(UT>xq zDh`?e6FwWkaGs=#r-EuY(Z20$wlVdTREJc9ooVC zq+2ojwdkrQT8L=I%13tPKdo6DlQ8x{jvR>A5k2VM(&euYY%Wg`jv|>Us|?v^KufSU zK=(yA4d>Mljoj3cq7OwJg$UfC4?i%vab=2Eh-QqJN#U8-4sIXbd977?>j?ARxwmus z?bxbGN!|cj#dbchG>?$69j!t>og;=N@zdFHx%s{KY8*HUI>LWrD~fJxS$KN~YX+<( z)NOTnyDge-w^{z1E+*Y>^Pv>hUG9yoy;e{T-PqDN5P_P!yMxhmcaZz`J=jD@o1G?#=?bUD>Mkk}C3amBLX5_4CqFaTQpeFYQ_A3)+MbrHf?!Sd#(w!0; z_2RCNu_bgPWq~y-M1JLeL!s4S|}}N))k0+Zu8uB0F-RCht8Kd0*5*U1$mR z_bz?B~lc@?d#ycCD* z0qO`G6O^JIq(aEfq(WrUUQKz92;@UFWBxt^r#{0LoO9Gm`*Zaa$Zng?fe7S7wC)G4 zMAS>&5A`(5-kH~#;MAGeifa`45bbp)ICUnrAP1s#glm^OR`}GSCD@rSteL{5M2-J(65XKI=9eUp7>*ZT83!@bF z0~p)tcAfdug}-PBv=Gs{RhYL?FYeU~N1%m>))Bb-MZLIJ*AY~C*|Nfu_uCPHnsfwK zMd%Zvbp+OMh%Ov~>}Wgo0~jk)E`|R&@j$arTCLUU-IuA7{e0f-m>N{c>ecI0spGlT zc9J>ofmrpf?)Tw~!sN~ir4UVT>JcLDiP84r&g+c!xdYA4wEL0>tdDzL`zK`F0T z-Dmey9tL!w6r!nGDx1J>wf-SSc0VvrARnR`dm*|jZ+|%}H}>@hIZDMPcQ8wJD`wVe zR#mf*-r7p-&pT)5S(~RlwnKW}<@|g@jul#hXzG5@SaoY$%@U=;nj-?o2hogeZ_X`=WYlTF=hvynSAY6x?k|Vim@P+^F{M=~ zg=nf|s26i8xulUq|3%M{57CUBsF=W83@fk>tiN!}zYo)>$gh_40t@GJQu{Xi*1Gqx}&lFPrlhSV|;ffgc~v2Ar{ zS}k`SwBu=iPCXKN9;M#S+)jOsrpJ=ax2dn8bHprMY5o0u3g1_}l#lueMhBXAX%$K# znqDQNuED8l*UiVNYk;03AEFssI;gM zU|IQ&&o7mh$gx7J^3vmd8)>9t-jE%n!=Ej%v+pE0e>iCz-_+Bk&?<^N7IljFwu&*e zkORjJ`6x0hSZTF9mm-o%x-%H)En!baj&7j4LpzoR)vQkrj}xI&`y1GGLWJZCXrkMn zw00+D#f!D0+_ih-a2q?YN&V+2@B+kZ`w+5ZwX_a`fpM81NTw~kN@63Do{^9tz zN~*|e6>07HsFn4^HzV!mf659QHtdv%Xyl_@`*@nD)2NE`TL0FT)EgLGMC*v^)D!JW zxwh@q@aEXTMzoG#Eyjo!d%WTl>Dkjj&k?O7;%Tf7em&Z3U0ziH-srxwd4!$u^X-`U zU8>6PMw+onkEDpYoenjd+-0qH3Ly0c&J7SvJ^c%#1@GF^T5@>5oO6%EsXfU4z5QI{ zcE&kFM;yC7Se$&WQ%sv7do>P}LNsHeQ~HY~hw`k-KRhC{v&Yf5e+RowzhY+X*s7+E z2y56?Jil>C?%>G}a_UX0I#Ip>ic*MXtm{Jw;;UKnj7aLFA_A*SL{rTW(n5UDupXaN zNO?%SRGXq9oAdf~`{BdsI)&spiLKcB+e z6;-j_7s$?-KXj|E)tu>cS$EK`KYJvnPQ1LmVahkwQ3}y2Qaco>`FFEZWtHLCP8q=C zLo}U#(CHEjxo+M}@1t>`PdXyDK{aRH;c@)-`~78h_Vi+g)2-?~cZl;q>d)ph%FdWM z(I*{2(T7v?u{u%op@?G!;uSr$Uad~6#|%VQ#wfz^MXe&8lN8}7s+kv7&GpHchzQg~ zU$!YWh@Xxv@1#%^mAV2E4iTt{Zbw(?#8=ihZuN8Ht_gA1vjpoo##(laQ*xjsSe?;V z3doOT7q;w~+HL=bUEEhIQpdYFde2?xLH^WL03!5rKTVRWwdwHE|>o z2i78p);T^4?!?8WVopdgjx(TtV+pfneAg&lvTlZHSk>e!WAc zS^mu9{M$L?M|xSsfl`R3vHHldK3<+}b{dzYAy5jfW$cd+rdv1ZZ`Q@Z{IP7q95Kgl612xU z`}bge?C)8|)QUY72kONqn6X%a-nH10O!;4)sn_i4zEVBG~ zXGi>8%Nm@-FE=e=FTP;>3xS##yLmj^={0Qo2ilIB7z-P-!8vy<-1_*@B%Y9O z*tH|Pwd+|zE8p8+(budx&UGdh9dA_~lBD^8wxcF`A1Anzpm=3fqj*Iz%G-HSWUvF( zfX-3xyW*nAxz*;YZuGIgZQwq&D1~UozPaK!UyjW-PbMYtCm!r+=O=ox#Iv2^n5T(O zM&I7x*ng1cC3Vk{12w5iMm)QriX$r-8Ic3k5?X@(srpLD%qH_7A|ywkIzzOI)Pf?l z?T^$pL~3oU0%#R?1;t&{A9p1KGgy1JR6?A`YsroU!+Kj(j=?#dhb1WqoWJ+bKGG@7JO2I^yNX z=f#Zw%cE%yEzKcI%3vGj(2TCEDc93rMDrDV`wj&>+8T<2Q6X&ZU8=Q|R z4^rmzIM62@A$LTw>m@5>;_$keBxMBVL$``Dr%9R9@n_DcQuI{Gm55S^R(k_k>Hll2 zkPp!+*V>e89hqw>r+OUdla7$}G*#h&IrloIG;3zyiPEj2>}*kXcKq4dxKYfT56^Q% ztNn*XJ5?d~wP-u7F^^B@pnPspK6h?WKBv6xaiC8+LRR@QI>^XCPp#LLrKiXYL{Z%; znf+xI;I9D85mW`p`9LW|tH>btwSnm4*^YdORuzCn6@Viv0Lt{{q6>!NK%aC3RT&ml z8IG(nsG9JsLbQ%3NqeZ}|HO8$Ye13H>pAFtP?cewITr4$bgK-rW`q|Ly|F?xV{)f0 zqk}(3d812N)Z^1Rs4lVIC_3H=p}K_X503+V(h(Ql-e7J2Biva<6#!*=^K7D<)ex;) zMOB9N-?7=YtTJ#{glHW>XGO9bB@*VQ8hGCrqXb4is!JBHbh><>BI-O;%7+NNHH&C< zt|sVQO|+g^%fK7Ts2B4JebHfRNzrX#yl677hz}9ShiE!oqMoHStiUN5bT9^QbE96Y zaOnGq^;(DnHR_2k9@?3U2;@UFV?ks3i}ba5PV}vcJFx$aXq{t*Xlor~s~R1FUn#(<7}13zPzt$q1b#aKEx{V4a0Kc_bm0ipi&c$| z!0$|;6xI)gBhV*A>j?Z_2I|G!UN{0RM6`~;c#e88@9GGQ=ZHW}Is(6Vf(X>4Bk-#u zI0}f?5%~QQL>G=gs}Nl{0zJg>!Q8H_%5-hZ-i`hr# zKm_t3TIay;`=DOTS2_nGkPp#12Y%TI^y4+ne;1<{2g&=UNT%6$>aDvAbP&k{R= zXrX7-zx+V-zYv)&E|cT8P$-^z-C^`e$$AL<77C&ZN8mSI5M4L|#|P1cBk=1fl>5A% vHTvZGd_T_-T{r^2oMT+o=37~=RNN^(|2ahnGW?Em;V3xQ!c9zFI+fm z3HoU{D@pz&E~E`Dki{q>vPk~h8W%yr}x_Y@AAfl{hVronf)0)M5iOXcZVkMn_M%qNJMjrbi}nbP0hi7&+%`2ZM>!x zqIJZ-w+>s)JA3#2H&wU1RjCVUY}56CO_&S9OLizrYm|TB<2PA*>3OB2&3=1!GUBJi zY|)3ZU-G?4h=c93X}POQ`m^2Onv5urRx-L$|4SZ5%xgw_aZV^ZyctW-wN{rjYFd)L(_ba^Ln?dEs$#xjR30^6&Lpp{Ev9l|TjNYp zx11RQ90D!GREQQrwn(xE=lZqI(%VN&tcl2nXd&)QO|mOoo09q$m1L7%7t>g)vgMwd zWK$aF+oh6EO`XHl>gt6;yUJ(J$U@lPH%N&vsN#eymy`o!6DqIP7I>mKTt1znM5(-XzZqfiFDJIM(ON|7h<}g%scPb;GPhGuE3{Te zXsay>_=)tWC;t9?XePqiU|%lTRcgf6Lk+>f<5uWr77 zBZ^v%Y9Fy9A8H&_Lsd)L*^P4~yw);>Xi#!lG;-*vbPdychARCpsW!1@lFp%Xw_SZf zmEfMHx1unw(DICu_?^>>{?Pkx59igBukULmh-Jg6`9~qVdY+`$v5b;}2tjXDJ8yFN zp^0*_E+_(*gAqZk5P_1OK?FHaF19owj@N3pi|rWm;?rF?0$?iaF@!jIc~KN2e#v|+ z1rewTqMy+!Xa^$PXD8Pmzh6UEFcVaZePzWR->!L?j1AcynwZLc<~(#cR86s~T|DDC z-z}diK}z)upIfpDPw(jL+4I5J9w#xSOf0 zjIG_sj*FWfKecJH?_~X=My~o-b|6|ue6=7#&g~Lszq$CO1k5W$>j)>eoZ9|z!&pDp z_J8+glI}C-sEbI?UEjncyI9^MCZ~FH_9M@VArG`vh!)~ZD@)a@X_1?El^xk$*MT}1E$J=3_wb8V~T+k6LpRA`c7lQSjvnJ0o zmb-SahMdmHr{^IC6S_s}eZ|dr=;oD;shx?oE!%Bdb&HZX``OcQF;VO(87eD6^#c-cv^#n~1<%K(r98qDOI0ZGW|J zP!#nz!Fl4~n{TNWH7r-540Fc6v&JYp{>>Vr-mq3Y7e!4FEkrcg!8!X)20IYJ&#oj+ z%Rf#IQ`ss_I7hpl$YyXE^qd_ob&lp+vnh@b+ICTIHj!4WJElUk!;q1K+cWYZT1Qad zr?jfkP}Okt%xE3a{@3?on4>`FYbn$_tK4n&II~2wj;K|xpz3!w#dguk1JOF-f0YNO z;%7HUbUUJdY^ZW{QM)H*x9n}yv+sJi)bnb@$1DA(=Uh#lQD?HOce}O0vhHO_g=n4Q z@_3Juo6~w^BA?FTV4O04Kfbm?aG4|eek^0+Z)uKM{{8m)H@WlpyVO4%Fo9xwiuCl3F zc$n1lst$bHrG5B_2PHyRbH*U93m$a+NPdQpL#*+9Hp;~m0OEdOzSaZsJXwwTBX(X5&5-L zh!!HzuB12~doOF2BcIN3X=6S4<4@<~qw49FV=CkpBDv56$@SO&X=97oxhG@YQ4{17 z!uV^fLezahw*wIL(+sQITe%?DjE{|Q3@`^cDP+p;2EPpi`$U_mSdsB|;S|I`@ z32~G9bhhIj_3^1y2`Mr6n)t3lg%#qn9yM_ONky#$R-1KP>Ib4>S_yph{R1j^O5 zVym}=j<<8Z-_?v+amRCjX0Kal_KI?`R}$jOv7aWCTR71!;ICjtPK-59L}oU!*3l6t zNr)N$j+fU)R4ttushoXIQ`RAg@`duT)-{z*IPj3NeWKsn2Om<^-)CAO|8) zk`Uuc<&~ws35(C2*iKs`L%BGM65kvGGQ;QT`D?*Rzb^Ak`N)@ zoHFTFM>}Hn!hNoVoQs%0_@yUAe#+gLKzSg-ede4-v=G^gOtdE!uVt}CFZHcxJS_i) zhg)Z!>a`5lO6U2&dZ*RC@cATrru+23B9EiYFoNt^i{m11%tuPg$h3L^F$-bTIsMYG# z=y=S}j4ej(GfAj_2kTraBAu3321jG%KXb7<=xu zv$0&J6{^;9`qxT}_TH;j%b30?^G@AzPtN(3N(J&tL`CVonGtS zu`%}iha2Ol|4==g(}$+^cWh&PWSU!96Zr{_aC5`WoT+>n^ zT8I~YhP-vYsy%Jv?1Y)?p8Af}z3)k*x{G`|NBvi#WaYiFcH617wbemH>xl2?c`KRE zsU?^SwWTk}aY^#U(nqWXBUR7fcgK&jg{%2#Wbn|)utT>abXnJ64_9Pf3IC_@dp#X` z&eT#NS_o=Ul3P@jgydATmU^NfpU!c;c-4(%pOd?o3b|>&_VY=SMm04K=B{4L&*jb| zj{D62uWL0)@2UONQ+ueV-hrtQP4Ws)lznNey&O7|dxoIyZYt(Ov=Hw#t+>(c6H#AG zMSXsdTaD*(5RGcAZ-7IMeJ%(8-FTuD0OdASP+B}pN?4o=q!HNiUVq%F65sr6yV8=4)M3R|!cDNFMB z;t$ogv)?JF5bmlorowe`A)1|@>?xP+h*fcPlE#4uw%nEEXvI0pPv=tn!G7266Wuv{ z`b>ZNxWnqr${?F;;64gor=b^ zg*P<>N)jTW$ttVIlb6g@>xSAq+hzpM!f~#S8q(_dD}HO;3)9VqQ(x0K5UnG~U@u$E zwhTMp!1wy(nrf_dQ)L_zowUxsUWpbW0ww8)Q{Ol6Obc-E8+U9cbZ|t~5kkDbYaxy2 z88yi$$wldQAV)??{LU%!kUXi1{ne-Ht0<_6tCjQ3=`t`1+1*sE;kPONAlgm;EC;4S zv=BRoKQcWZUpAut>Sljd>!`=ACC}5)(duH&Jn~6{1D;B!+Sz4SZc>QeV{e#U~$it&Gqg5xy!3>oYRRL=?gOPx3oJW z%h;DTG|~_#7twBc@NfNF4dqhb75q+g5EtL>XYJ}SPUAoX^IAb(j=o+LWJ#JYA&Om zntD#pXLaxUct(b)5dExHul)0duZs*?9_0A<*liz|EUiFV13g=&^)oAX8utu`n+o|f z4wbuwFD{PccE_nO7szrwcfEvF2-FJE>4^HyH;&{P8O^B-n&bLtjvIm225L!w^=U4O z-^<9SYsIykbBupDf3Rk_?T-KM)-fTrE=ZKVKf~?c`^`6T?G@Ks8R4RZumigQM`^vC z-|)&d_Y8>E5ulYS57f#<>xdl}Tgc&Mr||85ldIJ?K0EiK@#&@~Ca%ikDz^|5@4YO~l(o%mtM6LKfoL63X+?kec-H|l ze^{I~b961m@jT02n}o>MWvG0)`!uu8x8pSg^67RIsXs>cUp3vlHn7m{A7(}y3o3*e zk6Sry(3Q)1<>sLf`wsSyTi)Jh&da~WL_PWCw{YGO&&kX;%DS@(LxlmCabzTd`oSAGuk&;8kyODv-U%UKy*4{ z_KntQ6JF^hi-+AdThiV{^1MubK3S6yosL*QqgwM#_2sg>oI|C&b8XE#$jB zkC;ow{$ZW|qolEPda}puecUo&wA&NWTy%Re86v}_aW2HhQJ+(}2$V!88mC9eLVp!E zo0+xjpC=20*Ny*Z^^daLMW7@hPXG0id?hB2>~k`Qjb)A;C`pLX7wX8rh9{c8cdKF} zJL=BQZvRN_e0?2h$0u5MKMW##uH|kjM!2O(rz|#&k(Cxru}c4AMFcp42(AbGqjPxZ zD>c)JY-Y_e`*&nqxkC;ItNta9%!{U&Jufy($Y_U)KuL_zYdhAZ^;9d}aW~zLtA$(0 zE0vE}AM^^AdC(3w72DyWX{Va@Sc={}Y?W=?aW}WSW9MEB)^;})BV2AO!E@zhnc2DR zyOp!s8>yZDQX$MQT0bx|=9`PA@_1pT`Dvn%I?GiP?2<##U(XNKN9f&}=XkTzo*zfKMyLpABrd#f?JeyaT3ehUP z_tcz;vdNl?>Kqa4%XJA;VSUr>Kz$K$lukXdq+WFDNk{Phsmp<>5KSHfmlq}EdNfW> z{J5K@6>5TgKJ6|=Hy+MoAK)BO!jJ-lts# z1Zs%2(m7?pdCaFQ0_PRQQvH}bBJ^t7Cx@)Dh<;qvH2r)e-1)==6@Jy1#2 z_FPjhr)1=C+X_l@PFchh`MEZnvhefS57Y`J36Y6Pu*{wVR!b^D%qv6$&VDFKv;w&> zvpqY!tNBjD_A-Zg+rwp$TrXT=z2b9ZY#*Pj(`up@Ya*sXv=F~gt}?C?^(mZ+Ian6* zA)5Nc45tk_fB3W^qIJaY9~a~EKJwQuS4WXnKDT`YP8$Z%njKzuEJOs#b^q?Hq&l{% zo`Fw5D2~8MK=sV25UtV&Irw}5v$OvProucFqWtyP+N@RRiK%<&v;g}R`2%MMgM5e< zqQmHRynin5&R(9vr^gw=K0k=o5k;@HQDXn7 z*Q+;AHn4gZjIaiG9HZ4GMC*vtb^PYwU#6R)|7&tz$r*|x=jJepEfx7_Z({i<^S{mq zth1H-YFZ&$N7U|AS8m>2)XY1wocy}zCyHanANeJ=ZR8W;RPO5X-GV+bC0!zqX?+QD1kRNC`9vC>dZ80^RMg(GgNK@d6K3iSrb4t3YwVG-LXT?JpDU-D zs0pHV1fPeyG$^$;pNGR<2Ky-FbIz)94TQ65N-IR`h_9ZEl;htSZjCBi&lly<4M??$pZKE-==O2et|DHD8EWKs38r3HLkz1YX zbLC==2(f2%b9tyxVY}-a`}~MN4Kd$@D0ro&%n?1p`tNd0nQ(oj;>cgBfL3F$E(pA9{7B;PTS*732DU1AA&EJT=qZ*gi?FjffC`q)tbUD#p zJp7NtWwrNbU+7>UZA+T)FCOX&maJ0Q`?@Vju;u9%r$42{qGsFB3>5D$2 z9j<*s{5d(vPW3N_sZ0+|_ z|1F$iEud8#+$X2i4-K7;FzA%txzDm$b9eOFu5@Qb=?Bs3??KCHHOekWD@B|tAlJir zf@mE~;l$5wP786ja0~mR%16v)&PtJ%yKX8(vo1OZ<|y*HXzJPO zjj@M+GTl6QaR2VLGo$@~(~5AWK)ph(Tu&<@J~>z3ZZJEy%vvS8jfjl7;G${P=S{Nz zy?)pnv^-MPL|#4T_JL@&Bc0>VZ${W7XoY@GOrqPD7~Jm$+K0h?myURS>HvG@(1YgO z)Uv8Yxg3}Z(OO=qo&oEUyLZEAHxHjhxNVJ7U6}pIw}$-u0*K&Vkr3s`6EJOJlBAs& zmZjccDnviafm$J-D~S>AkJ^djb286xAUCHD){wK{QjgC}`dk{mCNn6cz# zYSCIapVP-w{OqEI82dpUU!^1UrT_18vKF1cDv@~K$7cr-fs$yy_Wh4Mdp4{#JM9?p zOkTOUi;^6x$$LPu_W;U5P26uzr>CBst%cp8=Mig^v)-=t2AI2Ut_#s(doepyhTCzp z-j4l8;G}}zZSyW#h`Q6G?63YTZnbdM+x=J87W4CZJ8R{pLNu*%-h9a(P&1F6^NSq3 zLLWq6?~G{L1&FC*-#r>>k6E@PZs&;-emXDeqw}H>C>OP*(YaV%@LF8RhL? z$K|r4cIDK{<7oB>|4#>s`193yU}D+OeD}3jJL2Og+yC0~G#qO&6{3YG_Iq`^Ti?H| zHB0kr9D^EER^|Uvzx$?+h-)&<>NQ}D{b>0pZ9Ki*bkGieZF(FJ4%F(K=srqr<`wChFggQbXSlg##Fz2?V<*YerTQ4G)f7TJ5AAU5PYmZ-jQ8XC zNtzvq&cLD6QhDV?-SZb)rShs^>w;Ro(e4thS#JAkRBU}(vy7n}Ra#MwV*Vgnh=r89 z)z)o^;oL<8YvSfKqJ?;H!cb+N_mmN}sqIHflUK$Rl;b1!tG;Xd%n+$_kWZYNk=-TV zIDW%&S$9l@XsrYVT8?~(7UHwOYOO(*BL~`~Be2Y|eZ-#qO4+fmaSqKUArAcFe5Jln zC69VTXT1DuE$WVFT0I{hsajN}kOncRJMtk~?MDUkir=^#Xp@fkUv_ZY<~Be7i)>QY zDp&pq_Q6dh;?L)8V!r?NSBm2>S&OLteTr8shDnP>4Eu8G`pqFn4< zSsz_1M4*P;6R{+UATV=~Ds#r-i0nS|nN*!)JDo5cSwF;_oPNU8&nHYV6{3Y`+O(g& z=*14!fTgw-IFqUnXcMC8T*lO#veeCv^6f^-3nDnn=rVt&k9_d_Y(8~SeMr%SyU-wL^;y_ITCtCgN`6fi41m)o-yMAyzg;J@Wfn{MTL~{=Dk5`fx z-7bE^xyT4a>xdfUOIGgJj*@YxFQ#&zoo{FI7%|CXM1D&iBWSIjN}Xs`vnZCV&enQa zGn^su3p)4u%v_7kOmvuTHM>39HkPz88jr2yKYy)=zigJQ+Q^AxBJFu?K5P|@OtM=H zZg1cW0LNOCL}%z%t+kGRJ;;t}-`&L3A(V^#3Mt#ajg``4w0$&3tckJ^fs$zTe9ml( z<5I1kGuy<~I+Tn3m=H?|F_aK12!XN?fs&|aXy0Ag5wdEn#({FN&ljTXlUe@idxzQM ze&1x`N-CyuM@}B8$=7+s1Zzy*KKA;!;~EDdP!g9c|2SREj@AjH3K zH8r+37;c|xwb9JDrpxu1H9<7x)#Ks*k4AO2KTpW6t)8OpD9O>u)#}yiGn6K^Mir6` zOU`uWKC265;FyrRw7IOq5WDeD8%$iyMokc{bD-tOhiJ;(YYohgUTS3*-}ZvGdXA}( zTjwZHb&=Bj(wYMD$hgJox#Y0|noU9!*!Qk^@W`4FumHZ)wN zG+EO&pX~q5$LhIh|9qN;LhP>jzIn6XaQkWTn%Zs#YJzB;12sWDL<`a6{$cY--H!G! z`i;4Wscy-GMD`Coz`}#2KBVO!c@qu=M~C5_tH9L zN6h_Pnoaag@Z(7{`q)4_w)+Yn%0k@{t#NplPFSPlTA4%T_d8ao=h59lq>jjaW2O1( z)ZupL9#{RiGlr=Ut#hCq$cJb;8&x&8+<&*7y>RlI+D;s%LT;U-d(?8J`>jzSGSj5_ z>bY6j?3zt91MnA;3%`u8dn8@Zb`()}L~9%Zbw@r#lQ((ARjMZLE4M18VzYTllUYr& z%djmT)uO&1|J2kuuG6^Dk;acZG>+g&7fgj{T`SZC`4CNh$a80#4Tz)W+}RfHpJFQH zrcr+8Msxl0LH74K+iQ7+2$ZC0l*6$_K8QPZb!Y1ubRznjJ6AB z3%9zrjy8UvIm5sSdMZQYh1|LwCAU{q zy4No9*zDJ!vU=vzzq(dmbU$p?p?S&itsnXE^dF`|w8kM&cjQAfo!`we!n{rXwHrcz z@T0z%3b}QT^Eb*X-M_i{z&shSqaLmM=vw6~HP?I+H`?ymKdR2d;t_^SDdM-|9%!i$ zt#hF6$ft9(vHj-fp?&SmjV7C@FQ!6njl(q?lsw>F<$@XJD)<(LZ5v_>{( zsp9yf=%C$bE%G5+vz))~lveDWS*i+_YS`j|9ZF$_B&AUD1>Fp;^?+8qV+6vKrVYF;AD#p(8UddEM z6rESXAa7|Oc}r_(iZUHjNB&K#=WUzsj>ED=4nzx4iXyjE4}9IRPrmy#iuvO{J3evb z6>pJOyi{KCl@`^eI0Jr)GZ4vn0^e$?oSg5$KyG<6mWM0XP359#7u=d|k$1nmMc)0I zZx8V4=tAC{cHdha<&d`)?n65ets}17eQX{-H^6r?v4`v1=Vxy~Hx*lprAb;j-hdwP z22_ZE2cREf%cvSdQ3_sCF>546(&4Y|;P*LlAe#KhocKO+Q_V8F&<;ePBq557D=R0K z3%B+f^)x$BcdVg8+zv#{q8N>?=cH=qmc)+askm4 zJ9=qbg;-H2pUtv(6^DCKl#6|rt`#DX57D%{v}&9j6S_SvIcFcs|4v!Ov6XsJl#6|( z5KHE_mH)Nf9@n*OJ{u9phiDdOiQ~_8g;JLj2O>~IM5~x>$_`!`W?5_p&z4Xw z&gW=lg7QjPPI-k0N6AghjA)5M< zSH{YdU8}^`C_Bzv+Gv$3!A1jMWgRA)lyM~wS;b1^w)_3_uHhLN;a@q@sqJpP!WtvQOgf#ni%#kB zX+1<>>(Xoc-8KVdyE{XziQCs(_iwLM9J{{BDN!!g7$K(SswPXN6|-kWeWxLi57AVD zpGrBhO=UZ)KirQTC>Lvt5Zj~rOLOvWtNZ%?X63g&QCgM#Jh#MDSeim)J>E}#nfWVg z(4S{C4n&|NA>M7(ULO8-gjHzIQ**|H4~zuL-47S!*J>q}CdH;2Ys#ouCF~o`W@uWW zCMb#aST1Ch7sr&f_bx6V@eRtw@~4;s(?2)op4@0Pr8vSJdQMeZU3$HcR>yF6QHbwz zmzBjTT(!QW-^hV-QIZfpAIfi5{%EXKV*Mytzh4u@k+LsLtChG{D8!qKrknMCEoomH zX=qxZCMbzKCwr2A;u5dbJ!GWp_EU)BsNTp~Z{^m-`=_{%N9#WQ()?GZ6}12Qt)-?F zYJ!r4n0NfPHR-o3_9scP8VAb7JvNH>PwgUw+Q$rPC*wa)@o|e<($(49WUY7y6ZgO9 zEDj-lc3PAy^yXR**OLFrJNukL1V|F1DxIyJMrUg;(b-zm7d1giLTscHreD(u(_(bO z^z~(Dd};ft`wJV+P9?W<-jBrnFCqH9CG9@H9JDr%4b|*G-BA*q1E6!3naHDRUZFVi z%Dius<-8Mza(SnT`S|Y?A8yDfyVWeO)!}G}iLwxZl9aEdU5rja)I9tsncr|;xjS*L zT-?n{N1W~01 zf%u7jj_5+`qN`Q>M0qQwls2cvREQR$4q44J8D8}Y#CK7$P!mLR+F+~~I}nReArSox zfJR3-TPPq#D#N)n<`4vO3Mac#ryHC-zYaQ{wwclk$KxocTgsYQLYyh09?M5pfWpI4C%uS|c_#xE?^ z(A7k@qp+c3f6D0_>uDvJ5uILw@3m=czOm|U|Bz|pwJ$H^Kr}`1Sn`4ydnv{qoDyMw z`h~6XD&_Z^CL-{giacK)?=kmLi^@wai&MFIf(VpE@e_|^kv5&#j*f1qaiCoMrlPpD z)ZhM1y(s;*|7h@{8V%Z=yX(fqQD1uag+wtR2yvMZD6-t)34YE;n?VYVB>=)mm1lijhiv`+GGXtFJrOiof*mdxzGqCiRs=PuW(v5hFAX zl#7ytc;jw;dGW~sYq~d^{nO&w%JKtwghaVG0~DfUNL$&X?KJDdh)g!hLIg?@f_+Qa z$An7|-=JKa0n$kh+6CxMEtY;;h$x&q$LJIn?caDlyR07`X>_FL6Qc!HDMcb~CRz$bPh@iPdFqd86foTK=9%k4@x5v=BpX^e{8u z9c^De`J#rvRKFi8rL^j7J2yCSf8y*SvsSDxk7}3-(L%ghGP^oW#ph(u4n*sSRLZNq zlvimP@(OcQxBTRcjiyDr8Et7d1LxG33eirV7_h_p%84|UyG8D2m#874HH0`bdWkBv ztKWu5MC*v2o?LRxJi~5#;gp34OoiG~l>cjm$cJc(nVDQoR{o)m z9h1L=hQL(2SA{FB&hK~bd}6(x)e2J~n)c6^j5ITm&%ufoUuu?P{^)iTYab=oQSKHj zTtMqfu+1ZyRzC)=G2rL9d%2G}1>J7{IJ+?~~+w$#qsuknA` zd!)Ul?S~oy=eWp692=KelTN&D&!^wWfpc6$Q@p*T;r8pbgvNnr9Z`*PwF~9$t6V&MSV_5$nz#w)XT) zvO}l8U>rJg%-4#>+J8#rcn0B0qOa7$k@l^G>2)fv-nmWR=kVRHBb?gn^zAqfB3ei6p`Pt^DnW~SI$Rw<4n)(*WkU2J#Ak$f zWwO)v{p~NHty1WS^ZVXa^Q#A!c12YyH&6B9S4$U=h}IEk$Ht;7)C{0l)liA4&^{-< zJE|4TyHX+gt;($-P?8Xv$Lv)-T<)_cq94{@s?rz;d4lVg`kLkJ_3xPfHXC4nT6CF-d4gyiG5Bt2GkcjK_R4b`P1FR@ zI%3Z7ta5D04tDITaVFLuTsKAyg&6NB&V!C(WjR4z!zox7>&A0MR<)iwCLZ&dP)B^9$1q)CAEwqIrweW>~)AcHe{7 zG_A00qlQ}D6nt(-bV7i| zOP14j@%zyfb6K4)(NAwY2SLD$=iAfKEH#~@Gu;6?GPaSt>fDLsr<`wK4>#yvjc9e}i~J|oQL_cz`GN?H?2l+# zHK03RY6hbGqc18VP?8XR>CP87%0GItA_67R-GFrGONjsnddQ+&tkXgizMf-4HMQ=Fv*5%!iYadP&emlCLss@BP^ z7STH55#8YyS-X*JPIne#-;QVBJV@ z|KTD~79vm*MFpmtHr)G)@D0kv+m+}P()%@RI&ZJ~M6}j@=C+Obruq_ZpidNh(;N3P zWy?J^G5#5%bp-ZTh}IEBSBIL*mQJ#3n#a@7a(#@#(I>~MQ0w=PCfSwSE{MhQz!6UO z&FcMlnt83$7<*k<-o1!GK19*G99&2O3VFt1`b8eVyPlz11ztYa0BLXE+#Kn$9?167Z**C8oH8DaD`mUjm znGow=t7Xq3#J-C~wD>-VKuP2|`Eru|Ri>lnqOz(yg1M{RW24<&L+4)Y#-n0n!FNlh z1|l99d`1*+96~hR=HWz*kSm(0bFV=TMC*vx9#6BV?n+g6@!kx$6ASsM7hN4{QHzoh z)S{>r1@HgByE1gd$ks#^DbW!hjIh0NTGEEwMMVoiw4fR8hmCua1Pbr z^QkC_&H*e|zTxubx80*DMnW)NIHp3h5RI>d*}tsKCncS4-%0UHIKucbdHISD%xIOs7&gW z&E8r(!appfh_RpiCJ?P77T&60M=W_keo6fm#wJ3vj`+FaIbOw)6Pl$&1w2a)j%9&b zA)gQ*&Dp(^5wBld9mVH8XrJ8RbxK5_B)2zpX8Md^%hlc;+!BOn+Pix%E3ZaL+Pl*@ z5UnHXhtIWS!e|*?=42H4e5l;zNFk^@<^r9e@7zVjxhwZe{^)?;uE8-mPFDv{ zD%xAks4kn41JOES{@L30B>?YqnPo;GN(kej@bPBCbQh$Ve-!7S*|yr!I3-> zts~wfZ{O3SI?JKt{mVXzt{nk?K84m1q?ecTihrLWzf`V?AJEy_E?+HG&tpOhX!%Ar zPLa3ost!YBKl1)%-%#e@xSW_jh^Cq4vazaX$eXXURvyTQXgbA8-o9_W)JiTR?_cCV zn{)))(Tco&*^Y0>>vz(BbJX*-@IsnRR7=R)_s5(4WdwQuA_wY@Xkt)5POC-Tkq^;M zayNHBCZB57sv7xJZ_GJDJ$I#OG&+YYQPVu%Z@4TQ@xJoN<=o}?qL>QN0i~Q06sQUE zA(~b{$lG^u-H!5H!0XrLz+BJ~#Nu`Bs2pjMj;xBhBU-lubw@r#)2U+e_Pz8@YiW`9FZ;5)9PG*L+N2{K7N@rJnjV)2 zpZFXeLZcf!SAHQ}vx!FMt}A>^jt!LE$om&LPiM%0VVZ_Qd`SMmh1k-sp<7GP^RLM&>6XpKXlCdh|qA-*90;FWjV$?$5qRRjT- z19L$~VD9p%QnrInu5z>me&)zMx>nzie{j<;BV;1^3!@#F3emb9s5|l@npPIaE8jlZ zD5SyeKr|bJPp;yqrgJQ(9W077A(zn(R^S`J;JCGz3ej{A?+HVV&UsE5DX0nZA(~D) z(fOFqmJgDj(0Lh-S;4vMM!I!#T1W6113GIU>9?j8qIE>xUawkhZ;zI%{|s|uau^&b z1a-%eTF>1;j2(kx6XC1|(K-UHMYN9CUT3*gBQi<$el$eW3UgXVwCr)%+V}M!d2qx> zDt-y)56@&!cbpB-xeR-@wZ6w_*=5!$ZO#z*R#UlvX!2P9d5}FP^Lys*#^f6gH!pHz z8?L(?R}be}Y`L?K%1`{JB;CB|o+@U9`|QpJX|0cTMHzO7&Z{8;`E-sv6g`RMU!v$q z{D#hNs+lD}yK*t7Ijz#l%MTe5sG*CdbCwioYI464sW~aqRNxG?0TG&1`D4k_yq#hp zP1sN(HI8B-Ap-eytuQJV%VIkqnw5ISc0*?k0#TajW(W7=yGn(8x>g*IjP2)mWGsuV zbt8YdJrVX8di*OypoY3uYbkI*F#8qR<-Kcdg0{IXv#OHO-n=2RQNjuuX@hf5k`xT*F z9D^wi3q_PWRPFty-WAG@K-4;y57CZaQTUOU;@Pi=eLh?cMC*uLA=PBX8l6)w zEp$Ap7{MM@s0q$+=)0D@o$i;}9ew=Dkoa}v;TG^EQV90>arqF<^@D$$xetCpGicHAJ+dldDxA;)TKSL;`-0276KJ z9A~$;kbPeMI`t;`S_b^N4EAcoREX9%1X_-Kh<5xS=iMnD&wh}|fi~%gzbdR!s|G8| zuZrS`7u@4;1QI@n%+Ks`s%v#G;ET+CW5D-KS&OL0~9&XCLQ7AmQza_P&^UVo#TnHPc1)ld=6c!M*)B51?0oaZ@Bik{73OqgsL-Xp@e3Tb5JpTy$^XMk!FMz^DnX6zeeuI2F&xc-r4nsbe4h)~ ziWnRV3FTsIrd_g)hs?|m2g;}UudAp-u2zWPohDZjtyykbYgVN%mP&QItNkcOsC(j| zN5!6x_KNC^HSf~?$E1QjO)J!d<3_oX=%lO@X-Yz*DT8l)L%BFg(1|Vja_m64`#XI} zqAWxNB26htLM*0piL1$uD|Ai~-=JI^QK`1aA2++??IY`~oZv>YQmc-L))60&Kk85W zY%?qQrv`3eGx%0SMBw@*`S6m@&*EE$%>?rKK|2tEl7u+4y17g)R9McUdvXG|45^i0 zl#6SN6j_z-#rb+z4%vt9$qC$jWWddGN<&1`xeU6k=goJ9n|$vQav)kqG`!tNe$X_( zteG&!++Sg>x)=HSi2M>Y!8JL$ll8r^a#-meMr8634S{@!rpR~&i^v9RLZqL5?`b(# zaV!aQ?knQD#4ESBUPdiyUZRZd^u6&*>+%``HPp50*m!}tX32l%*%57Iz1yu7$340` z6XoKn5qbS495hoWR5n}J9iSmlLqrSFFxTh)FOz>V+b()dez7B);<)v8xVG+xD@e44 z+jmA7DK``DLD%u-oeY6z5zt1WaIxBPu8t%+^EKK5k|fvNcR zA-;#%xf{?+b(ZccGWouuz+F3rdyA5r3ek?IH+i_3aEp>!jY71Js7?NlSLxR25#$dU zxN%0^w1Eg*Z3*s%OV|xp_ijeRY)|KQ01$tMS}*GB|OBCoB}b>z8S)umNF)WUm_aV$Ye zbk;e?1wIeq-A4Yk?1RB0CwnRLGq0-fbHEGRaAFm6YWk0Uf}X|CAW)K%mXl{huqTSk zfqX)|K%TN&pX@O+k+&?rAzujte32C&t}{6tkm<`29E#B(BE{h|moPYm|-Mm}Au{^a3Zqt88aWx&(h zJV@C*5|FLbu%nd_D}0oq(F)S{AJ#<{4;z{>wr0pe*P{LI~QyWxzYi zC`pKV)XtYsJD)`DJm8OEaMTEti)&eQzrp^7cGN7d*{DaDCQCy&-Xltq@{r~@6DCEd zP+kd~R~%;o<>FeF6U%~Py_g*H1+_v1dnmY)gh-;hSof114e4%He1mdvEh`ws!*ru~ zuq=+^fvIrqjOM$${;;;R5wgI%1dRg`>~G*o3PvL_-Do8IhNF?7TwKcvMhcM}DFkI9 zg8dC#Nx`TprW;j--*8kFl#6RwPQ;VMUrS1kc!IJJ!QKO|Bsw+uUs3tPl8ffpr&W}% zg!=~N;#yWP0*&cLpkV|@putqQ&LqU6<^^Q^L*eo+{YG{~u)l#TiSDAKNIHp=cbl)I zN76Akk`BtnRU;v~P?Vd5StaCUigJUp5E1YmP?G4*No#;?{ni)eD7tVH-=JJv(GemL zb;yLMLk343!c@3+B1Enao5`q&MdZEddo>P31UwX!BwBSI5GMb-R8!VnbZR&P)) zu4@P}iCPlR07eIV+&LH7j~-Lu3W5`FX*VIJ5F+4hZ9s%3wa&zz%&sIMexzCWfW0<( zzdX{kLJpKfp2Z(FmyzD{8)M3yX=Ty z4`5dkou{U_2H{T+m_-6{4H&_(6HqRG-P5h?bTVO5+i7O=d()NQwkrz}>@Dp|5~6t1 zXekOsO7qxD%Cnf?a102Pi(lU4T|@C1MpoQscBc3YC<_tnGwezdVgN-#`02?3a}h;C zz&9utzr3Be23M&BsqEc269&i2z*P9%?!>a-S~8vx$bpD}2e6VP#I%~n&EA({XF$1u*ck@LhonA{VsfO>e+e|pKv{?gc+M(GLbU7ngYnCm`$pXAiEgA2B`Xje z#Nf!0IIE#ZI&{}0&rVWlmkH-0sELkfLw7W8*nPmvM6raBJtHE0Cd2aGxep?c59cVH zo@yg~JF}lKA~+R!mKyB)%zt;E9R$tayag=n4Q|7JPP zGSfLS|8~azUgJTsA9)z#ybZ0@b2ouJil6*7T+SsAW7G-}D2aNXy4}qhv@$V>d|**` z_8{k+W^a4U1&W?Ts~>a^mi(DkKd^mZDntwM`pLH2xCGqti&`OCNBl`qBeGo{ARAEB2<)#=E99fIAAKk; z+z)l+zRt%ij*-AxadZeo>xdUWiB~5e-mLVbR=^Wl%~%nwBTf`-n9P>HLMIwgcSP%m zz7%1j_SHf1w|+bPD3_yAu!bB}12v>Oy}v)eaaiP;Yd8HIPonjNS_a2q!BmK*(SRaT ztQAqR07a%i1ddCHrt@&W_fwX?{#P5#a+HhOQtX7u(@b%9w0yt%P(R1TVBI;U3-TeF zW=jE%hQI3^h}IFWQv8xlWCzDD!I2*AKt76G|HlY3bG9;OzB^AF@eG~G)^ z2s&vY_Yxuy-^JjVK8V&46yHak-=+9I(OCNsts}nsb%pt6nIw5}!XWGFXcd9RxK0sh zkOR?lVyn#W=G-?r%GM(7x8WS@dZ zQ?S$!fs$wqfXvcE+4Wv=BTt@l578wG;e4N3@RM=uZ>_Li#cwFcoU6 zm&d#0tIuU{lYI5D%=xRB|ITp&2;sy7kQ@&Hb;neQ);X{?U@GLM89?{uhUeTcd4u8s z;I}iTLOz3tFC5##(A9)W@T!Wd}+si%_*8t@r zT1UiZI&QXW(Mk>xjQwEHq!gH%w005UFus zn?OF=`1vo@>{NNM%(^tqz^`p=6NnZf3&l0~u4D(zW&}SACyjyF)%|wO1Bf z2YMz+BYdJ8PsZQ~G}yZI_HoMds#WLSXj#q|rXesD_Qy^qBhLQ#k%quj{LJm#SrMKV{+{*v zsZp|KWP>!6i@KwRGz+I_J%8_wk{qoE5ts{zrWpXmSz5hhfPA0gF5wKB(fm!$n&?`k zP@JW+y+=wP#a%)Ku5u%qS}ny{8hGM$+S^{Hao|@9qNzMCs93Dtmb26;P%(L+$H)Hp z+>^Q9_UKbjyE1K>nnV7cV{ChEyxpqAg#<4lE|q+0q8}`xY2HrX|NNK1v?h)SJr%9d z2DxKeB-ssf{kreu?ITvJQWw&g;~H_GCg}A~chTKCY`xOiTj#&2!~qEAaOEPJyvd&? z*}lF_Qr9g!Xwn%8AE(;ZIFm%V|)?lYR zG!9*^5Nt=IJ7%6R37p*Ue3fh z9rWj>*q@~T1}ec1sYW6PYJ!r4C{Ze}96Tc|wOL|2t?r^+z2@H`{r~uNO8lQxBT*J2 zGPVM?(K)w0KH-6?iIaL{c_ydbT%a@C=X@$Q)sT?vyQ=iRE4k}X_Ddc{9BiLWB3eh7{r2$phy7Dxwp}&KKTx@wwO1C2XdS`-=h}g}i)c=f zZbx{nWwjX5pyV>_C(cAPQ^VDNeZ@qA=<3Iz~AR~a?@KWmHJ;&TCJJ%(43I) zK-pyX($PY!T=;=P%-yv9~{+p1S+HXl_Ny@{DZ|(R9ipG0DF1a%lVu)sC8o z;Jk8e((T}qW39MMX3zDi_OYd5h+H@}yV5EpUrwoWbUJ;+s!=yFHL87*B!rU72uy`& zitGG(ys~`Q?X8;S$cJb;moYcmj!8QZziwiT#(_5J2-g33c8GFK_i@d?-!Z3V6PrG^?Jn)V=1A2H2(iSf0l1d#*L zI)dtzyjnLjHI(WV_iEe*dHg_4sE#qWkJ}C1MHd+(XJwfYzl-WFB9IT!PWibdh~pr& zD1+s4FQIc#8XNW1IG+qE9$Q($H+UL`m4Yjw@(aOj_7ndu3jhsBzf(ysRaZim1vYneSZLU9TN5-)h(G-WC>TZL?(D*A=k6MU84Rt%lMpcR6 zn&|yz#V&5CtjVhj?wEo0;cNT&A5B9#lX~iiIkkRbYUB1vHn$wkD@LFuh<>I|3|fwS zh<190X8Tp2sBxf8I%0hCMm5X$r$Q;sjzG`gJ3ize%_bqfP0Mb+^zl9;$Nq^Lho-yJ z^C@(&hvPoc4)kOmmWv!{Q?M81K2bwpz9HHf4Qi(yNTt!h=3bw3mum*frCbQ+p%6c$ zWw*+Iyw4v(c98D;#>1tC8X}s`Gn_hNjY>?6Z%QSI9EjEtRIlupn}w!crh3I=Ds%A6 z5;dVZ26I#%&v!hX9#7-BjR@pJG_Bmxyd>&YuedDK2666#Xq}_GGuBEPYg4#3uvR>N zuw2eJo&sul&*`sJKbEc)&0bRieIoXv>KWU7I)a|Oh(JEX3uibHWH$((a=cL~9YYZ4$(+y;tkaWC%fkvV7MRxC(?A{AN+ zl(uM#^Iv<3sU2D~6_3tVjBWy*eR77|%71CZx2)EX0@ot~Cb@HzQ zp2T_|HDWuBksTx79Xvkd9@9V?^@Q*dRfu45C_;HidMu^{uPplHP8^3na-@amHZDs3 zIXbAS@xx}bX3ZTsj%gLYbG0tFLu;Hm^_`0oUKO|2Xp~~NPPOf1E|v;uA?mG(l6IqH z(YtbOHZgxt?~@v$LWR9rL+N5npC-^Nq&d;_-?}p7=$w$7*8;6an-f@&JPwTf_1rBwRsL*?SY9D5L|l=2vR$tO(bn=n3!{DaX1>nps_w)ZMMpG| zBM(iATi7~>HE+gZdr_Voj_aG$%oC)Au+kToJ{i?A}?9 zm8MsLnue~s&+m-WsRrK7!%`tF#QhOloIz)g8yy1&Sl?Bgpf&!EEoh(~FLUv0fUNT{ zQ(WxsHmqJDorutmX|Kf6L36cNPco)9Fc&^eU>rzuB1^kov6rScF_v!|Yi(^_RmZWg zc4ebsicDJX!(pCpJg>gE@s&OMlw3(^nP(1_p z3N`lcTBK727fH=hAuYt2dRxtg56;D2vv^*i-X}E#YG6#9h$&Lf8r$_i)f&{p^$A!L zr^Y)qW=wdvDo&M$8cVoW7)Q2%+d9>S4U1SRq=h&lDp+x|PZ?+HSCYrR9OLo#AE?JQ z_SPtFb$S1Jh{#yY3V1!vqk6bL)WadoiQtVzt-diggAWd=ZjJwHyk|P~qPM6QMVb?r zzAj`1gkA{hT(*|=cI`A>f@=IgniC~|4X_qgPaU_GdIl^5q&We3B`~kBY&cPOO_cSZ zS+c5oX{@bLeDiI{R|0Di1Xe;<*bN?xdl8b$NWZA~#Egv=E)fMOh1{21VDS zIRlmf>U~l}pa#aoi89^C=w7-l&EfigmQ2T?JXN2)GZ`VcR}hC#o~Tr6Muw@77Q)kM zjFqg%yMu#heuciH9@1LD?e9y{Tq~&aO8qOQLTydZ|GXm(5||4}3*n1gP~^7yMwOtN zi=yx7VL}{LC=MIdkw8lcUg;4Uzd^g0Bb<0Jua9o$YSxFTur6>yMed&oqaMaA1R7eX!GZ|eI)l5e9 zAO0B`64Lv=9FCfiA@5aXfwRcR}u zt$bJWt3UQ;)U#JLzv6j?8b5u1LzjV?Utubwg?L|mt2wjQB+r>DQC6kF7j^!q`4#FR zEksu8Mdc4igKkqViaCljC(x_f!xw3<)cgu_;nM`hfix$|uI&}<_N4VJemB-C*`lh> zD>c8G@m*(~S89I6BS)_ep2@6JsrePALRyI8UG5td-dw19gytofKd6VaSAlvT-Of=1 zW8y^U#7)ktUrNTbr}x7GPjXnN2CnqQ&ssE0I<12r(FPZRCNZP8w-*%Eq!PnJTgJ6KGH8cs~q z)N1yizk6%pY8T;N^h? z>LINOx4*WlwFU2}wrefgRqG7u-_`7c6R3d%S`woCwjx%EHh;wBZCr!RMRAnDd8rV& z;zF&6LH*2Iuiluk%@64ra;DtX*nAh~r9!+t+d++LV$F;sR${_G!l9lJ*_XdE7Y%P= zg%4e5-r8`~^Zl@kcBzcj*nAgfvO=s9wXD_6emCd#dBh0R<6i09^3Ik-##P_zIrX{g zmL56%>oYiW7UJl!8K&pYC~J7PN+uHMA@}N28fX`v^t|b*%yoVx?~+SDb4HKtU|=eI zPUHl7g#=pSM4P6eT4Tzn4hGuAH3v?hEhNwqC-57zi>nlzsN8p=_9}$R15@ET6DLpu z3A7|chh?vvU#MQa9kS4@)O)h+uUBXnSEht0e0GLY_hFQ^G`y0Dwva$eLZk_-F3XR4 zVy-^=z#MH%(JN4@eV|=j%c7M#QA<{#y1RzzF4{r@Em7n%+sKhGJDMdPzhxR|7gxV@ z8`LASYJSPpd}$P6{v2V>;J?FKk-11 zoc=b5cJY}?h;1~gMNr*cL3I~xA)!V%za=4F&S+y5d)3j&Pdx*EgLd)B^3$U;(wy+- zub#c?RU9?{pt+Ant*WTcv<|0NLeyuqnjnO4r6`(KiX8P+jq4@;R7kTDbmKF*TFdb3 z;nO`Q)LM^9MYC6rTC-B0X_eFF8ou?!Xj)H{>S$_>p6G2C=hDoS>EEUo`4)h)MxCZSN zSvzR2XnyM)dR^2vZ?iEbPMkbg%nGdI#I&4RO{y8BZ+34(U1A;zQG0ArYsjc?WBM(r zF4bJk_iSJz%{6jI6|x#EnI1i+LM;|K(wu?Sv|hqu5@OHnUa{@d-}dCaKUQ9wQqV3ib&O+XtHe?v&En8I4SwHIk4Ikp zRtqz{!I==(_z_G4^Nkav;`Tk`xYbUK(x6owTkR;R&$Oz>VxlLOtaqIB@yR{kZ|o`W zryHxsC{-TlJJLE1zlK2HQ4eV$s@^H7cI(|eTaJ<I<2YQ9&&k4|Qt6g2?6|EtA@OhcX;X9oWO{Wta^&GB712vLiDx`Vj z7%l1{ov=q=mGlp;*D6U`d^6;Jgs7hx)96Y^&In9aUwDU7I!d`#I^}C_$-tRkI zpVC1M)TVhN?c>xe-8;D2uzR-pMiFXn0#{p*rj=Ch?vfx4Mqnz`)@N9(MsNBBkD+}v zWmjpa`4xJC_08*5?b5wtYYe+*Ac1y~7Gh_qde;1DB|=Kh3$)Y?DngH zj6gl4X$NcLCNp!2MZtXzL|JNOQ)#I29PMJCFGSi(H_b0o6m|x$>&6K55NRP^e^xj4 zNSaI`mp+WO)GDyjP-89H#j#xz!9>I*CeTBqY1N?8O(#!^!sbx&O0AeH4K)s;U7Sk@ zQFh}d=lA4`VtZ5MNT7#E>)e%;yTK}V)$W4QP(3x;#n~Xu8H%Kq%WmY0{hmq?3DiSc zh#T%GS>w!(;3rf|)SidZP$Lf7#W_5kk1JJAcAHrut_0OYBv21&s=IW$ZDZcv!9}UI zs~sh!q55{Ti_Z++Q(?8!_K*FBS`-qfhqP|B`uYC^wOVCMX{a6_?c#1$0wIVnkU%}8 zygJ z(Jt;Z331(9g0WPB4icz`v=Do}wIrBoiBz>gX{g-{w2Qky2{lo*b4H*Z(lqO%+MdJP z&ZVl=N<;1Zpk3Ud(e2#HN9~+i6eG|>q!U`LYUfh5PNkuC$Ju>)(n7ROU);(}=PZ|vcS*I@<2z?*tLH(#9@0W|9a-KwIO(qOtZ^l& z)_Q#BEN!GYacEeG^`6dIW^7anPdeF1bHaBzL8v(#KEzu zP2V|7sa6D4v~&)@Ry)Tk-_&z0&nwhW?OCN#BPXUpT8MiiwwS}c=PadK5mXv<4!}k| zr0JB!F9Fuc`mOa@aStpGu`>eV7VqAsW*;fI8lDmMpJO4{5K0KMvHu zm^e{^&H+sCc`LWc{E%Ze< zS-CX<0vrA5{Sf+`!$#)MbICwhT7p( zsc3hJd4g*v-t>Or#^C0fnD{uzMo<1Hjs%UE3N1BJx|L}o{b@q&Z7Z*6C(cIt(*(wW zG$+EAzH;i*o>#vi3mw?0WGh9u1|&ow?{2tU9A1eLsK@iFcK+%z)u1O%%<%^f?6|VE zC0sS~?$=hLJ+Cc&9x(zvIVtCKZ44)n_J3HEjgyWtk?hU@b1oo8TuBKCF(yWuA7 zhBE?lfopi{yPlWm-Eh@&(r&n}CH`I%d)I{BaEo@s9ksXZCsYagJ>*`2hTf_66KEGl z>V!6^W=ncEToJSzZeuE(qiDiSiS_&ny+T6mVEZj`4YiA`zEN!u?c$t~5qdY=Zwm>u z#0mTc?cywx5qdXVX{i1RQ{i(0BlK>#KMo|+4z}MCJ<%_FWzs1Ns{++4weRdNHMEOQ z774rI7VU;RXbTCnL{F)K)vedVo|vtUJ#gTZ7JFjBXAvQG&~A7nos(Habr)@+Cuk{Q zH{7J%aHfHF@#%%_hD+E1*SnVfHi*wY|4aB=E!ss(31{v?=*%74=R~`>=b3QkPMwp{ zarpN8*>&HXoT-%N(=HkAbE(ftPt6&)hSx9ec>carV8ZB( zsgUMzAdzoC-h`1FX-=r~aLNt}rNYBXB91eZQ91&tp z%}3_OLgV(S8QC@>lvipFhXh*UUOoTXo197? z75b}E`FCI0ywvBGx6E<=`Qz1wn)q>CWj>Q-1g-VxRJr47u~bO&$lsmwmWQ&79)8*@ z)IgdOU(#*zDu1QjaMrgUb*TL+`&zO?1#ot+R>IUwU+p>xv0%#^=hVortoq5j+c)NI zu@%uM^CAyESs*RMyLrQPi_Q6{n}Yd`Y2ScWox6-%6MLBU zCf@a%tNopyBej94)cU0&)C#K*?Tgiu&&GWSPPR0V5vYf>5YC28&ZQq0$DP<8W&M+; zlQ(w{7B|qYT8C8{YNeRQ!JHeMzuy(N+6^wr2=owXA#QzEH#ozSdU4xmcj>|6%n2H3 zSFI;24YlI!t%-q6GrJ<_{s$81A<{xT&wa-XE!8;Wzl}W^fp*opxYAH7_d@igowx}v zrpATRUQz7yMIKcfRPJIbwOX$TwVxnFo`QGGOs6J=yk6gv5$GY(LOd7~Wxb6^=2>uU zvsvbsn{mFn>q5I~*FkBheGwsg7OZDIsMFJxZegH>1bT?H5WTj%F|SekNRzy~fdtyc zwO%2p4O*3`4W9Dt{P^0z8cc=jmox*IH{6N~oL;2Zqi&{3glG6MCG7UJQUDA{dPGSBR5n_1tEc5!47qDR4cGAOvG zE5pJ-3H_i4Jw%$1gGb-*)BRP8uM4=aZwE`%YQ2BFqw|AQ`!(@v>HHo@z{6=fMOjpQ2yHGZXG>||&q?v}8ej%gQ z2-{uGK)X;Y6KO=I>!OLZ>o|dyn1&k(^bqwl;r8W~`}x32dNjCFwvd6IKzrm~xltVn zw8S+&v@EJM{;YG?g?6D|NmQ@U77}QQX^83WOR=h_rkdzNyV#>@g8rxLuKRe?Rl0BA za(M+K&=MmAs-p&4;$9Uvb47baEy{zQ0PW!#sE!0$N+9&=$A)JYJSoR5u%o}*5%RXf zS^fD+^?@O2JKoTrXP??0Cq&0QboP<{oWEGkRH+K59A_s^g*4ZgGxnCYH8kys5Y*!u zUdFp7GylIknrOc4N*vOh_;GJX886Bm`0v99^E)DxSA~f{niKzDaVT0v%ZaL_p*+iy zL|CYSsnlmbEySj3Llxm(v1fvVd4>6dxj?6iXI^&}r_5P-)~jB!Kb42FHJQo-Q(-O$ zvAFtBc`{p`D(kjRaF9Sfq`i4dPN_0??-@SLR%NbocW;jA`m-tZ8tlvjyU zA*UYo4#Mm@e8hkE~)hS#fAV;|@;R|L|ZCa|25=EUCV*Y*C#qeQujsnlnGd_0cU zKYQ~>)r=j%vvf?Vt?4)0v>W!t zY#oPc!Q89e)rMN-^QWlXhU)HiidMz3c;yb33TYwYCtWv>R{Ok4rZ+rtw2PL6_$tpR zRSU%i>PwVYN<-x?+C^_Up;9SA`JR~YTcX=%6o=Bdxr@hv1X>cp-rG?VW$49L=oNZ` zLINn@c(gJ%9hed z+&-}83o$%!r>=<&6M2Q6pe1_#$h%Xw4;6>9<<~&F*wVB|Zm(b5D}dk#)QM&?NTA-Qz51uo4xPI+Bl95rX$^dWK$;Wx^YmAB z%02t%1CCk+R4b`!tq)fOah;Jz{*HF4^*SZ3i_(lNVQmp(t6CwaU#k zN-ViyzHU3Q;*YVtEL@w$R7mR*wAPLvy-$@Osw07xxK|~c1!_;y->jk6+m%=96am+G z{Kh-W*!xp23)k2&m0GR$(_90~1ND%mHJO<=^!PE==8Z@;4UDY%B8QDdP>rMya<3Td6*P5-C=+)~;4 z6yg8(Pe+cPpe3!LBvhZ}R%c`U?QUz!<_R^Qdqugc<|S^GyBG(iLYip^%q!GGnh|bw z{>I;O)X5ru-Q^louXGHmUa4>VWsa$kW*P!LK|Q2(?&=v?;>a--YU{eIyb`KK;i(|> z1od=H)I{PqkU&ei4SKzz-UrVrpCTkaYcIOqcb}(&IVxdp}lW>15;n zIeII^FZN*b%ZN_0?B*Mcz%vX;3sLm;!RQ0od&_c}t}_DdV#!i%7nPjq4)~HVMF4bW?1BZHCW8#f_rkV7tGjv!Z zxgtkS{jQh#1v}dqIqK2*lGtbF&NTC!;b&Sg0?(}=?TsU*@Ghr!rvZ#WyXc`1^KRU8 z-X=Ngd_!IZ&j?HK3R7WxA2s@r1`-$((o}-6&zw#a#{`N4Pv#-bHHr^>Zz`prB46qA zKK|1?7&+>By`ulS)ySs4QH07}Ooe)MGYmA4P#S(cq&1=XM7Q!v+45_kU5qcmD+MtE z^^oQoc=`|ZxJG`eB@@%kGsjTw;`yt@arnLUdPTLwR3*5CTCF-qrdn-cuRapGvA=Z=Yc*wQH&VUEN$@guYF#zVYAN_S?mKWsGnqzN6;1t9D=2 zXLVKp&vS3iN47@^;uq*AHVEofJr zv?k+MyznNQo?=82Z-k^OmvsZiUSPc(A=PwpatmJ;GnqqB~~camI3j$WzHs*ZUz zd~*g%&F*}ovyR-K3TupaX8FcDXJ7=3WQ?Y>YBZDCMl+cau7Qf5eyhsDvpDMP@xq$Z z?E%#*8|t$<4WmBOI|sh0t7l#5bB?sWdp%mG${Ajar9#@9yS^Ejz%xaO^*(A`3Hi-V zktKuq-~rb_ntK&>tB%e>!Bpu3XXjK>wiz z(mbyw|B>FZ))X-wTx@0GxuqFFU+FlWB}rm%uPWrZZ2n%mgw?NcK5NRU>z>NwRpL}g z)4A8oo6YA-H+xbnh+=t#dR(LX<*DY{xmB%}Lke0~US`sHr6R{vs7-k_{k$=tQW3iF zQH>Fp3rGtw>0)hb;jQ(q5`7C;cs6Q4y<|G_Qftn*cpUeCtZk{gl;q|Aa^7E~Y|lPGFuOu`Fzzr+@G9 z+FMSb2Bt!qPC)GMV*PY|itECFCnla33n)A`PSw6Yrc8J7$Rq47)}Va(Vixu_i9Pg&LSYoY-fLu!h#% zV4Nsb*Tl1Gck(5VRdM8;Go>Q;>W?fVt#0G4L~s6~E{g+GAx-bn+ZknLJ-gnsV$>#< zSEz@y5SOcsu%6vrZ@e#2*TItm3k!I2_sc2MJzOJI){)lKBoAV;U#aV;-!4(POXZp$ zQz1>ytdquAL+9SKx7O+zi=Ln!()1pd%ps57h2c(_-qsg^`nDiFJV*b@gzkflPJ-dZ=hhxJ+M^LEIKTP&|ok84Cz z9H;jljh>mb9?L6Ch1#SMSKB&XV56(pHw7fx4QigyC)(VrlJu78r?o9}z|KI4wlEda z^xHN6q_=WqFJat2*-GLm3+SV4PE1_*quF9wL2K0Yg7V{O1hhd$3(@9qD=XLBfY>peGqAiu zPmmU(9V{=?_~9ElSt=L@sqLH# z`OQe_odHNZx1v({^|;2wvzyIq^S67(42ohUh%_e_|9jj_m%6l7dTOAAp4!G7h4K&M0xgd(gfi#}v z(WA4BrqQ|0$htCi+HyU!q_Nh3gqt*yte}p7iHM&sWxhplezsat+9~C z477`9jf7Z#po@$-I?;6`@(Cl*L!^ZWo-{@-r}1N2NYCIM^$%)|)30Z2MZ0)gL5Li+ zM#vlI)*H9~uHztq9wIHo$dNtd%%|t=?9XnQX?$^9rI`iV#oG!(WT-tt*6+LC$o#kt zBTx@%dd6u+@1CPRF=^wv*3rocWp1Edyn8_BM8EDL2kvNM&oBDKjQ5q`LV8OldWf_T zuFbV&^49BJd6pJn8c1{Eo3oppU*_q)ggxV+C-^KP#G!xE%Pus2{C=_(BQPeUg{YM0 zvU8W_?NN>M$>V|J?Xuo^yNz`h>lhtGoqpa{b86>pHJOZ_KU6!XS-5WJ{x*-a5X~=7 zbyiV-)nQ0Mrhzmk!cNuJE9VWT7SJs!Y2#{YmTIFXSS$TKgLltsXr*uMG0DEs1jdAP z0zn_#a+uxP&R*k)np4|If0|I=_`O1!6RBgn$a0PAc{)cuaqev0Vvp+7-d>V7#)H0N z%@-mni7B&gU*SnQri6T5cb%Ope^a~4?K>XSLt2Pw-CM~AMfZlJe~^I@m%Y&X^TM=SFjYt{PBCYYcTQUOeA}vJDbwgzA1It;L zzLuG+{{egJ&*Savfu};yF18gRR_`1mvxHnQ_Ek7lwbFnCcDH-u?KksJ#vy^0gjjL^ zgdKUch5Rg2Mu~ACftG}L8q-A%ZCcN>C+dj_zOz<~?UCMu5F9C+?oVUv*doo`5BA!l z{u*o#`KcBo&=U2DABM_|QwG_m)(l~hW3*_A+Q+Wia?bmzo_|&ru&&ivXFtl<)XsbN zjtf1(7EJT@Zms08wtGW9Jj`IBIudA!Mz#7sI?=ZaTF1UCXjKZCZNKd0eeOfM&<1IR z<>Mc>1+~vW0xbz~Dtk3qxLwPb!okH^97v!gA$He0?zAaU+M2vLka>lkKno_XnowV| zlKPVNv<86d7nlm^gecsqoo8Qm!ZU9~58cjjeuXoq1cE+r0_VO+3o+!>AhS@z2G;Cv zGs&)blGs&a`s>~Y?c%H^K|_00sPpfh_4`vCRJ{)pXeoivULk=oAx$T??rbog{a4>= z_b|6?cdD>m@KAqyPVuxhdZK1d{$88jpgbeM{O6|**0pJ`93;>aq-hp@XM_DOX|yJd zHP;(xjc25RcCnuqVr!~xRmKhJU@Z+y$_Ug$nr?cZ9^}kv(7>uOCzE_Vxxd}Qm%C^e z%AaPsnI;7|xqs<=o6GB+ycV22pM~ZN=Xqt%u*% zHSzD5w64RsTj&~-rPJP!d*@r~&vdgbc}pX(z!9hBgb4X~=Dv^zdqV9xt3G%z71CTo zh@T7Apt_~%6%uJO2F88VP|SttN1gkNxCW*|IzfXzsG0aj4UFmkBE0ib8B<_;tI-xf2~B^GDWj zwFzsXh?G@MPxBMTY z_2X!#&y@)Iw|lVb((5MLD@=tn*T5V_J*4UB)P34GT1Yxqi*OCh1x|caaZ9wjJAQ-f z>Fb(04(`?5(&^3Q-|lm=K8}!=ugr55zScm;fvJ!dBJVdZjXx@RoX9ksz+6E3qfe^L z(W^q|ZCAk^ruK?!+CsMszrz`U zF(IAcl{>Lly0*S6survc6e6^ExM}Vx+v$^`>jxlOXLC zrb0SFgFYlG570weh*4%WbI0=?&K5hIX<#mJ!l&X^8ozaW> zjH7bDq{hIm#dI7a3k4WA{w<*6;9ljZ-p}mQXQ7ijEK(YCk{P4EETQATR7mqU(09~B zn$A=A?rWZ&zQ)-$FPv#$zHtKMNL?YFF{8~FI*xzmeP)DC$))4qUX=(NYv%ZAmh(@K zNLlW5dc$?DfQ|!GA?Pr@^FOG7)851dIF8;#URyUK515+W* z<3Qh04{0HiOqyfvPCnf^+dZ6VV7_qz<0#g*h*9OAsu zZSMSafK$3zIMcv<;{?XBHAyAo{Dhx%9JP7{8L79&>o~YqZ;P%qUrnj)^qvc-J^X$0}&VhR2Oat?c6Bx&^b|FUW$}>8S5sfWlV7)jU z2lvX}xyk(Ta5<;=!bn;2m}$%{d`8ECsgUMzpzo-MG_9U@-)YvmRM&Y`Gn{E)zHtKM zcpp&RIGk*sj$`4ZTE_a2bvh32)&5o6%_p7mI&Buyc)qZfQ7dYXjssI6&Er7dQ4eW) zGezb7W}}Sdoodx-JO>TTH%?$2|D~;CR5-j`$FV;{edFrF89EN`RjFiq%v-}#JA)TR z$}HRK8xJ!t)p1}dqN|jBn`O- z$32gXlx6R>F^X4tT2++?rb1eXwb@Ra@Ap;qtmzZZ2=owX`VsIbX?Aoiaoy`e&$VB- zF}B<7LX-yDMQ>@X@7yVK|FjmaMMLSi76|kZX?hFoO~=fCpr}#3IlZl*N~rPQ^dGba z+QnR_->%tz(%iK;yK#F;I3rLGY5EnVWwzO@<~U=o6)FEJ*~+*(IMAiyK)YB&=_JRk z%YVJwp66-)uy?TJbg>8fp)Pq(~gPjsM&t$R^z7~ z;fz2Jk)~(UvN2}k3O9|vvq#EmF^!FXAC1=&?q$hP(`C1bT=x?NndiZVtRt+AMx1LN;q*8inG& z*BWRSXCFcoYqQ&YRI04mH!CO5L!^c1cWsmT^@*Bhnr)OR%zYh*n1Qfr`HoYe}^snI&~?1In)j}3l8E0+QlaTA^r9@)6&oKL*nq-#UA0g}f8)yuFlSyl!U3^ZYH@?4KVD4Bl)~sHS z6X+q*w69igg4yqzS?1ID2pN7hyRm+BF0Fxf@tInP>WyZZa|%o~yA;4@fjnC2>&%+C94YZ5v4|F3p*(CGIzjMrM={SKNB2B$dbT{*Lm*wWflr#&! znABKlm(Ut$7uRa2)wUU7_HVM(eDe>@sewQbk^VSBsWmcOzdD-brmORo%KAB)YhEwjbJo#ydP;amgqjT0YLcpMcjEOd=5UsuP$y=p%4Gc!Zi-DcI$ zNcr@;Ev~xF>*zQz71DI3Xhv}}?X3Og)A`|yz+6E3qfaVwjCTC-(XQ`XG}K;kjSv64 zGTs;5Z${91V$<|?G z9#lPVJZv0o&Wnnakv~PbidjvySC|TE`dzZkFO8P@r8#&|I3qA7q`6m*BL50`JoC1$ ziRmZicJ1ubTzkbec3)X-M90UPeMU#hLmt!BcUBAS6{bR(YhZbx9@2DzPM$V?i9cfY z=@HH}Fc&!SQN=CMuASs^NWpe3bsXHQOGWz{U&naNe6-eA^KKf~wJfc59GD7edbh~c zB}R(4DLkswUDKnAg${ug={Ay*q>)o8C%$#WngR%Ve~DZ<~R%ayKqu zdr0+jq1r1vljdz&xkC-i1x|ca;co z&+{CPTl1Z_CUT9;-9LC1{cD>^X;tmg$k}l%3wgc5R7ihX0|_jDAx6h+_LTYVv^kqr zaZm$ufzuyV^a+TBIC}2*%(MD}w`bs9h23at2k-Ehw`f%@GU{dA>~-E2g{hFH)41KL z*kP+qnQJWSuYf=gk^bnDDs$h>7oEGm)~MxaTeGQdQC!2Bx5N%R5o>-+Yh-g>WjzJL zTI!mJsgTwhZm$xL9QBZRdxfcx)*5cF5|149kQUK@a z&bKE#W+bg&A%VGo^hci(=WgqFWJvnN* zv{#r4X*vm*H`r;}d5>AWcQ_-^L!`M^GzN6J@58oS=5!a5F2h4e=S z)jrU7)I(YbUjST5p|oJByvZ@#i`Y?$wLA z^uZ{y#A^lN7#eu$~9@0W=*)+lVYQX|iZll#&(7=4-#77k# zN2dLG>=M;7={UGoSMyDCsz07&uFM%Jdk@TOuiBqQ$APJkrdm>MrjzdH8Rq#OWL^`yzh%8Y&d%}` z%#F(<LG&HLJYu zj23B5+{t{@>9a7#XgM>Sd4)O6iH|C7*?esa`}_HC^{#HKqb=No~JZfUpgwOPl( zz50ILVJGQr)5x$hLb_sF+w=Z?7P6CSBBnx`dxgHE9@4bFoBfFMqTpmBtO3`+8pDZ? zDsDMtSu5M9(@4h=eYut0;ARRP2luM(HOE=K;KPss5 zK;KahY5G0k|4ur+rj<9U^`doZ(7=4-#77k#$FP^J?5SI-#H!wodzJZ~bgYNVL;h|Z zDbwC)V~1a#7`%((z*I=nTOEHpu9dbNHyLvoDBjt-dZR}fN znc_x~2HM435F+>4(@x6pxp7VFgfjv?M4I-`U1ywJEHz(9iH*I%Z7xD^IVSS@prqzx)seire$<~Gw7!%TTV||O`B=0lcen~r6qu;i& z(*>sY93c&~i>-^!Gb}mbZ2Y3NJ(G3;kU$TSraSJ1PdPQZt+V^Z^<@Ow#n$|>j;NZ5 zJshUO-j2>QL?3rrEsFQtr@gxy16tVWpI7sISo6Vy1X`lsc5)wbIv-nLry9Wtj0tHW zuKzGr#udt}-U;CL+uE>o}Lto-+GYdM8j|+uXF2)yW>qWx%Jsc?PZ&LcyO!R_6TCuC@E#n} zw2SQ1*!0_x3a9}$PCfrOp`!PHqkQ*&R(XXq?SFhCcaiXaR+i{DS(^)|>Ao)3#lP>f zyL}i3#z*&Shi13W%pGZsyc)y^Ooj7DZ`o1PP-X6}JkrolEN_}6u`v}sWe5?FrM73~ zu@Tmb#f=>#@b)3n^d$Uac4OtdkydXfh~2eByZEF}yBWb5s@$(P!ixH`4T}Q_yhTY* z6RC%|%(FwSgRR}p>S7fV;y?mDWRVMX3sbFSgoY=vkw8nDaQpH~VB|=kCEDlgFU+YM zyI4Va99S<;=GFKvmtKyA8oW(Tw_{^2(yT1h&=gMYA1h( zQL)pywYO8PUf{u0NDC1*^m8l!oC>d+6~NK9}knS z?!B|IJkTy$qI(lF@|cML{gENkE{DbiZQR2nLFBzP*+?vnMGvus(?!JpAQvf*12G@#!A4W!>5+%I*IOu53D4wEUYN!1&oM6TS%ZKI;9sjRBlK% z!R&c?N>!gN^YR+$;C4UWuczNw_tr$~vxY09(H0WEdZjHT)OIVr#ezaq;Z=+Bf0OWT0ADNc z#o=p%dcK>;Rsz8-kyj?Q56jm+)ULkPK)d9v$N%0q9l2_?R!?dlXbTC7DZ!F%9~QL_ z%hx^<-hhdADc2L;?x9Q2r1oL?+DC#dB&ci>Ea~=PQTs4`?L+NU>p0LZ)t-cXL)|_s zY9E%beI(dIg6dd;CEY$OY9EfTeJES%zO!l{33h#iE1`W@)ILmK`$({bgzvMqq}zu@ z?L+$7hsqOWOSO-L-FIK)J`HLg7PSw@*FF-wLc$l5wv>>&($_vz+3Ii5uCD}r8q_{i z2})o4Nbm{?U)lIHeDzBDYI}kP+V#~KA3=4A{^;>s?1EoE#dl8d_e{)f`_5QhsE;gk z?6mXN2ymt95UNLd9GCDt3POz7GuHZid>!LJ?{RUJ^6n4u&kg>4vM=P@#ck|fkKcNb zrWKYPKLj`ckeFWREuE*dWbaLN@=#;{Qb``89O@ODcNA9 ztH!hXS_AFkI}WH4=2%PbBJV6KY>s9GdWbar!qM52=9kl2%FYijI2E4lbBWN}S_AFk z`v-)GOciI&8P#6?yCH@V=poYdy91AZF-xv&EI<5o)=84}jH_IsYFY#B;=2Lp>_>r1 z=D=;O<;%1lMxcjC(-5=wjajI0U0J=`DQDO6J1$R`V6B06@!q}=6+oJvezWk5Q{qZeV}q-d)r=H$~Q2d?g8Cq9nGLAc^M?ZDF`mCZR zP!DM#@=XY^COFmPuiK9>4Wv0ywOdx}c)dz;dE|NLMap!>!@GsG26}=w~7qj*@%P)guytA`-USrSUY+3{D;>~g)=GHA{C2vq%=13jG2=owXA-)+?-ulJt?AH zye%z6>OZPkhdQT~`!{VGSyC!RZkGy))xXE#qjDgIWXa;w@t$@;A07b$j6a)b)h3 zV2WkT?sQfY=poXy3y`vvbz$3Or{(U$Oap07WXc+54eP$o>G<}%^VP8W#>>5{wFY{E zcZO+ouy#9ZL3Z28P~Bz(#)PyG4V(_vfY2q*+??^w#957vsFl;T2HFjRd(c9(SkcKU zGJU<1s%-T?0I@6BFJO2bUH&)f`t2NLr-nA8?eY)<}#Ne6Ehg;E% zKo60om5IUKt#gZOIbAZwJ8%AIX(V0j(i&(N@4?c$Kd1My7B24Xq_`2y2=owXI*~HA zm-T8#I%mey^Uk;;p+@*u8MFr4#XG7(G|br7niOBj8Q&w85$GY(LX;JKt%mtF*%jM; z@5CQ%V>BKl<5Y`6yLjW2cEgv2TPsHy1GKX|@scEZ`~gc*%0 z)YKYi7jK->44`0y_1VQ0cDf^n8G#-mO|!l=eXYUC{&mePf7Us0Cd}yfRizLW2inCO zr}VzQ4dGUS1vfp1=AU%Jv$r+stiBzs2=owXA&TUPv|ep+T+I$2Vj4(uVwdP+z2Cdj zXgubEbKzziW9PTg+AH(~@2IMNH`2QO&q8DO0uLiFCZvT(eyOKbxoak~RO@)BSA$Sv z*|Rh*6$jeIJF0X$vwMVfyy$!5S2~}81bT=x{qjkU?pC&u^~`1tjZryT8MP`0X$`cC zcT|P=duCtjn-=BG&tx0l)yV2Lzdm-+X;izp;r^?q)N0r{6NWTy} z|4w)F$K)}LKo60oaqv|KtJ|h!rs#Iw>3p@ZG4Rb)t$}v&jw+p7deP0=UV6H@;(9D2 z&_kr@PTagOt3$?vW{PjlIPNp`joLX^X$`cCcT_2Nt9PtRszMYzSI^4z=7YKXWgH_gCLYK6=wRzZ zn{?KL3GvR!S0#<9C6gJdMWJ21qbfwzC)KUt&(l~fR>m*_Jw%$`0dcIHRdPfQtM!(6 zr`__x#+>%)vFfwJ`FcQ~gL@(f;TYAnpoAYN^%s)X|1MT7sS0S=?3b4xjWm*mLoN-=1dgi*ku!1JgL!^bc zlTlb-rLJeWQ%R+4rvX9!qPWCwNnno>-1QG`BZtYDM;r zV+6*8G~L2pb=*AjT}$iq#(3w*!~?F7SGBYT+Qoa9bn2z)6|+TbYin9)3?tA(q=o3* zeXF^#L0fD8)Oe@Dy;ZKMtLtkGw2QYWX*c{YkJ-6?d+X}fXhxuiNYkm8z2BPmqQ0_3 zz(r@mxoNKSdm3vEw2LZ;Slrtc zQ?$9(K)ZNfk!G(ir<+ArcC*C2I7Xm{NYhTttqSJoGQF(8ZKs@&KZ0G4KeW^uXczAi zQV9;~VODP6(|WsBG6FqBT8O{ay)X(C?qdbCJLBX?>Ir#tp^er+yLdB@-mBKGyqWv6 z-qz2*9&@s7PUrfzYN#gAL!{}1(8~|TnyG!Q53i3f4Wv2I^T2pxmea@D9(>+;RnHX? ze=JOEpeJ}Ukov3fOO0QCjj+}l4kIuor0IP!MT9HoPC&G}_-# zYoJ}cB_>4r5=W8^H1t%4YZ4QzJ!Qv zyT>VYw4+tD!$C%%he*>(YS?vWTid2q3)e;G#*Jg1nq#VK4YZ5*vB;~GXPtIw!mQ~J z4l)8gM4H}VI_Qb>jk}&za>xbe`|3A6i#mm94YZ4QrD#q6(QnSRDb2072cj8)9wIHo zw|A4vLw{DYE)75LB>Cg9r}nanS_AFkJtnFpuiiQv8a1$HE{S0TdWbZw;w;D{+pMZ; z{rS~7$GVl&o>{q+)$4H1Q0cqs9&>B{*eX)!{50R#x;bd;vd}A4FZ?3aW*rjxK zuPWa8723rcLqgojoK4Q%9b~nB5yuGh5NRQn4lW|ECM#kY>(4kt8fCXXtjnY0K)ZPV zhx(FPf%0vyvX-l%%?R`mX=+h3%F2#Ma$DUqoObeAf%bn>vuF*pi??}%coSY+9vW4| z`t=`&5$GY(Lj034Sk8Ww$x2r6r1SNvqV}RE0a^p?;@un}x~?iOlPAq%)jxiS5$GY( zv_k)^hMX`dh4tv&G3QD|8N2_H5BeDg?c%)|+65>WBIhT~Yz;bhgc0Z=()4}?cLUij z>Z#eS%?ZcTz_1H_dqr!YUAzS&#Ob#+Rnsnd)^;5x4fF(W!O)x`Sqs@)-ZZZcJIn}- z329mpPS!@Qa64xE=4YJ$`qZ-@+}YqdMjB`rZ>Z3T-?m|LY^tMXoq$7(Ko60o{o2^} z@?4v>=C~8*ob3A>*%c;#t8*9a;_VUY8E$u!8>VhCyM5^}0zE`ph#u>@$n4Ljn5kNx zbZ)h7ZeM-d!?lOvK)ZNPgU&5w=q~p>nPql$A7li2h%~(c^JEWcEpKOD9d+DkFsqe4 zczjvcZqh)zc=v#Q-+5zC>2ZB!HVQq&2=owXI$L|Gm;AC3_Ve!X&V$8ac81=4;_k-3@}ONjvoA#8zJ799vF!HrbkU4J50Mrk zg}b-BvHz9*=ex5`-gRy4(xp$u{X!aO7thnv8~%QekQKLYw{sP-8G#-mO{<*kddjpr zDmtEeXPv@vt?laha(Y@{e&s>Cc%GhCaZZQJQGL@m!;-}@0zE{U=80E($#rc*oRtrc zG6L=534B_a*fLyxKfa-}rpE~b&&{KUoJjIvkQ_5$lG7+-E_O~IQ{kC?dV^WMxt{U4 zM#|4e)?ue6@zevJZJ=kI_9@K)r$@_Cd#~=#5$HW-q0WC}Dm-_f4}K(^{ZOYK{O2-| zKucaC1-;R+diz7nDZVU{T_qN#`A~CxAu8PU@AO! zAcWm=zIlAd*Rp`o#6S&9g{KJUrp3)2=8|OtWbKfB2S-kx>bmepV_W4FrouA;R34AR z%{ucu#xPW6LX zeRgkIb$-EMBv21&>Z!M9wa#{HCRe;q?m`0X;(omlV-5sb^cUqGv z{-rhTnklEoH!x5GQ{i4Zy=!trMXUAfO7gdfvC;LPWi{UYl~+fOsc>hUR<_6GvTEmR zB=2_|6@&!pAx-Pl=}haLyM!G3RZ15UXcu?J>11nMD8Gs|&bSyhX@bHbjcav_0sao1XiYOlLnIhOq9?D+32BQO>2K?|{CMPKWg z`MtC8Z6gCUFct17)0{f%0P9rTZYOBug(@XR*Eeb{TCF3;RJcD(yOxi-SmCE1J3X$a z3PJ+)kfyg^O#Rv#F<_C?aesgd3ABs*!}Oa-m4{ikLx(#Rs-0&9ro!D`T0?F!(t29C zrnCEX<|@Ax2sIk7&!FSLRJeCbYki}JSgQ+8a~}WF*o6doh_n#S{L$8j{^^|B1BX>b z0`217?f)z6EWoQczW2X)ahKv+ti>(K?hFpWC6M5*Nht1+i$kHfJ0)##hu8{Iv^d4u zFVdD4DOzZOV*fL9_ujk%(A?(E=e+04&dkovj!dl93O7uJ?^UTUIyZ`^ z(fe6{hBelaz?hKMv;!5R__cQ57->$#)<6R7;(Jw1TeEi@Pub%WmZn@LMFUgeTT+@i z(0>fqigVVv+M32B zn(9bkOi0r{+bO&72|Zr1y#MA7KmzUJ+eLA1Unoz#G%Y_=EwiG5sqkGP&6-Tpg0Iey zlfQP(D+H#(H-9vKwXXqxTdFWW_V$Zv#JCm=ebyg@5_^3(ZE#rR*q)rWiQJow_&`> z%rgpssqh^ewY%*L^SZ?v@G*y*8R!+J!Z&8L|L&xmy#1->{B*;wVy!_bjCY4WmwAP$ z@QoRbmjqPcDQU!O^V6SeAc1;F)0*nk>3HU)p?vY_G&&M!7vGrC`>0BlW?PH$1H?35-wKXkd-9CrFJ3k?Fb+(G?~SOxTeTMZU+*z|e8++{LSq8;@ySADUSTSHZ=`7l zcdchR=MLrp-@H`_)I*x)!}U$a0;9+AQd!gKsDXCzy%Ft<*ZDhRLbfRWRn%#Pz*P7a zh-MC4yr!pI6vcbLYHFYcrowkR)c3jd*xdMg6#x70+&i`XX}%ZlqeRPqsqhUAjahEG zX1p6ep65BAz7i6shqR{c9lFQ5{$@O%(4wf01lq+nG}KRgk<%_ycpOii^Ql5$DtzBU z&*%TNuoFs-=8r-L8>oS)@a>7Fg*2IBZ@e{(|8nh^LSQO<7ourTQ?0YJ6&}cALvk|I zz*P8VgGN76Id;0qk^KCw74cseS!-557A$iYQ{j6Gx*OE4X}5|T!)Kpwq9cKNNYkjn zs-NxKWBc&P%L{{$K)d*!g7!A-^N&4dbywc1=(manroy)ln)c^{G|q@iVLX0)pn)2g z3g016X+N0VsrE?=e(QO(LSQO%*1)tt})mHDoHlLL`JyEs~} zX)z~jI`_Jl;uB^yRWvXaj=j@cOQVr9bzgqIeNQ?AH82&9q|<%?M_M^f+bsOq^~nl> zscwsh;yFXT-ae#)&-p<8X8kQ{l)hz4LlA!bvu2 z99tK*NJj$okfs{-ILfKjXNO)Uuu&iqXctFrsU#kaa{9#=wq}>=sAym+9Ea7kOFxcx zK0g_6_53=OGRldma8#AXuP%&rT29Gfui7w7Autt=k@`j;#cvOvv2Lzh87A&(II4!@ zOg_T9{v20y!Zjw+NfYQ5(jO2WuabxV@@G-~#BWV35eNE?qee2V zpV$*y-dw*lL=vcnv`UCo(Ov&&Aqk{EAiPdd?xI&nCru20u}07EvZmBP-*F5`^$H2p zLs}*J$7MHu-ebNm*^MHLvl}9>Fcm%_sTxS2he-Q1=!1u! zUA$KBf2F3>K)d*4p=uz3dPu7pkA5nq7rxv?YM@>0!>bxdpdQkG!Xx5vTLY<~*oCJI zl|T)J@U}|QlAoXtss{Fuu|KC0RJToPeWWc+g*^^G;Sn0t;+WL#y6Uoh{D4*o)Ib{b z`~-dQh}OrV_R4D)da`(@_7k4>3Do;&98!a7szq&ytWjte@AIk#wI3F>aFRd|kyZ)R zK>DME^onY#MXgV)s8Q&NZ?7=%cU1!k)I-`&NDZoY7PTd^6-B$azgN-(>LKkTyldR? zu8(`jVE;kWR_`CgeyTgdNpt?HvY!mn*c+gyqUP<{#L=Ui1uJG-`A?h=%oN_<5_y8D z@ZPRzvx-k(Hwuq%E?1bL5V(I0(lQQ@HyRJ0nJqSCnznOHHC}B=8OM0mMbQw1k5-B0owD-*a~e5w zgIe2|Kj@+AmB=GsehIs7?&|0j>d~$d89VbQ4RyszQY_7V-W`Bk648?Z;D@_i#d`y$7f1mXKpO9`gJ91*EK{Dx=9-ZmHK?M4kG zu*7KEg8cRP^IiMxiFZ=)9lJ9n?3~iY>gt)N!){*&=7P^7uNLkhfMfPJ>eaSu-FUlNhwN$f zzGfH)rb1ec1NMqCMEl|H0%eGHWn?P3Ll?!7_~YTYLkp%tn#vXJm^GE=@HYLkKNsIz z-q6;{y62sasZcvn!7X3@J!_E2-eq@?&qFWq70u%KmqjWXmq1FovK<6mOXK=Fdb7NO>19i=dS?T_3M{^GbxcHA>tUi zFx1MO@{LYU!nCj2F4|MAMaGMU*t<*2lPO;7wY(m_R7m^c@ZNFIE2KY02-3r`eqd== zQrn_qmj001ZPkg4Py!yTU zdbVgyxHGY5AH^$7g|zAw?))?T*cG$d^I>A2J7YyywE1Pd4dPiN*b z-qMbwPtF7=8kh>{L#P3O9=Cp| zk=K}+%X&lQs^ZxIcI0X!SwBuv{lHX6Cn|`@eNQGr1ND$riO>~|tlIr2$=pRcX`)C% zJ3}GE}Kim?b ze35%gBJ60Z5NJsy@S3AnXvs&2-yRP8Hye+peQ7m!+jjK|_7BtSCp)|GoX_tl*BnzJ zt!m(PMm?le0#h9>G|{Ty-qlo%?#GAN3+awii|#n7Hg~aVyLTK+g*2TTK0U1+P3`V2 zYIpHUA%T{X_Nr>o9P33N@BLNP@aXa^ww>^~3kv{~>WDasPJBXG>`K zJ_`bARRilC>LIPh;rj;TcwbM|h`Qav+L`h*8As=h&8!rsdYB)2m2FeBUD_yR&g(vy zU!uM4KcT(uQ?Gxgqwh$o8t6OfAx$TZR~Y7$ud+bw5wG3q+0q(Uq?Z}dR@-!Di&8u4(ez4ny6}K|ijZktIQz4zS#$!6uB#rk>6GJ6_zU|l@Z>+N3 zOj0#471Hl%#I>^iy8c|8`C;s%vsscw$+KAum6*Q4whwlmXbnjd$;Z&i4!P)Lhr_Gh z>6i-X_cWj+Mu8sEH13n@u>F0PW!A*;;fe-c8=BtyLR3?Zzezw2Sf4Du`Fd?AfQ+>M44MD+GFow5D}zdBD!vxTf*c zj^GBJ4D<<|478Ip&@NtCD!X})+2b}=GR}7iR|xbFX_~(~{GdI1(NyEF>Z%6X#deHl za=b9@8{;+`RsV_Lv+2aC$0^I{-;r0C3fp}0ssNov^7AxfUN)7$n2@H^Hm}6mmk(Yt z2Goe;t?6{Ga&$VE&_KI*f21q8<)EFvTAa~!eYirPhe*@f@TGg~sku_Ha*ZSTIy%Yh z{L2~Qd^H{IVo#R(BGnvwbiO-=wJTg9&_kp(ZPAq-_KXAhSi7u|{3klYEtt-5+d>*> z7kkb$pW$t+y?aVp)|0LW66hh)G`Du;Ry*LkDs26n2>y&t;oDB9@QFCkEBVgIUWjRRTT1 zr!d+zV$C}H;k1sd#QX@phR!%V|N4%M15@EM9PQ6AdV{@lZ!kL&p%R!2NNZY|M$7Fo z(+03|dm?ySI^FTVBX4EoXcwQnX{E*FZ|tqBJF~5{M>P`YA=0$J&*b@b_LwM^?_2~= zUH&s`44rE!au@C5vpSWlKUUb*&x2X*GAe<3NNd{dMqk-apH5@B9z^hIbfV`tI?+>T zpj~{rr!mW=3++!noy6v5Pzm%9Y09hh6YMwB=CGhos1DM}q@U91r$Phm;%I`V?btNS zZqaBK3w}a%5D4@TX*!{T53&nOhQZ*JOYiw7lw4R-95Xto?cg@mt%CYbY zQz1=P@L_lRyVz(}d_%ZGU`$A>Ug1vSi~n@Y{Uw?7O4YdXs+wJL(+2iUXe7_x@`CxI zjxN2zR7m?Z=z|(L>LE>M#UE^DKiRRF?VBI2Xkad=M52m^<8I|U-)=C6Pm-sA8>&~E zI~TR{Oxwx=`$Y0Bbb9tOI&WL#E~Y{{Q9;CkzM~$}n$~c4fL-mso$RD1T+zUMQ;9?s zHIB;T=b87*HI&yw^=ed$jCSTzJ6Y?Yk-YM;_2$F<4P+dc3Tb*Le6pCGYe5XVGALXj zFc*+c^hrdH(O!5o*sSzf6X}(zVQqb6g^t_HwvLbFztCCn&$~B~USTSvX&;uLjCNyM zHqyOExJp1wNc+9=yzkZg47JVZp3S9Ks>ZvAhpaEYj%7usNAj~vdzfu%wUAz6Dx_)F zWTE@kjqmrfNul8ifiWTN_liDvIPQY4kI7=Dztd8BrD~+vx5R3iEP?$nJCd751v6_{ zYv~oHLR!_p>w$Vm({3aiP3v-oAJ~BA;fe<4f=ak5p7-N8dB{v?wym{{L-p!l%C=U_ z1(W@;Ad>$&HBFHDlKimb+oNLSQZ+twv6siFc54EMwXK$|scG z8zQ|@HA-!JZjMN8v+Ii^dH3;i5*il|m0n>gq*V>fQPe}4R#dgCZpF_(#un5LS2Qpe zR04As?G7k#A)vx*Zyc&uC$6P3Pb{(7jwO-2%9|ze4=;M-z*I=n8KBNav+bJWtXZva zg}_`uT8*6E-38H!Au@L>tnV3=Ws=t`RfAXTsVARgvrgm{ZT*Ve)`vR`XAZ7H40N9O+B*1t&F%#$Jp)$;R>O62)W?*iayA9!upwD?};HLZZ*^Q zuWBZ1l&azBxZe10LOlDGTG6@*Oplt~O6C=&LRxB2)Z#~toZhSY^^m5OtnZc?9sWMd zjx`HcG%y!b!fRjiydOuAMN#^wa*bsis#hzQoH1rUjA0F;BKcp}2I+Npa~TJwLYh{- zBs*a&%YKO6Z5yr-mxW9t$<_>%_GD^=rN;aA4geS28VVUc`R zhWYxI(v788m8ttahEV=*0fzqot2qJg=f5{Z$har92RT`ya% zwv0pd>bL*0u`h4$V4wGm!YG|>6NO{{Y^BP^14n{`mHlu%Q8g{hFHC*hl=S^m3w*}^Cq>jMH~ zLfY?@=Y6kEp8G|wHK>~OO4WEeLT497e$SEzNAgbluj=C>0;N}&3TaJSJc_e_a_?Y+ z=7lQ+dWf{@6+M6Gbi$E50c>!tCwiu3<)v4u#{7sDEcM-WEKSu&zM|M;Jy&>T=@q6z zT53?#;zzw6sE0J|%2hLjbzHEKt))HIQ3G>9CA{{%^*prUTYcZJWh^mH`SpS1#(^TG zWE`qjQxEiD_YbXLZwf{7(Pxtze_CZ_9GD7eS3&;r@SnfFt80ZTNe$FP+MCqN$!8pY z?jo%cwTkp*M~8mHoP==2E6fFzaQ*U#-2FUDTH}72V$!Pto(x8O_QEo9HI9hh!`ZRS ziEB)^$8qfsZKn2a1#A?+&2UmlLpq8`#Te)VoNd%JHr+j4%Xl>|uZ#mzA+5%NzM~$}nzpC= zRF=ETeD=koa76=SQVEQsRlj^jw{Nq`I693fXiRUCNyedi^@TZ${a1J@TX-RYKmMnX zap_eS83(39T8#sJM?IuzKY+cnS@Ib(*z|O&2IiYeU>whm6*KCW{zS&n{oBus`_U<7 z9I98hep|@mPmW=G_eSukQ%e~~AEuUZU@D~5IM8?0Lz>P77_gZ2so-JFOQ{-|Zz_Rt z3|&yxi0$)QzS|58C}(6z|Bt-ys$PXIUCFWx?$2f{jNsdbRWNSve<4Q)F%{Bk9Oygh zAx-o8qE@k9hay<9U{wS2O(ign%!eu&OPAf2aa^rX)o6GBhKxh?YW<`2>`bdLHnzX2 zfvJ#I<3Qh04{1N)5v@8+FI;1`!y;3#$L~UdhPSs%>X%F6q3Du3# z`+k$Ti>Z+IYtRP|M^8`>Xf%&Eq z7)O<%b&atLqGcSfOV>9FlwK+0P`$c(bQc@g;!}3#R0Mxjv99rZnLRQNOog->2l|eB zNYkqL-*>Q0W_i}AysClurViCp>Ecf6PY|-5a zo~&)KQTp-<83(39T8#sJM?Iuz*NCC}*!Y0FEH;a(f%&Eq7)Q|gCWf}RpNwN?%4SCE z>R~bt)vLp6;@HHwKO2)%&`4@rQzO&Ei82mMg|r$6`i^=?(@O6)39Qib6fEB}8c78W z%r}+5INCgDZq(RbL&j0-S_`AxUGK~h)vE>BP4;f*R-tx6X^3&%nGh)Y@Tyn+Hao20>P7mgwvl|`&`@LL z(e^S9Oog->2l|eBNYf4i!;i8pk-3bfi^CNS%r}*2wc24r&Q46&(le5m`#sdyH|A*# zk-O*#>S@~UB{Uw>qm`b1Qn*53Oi0uG_FFbPT>FyQcW@-HH!0KzUeY*0XrNt;kM?1? zbBw(kSDjHwGMIbzWt*mh=i& z2=owXn%A{3ffeaG$LcmUl2>gPVnoO1GesO|7we6tz5L=R^JE!p)oK^65a=P&bmx2- z%T7&5u$s{5IiKH>&hu(6HP9}$F|=P_p~LL$>Wx;K7Brp+1bT?HrVTix)R|B0b~H}iYHP5uEX#6l zUco&P?_G2%;&z**9h%Z!S0`K{P*3%Wj=Eu)wiK`{Esf;Gm((@>{c@MoK)ZOKr~OM> z$Foth^4TwIhARYmh%}8lFWJ2)Pe={4i+v(Z3$L-4ZOB~7{*^S4 zKo60ole03dX94@`*}pD~HgbUi^~n{bu?Ow1nMEJX)|B0 zWR-7(+4<*2^0~<>8X=XQOAWM(J!hI@7XC^_rcvL^%WCQZW?0zE`p)6(d3SkXIU?X43cd6s2`jXVvq zNDZ`$Ph^@lE-N+AE{=+5TE#Bo*|%L+*tf^g8!RBu zL!@cmYvGRU%GgzQ|3;B~XUr45>hG1L2HM3@BN}y{*q?1%`HfwCPPjs#9@6T45Xatv zlKrHQuxiMsdsU-qL@+y>HrfuN`B(LO{-RfZ5+J?8R7lgf&$%|tF0;`-@J+ZvU`$A> zUeWt=oz6d(J+kPXmR@}?lU}JBOJ7uF*RpT2XB4A%^y~*cbJLpAD@=v7s)3QC9?~?Y zsC7;DW$NvAa2&m(2Mx>xl}J>PZ^LyuV_n8!#C@k1)9T7NRIfh2ScE-ayxo4Ap5`ZZ z+M;iJTu;Vmg0&0#q!+)>PPIe|45-G=c`kq!NiLY8;tApQArq z)=u9=rL|2tN4I0{zORMludeg*44p_he^-SH#+p_retdJw!UuClNVD zd#>sLy=+ty>6NMxAO6TF`)90O=5hoNo;*yS|6eod6{bR(_7`3D!uYhVX$PiJ35*Hp zq`i6>Xy}JGHslX|KK=7LHjs>nGL{y1=*uI$Bx7%d+hW>M^p7wf=j}P>JEi<{OuKw6Gt&9Hrzgrb3$D z#LbQg=<|0Lr+$joibks?dxCcCX=}x?QXPEG%yv?zR11ngx5yh zHA|$PU=4cwd&27H*X8FDD}GAYoqMJw{yrl8ksy`8RP&<#Ckc^CCH9s)7I&&jYp3F- zEJ_@>###01dFr>u=Oz0&`!^kDSQ0VS+D2*hDIMBcbS4_D%@9AsrbRd%emTU1UH2pb zy>&kCIRqjV(zM%K=NHED8U39`OAax#g{hF%w4+-W>!BA%JAKYKmKwg5*QkfI*DESh zj`)PDm(ecLDgpaq=)Us}#M%|4X|LiQVJuaR(az2}Wve+^XXp)I$&&<>R7k5DxGEa; zR1GilVH`-S#CKIvv%Dk5IsN`_YGLkTD)g3meSZWQOIMC|8b>!~xJn)KM|}3>x*7-O zE)rN(NKvdd2R-F50bmX$lXDFJ9;2Z&$SO)vhgvaoPqPBE%XX$m8kjq zI46IKKiz%s) z*0dho#yO=IHwdbfGn+jVJuIiGOV`r+Idi;;S17jI>vnT>6%zXumE=bU?~ zBdrqaHjH*=wrXz2_n&Rz`Z1(cA~;~AbFar}J0apk0S|!}v6~7#J|0A)pk$=VE z`#DVs{XgpUKw8yUO*=Zuq2RHiHs9QJDpRsWbKyTH7D(DW3679M-oV@ zL_(o)PV;?vSn%c&X4KG7>*~s%f<#^+tr9Dbjdw2hI%-VsF)lu2N|^QN-e^f6trBck zl=F5-1Ebp6jDc7ukX8x*C8tt?*8}ULO7yPN+$mH$7a#GUU_#}QIjtpM7BEB{Z)iWV zaPQ8#%Jo;TIqf@VxjW-2sgS1qkPlaOw#=-^FWJTI>kSK8gQBua4b)RhNx6sINnN}o z|K#!itRG*Ov~o;HD+#1k;4y~k|fyut~W zmesb>e7Ro|NUOy4@A^93)?Q?b+Dr??I)SuG;5EnVf!ALpwscJEJWmnEujj~YZu;jt zGq6`fnY&Gjt~IlH_o`N|zk1DSA3)RHsZdFUw5Gk-dd?o(qc;yI_Nm=|(th*I!rD>; z_0&?5yTM~S-L|egV%Sm3u&$W9^Xig7S|u*^N$oV~-HzAJ(Z@=+<&k+eMO8^4trF$d zXLl~8Zpohw{>2oa(FUv6gETx| z9gjmhE}HH>kng2Rq&2POmfy@z%8%ta|M!Lc?~B?Ax9u>4PIuH%Pt_PwakCW_G>-pq z@L#L-&4UTEVnPj*2&7e_R=&)3rtM>SeAjhW=7(9$Vp?07yGW}<_?Hds@S~%7?Rx>% z!Wy;BC5u~20%?_KNJl%qP8h+<>YL2c{|qvxk82?bq*da{(3N)O{X=-o=GzlG)thVX z+TTPHNUOxcg)w&5{|4}gPlp6z2}fEb@S5ZG!0WFP2aa4f3XU1iE96@l_ve3s`Y&(g znZ^3|8-w(^&svLJB$ex*s37_b^iTA6KS-t0KcuV0O5_;BU-oHc-QSl%e@AZ>#nTq* zVHwl33=!#AmwDrO`9DsZ9kQE2JG^Il>qx7_SEIf&P85&g1M{RaUxevFhrH))>qx6a zxeC|yTeqWl&u1l~vGgIW5{a>^rCm*hIWn((G}|>~Fz<9YYy4*`_vz`M$@A#-l9gg~ z{fsi<>~S|(kk)iw8gB_)}cJ+mo(<)U48X?CFEK0I?^hUb>;}h`;O!{ zQ;n#O*BNP*NGftHV=8g4OG@6MU4=KRo{#@4-b&-CwSRhAm4hqR`BmoXjBJwB9QOa7xdt;$Wk z)9nCBAgvPBd%k9#xXyg;yHw_9dwa>ouN<3Oum_H3^z#AN$Py??s(khWu^d|K-LMQ=TQIt9gYQ?rz-jsR&act!bTahVo&9)AG8rPMd>nRW^>Lc`7wf z4{18jt4s@i@l6ii@?=``P1-Mv&vK`bxr?+)EIZzSAI?&kr>_5CFJ3jIRU)Z4u*9gu z7mp)(+mj|Mwz-LU;966o@9`Njj$e37V_c;^G8fdyQG=dL#lGhsq(WNLp7a{Xt4`a_ z&Yn19F8e9i2>D};)IdE|BS(jD-m&{})_!$*Goo@m!=ABM5=g7Wv^l-_?<;;|GsjJh z-Ta0dHNQI{38YoxbdE0kZ0T1l#W%NO@TwuL5=ljlB}OH7e>avlTV9+U7}m(VcrDa; z{URnvl*9=~!;B_*0_2#Cnpa6_U@D|FE#r6Nc&Go;u-etnndh3eHJYqRCnHBar0L9; z31fJg9~t|hV@7jB{tzS0FEu2Av`SQ+JCY|)J&bj@cqH~orkGq z?jpvQT&j-O8EKWcv?Pi@t=7$Ix3iIX?O>>JJH|;6c~zitTjO5tjHc)_KNPl{)@1 zR(OT9N*tyW3j?SAsK+h+D|X?JVaAssRpd2CS|uVXNAZ_C*BMV@F4VxQhO|l~6*<;N zm9Q2J=O@R^u($SaY8IT+)OfsNrYYhWFgw_I#^tG)N=_##i2FG`nTlQhKs}^2txAKDyxX8r_U^S=%!apH8(&B3l0aG|GBzE< zOEsxuH!e^$ZhDEf#;IYMB!RR_%v&&y|2;2*eZ2L`8hD+NR*A&e)yT1osYLQe-S}r4 zAKMMXTbO$i0*u^;Z%VJ$cdl$)nk!FRRdU*|;CVlHF-MUW^Wi%49Le9<34!O$$+Ng| zuEj~IfqF=5TJ21|cr=}``d4fwQ$JPL2&fYy38YnG+F$*-GxSHh+nB6z4@LzWmA0&t z1kx&TCFelS_wKY$1@Etp*BNP*_-Soze!t0Q&Zf4F<5K=FhtVWOK}(dxWKIrac%g!p zsKILF{@kLH=$@PKK`Nx_wB{yNc#j5EohK!lSq-WbFc$2~DK$_})p(bdaZjJJ&Xe7z z&Fs0T7xprPB#>5#9eEq@h(8NE*-ED~r;YjC=yE=VB#>5#B{Q1yfxqT-+J-NUDcq&9 zv4cv6h#YB^=-fV(FY2GpIooJ$3|?oXRU)ap!Wyg+ZL8(wzqW1SG@F+^u3_wTeSEt> z8Ar3t*Y!>vNH3p228vwS**)R*8Qi%J3tp zIqmBlTLVi5(kjuY_eB=8r?1oZ7asRHo1ts}G?g0oK1z+;%`KT%?s*)t>|!dUHLbF> zjYTya=#+_SW@+8m=yM(hdm{%uq^Y!<$C%zf+*uWH#>|p&ub!<%JxL&~64}!I#(vt- z%Q==ky;-FE2|ZJRnvy_TB~q{bk4+2e;&ju#kHxEov`YBP3DsJR97~K!WC}2tK5>jQ zvD#^K$g1l4A76w>uka0~npabn4Pn)zM>>}#r!_10?4`Hv+ENlot3?0h3)%huhB`;K zm@#+-kyZ(e!#(*#UO|j0X~KQNmITr&(dGN{tmvqIPO=|t<&8T=jxo{d%-HVi=YD;h zY|RrG&fdUO7?Y-D%Uhjkw|hCu51&#rkU&ec*UR*;Sg~$BozS{*3}?EaUCcw8ZP;Z1 z`y^j?XZ(P(idRUWB|2E5!g{9n?&@5Lj%7Hwy?f#JL^ zw2O5`({>#{%9c-Q?XY)e6t9p#OPW@x#~t?Wbu;IM=`frFhjy`U(!0BRzp~p)nmXH3 zoKn0(0xi+$@&jM9Oo!_`TmL?$XrNtegEcMHth9XYrkc)-KMyjTVTh@)4W_d*hrVWe z5*j#bvmI76kU&dxvO~`teAKo8XJ|2-;oM5Ji>)@*y6I{8-UQ|h=zT)*3JJ7CBX^q$ z^3W?4orGKQ4CjcVUA#-sT(!PAxZSj>ld&XtnI$HF;=QdgsJE zli?g{w2S>9+DmVH5T9@&z0>lmGm2M8pe3q!jip5@<=&);?&$Uu3y!Z(M#<(LlS{Bd3{EsY3X~Wf$y1Cl4^31&^t)M^4YR z*_-mHZ|>R^S{+d|kU&eC)~jB7J|eAUdshVg7Y_t?+=Ijwkw1X`j~r_=Z3Lu-6(Yrn-Z zTwQ^7@o7@izO_5@;%%1Msq>suyg~vkY1*V2efXj^eeD)EVi~RyLA&_;NxO^P=*sgv z8)LUUd`|HS3AChX=hOG+t$(j-uO1xFaJ38C#V1xx+dRA{->|r@JwN?9#VaJx5}kaq zh-UgOO>TFLv>2}1LA&^bOm~BcefX}e8SGF0Jgsm%NM_Xu5z`~Kd(Lz&Sw_rcR zbyt`QM_XvM?AmbtPqIs9kv&Hh4J6Q#rcIHIZd1I8g8OLxP9NNWEJX-VfvM=Acd%KZ-%^AfjB+wGwKj!!6 zQ~$2WelTMht{FtTIPOP#0(zZOyg~vkQCqUV4{tG~Co7pZj^Vmgw2LE! znl>R%Pkv~8Lslg2oZ=M{Xi3w~J?p_6KK+W_N|V5FEh^f@kx4q6{9;%BJdcMx`|hmb z6%uHP&hRq2@VD>2VGlxWhU<3GE{<7iTIN)p_@6shu-0WxD_$XimT2|B(ssOjg?Ki) zU<|AN#R3FIMaSV4RK)d+9g`SG4*5P@sYJ67yvx-+p zpe0R985+o=8|CEtH^nmCTLSIk`yD#_Y;Pd%+%^MGxA2_e6%uHPTIw4WdGp+b_{fkr zhWl`!U3`y6Ysn5*3kqy&b0mY`jH^QUPAdX(Zv z8x-aLYkXGm3JJ8NY40u-U@CkEt!YhP=HTtVug?4B{Xx+{ z0xi+b!zDCcFHJ*U;=Ijpry;b9Z>_0Z9sh*49maX#9mf@~kU&ecoZ`+s_O5Yreyl+P z!+o64F23ic-Hl^ku;Kgab7%i4#VaJx60N(7_=!#4*M_HW5XW%OE3}L6)irHtmmBO= zWK*7jMh(yw5@?BL^QW@d^|~E+`;D;-cl$!SIO9UoqE;Vf_g1y$ueO|1y@Ht|Xo>ow z7o*v`J6-s@uj3f*bB1504ywXZKIy|B zr#!4^Ac2->{ovf?M#)&=;`j4)A}Jk zfS>s-p5gwIXcuQdQA@pRqVb#6k6$uQD_$Ximgs&y|B@LKGk_l%6w7dDO|*+M_Go9L zESkRMKtDcr?^(qwB+!zk?R~b^>XB;z-+D5J;Vz_T7w7oVijmHBt*=-=UUlg?#VaJx z67{K{r?UIaqP^Syj$yd}D%!1oU5p56>80}pTF$F_j*n%ULk>&==t2( zWH(*ai5FbvFx;OS?c&@>nh$43+qtiG;4xWFDqbOhmNad9;9o@TX_wPo#IK!Cck@dZ5zwOk5FVlWh zyg~vk(K@f#|LmfN8}Y5n;u-FBj&^ZQGVLHx_HVm!o?yPD*-6DKB+wF_Aw4iHZTwlA z_Z*PGa9?<|i?f*NUi)b(CorHE?TU9&@d^pFL{E@IayW$!2k`PMEQUMcqg|Z$Ok){w zS)AZgHTZCB+pREW_YFn+Qqd8^jw?1q%&^WXME{_BZ^l@pe0RfU#_yVKW%=VWx37p zYzDN8s}(fuOQt8rZM3JJ7C>%7b$r^(SQJXwVU49}QAySToA`ib!Y&gqR= zcubMwidRUWCE9IaOKs;wqg1?n%n?Nc?c$0EO$+JY$jRU9U)Ju20}M~sz*M**g5ua! z+qu~;6^|LFY9N7@sD*3X%E=mhlbwGM&+wEGw2NyfXt#xS!Or3=PuPUzCl#-dKua{| z?#nQzn|Xw-Ii0}pd=#{cYc}XU*rkQ@M!UlDk36Y(g#=on9f9awRGFdM*srhR8J^mL zc5&sCrZubH);ag1#pbs>t$2k5TB6axQr(@FUo2tM>%}uXeFp8~S}7W#&(pzadE*;4 z>HJy6D9)_prpj}*DrD=u7c5xO)Ph+E~PmQ*aKudIjORE0P znA&w%LYWwbrvaf|T#uz`tt#|zP8JVieU6+{yg~vk(Oa3{!=11enV54hj^U|BXct#- z(T>(ddOIlt3bO{|&naFZftF}j`4JJ$`OI-fjdeD|^PJEwuKA+2WNKfh=b|%4o|9)3 zuaH1X)U!O<-^pIGy3s7|grb3VagCX#4X+aEw7n7-^yk<68J=W?sc_w;ru`il?rf^9 z8^O`X6b&TM5}jRhd4O{wT(@2x*~joiF0_j)HEH(eu71wHF{R8VkIyPzA%T{tpBNVD z#P|Kt8vZtx;mKlX7uR;u8@n*@_$FEIr@ZnPN5-o<*r?tLS{r|LA;9!5{&jO{6tV zoB{fZhzDKYRKC7>lQp(W2Wwe@IRE*aLIY{)k-5a#Z|Cem0?z|gHH0_bA9b}X*nKY! zq4C;{12w>|34b?fM7Vq_r(5xCGV-qXcUuEq53@2&tc$61l~_a?$^KV^Z|hZeFMOj! zi+a8o#P7t@fhm75M@@){yc$`*8?RaADHBYZB30h*Jf%~i;e@?VsEj*flw5DCZf7Q4*b3Fel_{C0K_dhdRig}SE*1LNrn5c)e zrd@O65G;J7>{0-Ke=iPq9h~(2X1`CZu}ePvASOCjW_u=Hcvgsv1ESU8vx&4C2l|eB zNYi`HB=QPV!DlKZi9a6huHlrvL)m@LtAs`M_?aU`WgOtI4xitvQK*5wqaM;p=M|=c z&;Lgp*h*kbnwC@?m;23f`oQI2WllX>E| zCi1hU4LyC_%6MSBW9N;I^R0;zggYP3O_fMX4NGW*Y>RVC ziS!CRp%p`BhL<&6y&XcuW(^Antj|9CdUdGq<8c=rlQ4YW%uZLHt7 zWp_1lv|YryULWe@%X&xAKmsjMxUcK+c8!WUvlCjzxg|qtpk23p)J0Bf+MB7F_}uS9 zoNXai0NO$VEzua+zuowSb&u^w?^4CPB|{h21MRwdPPiJW7lrWJe`Rzw4D4y3EhNwq zoz`4>49}9kzTJH7#dzOd20{bvx_=jIHYkp68OHFmkqzysJ;n#3t&b2jyyZ<0pF}of zlY5MhcT<_-8?=ih-|rP8uL994B+wF_eoB$o`70yeIIySXyDte1w2L*^pS$e-yHtT_ z3kkI3zk<9^s1@g4HA`rqU2HM@rG&@CwhTa9NT4N6b4wzxlJ!oUTl%C1+Qrt@U)uSd za)ScV77}Pl)^ky#xLeOf3m`RAyNP!qO>=84uYP}90NO&rt%K5%zh&U*F072EeE3G( z)x4!4(XQKKSl)8wwpX&HR&6B`swMKurnZE;ZHZ1R@1+LXC2w_VOI!_VOGFFD=TKXM zwveEh{FY?yI@FeMw=L0We+H?6b}82lYD-)Vx`H;fCERUG{I-ywYvZ>hONm2m33uBP zgZBN98fceFkKy*zylsg?Z3%bV62C1ZsEqk7$*lU| z|Dcvy!9Pd41Nu?>((xpp!+uelSToio+sgC_NwSVRHNO-0`MpFq1v`|ls3FB<5pMIsKg>#Mb14fp=xRH7aL5~znXX}c{0-9G|+ zt%1-$yS~=PtAVW#5~zo?|NbHRqN3L)T58df>1fy2ih4DuM<(tcqAzM8fqF>$?;qGw ziyowoc6}|lS3}$lL|-&5^(=kuxgbyvY1w-f_Yct*6}>)rzY_%7b!l-Qq%!8-KiD61 zSNjMdJw)1n{}6pq!;R1cucTc!7u*)ky??N_)YC@-^;ECiD=7M+0q&Kuga+DmucoWv zmJ+^@o>-7TJ*55j578GDy*|;lOAWN^mP%K{y?^j`^yGyE>LKla<`jKVQO|X^FDmM} z>^XU_L1Mci`=b6{9}=ji(!QRh6P~&_)fQi0)YpDU-^r5f2YdC15YM%~zNp_TY~fT( zz8^a|f#{2phWlJA`l7z4 zZRyoV2x-YnxP4LI6Qpbt(XQ*2=!<&WlJ}psr7a{}J!#1sx!V^NZHdTt`3>52bHwm! z_(lz=FDlwA5$y*ATJm2((H9kMi6}qvK8SYRE9+|bMn9-88i%%!Kui9TDEgwlCrGJ* zcHI){YWPNRs4p6iwvcekv9#oWN)>%k-?Ov)2JN~v$|b10yFdQjtSnJVC>7LsY%zT4 zsU`6Bef+k3y&AXm@&Db&`1@D#8%#wpiD$U~4}rcT?Xxd_`}>K~7TTq2Bc9?SgDm$YJY4*ny*K|Q1s(~CGzgZ|%7Cry++^OK(U z>@Z(x_xDlUyR*Dgs~R1i4Ab}i@RKA^FX=c?1L>rRffV(sgv`}Mxk687V}E}oX@bfU-r+v<$|Fi5@!wF{m2sd3(y9g$ z7!%Se;kHpS4)p!KmdFpO?G@$%(lWWn3wa#!B!RAnF7h2)ZSuQR zJYLS@&{Z?3BuWju`=FjTt&c#jkp6)1YfyPLsYdN{Ym~T$UM7{qs1~Mw!&YNdoB)2!TlgJwZBY0_~C&e_cTjX?FC%RBY_&aeULhjL|~Oy&IS$ z>u=k!4W`+KLsHw($Hwtl_@ZPla(+QoLB=6>A&f$eD) z!T(uOG7bsULt4|)*B!w-ESt=tOAQNfTW6_(cCnqOxl#S9@(F9J@O~4*o=dp7>pWdjGQiD6seyLgoOX%Q-Ye+P6^ugy^^lfjSCkURExV$( zBsEmKiFJkMA$v=rlYLc8tXqC0fqE)UHA<9raeop&zIsPB%Kuq+Yk?bwTL&e98c4ur zvP53lR6iWIeu(>r^a|~ghyFH3)(=r@9k+h?3ABr}tRD{550Sf~eu(>rFLJ+K%4vV= zD(i<$^~1@xv}7FRiC+UfK})iJI8;AGDG~KU+zq4#+NBcXzpu#p;ZXf>vUE2e zzr(rSx*AkJMC7bQ>0xnb3kf$SY000v+^rwt8pvqH&&dxeC1 zZCnkvT=6ng+VLB->y{Fipz`DX$hjZ>_feF}U%My))&d_uZyem-i|AkZ-m%EfNfTJE zkWQMQRH6rI2n`|ayTg&CAh+Ko|1R#c;>SOS+RP~GjR{T~E+n6w7_7s+$SOV8EKV34WyGM@E+wp z35k&#-;5-wr)s!&GWiYC=%GrWCrBqv;9ZSslo)B&g;(gIU&A9xJ9>ijM+rjJwjIkZ z>Zuxd=fpch(gb>fv`U0r|IT{yJeYU7myaL0+Q=%l|4Zv+>GVdb&0Vb8&xcu$BeNLy zTh_2@(dVfmI+T8S>aVR`g2o29NL^^3=$EdHQ-S^KM@|8l0-2B zCfIl0X;3j91@)+)C@KnyIbZ_xR@L-0Pw%q#cmKHjzJv3z{nS&{p}M=etM~j9yEOR! z^UqJ!mHm^~{Bh*`y@EYITo9<+4leBZ^jonX#N@hNja!g%0d5ve2A9f4nd_-O=cXNL$r@5d2O7Dri|$Lzlk*>W@oKP z_gp#juI=y;D3`x8`zmOa+Cg=7e#!O%*VT$OcX;)t)U*);&8n{bJC-zmIblsiR=L_m zv{J3ej%r^IUw-+-8Xf{Qsl0Yie|1|GPo7T?b zK%0ETEej?^b>FO3y1w5CL+r;(o0IOS3Gyj5eZi!p-ka6R$|KMwM2l8>zp44sZ%Hd+ z&oKwLGs;E#sLh|998q1Baa|z-HAJ+upr#h=$Sp`MB^=ztQ7*Nn8wJv@H1(@8?pKIF zK154z*VNlP_M_fTy*gk!*yEsF>iH>$G#`y9O(SYKk0?YSAENy>=ibMCDNnwH(eh1R z!sj3l$Nn%+9xmdaNDI5!yIZpqlt$uFb z0i}1=YNxqvMJqyJDMX9qOq0zxu04XSvD#MlC7vBv3b}>D*}AOa<&9?tp_O_~(Ma%yLki}r~xNlr+8iKi7JP*OS@Os%$+eMv;E zCLG+uQ7(=GrOu!^O6@bCjQbVJLIg@m=h{mrUd5il<3PF8+hq>sm4V-a*L=}09p~Gw z3d)aQsS#Hk`mP&;h{n<7K+@Y+pVXwtvgWRMGNw|Z3723Eg@aZGg2-naBscxZ`k%@W zfszD4f2AV|Ekp!L@)0NtHQ}0Ot$1ZnIRZ;@`!j;);K~tLihHG4PV-~s2rR{8ML1}- z^AWBMsIIUSdkL|F<}M#m=($c>P!R%a0nviUXSItQh^~MjSlS+lKuxfZ`C2&y^+fkg z8di?z{ZG?SYLQB1-`vN@Ci!>%&N%qLd2`>MM}?ms)KGdNmO^xfNbTtNV`Gt(-*{Ip zD`o4==g4Q4Kl#b`Y3;spZyBPI&*wk{mZI+>+gHI3{m8TX7B8N*GPA>#LUhK#|IO@2a9Tt|?`j5L}eL-D8Ai8pn2~Yk|IAY>afzxJE3K1wtsYwrBuc!WgPsG|CwW@j8f9Z(<_wcN@ zbC1cs`QMfLb)OOX^Fyab%V(7oN-io1|Gf6-3J8>>)LT1->)Yo{jb5+QpwMVSN!agz zl0g00rI5*G4wR%+!{NjAgkd*F2fck}*~QP5gpD3*8m#znN&)K!(Mp|l9j#z;lcLw| z9_Vo(+DH8O{ZM`Dw0oj9i|-3j->ei{iz7H|Kf8uovppT>FCJZ5b#*;y!4*T=1U_PX z!;$)q2j+)8h7F4P)h-E_&u$s0;I58X3ei3XdWIu`57A0Je(Z3)YTlISr|9tzYY}bo z5%=}#rx%^PIXZCFsJQWYCE?+ZQVaH3SB7XGv9Z$?I$W_KDt`V|q1rhmVUrID@x#h8 zMEi)P-(RhN+`KxPRqyEF@Z(FuA^pkn`|Fh<+DGK857PI|EJWWuvww(ng=im<)>hgc zrg;@<1J&v5+~gx_%J=OZo(ufiJ!<`Vx_yE=M3qnUs*jn zs@kibK5K3bvE%mZS9+xo?b(sv_iZKh)9H^XIpp&>P^%jI+uB`zO%BnOBd~rD?ISKb zyNAAK=w;E}V}FUz4s07Afm&Vk{O3|XohA(o)}8ipT30Rp_3BNjbJ{o6$w`j{XU{vq zt1GM@M0<6muzrva(HOcip_`>|qz`Lnpo% za8LX!+|4V6XpcjoCdlV=G(P1hy&xGHO^e!k99Yvn0&91#-;YUkpSn4yzxO-oYVxYO zp|4e8Yrkl6@y_Ui^9Jc~-5FxXAwM7Hl|r;{2kMS|K1YL1>!J;MQZ)RiOFRy&Hy?p^ z{90}Q4!n*UT<4GA;<=%$yho0xANpGTXVKj7tn zkBM2UpB8QoTISA@@7K;cIP^IVfAi4f(m}UIx!s29=;(<}xR-P?jl5Eb_Ba%3f_y&5 zf`1Q;&h2|^^guhG16$KaVC|mO?Ge#^t|<$e)O}gL*PQmRXOmL3hp$gwSUWd*XqNQ$ zIP2}GJEA>1@?*c6n96Wb%cEQM&# zaz%5L$mKNy@*&zs&`g#hXdXm#E~RWp&ly`^KW- zitcyke9NazzRnD8d`0xh?5jNvEQM&_a#|IOT)Q7gYk^kCK4Op4t}|oT&5fFGzn9l= z(jL6t#ZsB1bTyYiaaabWxVh^E7bn@O~rU@qE0 z6tfsW#$oq6&OW8yeBgR>Anl57?D;@}*3m`S6*{EGceZ zNGs(2>v$jK5GYBhGdEpt?p=3hG~?(aLes9Kc>e%eA$K^U3~fTRQinY^%*?s|w&>IT zw**zsDJizLt8hg7i0I>C=BuY>M33G*A%|Ka+DBxq&hZl3TNbljYF3Kd1KY`!&)Wz~ zh1z8VN)iN@mgpeGlf?UQ8&KTGeea4RMbNG&EkzL)L|2ZWb$g1Sy&9q`N8s2-bOi+3 z5wLG(J8<9TBhLNkax-f7XVD*r9vZ&d^q}J7Q=iFp^se_|d`78}_YN>smb?-TKH`ib zB0lQdyf}YGn+j;9`mGybro1;Hy7l6T0oFTef@o$iR;HGNvRhgQz>WWW4e`PFR+3&|HghaYn6ND@33qrN&GfE?Q0hc3Q%+n1fejC>Pg3 zm1~6vl%&)re_f%gzxD9)t*@?6Xa_0n!8>}Ciz_Fk*4;2%x9m2%Xb6 zmnZ1!U%jO4svS)X?FWT}cfu$aS87T*I1 z6aUZ9UM;nQ_O&P%*Vjsoe&qz+Yvj!x-)Yd)(+UwNNvYu-KZvF*->YoNq^k_=ql9Ax z?Kx2{uIH5+HfTq*pwTVielK3^X@v-sq*Tq4*3lbPHr&T$Glcdy1zqLsSQN{==6)*?y?ocl76P4P%q;>LU)eWWPwL%0+ z63Y{^yvUZ5wZgH6c10)`_tZ*V-|>TlYPXbY7iA#=B}ogKdLwUM&Mio-CLFxGL%A4# zkX~Y%zg@E<_Y#za2$Uo}(Hwf_+U496srLy7?>|s3MqZ@1n{}^VQhFuzc9ew(lq4g{ zJa*3PEBlYc0 zF3kq%3Wruvm1~8Xpd^_&4a}U<9z1iRT$P5$Sb|44Mc1{wFsCaVnX6-)l=N(4qwbQl)|Mw)#&euHat>I_|kn+hYqtSPV znG4=OHaPXQGk68y*im581S5=m*%^zXbz1Zsll43TO^r^Rwk&bMi( zR4l7y)X-|B)O8ncF8%7?3A)Po*|}o~IdqH}qP zY^wC0jJs>%?5KdCvwuP4>Anx5D@V}%0%7O-SBUlzFAaT*#+6dvlI2ZT*9dyPc7F~m z_gho6`eaDs(uM7tl>Sw&u6BVAxG#8hrLcZ>xrVohym$u2+E$BUZ;)vP?Ll_X*mZWq zWJkf;;YvA4yX2srSnxQ~p6Jj@opQ%*#g{(4A!)UCxNcvq*3or;J6tR**JA(?J~q1a zr}6!A|Dn1n+djLndatx!A=+wX>+01Njms|jtg+PY$2)4o!`r0ofoLC5|Nb)zed|su zTSy$FQM}*x1D@o1N3@SP^Oc{2zPX0MDW6H3yShTOkDz|*wa3cv@q!vYq`;-h)thT` zAJKK=s6wY77NrP4XXBCE&PQDHShYg_+gAmF=*khdopReV`3K(>1fnY-^32A%4_;I) zx59EDx^l$U&qw7}SUV71IbwA9crI`23elA#z$eBYns@rrck}(V$(`Fm_y6tMu*$j` z#W^k4%bpx}@pykisj=P9F?G*AK#$opDMkeD?h&ojdvj`;$v2;`-|2Hzu<-l);`19H z5%OIFl#4emCS7xn`DJ%iX(fnEF7qK;ssGk(6`GeP=!?cQEJFmA zLT;s6Osb~8ncq_{-+n~yhp9IPxr-VI2Wo=1Qz!yix-go5=5_k50rSfqX?9F-T#x1z z5GYBh4()Q$-zB5;9((Q`Avy*Q zo8Fr1slWL2+5)m80wvL^@1{V1b#zNzs5!lWKS8;8w?%qMK)po#BGqVt?i3ZdZK*wS zbR(%~dyIUiZBD%;qFy2h>KOs`-3p};&0b3Wf<{zCBg)tj<+P$P;m|&UdSXaD(Qr>ht*DQcQm^!E;#%0L6Z`nOZELol7uAfh ze)t>F4v}ZXv;A+(JY8r~;omokR#*zrsXAPowR+;=sfD{{rFI|!CHV-n5D_Rz5caRUL9d3I(1?m@ zY>G`vb!?YQ{wf(|cns3Gi|KZo^b#zEXkV*kGpoiQKem@xj-`-WsZP0x33)j46nQwT zUF1Ww&w+Jm&Te}$T0DMUMtJhvcPh^3I*A?PD- zaPC76@-Z>_F{>5%D?|Rud`bR_d{j(#2c3?7+1MmO^eHffgbHB`Nj9 z+MJ>J!#qOs2U?37BHD4#N8bGW+tI~tZ$FS@|ABVUjm9F~jkK229Y{lWAd@n>1Bt#C zOCj2EgfE_^2r(EQg?dM71pw%tL+Ni-!(7AcvYD z+DFv8cZ@l`QxJvi@AA$wvB#i>w5C34yqSIGFX5g^K0r7 zdwZ=42$bX_P+!yvCHV+sN8M@Get}jvvLkbdJl7S?;cnfIr4a29^pQ8*g6(eouk( z=OI*i4n))Vml|P2_Q%y#0mh(wAA$2ZB2bc#z!e!HP?AIBxtCCMAf)^cv78Vbq0hdH*>{GJ8qV93<5*E# z9XSx4A<}yQwAT+PVW z?Q_tLanaXi@W?mE7AtV%v)+hxg=il^H#s!j)yA7^>=f~H(M zM5pC5gpJC_ob`w3$`LlEAM>jbh^`!AGbCj`MRWy3KGTZgqCsXkqAN$(^C77#L{~t# zy0WKM;u#QKIl`W$#VWl`m1>y!71w+G+Qq($=n5Rpa%^)Pk3NEKI%&G;luV3UQf_6(zlEim4#dnR3?*yY?yo!|P727;7=jSs7&kT}%W+?kCvDs%u%08>Wf!vaPW+?kCvDs%u%07#2_F0if z7t5v0CnrgA$qeO^B{rALAt;y3Y3OT3xnzcN$r77O#`i@%t=L+eOT6)+XiTIYjz$z^ z28mWSmrTBS?ox_!$qeO^6>TnAk#fmmn@i?OA=>A_QG|THR+LL-D3>g;xn! znW0>=#O9I}DVHp^xnvIQBPf^5P%c?wbIDv?Q7)N7`-rr*(sc>>E2&YNOD5komrTC7 zZRno<`tuCsk|j2mjPD`GHkZtmqTD5i_S*y70QvkDq+BvXxnzmWC375nM>uPLAAxr8 zeKGFgHkVAkZ7vyTMY&{#a>){#OC}sPm&}!-Y$u2I?V!6VQp)C%Iljs*r<*5&;5#gc zt{j2&gJ>Ud+1Wh|<&q^fm(1B=?}ba-_z0{kzW2s;Wpl|=YtvjZu$*$q4CRu=HkZtC zVEs@=l|%b=h3$cSi1rbDQ%+hi%_Wm>n@a{9luMRSE?Hu8$v7(|wz*`k6y--bw9kQ> zAfIms<&qi7B};5Bnd7h-3NiN>AAz;YxAE8xzSl=NQG5?1UXkXKfmW1DmQXHPVspua z!{(B?Qi%5LK;4ngx14gx63Qh@Y%ZDOuvsZmZ$1L;;JbsYyUiuz+aj^eC37|@MY&`} z$|VbJE}7#%-6^BWp?y10cjQB~kKlWKtclGflW&_#1{{=27Evx)!ntIdMvYy_y~O5{ zxl)w7hLXM^G-Ard+bb=8`!(YzC-|S|34~VVW|-5}O$& z2%8z^>I!$^ew*{{NVbFLDBQhNURT&2i1rbb=cOsnE3tWAPAi*{D{bQ=C~Heo)>dM( zwj2U=$Gy652kyzUZ(fV~2+G>hl(m)EtS#ZNSzA&I96>;|*SriB5X5Z;bpK`D?RGA?^)9OU=o?IuP4bjqBET;av;LKq!jZ_M|p|Od!3RwvezkD6E1~l zc~LIYN?xbT5Lk-8Gi@u;irU%UXpFPhDTR;T*sJ(DrO2|cQ)ZH<6pwPS%Dpw2A*hsal#div zd}~s)vTsd_<@DMY#{DY3HJKs!9WUVHyTek472lfVQrv1N7bArg-Sg zWDb^sr4U{5t;tL)MDTYeDb*=k$zUv$?O@Bv4tZ;mzgfeIZ%qn^eQPo+h3JZJO=bwx z#J6LYbw!?31(OUZE_kKlEJ$E3{Wm=q|-B!&!y81iQ1n=-?OG%lk|i!z&O;SiK*;qL5XuVjWabD6(* z+`--a)IX;E*!jwe2)b`xu(#DcL?)>sg6^~z?2UL2kx8nEpnLNLd+XjqWRfZ(=x+XT z_GZ6_$Rt%n(Eb0M%^vU&nWTyc$}z~<3XQmbKjDAFFQM%dGC5Vo+#o;qe##1iUSe+y|cGd<~`>R z1~&7a^X>{Z^FGyt&LHu0k^Jsqha1Ygk8S3CK$-Uin|bdLHiJ(jN#=b*nfJlzlzC4X z_6~uX_;yg{y`jwez-Hd3TJ6kHlv7fSAh@i?m^1H@9d)-kiUmcIT&`u_X5MplW`WNp zP%g$CB=cVOQ8x45X@v;>&Lp{<(Y(#PPk*vA%TyvE7~^nSsq$K(Cj2cNB+2Ez=56M^ z{KRJ7%Z{GEG3Mm7%H9KTvQQKLW)4QDIlPp4-_d5?i{&=+UfP^vSr}(Z^Mon$Uh;%d z7HYy7z|6st(p+T9yf3wx_wo~)c`qCs{ld6bn(s`R_mc07vQQJwWEMLphd<4!rp$ZE zspdRtVNWyfg@a?H7>!Kxwkh*o^0rYHYJ!p^^WNo#b3Qn8*vxz3;20@JKmGi3l!cn0 zB+0x_DDytcaqqw!HuGLMY=*pxs!Qg*%cDnGs0nAtXOblI-sS33shEFKUM@z}CG$R_ z%=_#;04J+ll-o)2-y9%oMI%i9UmYQkYN z?}g(tYJWVfN#AFn%zJsC0cD{kC@Fmdf->*r4G8Le!omF&<>EP2`pyJp-j~_Td#4p5 zP*VDq1!dmLTNX5m1YtApQ#)uB(MT(Dy}41VDf520&AfM7p(ZFvJcH)>!)D$Wxy`LF zadOG~$hXV97lh5ccUqw){GCY>4<`tlc`rY)nfFdEdC~Mc%e;45F+0o3&N(x=zE+fZ zF9@4?pCVGW!{H2^WL!|0wqc2eMFh}fz7;+Df7NyGw+=yH1DS0wBn%KBHtaRDf2$= zLYeoJVeb&A3Ep!^*B99;gJor_36x7~AK;+O`-l-X^WJeF0wsy`y!=foe*6i_n-Y(pEP|M=(<9{j4t=1w&w2vq~ zVT@_i?4)E++1`cT`y5?7{mH#!)w61hXdm(WOQVc>pm%cj$ME>-J2GUBe_p3-aF{jy=rXb z1{or|_e^iX9X`g~bxfCN%#iVgd1U#FF~8(iRBsU@+Sa=8DYfFZv1a~B&7vcp`eQk2 zg=im<+%wF4_;bA-82Nn5m-HTK)_44}xS(w>kAwL#w2%0Vw5t1iKHS%8b?IXb3Yk`!Ce{w=F-i@% zJk6RMw`_!PWQg)MWoXI(9XZOpc1gEr!H+9LE|norF7`3{%@F&JFx%*b@ecnRmfa%? z?AeWbi4R*-sY?$XX?hPH8&$o2+47m==$6*eB|-k?llgsezQZJFA92@&k*3oD!=rk~ z)LYIyv59?Q9ML}Fed@bc%;_ENQ@p1m_6$V(2)1K8*>UY(=a=H^d-gV!XoVUowPDp* zQ|E<-(E|^(^j`SGQm7%_ReOG*`Ec6GWX+NwL=HsYYk$zPr4%7a_X5m{0YiM zo2bpZ_Axu|T9Y*UvVYX(`WD5n%jyQ|-Ejphg*Bqo9*6fa|18~-31nRx{-b?BD2D(!JJL(+$o#V|{>?lNluNhJ+>7=!t9^aE{^Ib~X7YV? zB9w)t?D?>~xvtc!CmgAp9M;-&yWqKKe2)Xe4b!&f^6SF@OWBk0fNw1*b^ey)_3nhY zcBapP2$V#(SQjY02O%EqT~oJh^LM};ZI&zzP_Dg2An$K0^#y5FixB6O(+UwNNvXq! zJ`_cS==?-8eOuvK;rMLvZvo1+w>kp86Qa}$q*Z%D%qpi9B2bc2x3~Ht{N&KqX2-o9 zboc(DaC92HPl$5y-D0JdlUAP*Vr)6B5P^~?*R0hS#l1+Y_lV5T#=&r$*meyAzk2QNV zJ=&ao^Z01rYV|}bwR^3Os0m77dDm-Ub;STL1Xcew$ z6&~4Dcu1@8z^=j_+DFhTT+=E%va4|S+f`@{@6bNNo@V6Pezs5z9{7mOICOQDSGIYj~)^4?tqx9-ax+Tx2E6Z@e&Na2GU0PYX zdQ*zlySo1G`QrZRde=jgw<)z_(upJWe)CF_mgA4-HG@N-T-xurnpUdyNdxr19cCta zsjOteg|u#0^{eo%$d$sHCUYMjtWUYGK~i<=EaAuy$cJd9j{kg+9=m;3^1r7~@enAN z)>p1&DHi_1`MN`k8fNy8gS{01mcliPQgbfrqszWqlkC>#D&c6nrf!h`RaSjYF0LiW zU-iCBuetn{K((lp9Vt;2~wdOP+A~UXr!HWX0>|yN`&b zQdT@=rn}#Xgb0*Wv0p)Esq2;4-x!ho$!p5I4LcqFa1*<0^bnaO$%@yv)O$OuI{k&MV zx!Og~kkvH30!6-rcJ$#=>r1BX+&g>ik)f6PtKrdl?|s|pndy!`T(a%c0(%D9b2tr| zdnd=!y+`Wa9ls2}OLz2P#=)Z~L;Hw+OHU{Ads6q1ZnuXD8@MPc#n?`SrB`IS@fBCnrgw2AZMVY7kP?AhuBhS68$@cXcRH15Htb$VLqu0yXhDem-%4-dH*_`Y4SWxG{lp zam*|Ax*DV}sWvORA&nY11g#AnAEIfOTBE=2ee1la-YF6_a0rx(BUq_B&g*7gs(zsE zKW-53=!+CJh;7uMnDt}Kc9W=qp{RkjQ3Hpd8QEnYQrkGRQcKS2W)42=K)v^CS9%;M z7qjamYG5d8pl#HkNKu1=jT*QtI?RugsDYuVL1d!_PAim4JAEffq6UVd2HHjq+)q$0 zullpxHHjJ+iW+DeHE;+lWp^)ft6ZW6yvNZtYQX!Cf{hyRu1HGRJ(b+2m#6{nytIuP zI1ZF+cSRyeq6UVd2HHjqcz0KT-JQs_dqc@Rkf?#7sDZXo1E&>gVt02UNumY`MGdr# z8VCpMQbn%a<4P`wL=6l@4YZ9KIIU08vE_A81S z=)(wMqXr?24=0yKmwa=UheQoH4ySF@z-fh=(D-nYBx;~3YM^b@Af%{4Y@-HFE@nhX z)Id|zK-;K+$g)ubhoF7ClO$0CO;H1FqXv#0b*HF-lO$0CO;H1FqXteEYJzi#L=7}W z4YZ9KI0Tl$nStIHJ#nO|HLoOUp6&3^Fe0N_F2&z>3+~5P%h1!E_+?}gNF8l+U^IP zZ^u$N`_K*3ZkL%OZ+|6P*m8O_erSv0)z8y>{^qy>Yn9oAXlnEG`k0aWo#?ecujDR#Lj z5h#i7^$kAO+_Pm-^5fr)^xENdi>H4$C%5ALb{=x4N3YkK0e*cAO1m%R6d%eHYO_;;Wl;$*R{bG7~#(&+L$XHTA&S#ba)opIb3}a)H0+-MKQC zf1xg|y$*b_VQ$@x7n{XrD1J}hy)ccX5Utdfjn$K}m-jVCUiW$Q-K>L(8*|&Wd_AuU%X*y27Q)GO(qTXE}CQoC7A)BUTd-th$?8R?JWTg;IcfyCXE$lzH zgL(G+V=A;qhG07~Ni-XLG&K1t|6%g!{=L01$Z}t;zO}T|6|aj{nTB+G=Z$ft)i-{U z{QcY&!jZjPj+!8v5bgUUcdqy|ny?)i zH|^CrOiTV;yMJ=v#-SDLc)#zWg)8VScVDYP3-2wvZr~xw`X=Kl*nyU3XvYy{9NDO~ za?7&1+KH%sNdCD|0}qKdTaN5qct&KU5KWo)11^wz$XA_Azc&Nwhrf|8L(|@1dbQ_= zcW#{YeR^yKJF-$-R~ffbXIJf+Jh@_R)a%mAvi1;v#hOs<7P6j5wIDXpJb3u{(i$5- ziLy4&Uc^V;5v|k%cU+tNy!%(t1>1WGN2WXaD@4<8SpDeMvau&Oj#^neGJUZW+mUg* z5v5^7IXkGg7czg9*`(AnGi5~SY(!>g_{{d#3+kfAnddC9=kz&Fc}u*ge%gA`>^CA{DgGv(C}_Hq zdfbaie#Vu$_8ncKr$*N;-rVhrLjK0~h4Oqm?YKPZkqqkERWCYYU$4y(jeHbM9N4zd zYi#To(ETmv8Xa3|PwN_++q2=I!Wgs&3j{}Ux8EkvxxYc~EdcL@4(su4JQ>w;!99Rm` zN;NyFfoV9Wvsu#n1kVm!tD{YnW74dVY50QH*NyHHbvdG5@y52lQg5GDhV6l?GwN5p zUQf<=`f@$*=`+1HM+8cuIQ6pn=FI^o=oL!>j|1i6PKI6=TUy_I9-d$dKWWbnJcCA? zlfcWZ^z1SsYEpL(M_jiZx+5?H{O(9wlYMm5bYz@&8lCvbpA;5 z>)N52_mQ<4qJ29CS8ZU{>n`T48rO$--j8*Ky^{87$Gx8Xysp1_;fRSI0!v{n(2EZ5 zo|ufR($Cy^{CnQ*1T2NMpj5Z{HzprU9&Tzqd#1;Mr8+jN%{Q8*4%5}^KA+R?n|NVc zfc1l=5UtcD^>0d=%^z-tH>nk#GiXndwc@Ksa##z9PC58YjlYls(LSQ^-CfCzL$5cl z1j9nSQ?`g>#9D9)) zTUZLwK8MXX%5m-zmO^f&ZW?oAv}5#e^HH-)y_;vqhiJMj(DuftYoFm}O6kOq#&bxX zfqLS!GQ5T6BVL%fBOLwiIJ5Gc#v#pWAci3ZPRkMuyPL0 zQR7maeTJnFP4UFVzlPj*_a5O}j(mvr?LZE!1t0OzhYttM$&LfwzbW!>U_S9MYdCmy z_0ZQUWl4J?a`>foqUkVf6CWBr(rXWUiYUGd(SBVa2ioK#R^A&WEvY?*rT$9n z;4`nzqc@0#4fcG{vq?Cd9h}L?c5v<^>W*loo+pmh#Bp)zcU@hPe{_6^_U%9pw8=*- zUo#}Rh}xr1I;%Okhfdy2)^l@d<>YHcEY1$jmSj6PPZ&!f+SdvZs3D@2dhDx7$p-3) z-=?#3F)s~FZNciSPIcf z{onn2Mr#KSH?N;NIC{Tbov?a9zZdzuCI#d}v{Jo?uLyU{9Bq1R?ilrGUOT*pPa3{l zTZU*Kp?B<7c!74pD`_W;Yg|P8h{J!buXn%pMDygk&7yhpn}i#-?GdP_E-7GL;rg0( z+b5l^pMP{ebKsBzJOrH;xqGOHCO_Zp^=QKA%gu>X&WWl&STF27WOGj4nJb`NtOcbG zzOadYI10^#Gfwmns3D@2+H~e_`tf&8HftY``K&11qth3;{OI-t2N+&BA^r zxcUmOJrM09{=M~Vz4pC*%){q27Y;b*be5xrN}V(KSl#QdgG}iXIf)Aqfp?O3-rwD^ z{7Bv7*GA^drRzNol#4bg^|z^_>zvuvyf@(=4}qo7COSX=a8*?0t1HdWH;;)ZHW_9o zF<1)wm{MIE^oaiK(ba6}DA8JH2O>}s-FkU_pXlsMVCE9W(UQ39XG|oXV)#A^1w)QM$7BHF^Hvnt&TqKbp3KyrO!yu z=tDZAkL?+~yFtgJE4!a6XY`uR=(RngcegC?W(CE_oFqBn)xUkSDEcxz;pG;Tvk8>T z-`R~;vSY}x`rfSv>9Oerr{O{NYL)Hb*~t%& ze?iM>ctoe++Mb4obQ)f;r{NyoP7XQ^kLWa9+tcunPQwfKG~A()Pfo+j=rmm0({LU+ z6m|Zoj3S#3?IXBm>1+#5uJu-XLp{p z*?Ao!cGeZ0hL_Q4cy@LdWG{SSDgMsTavGka({OE1!ySUP!nWDTL8svnorXvDG~D$o zmYbc1`W$o`UPhH8qOTqiMtzX7LnZ? z00fJrS8mEJDyI%BYPU|IJmB`ZFbs0 zr{NKuh9~wkoZCY@0L!Hs&F*DzU5QO{8eT@H;n@v{AbZsfbw{+EhDUT7p4iiHS6Aq9 z5Uo^|k8Ulc)9}QehC2?n1M6+4R(3>X_e(rGvK5D~6`h9jh|2Dl1le12Sc<O> z${A!tXOP;SL56e&S+Hl2ZtkOVJSR!cAT^yqYI_D5(ivpIoVw4yV}h|VCjJ%e-{s5_$N3{uk>q_$^}P7_>< z`13iP_Gvop)AqE_A@JrZqUE%&K&O4$p7yyH0(`B`^#xxM5le)p7uEemZEb!R||657tv{-wx@j#fu*n(`ra`y2vG+4B#n1@fQdLFu$l+tWT*yI2a*a@rTsX`i;IeSCgau%~^F57ENGG_qF2 zHlRp>L;DCi?ThHNPutTzk;_>Scq1Co^xjg#H37w5wT-<76e*IM?-YUL$aW!(y>?o_ z-y9wGw8~R_&%KgHzfs(k^3fD~4Jr1jIrfUT?rmh--n8F|rp%WQAC4(btvOCjv0{z_ z7v@qF7}3b*X{9Ja%P|>w?G4eDBhU^+`v{8fh7{k`HooiXiXxlR{x-e~^_J?Dwjgp~ z{UBQ6yCKDQwTupSvs`DcSDNrY8&5mc3@V5 zuNB&X9B7k|p!jY?@m+1>yTW1PyP}DW?}Apu;q0Kuru@XlcU>upayqoccO#1LY8&5m zb!E@LB=fdv@e0LMztt z+n8um1f@7y8UuPf|V=&2FyBj}W@ zNT*~vq*F5VQT9Aae4_8|zMxYXIv><~(fJ^q>c!#{=|st%%1AB|qUF@G_$BocKD9&+ zMEi(5otV%mvgT7{I+qm=K9{#ACNiRsk7613MG2j4Yd+hiGgCp>^K6Iq5!cZP7M<|w zMRdZ8njqRoTuLVmqsVeT)u)s7B3sTkQtU~C^hDH9?iwU?*Fg88QyH`a(LRFimn3w* zMDzU;np1^?Z@OS6Bl5|umt;N7oP6trZaSn0x(|bBA3=8}61p>?$I__`YJzAVL3daZ zy2GOF9Ts=H4Yfi(>WBZ-H*{{G?YV(N;Qcg2d!tsNRwx%W^bz(1LwpG$P?C?Z=N~en z>?w(?sSuqa=+=woTQB&kBbGw6&w*MYAEK4|@vKSl#UD=42VSkh=T50zZ1D`OsnyTR zu@rJE^;F4@;)Cyx(^ntRh|gHuy;nq_B)RXC(0w0m@B26eMgCpeAlkDdZ%?hnCt{6a zpY{><)Jl9JB2bctP>8^KL$rs;cpCW!VC_;xI!D@7>O3elA!^7u9` z>W*H?(@G%%`4H_Ra5af?(I0z=JR*<}(J5kZ_bW}GGbFpl#qK!fJXycg-hlD!g2eFU-@q!BZm&fBdnju(=!pU$OUJuFou?)r^_nYjIAW zeW-AtTzt`9%I8y*k3bC(P5I~h<;za1_kP(I|4uO5zdj_GvV2K_e@_F-#aHZo4n&}a zh^AP^=7D8*%>JO1IXcuoG#L5s;v93JT>32!?$vyXWwf4=J8|20Wv39L+5F`u)z2H43`+`TY4++b5X)J}3z`?Acy85bY!Sn;E$i9{aBJq7qBmQSn9AOdRv(b7wD)Jt-Qj=b%O1?q|N6D&n-9uIGGztp;~74-~< zKn)R1nHKxyOQ|PHFQImhsV9moluK5}`+Yy)$%>XE0{IXvJ+YK}qV#rZgP3}v^edE$ zzi))rK4wONdP$k>B@RKoB&I%A0WCc-rk;2__eAP_G4)-s133^ay}dxaz0~%0hd`SU z?bj}~bAftdYa6y28In zgieuvYf-jp?nvG1&!Ju(3$7DT61~Mb<%7biZ^!GkJqsa4&s>HJt`iVV?@ZkOLFu{0 zG5WUMOFa%m`-o;k_efUG8mo``qs&{EAP1s%))bEqY;$bqNi;)HhQ)ktCyF}1J(`zJ0OpX?GA7TC|JW*!7nsA_8lH_J>x|4du_Y1o9zTw9@TU ztzu&58Amu!E@|jyZKd?RlcNq~`Hej;Vrw0u93N;!wX3;yYYo~zrds6LS=s~TQcb%# zSgAe#Y^!Yx28cjDM7!~k=kYb^|B4(AO?J3%l9XyiBPy~Zifb`vN0h4t zTZb}B$cWN3q9Qw@90KL~TG5E&_Rw}jac>X~lxy3@&gZtxqku+~t&<7}+k*1%GNK|H zQQD3u?mvMYQEnY%`4(>L<5BChLQQNx7D+OqczkF(qIgX$KS8;6tXK{j zQ9K6q?eP<(C<_tv?Ifk+oJN$Uan2)(XHMZjxumUIeaMJPXhi7;F1jc{S%^SM&R<1# zMDdzIY7ym9t-E<%Mil!*UH!4?nU4~!5J9c!B&D93dV6&1({pn86O>E6gx4sx1>Gp5 zG5B`w>fn+u&MQDqlyB@~JInK^U40t&=5&ribma)_SBS10L8W4P_kTWXMWyIF<+C=4 zhEA(IYekyGWQSOY2$UoUD$Rey`?xwm1WHQFrhkj&PAk;JwvDfqaJ+H%1#yk}tK}zH z%J!I;?ejShfx08wM;z4Yp!oUSb0Q1n+Md4)4n!ayqJ55j`y3Qp(>moqxpoBaf&&rA zhiKu*r%ZWse7_5V`Pb6f9n}fSwZ3Z?wTlSkL$uF<{T1b+2T%3Mv_b^(AzG;q?i^)a z_@Qqy=KtPplD3*sYnI#*U<+bRD>d@p5vK7YpM@>JsiN_3OkTX8pU5CJzi7 zRf-&l_7POG`K)%a)tZc2UHEC<1=5#%t?oWcv%hC;@*A_)wSDUvsDn&#& zK3D6~g4(uV8MRcv9*#LsE{;dKmvP+g+V+xCL?9ocrSIyG)4p3qeKcTC%^WBf$G?my zZAVloB9IT!GNLq%^P(N+jsxY==;B#Gc71*?A+PUNOO`Lk{?SK}_tE5iq8-QY)!6Xh)!#1S9OJah<58My`s@yJma{!!cxfXbD&(@pH;5a_(LZJ z|E}3lV9#KElzgM_@;NSSJ1N-u%XYCG(Ul|6!y&qI1eJ=3Bh!R-Na@nY}@!+2?ruj6GZzQ z_l<8CU-5BY;Xt{zAIra2jzB&{`-pXaZYym0zeyqs<=Qd73l2n}hKTk#?z}T!=)TVk zk%e-t@7e_iB9IT!KF1pyC+7NYzg1+RTg`|sPW7a3knyo^l^OBlw@j4&dhsK7 zxUoWSA@v<^qVvBh9&^#+h3QWkEa>#?;{ldJG`-7t>3B2o_D$i&W~Y?dpX3;Ue28`& zayu0fSPHqV39`fU?Z6S`Yjwk%A*OH1qsh8|&Mvc>6j&=Ph3M3d{Oy~HUp70X6cMNi zqUo*sH!d`vG~3;Lck7fg>obG{<>GjBcF>1!2YMVt(;M*-(9rX4H-lfqaNo z>dAxdDP2mt)HlX-ERd`mdmrXNxj4E6QDzZ2L?9oc>21RwK8{$cGiTIJh&{(%lsQl? zjz@YS_OwOOt7LhvC8iV+<@lT*Q)=&@yXX;AyW48@SWdMV@NB>wD3@y5&Dzp}np^PU zWz{<(0{IZ_dSae?BK03PpHsgI$V-T4@Hwa_YTFabEJAuamO?aTNRMcxi_{YzIOL{; zdSAdZC)&_{av<7ASWCnX8l3@oHSusXYH63cq7l#3zEODGQEn+F_ON86!ptYLYZCekw3$182h-fy@b~a$&C$dm?MEe}5JMtk~<`4GN zn&%JH7fV^My$d^VCv0Z}vBTGjW*nYBw4HHyy(_Y?6rz1QPJ~Gml#-X>U8>lD2$UqVv!U6U zJzRq9h(Jj)e;At8qJ}%p=Gob4g__W8z&ndw_}!Jy&J3!wx}^X!j(p=>;+1Y5tQpSSN@; zNom>i@4Q)RX2$Wrn}r=Uv2EjPB^-!AO%UyK^g4cee9nrr>1)!ch) z#3x@kU4DW#A==jpIS~E-4S|~2`D&+D`IISdI&JG52&Ly%S+o^AV^aqJ2A% z1LfM4%uWuc)w;u`2QS{0_A4x9S7*EEyNEzOM2l9A1HA#twQJE`a3BKt5UtdA6#aPS z%&&^Gz8>>PI*J-B`0T$=2RNdz=hN?ryJWoSee`!uxz_E>J$05-VL|`f8 zrniIV4l$QBd^FjAuf+u`x4;~z362$~RdMo5kLD18auH1q@bwGL^G$a*pFZ?Kf$Asb z7Gw^Ti=&HP1j-LFPt!T);(8l$h(JC>Q-)iWcIK$v+nKF9nv_vH$J}?B1LflAQtH!| z`&c=Y=fj)|Z9Pb(a;I`tAh;-wQ8 zB?Dd>Vmd$2J|;wgeF@uvr4UVTa`c>+jJT$md9ijIjR@2b(Mlcj!{X8-f1F@G8oN9u zSvl5(IZ!TYORs&7nUQVxN9h!(A)k*QXO*aP-(%z<)AL+4}Y{QSg45nEp4 zf%a^zLzLrl-j#k^bIbkomDGZIuQrBSDq!Ev94HsZqqLy5Ex4RoE#UdX)~@42G-Vc7 zX{Sr5U)^#*(^BL>w2!zlKSbNUTcAD~@I1&Is0sCBw_Z`I(d!rL=V*L<_Rt48L?9oc zWejTa3`Of10-n#A1Le|qbSoSg=lW6_=LhYzI7g$?A&?Kz(s%7&5>IqHVT;c3Eb4QR zhtuTY!sEW((A54!u~t|L(c-TdA#n!O3K1yD*NWB#ZtraE2v{qhgFKuj4;NVv$Mr5= z6iXr6=fG7T@*&!_M`(Sb<3Qbg#7-6$p%>k4o6EPa6?sujUQ}Bz%JX2rwTqqa2Hz9s>sCvtX~nWd=B#M>>0H6?M^E!h3LvHM?OUR26Ns^ZbFeh^4I8wzW(12hRrD&L2FJ$xl!d zXByVU^BSDse7U5hESns7T7 zURlW8PJC{b@Hr5HeE+W;6eCeb+BE}xr+n5X(N;L@UwO78COfkE+*wN;4qZ6{OOdvY z+ecjR-L>(G7Mq0~HL|?KuMxiKGiL+Z|QeU?xxkLj{KD%5M2S0Qk2sQ(G?K+Oe^xW z0nH!Mcgdf-*%CFh;^jZS9f+=ga2zye1T^Ca2hO|5=X0Q3MEi(UWnH2>{(dHCQGJYF z+~UIc-@!jLT(SDG0B1Fvuar9V&DPP-ljp=En~v2zpX(COAF?pV2%M=AO~27x6wW@B&-vdE!|r1mMmO{r;~~%{ zMAL5ve!lziUq0y9n$LgCUK<#EwCSKt4pv7>sBPCUy+QSqq|ETt&$k3~3A|b__ZMkE~2XM9UbA zXbcwZ7>u)?h;niEkuez27%bW`=n$lx<3qGk=U!Y}*Z%FZaLyg)>a`16#vP`ahCj`^ zKVaXO&55KPOOo-g)cm!z^|6=VT`W1hyKcR_S^U#W$K}c+P?Ayyj5|=bKK;Am)4WpeEL)n0pWXhVH3{>xbT25Ux1u^o&Cg zs0pH#di7ML`%Ld19l!qt9*4E50w29w+iY(1#M3`UTvu1#zO}&rW35mV+nQFZB~>>@ zTiZMpHK)2l1lojXYV*^-3%S0yuBc`Uq78ANT$~x`#@3D`x@_~G5nImn#Iji{_E9xS5n()n^Suix!u`v?uA)hAs?c}@+7kyIS}n5sJ#!BwmncQ;op8Iew9E~0&qx8bMMS*U8x#(cF}LPJwCc> z`Jo;H<@$Eq|5p?J-t+%N_uYJehd{YFg6VfC%&VqX-+YvAUV9IH)gjLnj;OOyw8B!X z5li4&pjYMJYN*fOy^20yaUG8X5h#g%zuLIj(Jf1I`kR*y_c%~4j$oRd&-pCex~;oz z71q*Eo>-+&L0-jR(|=U32UC`F#Z zkY^}b&k%fmOoRE>GdP6h6G<}84UO~2j&r9KYC_}DNs?7Y!n2NDWv~|&S*VHi)Utk* zH3NIm#I6|}0yROjtQiuXLty?84wP$W9Lqs-N5XRm%pZcV?NI?OYlb4vA$HBc;~-!U zfO2sqD{F>?=McMQ;9e~V+pmNJ(Qf86cFo{8Y~QWGN7+uas^l4gEnl+qZeBA;Db$2G z+}f9J@6f7}XC0n#5Mjq)1+=UgB3d&@3z8=6`!Y?OT&iie_En14h_q%fcFj=8>I(UM zt?X(^EJqH~%AtJ(uMug@khOV%Yn9srHKAS-a}B#SL&WV4>qJ2yAEIRi5YY-iT9B;f zxkwPi<@kIKyWW+)OIF9(7(}#>pm~seNn+qaowc*ZUBprLs%;dv0p8jcU^ zOGJ`VG!Gh@2NOFFIu4YJz0&zzW9LEki6RS2u|_Px&4Y&KL1X7Z$AJjzU9DC$4<rCM+!&8dVbQ~xb`>|WYWqmi!`Yx8jQ6Tf6rg_lVdC+kn0#}?AFBvr0tXrE; z_CERA2z&MT6Sm~G=^JyMZtN9o(=~%(Z4PS0-}FA*DI?5}lO`wk9Gf=g7(`Fgv1s#AJH)w8zTy z#l;5}R1MzVUaL@EE7Vr0D^DI_8cdoT?SAza1ws{Q90b5^Yx5sv4@ zuWgveJZUf4Sql_fq8`FMW$mrCmOt_E)ZAUOwpgupmO`{rQS0@|SF`(>bJo}NY8UzZ zx>_=|t@-4JcBaMu?bQ)E&?X;2c0^!@8?{ubz!tL|zE)&M#CDumrTwzHZELoRbX&w%E3Z zvx(lOqBkJ9C(asn__AmF-&lC0g=-I23enOY5w}M-Y7f*My_#=%xM^~<{Qs%zT0*3{ zf@n*?g$SX+4@e?v)Qq3#h`+@5xtfK9fFKBC6kNG=5kwKp!p9(!jrc=R7b?!61I{8~ zVkY?7?m!Gf5Q45GA|xOvL=+-!)Fyaty?Vu|8M_zLkDhz(sd{zmoSGh{=Ziy~@iX&3 zXAaKEBhcsJ+@isDANm}AyXY>XJp%p_;2*jAN4&cd)ns&CO{qr*^~kjzagq@PYdg@Jbde{j1oW!8zJneN+JgytP&m+o z#^*WEgB|o>u03co1A5TV9-;0WR2h=`{SuvIrbK8y7}P&D!arK^USXb!(^E^8n(|Pu z4dk`*ZWL$BXuL=EX7;Rn~RNLcBEgU*!NFE-cJ{Z)`OZa(R!RQ}S z10R)oZJkH-TH)YT;4rlKU=AM)>VpF#T z^8RXHzzmn`3}^d7Kdc{pRO)I$CreXmb-4QM+FkI;M8SN3w!RX$ITZ2oob-(Qtjt7lZ+5gu^HcjU99K0{1IYN)%RmX}I*@>GklE}e) zHKORmt51e!wq`sSX*EvFE%%HzQ@O_LxUOEWm*ZIw1rV~TI6gPwRg4x;p@_ze9~5za zj^kkNn#Q6s4xlBH;{F`R=Q#$Jcas?VulG)syzkc&Z%cXo@M-+#lj>1%a8!)oojk|Z z8>fV0^OkPO`_6uIQaCn`btiG~UX0+Kd{q1$-nX;t;RdPAwI=2WJc|16ay`ITWqS{i z(tYy?L?U?g0QF%yKpqdx(Q|ko`d&g Hv`4%Hef^3G literal 0 HcmV?d00001 diff --git a/wam_description/meshes/wam6.stl b/wam_description/meshes/wam6.stl new file mode 100644 index 0000000000000000000000000000000000000000..e3b014a489b21873d37569bad9dbdb976ab763b8 GIT binary patch literal 139684 zcmb@Pb$ArX_V)`57Tkga3GNXRNT#|AcMrjx;K4&&26uONU1aej)63QKIeN*>1myg4Vskx|M~YM2V#F#{$FGzMao3r&{I9N zdk?;2Blk)?GRJsx`*f$LHnyJwhJ!#>R*D^2vbCflwo}sxRrubOT+Nl)SVI)MYqeQ; zslS)Th}3#18tt_HB-f+6I@5tfY7L?7^oRc=$8m3SAKWMNHZu+p6GEXwtCA@mDvw1( z`|0m9Qsj_k#;vThm2ENNO4GC2$olIzab`nt`&TkWqFFgkunkTKe}$f?D?zhzvIg^4 zcm?%R;$V#9&q~TaFNFWiwunc2r1l$23-_aZTaLr^@GbSo*8x0oafE4zZRQoEg?;v~ zT)R*Y(sJ#JBO(qFlh`l%mC&)0HNl?(qRMUNzVDl`-~U2`vuR>N=*#EQYPpLsJPzS6 z(-7OtE~JHhM;y?1s0V4<`#@cZBe1Sg>&Y4e+a=hB^jOP%ulM^s+gtBrX<|Ys)|y?9 z+7-*=5dJc|Vw=SQX;}mM4)q`{*OfQ|eNU|?YYa?ot_>eCk^A0!Voxm~_x3a~Ar##D zntnHK5RXIn%j}A676+tLX@I(ddXSduN*sZ{r`D4-=(y9wEW@_ND3ZMzGOdcy^QB{E z5J#9@vCZOuw5-wk?Idk^bYosWP!G~F0i%VqOu*U|M_{z6J!BeIB9xdXY?g7()Mn(+ zLy2H>J1@oTifs|Ou!K;0b(NYBV;-TnT78UjVei=7&NaZCXtoWk1<5Nmi}F$;4&jN| z&pf2FkKt!jZ|uW*qE*;pgxF@KV697DNg9w4+sqQ}iRT~b4JQP14PlEN5!+k?^l8Z} z1Z_!#bEG*m8k98bZb@-Q&ULx%2$kOO-|fwO<%HuLj(>zU{#`*oJuSwVTyqY7UGAFg zmCNch1hjmJMSza1H1Q zoLv#BI^%*eb!(h)<3LZ^Iw^5L0$M_7maRBhS)qjyxPG8!6di?q`w!q6&@Rj$5DG7m zpJXfC-U#UO5NGa?32QxheN@6oEcny{ zZ9z|9zQX%1?;&i9_E9NY601JjFZwY;0q0_k%PuY|XUnX>tt*r=GYe5l5G>Qcgz6bGebg3$rLdrGw+5md%%z&K$2K-%FCEzRe})Ly|jM6SgMIdU>6NkmhBrf`Fq4 z>OtC3RuFJCp#4~5W8OJ}%~hMv48%DzurbJwI7gIO3evI$BZTizPgruy4784TpQ0?+ z5IuvH5`F1^6Ji_)!r8}651Ci81{il5q@~$Mc*SN>DRM|dLPT#hV6^{*EY%J;+h4A$ z%ws~xM}5jZpW|A*52hWVLG9O1{u5NI*;JdsRH^RBh(IO1vk^ z8o$>~R)L?=pSi?akW#-*d}qL3Kz#OR`rm1E6-X@JiNj zFpeHCjxevpHXC=4mNj7hkxI|31(|@E45Xo+Ou&o`(&-a&KA4ivrBA@j64E~$E0l!s-X)FYKynCvjxpIhqSB#TMg<7 zOJd$-)K7bfsUZj{4lAoGXcw+avRAaX>#Vo0pS)~8?ctb>ZDtFWf;2*OMCoiqT{`u( z7F34>w8Y1`!Nxh8ujtsuY*u3$&@NmP5xP(}S!Z)eNqa?KXbTe15})CW%5;WXd#~aF zI;&wepEC_;7p}nwQI8BZ1F_i$+JXeMgb=MKgUt?spD)*fN1$Cgx0~5H&#wr`$TXIb ziM0=|oMJ`gy@a-&BU`$jXPUOB)hwR-z_WX?ikg`W$5@*~0+yng6W4YSG*1*>S;Z0N zmDpybAni2I|KV9*nm9yEVx@Kz6@8axsnQxQN-+(wQp*~QxOQZaSyzI9mV}0xi%MQW zLRdOq{gN7xl8v7MTBSadTL9#v~ISSy~vc-V`VGbByzcUO`$WQv9+S zt7ax^|McIN$oi|t!qZys^*$E1EyvL@&sbw}frV<|du!sSd8f6eezh#DMqw#P%e70d z6lnNhUS6Y657H?ao=GkBYRcxNo#@*7iMz_yQ*ep8Dg774r!+X|3|JXs0V3;&eOX37=4A`%@9Xe zPlPdv{Y;M;H?Jomb|iK7!s!1^h#cop06H7up6hjwSP%LBzr8M<$Y{#*=Ir!tJh}v;3e}kd}!QzxWu$ z=f4%@GxfZ(`*6jT3g4FFcvmiz?9Z@V{eHi6(vCX&@b;DpU!!0tNT(>U$YHc}zB2V7 zjnEITQ1WrtGSz*{Hh-uAW0Hv!6@IRUzeLaEzTdAm2_KuiG)+wOEOk^cbyI8CS;b^ncOsm{xJ_84S-2VAhY& zrgK4fZ^R3Gu7+{OR?nh1u=!r?&mE^RJVSysLW`?sQ)bs`qF?$qN+Mt>s7;??Y1l<~ znY%^bnK;zwnstiiLS}Fc=m}gI5DI*7*q;4bE`#PXM!CQp{wMMrmWjw5UG&uhx9C-qWv?JD6SHF%>zz->>POm#NO3^l;cACa z&Zm_@MNeFes_=7D`PS46)XjF6oj%z6xO3WFW7&15G@g~-XKk{AwN5zmuhvA z*{7`?nj13>Xcy+C2>CQQthaqMOL1QoA`#F-NF(GMyjkyVbW*ctkqKxQ=D`RhPwl5) ze7sRzxOk{h_1bhTZuMmD6)XkMG7u^_XS06rO(%8f7ny)DK^mb_Ro~h>`q|YPZ-%no zuC0vN!!@8?ct(cM>TW&tk}>PlJ24>=0X>8?AA=elgNkzuni|k99P{+)gd+tMI?h$+ zI8XGQe-t~%xp^K<`>r_?A+(@+Hv7CfO;k2&=_oP@7?Z3)N3BXnt?C@LxXrNXJaT9k z&U^^9dvI8xqn3oyQ42L7LC0fa9`y*f#7C_{N3H4{wYd7!ef$V41!>w7b97PZs8yY# z*7S;wT9cNEIkAh?j;CW)=cqLa=sR3}5UNsbmwGdqsQ)@fEq>F}je7-4!LbV!pp~)S4Lp%nbObRq3czoTJtx=%_XIWUnHQ zC#!VS+MS~o=gyN?bB#Z=1eocwZJ1>;!o2VN(@bB`!jh~3 z^BrgxW`LZqIyl)YNI*-b2BoZ|t^0bsGHwyi+hHk~qi}+jW`8mPYXQ=ZvaC2GGVHhF zqHWvr%o5s#IT0slX$Ntq^&)(-SAI@F4@fEpwJf9#*V~XRH#%BP83lwul!HX~;n zX*Bk}DrdhPYv&p%#2t56ZL3Qcvj1pS<9S$qd%4Q)_IJInOQo2Gpb@&?Z48cB+Kf!l z+|zg^>_STj?Qt7mv&0M`$4338H?CIEUa(?KyGyINTtnDp8lpxJI-_>Q*>Et)cmA;s zZ9z|T7Fw`n4fY#**s?(@t3bPOrAFuOmTznUy<{MmuwmS6iBC^GZ#_zOO8};`T}kv!ge z)^=QlGnK3*5zrDnE9&}Et+%o-8G53W9jZeOXbGVLZSU!7Sbx&9Xl{G0W*=>%%P+_3 zP#*<)0@rqg`kZK>H>ep+F21^fApt#sG(vY@G&M4fE=kts{G@q39;7uXFbs!}tEND^ zaP?tz|;Jvj?lVC zqby!@zDl6;)rNuiD|FXk1K zMrclC53SFPQ1W{-J~Lo3Gcdbi9)vWH!(jhqf2@?4mmtBmg(XKx$A9IgMN$*Ol1#uS zo#4|=kd_JfG!>-NC*U()kWQa~Po6!(Jj*HAbYgd6C+A@l?8U zuB9vI-X{5#tvTK8FV69m(=5dZLDT%IPZw=|*xpIyvelW_mGiD8 zzY{061^sivnI}ke3eo9&UJ~21B7RULkUa7@h*^g0x5Zsa9TOmGUQmx0w_XI|zE=gi2Y*)GMaS2aV~%4~JhmZ?l#cm+Lyqf3qh z5-=u6BQ*C=FS5&8O6gMMliG#0HEZ)>wC$l?I93ok)Nd?lHf^f1>GCXf>Yp_^k$pGD zP!G}wRl7fwEIm2TZp=9*X+T;gwoFyX)8eymzO27AF&NuKT{ z?T?M(5&>g^G(z>R6(@N!uGjo?w2*ot)RQ$F_3IdiHLGplt+xD_hh5aJ7+s>BM0;?; zx+VOwA3O5=@K~Nxvu#MQZHYkP`Wmh==jaDbY`^NhRD*h)u!`AX&e5@)pnE-FDM(8i z)*YGFrqN(}kd_D}h{hF4+r{?(B&@Km1i|Pu8fF}xt%q^1{H^g8SPI4`d1W0iBF@5U zG_>z9oT{d|r8Ko`EgbWK6UCl%z>tP|vc}e})w!**_p4(_r%wdV>%fUpTmQ8{I(-60 z4(ap>afHq#8mwusKUKeiBNdb~+uU(>Ct|04i@n>YiT+Bn4E{a_t5KM7q?Auh&}Zn) zH&h^tLmKCF)N&0r=7k3P*Gkxt5&1LO*%4SO-Eq!V9BzwVvtr|pZ?hf)X`$hW ze17mSUW(L;v%pf2mIyY^IpLfWO+84<1f30dDK>vVI(GTQMuOOY8aMUcTV|oO? z|8~W~)(p1I+Q!-Q`8I1!RxYIlsRlnn`>qYH8IYEVXIC6E^;YA94btfot{G}@jWW}# zYmiQ#C~(uU;$cIXxK zL~OJE=5)xZ1J_sOi=!tRf0Z%wAO{ifUp&`ne61!H8te$P3uzw5|MW`GERO%})%(93 zUS(cX)-G%0z3uR-^!ZE*JHl)+-(e|8)3>le9FTx9L7IMHqr`oF4<}(ne}ma#8q5=D z7uF$to*^BtAOS7O?LpTf-j~=)CbroMCuUG?wWIN138pAFor>hnFMQjkW- zYs-DLN2{Dk-COmS2WAb$8misU(b0huu_m_*3ENHe$}AN z(LDCApT2Rggr4xqq4Bc&Qx#?Cm~{14KS=}Dn@ptEfRRHzHZwRhm|v9Q(ZgI6Y@7Aw zs4EBIpqRSz99b#_XdZ=efimTss8gVVB02ZU?YljcuHRl zTI;4q20G4!F9tQ#U@1t;8lV&gr7U1S?In>{BX~VsSv)e0hVWe`sEXC0gak{3eXmWrml`9my4V$e={(r4hg6SX@nlX2qP!w_15hz3#*WTc0pZXgeqC1Nt0i) z>ot~Tmab($S|&uzvVZ9jyXZ?`8`J)#Irmcy=bx306L!Q|?@}p9n*eKfHfn_})~`%G zu;0{h^j(^ZaDrws?A+O;!FDQw<|4cl&17&obSi@8B0PJgnGA+>`WiHo;RHL6f^=#k zWj$v{z?C!+2d_6#hjLxP`nj6dkJlBtgSLSEG>!$OV~zF;?kmS)&MEbp_}W=dtkiA_ z8+W31F{EkdpFi5zIHR{-vdnN55*`yOar*JCY3%BkNh1{VE|kwc1J5pGSMKb>Uswv# zJPxZP8o8H10$M_-!;vw@%5e+z8PAgK&@1RWpfyof>|ZMZw$kfYl-Rx^-uP1Dur0Pl zAN$$%-aOhTkMe6!Pu8$1p~muQk(O0`m+9?4RInfYw}$;kvw0e%Wny?)URTzzoXd6S z6{KZ?`7fejy+q7ppf9nNf%llSD-P`8@LWU?KV5N54d|gv&@4j-S%$`PAC_f^Qp^*Y zGjOli88UryvinnAthID~H3_=5^KIwa4&rF)@ti%wVhtG7kIyAw4L3_c+R@gquE2_H z63jzkDJ=n3PO}zZOlb+I0ckcTrfm?lHF|Eq$6#u& zL@7ZFOQLppZ((P5Tm#mw^IVPVIW$rjeg>H?!88PsGBf-v4xuLzhR_jSG2g}Z&%82o z>NMAuM6`@%z1`u}oqbL8Wj~_GpPeq@h}aRhZ4$PZDV*5@UYUT`91t4RDp~JUFobNm z)yAIPyDwh7O0iofj=ZYq|#*LITAT1N&a}VlYs)Uf6Rg0*glyvn2 zUe`cq@SbCOQ@;?huy||5UTp~XYGcI=9?*Aa2_gS-xs4u49mvJ&xfB>VB%mdFujtT9 z9r=WiQa&S9kKdYe4STg`Hs}ewc7o8KgAeK%C~??bjsp_V5<QPte-+nRQU5{##fJQZF=U7hc_A zZ9Y2gyEtD9 ztHCt#PQ4B?uWZ6ASPEY8qP_0j*kmxrzickrx_&v2@9hLgO4oBa zUNP^h^BGQY&Tu-I0VD!i;xnA;oZ+N6pa!(WXE?iahLgO4p3s@d!ZHAMKbp^Qx^sqO zUWs{Ey6;Tq6;81G(R_xpJ7+ja1KNd__zb5zXE+uI*Py*Zx>HT(70kS1cd+>kr#ojj z$t&myw8UpP-8sXt7R0PQ*uT&&omaR9yXVbkINdqJNnSw$TH-UD?wsLRPvjcR3uqVS zL41bOoim)|6(pb~K40n1`AX7&cIk}4wOK8T4AGHY!aO>4o+vUvnMj?Biu@DO5@CgT zJEYSPR*}0y0+xc_G7U3(Wp{owc3;hT=Z9~@+?Q?BnR;O)&ydI8>ZfmfF^8A>@mqZ} zLl%U%Lzh+q+#izkU|q>xfqPK=-mUNu5?qI$gSe`WvkCi;iu??cm11X*q81!+u=1j= zg7>Z9XA@U`c-bK>6S;!oj5psG;PWFN*Vf`fBj$k+X zNmyB%Kn+O$jBt!WdL+$#PUuydd-SRAbHaXQS~9(&8&(pxI~#6)Ge(1Uo!gvX+cNPW z_bkhT?lU-nPF1X&<@lU5v`iGpJ5FIDbG|CVciy#1GU<0qs7{1k-RKZ`NEV@m1+yB70}b{=ur zywz6`+x!k0utdLX6u&{4WKY2E zCF9A9jwdX+hRwuZde%~)hmc0dbHWDY`^^NLixLB`9J6GmZ>nb*QcHofOq?m|re4bE zrfzB;Mas?`YWX^HE}k9Xt3X;NTDKdh+;!iF4^5HB2c%_!jgLys_7F!{ z77!X(K0@u*dbHB+NjRCYq&$A>X~o@IdYSJ>u{WGx+t7D@w&qp)EY9kGcz7(?Q{a+i zM!o6yugY=@!g@pKmkWheyl{C!H(#0P-0G&KVfaj ztINH^74_F};&a^%Z}uFI%V&~HL7IN;?Kx3D{Wk&s7#28qt>_USltM;`^!GEph2syemObj!CsF~oPaW`dlAI+yaKXjn@cwu&1@=mr=x}wk+P-2x;e8kB89y5o^_i#BTvj zi;p1#Rs`Ywf7vZco*D|IWuoT7>FV6^Gm_4Z3L~?EEV#E%H+=e^nhK<4;^Pmidb32b zWu6u;5wH}jH~NO#uZDX5>ucM_Uc;m~;5#iaCWLzapzo?h4_C^B&y$|Apl`A&&i8rw zQytj` z`UbG#d@os(iJDgew9Q?ENuBPGxrVrx21`L2p@}7jko@P?*=LqME5!lzAWffinmGiQ ztQATQhc1&eU`#Uc>JuimQ&n)bUDb@hzdrG|gx){NEIoN7d*vQ9O{>N z{Xtkter~DElE$Rg19y8xQpSM3Lp?|%w7%sj-0`n2q<2#nt|96QmV(*{UH>D8GT6tP zykA^f@(Oywh?F~{VIFz;`R3$#f&AGh_T&J&M+=|Df;2*H9~K~q>sxB8U$vF$iV=dA z3Es0DnI+3bF*}!KxhTyh`8GSRh0kI+%8Oi-UMb+E*nKB@J%DdJ@2i@$Oh65q$?{Up z^XPO4nmh9&>?{>}1!=Bf6<$FCdI;(Cy@Jugnnvhk^D4YONO@wgI9QFcx`L%(O{Y)5 zT7b0a6}tjrjU0ZCYpi|Z$~8m_!d@v6sP5B_oY=Uqygjvtf|d!W0ckl72g9$KSVtwf z^0_4c%X1p^1dbb70}@aV(lTMo=$NnY$kiIO3!lZ32rDF@9;77#sV}SYI6^wzutB@< zSuBaLhL11Li5n+7X;2T+G66Lpoi2f*3)bKo2-PhMJ%R78Ng7fdkbstCqRcEu9CsUb z!q6^!cTFbtzjoAB=&e63&@QB90%|}yeWKi-j(*jA={XENf$zu38jyf`kd}!-n;au* z;}us0+J!5%OnmeDmyf86RsY3M57IILH6Se$K6#SWX~kyP3dDr)OlEGmBQ}=F?4fTq zvXL4~-*imhD~~>%c&S&@%S)vojZoI_zo_%?Pt+zC9z}w-_P|RkFSX?yUY+MYLQmGH z^l7hp=yZ_w@bU;USnG$EKI~>Y@Vc4;X_+W`J6Ziu{a4$5dbb*8VUU&yM{PN-zrr|R zy`@jU@88JL&MnL8&2i?n?)NOJet1T?%;z1yUvu^G5Y2HUrIbuVuLkbwU7OhorDGA6 zg4*;R%aZZR#p`zM+n{(-a?=h=hrwO7wWn&)^FI0|AEzFq5jr*4Qw{3h)^?_93~3)+ z1{dyGMQb|UOM$dZ^z1)D-8802fcvm;sh2=nCSV*nTHmm+IKt^n2WvWg0!9vLnW)mS zh+e%^Nv&@6Skka=8BHBuMcXmMOZvVKebX1T$J}-S`UBfCt<|n*5;A><%{Hv7#;z1W zS|+mI8g0M5{@aHAGab+Uh#G~oOwh=!^nYySWb2^DBB$%1Ev~j?;fiyxFL#r7pw*JtLxhT@tlU!@&va?#K_v|5-BWD6agRaQDu4tB_ zz*3NA9jDxQF zJPw*OVCXx1qLqHLW@@O>BR&dGZ@ol?zJsSfC7SzWYS3JSYtU>7Ll2>zBMMQw&?`u% zAxsUr>T?ZhVLkL6K4&X?MROlc(EQ2*^&l;K1vMZo6El~MFusgfYrlJDxAesC(c`7K z-m1mBq^Ex+udFmr;H7BpBb9=*L?D{IaDwJOHt1oR$SLL+A5a6*GI8==3nR{>wcXOV zn2{k@e*3H6O4u8Y`&0XN<2xUZ9dl%~r|XrK<|5oHnk{Lt6r>T#IH{LW=|(9f?A#}* zuAm;I<@SIYFeaIp)TA&!TS+8s*jcK^&LEvMO2NDQ1by zU5utri##c0+}^WG^B>*D@M`*se)-$Q9=I(#J1a8vWR0v3uyMYf6*thUNwo`UnE+lP znzwOvn)PY07Sa$5;wz362cTtwoQdpX`P-{YHH0JoaQSZ&H5| zzxttxYci04Z9|`2)~Df$&zq8?i}+O>lYpgQKSs!HTWwq;OE4+8^9j4Qq={=XuoQgC zAEBj7Pial*Rh&+at2m|xB%mdP-d|m#CEo}mXX;OpG@xBDYdi1PP6`Mm$0PU^FVibn zifM=|dXDyRUhC7r5&q7HvlND_1VVmgZMdlsNeU$JFVINuvHYBP=c?-`%e&RNen8HB z;8(z49z?U(XOs1F*WTlPSHnoaNEdD4f@!$QKi&$wKLlxn{yMf*_gyf8bPM^RY#v!g zD|>1jUO3H5Ilj8M);nQ5-g3)Jk%>9=j_JEM z&(d>^b+Pny3nOPED$+Q@u$!ls0%@5@XuLol`u7E8|G6>bqPwb%3kks)kJMBkEfeGa zSf*D=&aL{+97PU=^bTAb&D+CJx%beYI+U#!P1e-%)FODGu<+(_HfCkV&Yttqt!%U%UdbLyzo zdg!?B{_}^8VP}xq-<^Ui2OVdSrk<>^@#8xE`)iMbgKmtLGGs{0M2*{v^sMg}TmCu~ zO3I$9r^VbHjGtL$ub{W|3kw|<>f>9~P{L1!61R6mdscQRF1fCz0^3H`m^yr+o@ae2 zW%_Tj2Bc-;{Kp;k#&N$Z9*1Mu9rq-0#~t2Rg=2-@;oT9S545^jwj78ifq!SvW(=8* zi&XHDMigv+`UX#l%6h}Vx&Z}aVu;Vv_qI`$rs2hrKFX_4uWUmqPQlBT$u#|)(L1H} z92c$y=v_UVxF-lbfiyw~>(tO^SI8F-+mL=kQTuA^u1v?j1^OsZ57G!tNbu2J zL&E|Nxx`3uKw2h_Hz}c4z1Y$6>_-f{&uJ6)IbkX2E&Wn@$Z~s+7M0X}C!>kWjG?xS zqvql{^bRkqX-Ff~qS;gX;Xgc-CS~H--Ef<@8xCoi*!#&%?{;syXRDuE^^|Kb-wh@aUy#bgWWlXr6BFN&FmgDr0Mq)g9~a&V?B~ueRG^U4{SJ?e>2l>_l!jLEJjcIEQYL6BB-Rwp39(X zk5wFTKKo(D0cnJ?9lNaEA3ol;_^GTRX!cAAY#aW33Gs2>KNqE#2CN0K-|<9Bm7)#l zyTA0V-w#=X?W=!xTAG*;YJ4|PslPRz#Qka~%`jLH4p%JRtp``kNMjrpI zMC~86ernPBVNaw8Pnd@?J@;v#f~m%+b>nM84M@vGlkfK}+ZV62&r{_mQs7fBFedt~ zu)Bfw22^9u_RD_oi4<5$rs?$(cIC+`u9t{5htK6e8lhOK!Ro5gVnfn^G0DW13&r(< zt7<1c%p6PHH|?-JI^G$xD_$P?vT9}C55r67GXdL+WYucc9gLgNZTdvYk9Z^O=pOz& zt2i=0RxSl;I%+eO(tnL8sXf0NBWVbl*`4}dR;^>}0eJLZOv95tZRmb@p?b~dUSf83 zq|E?q8!eZDG|O>AjT37Y@~0-n5#|-7#ePQ|?awOurOnO!qvz7!0d1dMTbp$pF8iCe zl29<4_NKyU-13&UR15Tri{~PYR`*Bh1vdC=>oaE4*8DRH520ScXd#VI!YqsK{@+vo zuD?W+PSY}KjoXCbo+W)0s0V5K9P)ZUy>8V4wyY1M$<_FewvV%h;J)-Lw2+pGwQq*# z?Wfk)U-k}_Y8TQnG2&gkk#oBr?)7+rb|yzwt<{NPxJFz`3$l8Xi6uQEjh6if>P3@F zV;DK4Wy0-#J$)zkJ2<&#G-7pVeTs|v09+tT%Iw=7~yt}KSw5x zFb!DKV!wl^7~4uGf8@5<&O}LZWPDXfi)l0-pQ+-l$X?yo3K=gqv@zVv&PU_ggzt{GP-PPW3+8hF{#nZLRvo>?GD3BfgVB{q0I@U zb^GNQqgOQchZ>NU3BOY-)js>i7^RjDus{NO0?&Qux4eVOlCz~6@m?a1CoHk^D};`A??;T?Pjxc8yM0`P^4f+nR=nt;r*w`3&t4E(TcJGJ zQ>1}0qJ3Wl62dO?Q1&V@F`js3t!7`ie2q4=NkuJ7nHb#Qq^ERN1kZQq>U^(1X;kK} zUeGoTLjvl_UL9~9qDL;dQ`^%&l6=fxQF~IpKQ89yrTjgky!K1*D4e~Omvl~r(7OdA zN%e%CYOVQIl!p^3Q8FB_J?1Huf;2+I9}Lx%85)dadN#Ow4!fAa3Y{ws$EDU^mXwd{n++OiMiUy?E&?KCDu0dow%H%iLPyCYpqorVHz+dvEM;l zS>IbPy5P^+8;{9xG??P9HG4h;Cm)exqAvt)d8U#K{Yckw;r75hCACKRhvKuXPZkq51Y4hD+y9sUPN{9QomSZ`I5V`;f-n^D0mS(lXI+KqtMu z`nt}qjp$c_fE*I2ZmfU$$dbO9Rj2_=L7GRnh0kvyJkwyO$(=1zpaivFI3Z!LX+_Y}Go_SiGvaV62vFfe`{^*O(ANNuq zEfdR&_R>AWrzdRxQ*Lue%S6nQ)_R$Qss4SnC^D&8er-%>KkV1dTgkaMul79CNc?q# zT+;}}%|iT8tCS`ni^{;|MY z>61%sK~LVI(~`{xo3-(Y8UE3n%*%v z&_r+9)UVFMLb6vME9KI@YolT(wd22I6*`yp_&bT(viihT~Pgcq_8T0M9Yx z?6iH9Ry5TfOB{kfy&&wZJLp@nzXL2xEe&(TiYhHX3 z)DXV2T9Ao0P2$PBr%UbK6JJ{jWpdTp1`Nl4*OlXddi2g{?=fWa@zrYS$X+%`Ks`B* zksDi*?iY&kY)RM}9pJ5qZB}ov{b@!<-vhuZ|4brmk2xipL>r9nR;i zh;24Yz?q1y22+cZcR?-E5Ks@&^lNWur`;$NZ>%i)-G6NJ{91cDiYf{w38LIUcE z{cJ_0zcX5{x>0-{Hmv0b_~(0ESo?G+7?0iSC9P_3y+UZ~xwpE~w~sM3#Ki^)VV8L* zd$m2J5V8H$hQ}dnomeifgK&kTvuKs-#=#jl4FUCpCAJ15lxbKY5=Auz)&AWtfv&Y> z=vsRvN?tkPnuyRj>eV_*WNai8!Y=br_R2GFH~nN@d*Ye=QBs~b=YCPG^OIiKc<-gi z8h?zePO`Vagboj@I5N1aTnf^(mr$=3I_nA&Feb5|Wd;a6DbP_r?L9r|TqoJ9>Ddcw zRr>bCo#^P2H41IgRNrsI$T+*Ft?%ukTCRt^uuji@U@1t`UuyEKP99FeWXRQW7DxzB zSWJ*cXhS7W{m!h6`u99h()E&Sdva;pyn5sK#q{hRcu0R|bV^74PKzkgs&^+X+t)(c ztX@6wTir`41!;s1w5+IS@bc5z&frglnRz?B!X|4}dy}Z%nJ}FES?h)cYQUIeVrPx= z`nSgg?Uy3ut7<(uWY;|Z>4#nDwJh1IJUc2FecIG#ZH~l|B~|58kVfcxayR{MwkS?O zuLRBNN^CPr^a^CnGWx-y^R#8jvRCl>o~&_Udr#x#+W*v(pH?TX4a}|uyy=IV_Vrd^ zDM%x9+*ZN3SFb+l{TB{^1oQ;b2<1M|(>NFNpBfoZ#2;P}gtV-&aacvNYim6|&c*$j z2)b^IZFZLw-jzcry8QuFeLdXx?b}FuyFMAUyuGL66$iW(cozuL2qjLpss6sh(`Z0i zChn{lO3JCH^f#N%C%rA{s?EMN30sNm3B1lk-)ihvkwosPXLNb8GO6Rx99o~7Q}FQ) zDRHovOnaLb404;?mW5Uk{QSA=Y=T;(BX$ z+ONbmyVeV@sv>l0`ykR}&Q+fEiBgP!9*X^pM(8Hhc=zLnTBLA~1DB^~)ULM+!w2`t zcHwncgnp-lEA{H`g{~4I>@q#stNQ0l>LJw(E&Ek@L_J&d*5>wkD6TWvN0Bui|M;Qb zraEk#izAoBzR7a9kvD@eeY#C~=)8lm`-?t1P=o3w89-BCEJjsE4OtuOs@ z`h>MU^j=YlhY0;ky}ChlVtO4u=(hN+EeG}ec5%5Br0J7@l*qWh2U$8;CWI#}CRyX^ zsA~H2DJv6QI>(R|#Xs5FMNGn32Kgw%LcZEIwu;2Ff_!Lerg%u_!F@f93<&WtD2@d9 z$)zBTkiMvz?!IVSVr<745;gsu?Q)yRIOjMY1?mY)tQP2RxGk!zpQ&3p!6iI~!27b0 zmI?QQW%PQ6i+{1-G<`pc)-LT=`nxsDeS3`f zYOC2c5@&txEwu-vsY}QG^dt9gB(Az2P1Ke@Y%$ZO;4Q>QfqHU#O!4v7r|!*gD1%!J zIkxeuZT{ZLxLpSy1=2E+>zA5(@e&vPM%R*i38ZC0^pd%K!Y_ zb^b@VfilGDxeT0GnnqihM(a9FE(K}&=H##ajNly4^uqod>p((y!fHX*`0GNraVXTP z4sBA%pV^9`p4_&2E6^^i1%$>>uU5Il>1CD|NQ4B`gEV~}?xwd0MTJ$hdcjkbruSMyTZ3r?#N)jyvJP*2dM|Qg4U-m}VJg zyp5PTwfWo*38*Lbv$09fqiR+sFDBDWzrwD7AKSm$`t6^L6P|iY;{*15+BYW7(0V+N zC%4`%#-aUx*aBxw!3(dXc*Q)Fz0!MDBUKwJ#P!oP8`OZbOtd-LhG_E(5$~Q+Nsxe^ zz!{Y;OfQNUk8`%>k&7eCzj;gZE}T&jTD83m*}1O}Bdm~sdSX9YCFoV>mqm;bRO8B| zuYUXJ+eU`ftQsQ|!Y=a=()2p@zE;MEer|ll5w=>^l%My3 z&*jijOEoq+BZpoInmr*TwwWb_rvI1K=xy(8WSo@A-nZKa+luFvk?aE%wdAi8{I3mvIxp9-dMTT#-t3lIowR_$QvI>5E?NuyrQ#I@qE08QY=2NqAVR zS_)hf5jy>Piu&$C81E(G$ZrdLq*9QkZSK>R_}i_fg3$Qp-B4>#7mweeL=9JyLeE(K}&ZIMCO>{Yguw*0arPRcBy zp0LDf0ioqIj?c~(6i1i_tOc>(L5!twl>Rj*K9VYq9IbU*mX1^KwsEzjm=HQf!2)oQfv7gZhRX!AGw?z-uZ0qFbujrR_lEim-WQ|6z^6Ks(v7~*D{Fax+2iczQ zo{29N@RdA)G(Eek9c+KKf2HO*J6>u*7MFO2N!F;DFiUUtV=QUj!NmqOgzqdSnP}T} zuC}X>E$Qe7IS%-In(Wo-&oM@i*Cp6F4iZP=7yBw=+xZ0|^LamdkN#j@y*~YFOKJjo z2xicqK|PLfB<`Vn6%h z5q)Qr&h3?)bGxvWkA8bcY_qR5!IdF>uOK0|nI%e4jjB{*U$&ysiUUif(I6snT8e)+ z%ITH)4JjIj`Q;}1#-UGFqa4-fSd42}z^Z0`vq)HCG10oBL=9);bR{zhSW0X=;-Ixl zM4JnBXM32Q(3&>C4#n%ri~|zTuGsHrk6*ja(*JffdkMGY>{q5;_(dpsy`6eBAf+do zgs|&uf0IUNaj2`_e_^cAp=mMOiq1nVy__Qo+NC`|Ks+ywP_J6E^g8*&jK)2(TOc8# zWgbGB&kV#lGgyT!=UigirL%htFK1%UQoaf-1!?*V z#8jik4o4_B%2FnwJoem+;zkW-?|?!p|_)+I;$uAlWNe z3epJC?3IA*m3!jM+ss;kG(t+*f@(uD!GBrnSh76J4NJM}akxlke$HWjyG@ScCXM_x zjl5JW&%!MrZ#Sc*8M#T*Yr6jxRDH(>1*~WsOM+akTZZ(H!il+RDNs+==v6(hT0d%a zQn4{|6`T?_B+m_&QPyvQm=M>#H+FGxCmEsxJvu{AKx?(LVz6Sxnok92hTVM5RN1yPfe^3Jw zvZa3-<}l($bRq}JguANJ*GvCpY#(ATrsBx2=Xt+^or1@(sGWSwXrzDdWqO(->-pRrlHsR=-K0ggR}T`2B-lEvF+$@duD`_*3sit zYo@+z)Z$;NZVO;Xpj{S|_#Pob&3ea^G6}QoZrS=+pe;y1OZ1tdN)yz&$A=|(jip}; zjqo9YeCUsgn0W0U%OXghklJ|msv!J}x2FPWnfTCZqFV0Hc-xv*;UsGx ze>{6oXZ$purvho2c++W;8os!vEo&9|i;Iw!iQ%_gNyhkss&h`nqw9rPoO7btHZl=B zYQ4H(e6ae^F(;aJMdw75mWdhVa~O0^H1vP@oM_Qnbmp}SYZT^o^bXefZpy7=N%kUh z<4C4M4=feFjKJT{`zSE0fi!(TYC&b%#M8~KLg;fs9~NXx|9&?@TK zYE!ky;21JD%LmK1!o%^`2p)lp+{wbR5JnDjHc?aX>FX+8HK+8nc zivDW0Rn@iJ$MGO;LA3w4@%Gu!XaqDVEjy!hO&!|}0jZw1ma zG50Z$gRsGnHzX(So!P2a=HABLB% z@KPWx6RmIbQS-dXo>*vaq%`|LS|*N{&S^Bc+R^Cg$NE9WJ|9a z<{a9TJ;t|J8XR} zg_Hi5>uW)W+To$Y`B!Mocjsk|ZQa@tnll&!9XW$0=5|<$&Q~Ul(2`yg^d0@HXn06C zDRcpAw_gU~*?-hjpdO^@J8}K3`jq%TZNa~XlTN4nv=SA%;`WNC0%@7>rQaNwvSNT% z`PVRFndhy2E!_bR9`C6@S|;3|kJEeqmQ!22GMvoqQbWsKyfwab+*5(HOib!DTHms$ zfUQVU1Q|E6nikiu4PJ21Q-QQh+^;rLA9dzZ(&?KKMBQCQE3l(2&iunufwW8v@EWRb zj=i4vZ$uh8xy;HZ^|4dzO)Dw_Yu@ zI5RS{)!A_4<0L+Z|b-wsQYjzH-7+&|BKQ=fBW%)%ZnqW_>0>^EU0)`U2RQ^_ejt zG@#i7oo0QiGwU(G;*I)k<|vuG z;`gy5cj$K}*vtS+!E-8}^%*qlQ?GQ1*$)Y*2Wk4gTJLzHRKjc}Q(}J$Jlle_tTEvf z{RT_R-aNAuXQSDd%V(zWJeq!~Zp9`2cE`cSf*v>h8q%+^WBN7r6;>YwewkfZV%G*} zMn(yZ5^UxXN0T1K7oBblJxWH zrALnQvp_=FWqOdNzi{NOkZXghk+FG3XtkUEX-Tq#;Wew|+y`bgbTudxOY*)es*XJQ z#sUebCwrxz-KJV5jACbZR$=Qxu$(QyJP4u8-!Qqht6CZY>Iq9MQ=`vi)c9)qNWYs< z=HTn3w<}*;O45w%PE|R-f|(QjBG8BfYNdjGNvXlB^gmiWvvk=v9Di?;;uZ5y_G;9g zVd}FCk!0bnQvpx|(lRmH#X~1PuqmnLXqF1~?7Pc@k z1ODni3jbD7&gba)c@|_G`_=Izps+ROrMHyzL7IN|d@0hae0JRPf&}zX>}MG#eG_R$ z9ks{Nd39c&kCwdZcr!B&tQU&&X7W*Fji;5ojlP#^lNC#{Ym1D`IKE6M-nYzKDg|kT zUcCRVPyEt@G%3?w+q^0RK3JB%`J$)9!D5m%3a|7uMzr-O;dkC!pa!I6V%tBeYQcGu zmW_`lcMIplzP(1_dWYy+>Kn4-hHlZ=@3glfdo^KIJ7fCm{A5f0>KJOkQjn&10g4m# zW1yP2kp5;o)PMwRS%jXhYM>s{D*6{}CKL7Da^W>Y$6+`6ERL)ZadxmVX2I|LKBqVm z(o-%4X?le|ww+P7Yymc+5F}tsVn3?|I!BFdrlQdCiPh*Y(vJT-A1+%e7H{b7tyI~Y z3ujK6h@+nfl^z<68CveNzb=h8i#?nRr{Usu4Lw;ctOJn*M@)w@rGMrla|)CTum2rDu2G_eS6^d(akqQPrro zOG!gO4n>@^bFXHLAuFYHe#Sr*gAP7ARUa8kyG{$(mwXgyS zVV8L*d-bZ;6SeR6e#Vy29QN8tUo0iRO~dH5xAYq$@Yh4=+h=QED2GeL88yolRv-cO zWUmVEtxJ}Usbu7^Z`W$|eQPQ4*Hrwmg#4={@b^X#I#c<*+V^vBqagjl6eOUY?A5}e zBT24xdw3=zY?W>-|Bea#g%bL9jaz;4_<0519*}@~Vn6#06@*^9d#FXL?>`uQJcevL zNq@g>;aEKTw2!j2$z#jWz2op-N912Yq1Q`J#*_62J(SyDTVv1Hk1U~OCgKrYP7$UwQHQ0e_aLY$#HDkH-gOAzE5{ctgAr{;XA7ZnfUstg1Yz6HUGQwW5||@ zuPnbkAC2G8+^0dgx0W}BV(_Y|a!mB=FxFP&;#N0uvs7rpuQb{u8toRkLPFmmO`l24 zT0w0&yr=)Ql`$mp=~Ii_`7v18@1sCHNYiKNUwNnp65A#ew9B;%X_?q{jo#TEkx$X< zX08Lhg0&zMFH6=?^F6;&XJw-p@@VT@OR>$P@kRQJI!jA_v)qk|!Wmo2wLsrwEj~wm zdX_)8WEBxMreC=c+pMl2jnLyvl~w8xKZN>e6a%U?WHo~<7c9Aa?aFVy^b8FU-%F~Ja+BYYR~^>aUB2c%`<=<^`5 zXtk?joIC5sW1Y8DS1=}oO4J*vZ@Ce{+5?F?VFc6@`&muXFX`-7iQD-q#=OFZ{Y#(E zfR8qez^ycIsjgrx(Dma{5Lv$2)mW=7PlSZ9%k*Tg)@8n}p4>UW@ayJc@ksh^xi(`g z9&nxhnht0i*vIJiMdzqw@7pSdnqzDdB%mIo>8}GH`(PhhA&%FTuoXeyV-eeItiTaW zzje0$FE!%$fHVZugET@7_9pAGT|f4?^RV3c)%oRBdJoDuWsBR z1v%F`tr&p{oxd|$(?-)ba{t)h&sdWAk^gY#o1U_@67=JQK)cw7wCcMy#je}zZ*zK5 z1|1QOUFJhH-5*?e%32e;&fwTuJRs8R9P>BI@G1q}^STmmZ~3mLJexocL^#K6iS{X? zYZ*3i%{{?mB%gEk^WSRqP6OUU2)=jsklrh5wV*)l@kMgzkNS+# z-)I@(#q$Km65r*}wDV;D86mh{IlnLmqMg475w}SdzeP80i5dAd-T#pmfhCaMU>F7v6Xwv_2&M;yp5xOW{} z?`;oP?y=zAli-_3G#)ap5P=Gvzw`Ya+TW#Pgxz&Z9nqz73r{}!{@~*&v`5ZT^{x!w zZ=t7rb9J%*x{+P1z8y$KgkzT#s;b8CoMAmGIzcq78?JA-P)z@R$Q1haxq2T5@6ga7 zR1deq_SY4^XQ*r<0{K)``i(h8IWb;jT2w_ZRKBF1LidU;cT?~D;5{9>2GGlARXj04 zoa|lRL2cc^f|vQsjId^G`$7!w2$#uo0WCTeXib*LO#b5-`S%507}1WOn4YvCpy0{2m0jv zJ&5?$j2E8beXQ1Hm&bfOvaCM->_nY+Ekh;9M|+sg?=C9-luqP$XQKX$ysg(PQLj+w zxgX4jXidxeI9{Clv%59-^fo_oAX-JN>@`@tG4_<@pV2!N5vT<3vC&-Fh%q_m88Ur{SI+?eY8jF{8k;A#yyNUyAbn)X)minznHGV38-{l&o-0 zD@LF~=kI*qkgm7y8(@qpn_Rcika$sZM0x$!`~&r+J;J>Q`d83%e=|mJ&?elga{NoG z{#-glT;6@E))3OZleCx5uC_unT?@b3-*|TRlRd*GsGcLA$}yfe3XY| z3{yNuG+mk4Jji(MuSv=Owo>~F`5a5!Z**?($1&p%>MPDD=NIO{eslgFL`*y~%7_U2 zJ^Adui6Z;;Fg^V3zWU}>Vcy!4D(PnOB>jh)s!#N!EbZi(E!#qURmqF~i$g2v+2>5u zi_@Jr)Q)Jnij!rOu~mDJvhldefe7@8b~o-j)E?RBuu(YimIpZ;?d%hxH7$C-C>2ni=9N>Apjg^o|Eq&k;>$6J4hn-wprXqs^b7 z^c8*&ROKl9_Y^zwSra{b@pL+Jpie4d?ts$v2Qkg;{>yDWeR2hTVo9I=)m3`32EO}? z-%h3P8w`rI#rYqtYg&be8?DyoM%g@bI=0FeRKLlJUt6W`Z9gt+zgDlw zO9w`94QV ziC0VNqv=brcWI7t?6N{c(=)=QAA8G}oor7oq(vhKqE*B<1zr(TO18Dh8%w*Iwi3+H2&Ia4)vPtHboXXx>-ElG1JM61@u5MFc8Dv|KH5 z#>(DxY_0es-0K|kRc>5m(ihXMwqiP|k|PMJ5aArNrRS^H_vWdqS8SznWZ&6Ne0?@Q zEAu&bj_01Pq1;8r`@{5B%B**+4z2tt+fwPt;@-lnzU&RX{Fa(t+*{wV#Jm5~{yt>? z&mHaTdq4fMvwk08_Fejh-p8ovMfA&v$Angwt?P*BhL?oJa<|#0_{3~XSAlBIh)_s2*s)#TT9ZZcJXNlLVzknICh!O`8z-1 zp=nQv;})UnjMZvKp481k^jyYILux8dS>W>%^b89j{wBnCSyY5$mldk2{-D-3L!LXf zo}H|zJePq_Txi-u;*O2ivmf|W2VG~N*0)2RBLWpVf9K~;Xon5r z_?}Q3?tHoH1A4w>7(HLIZhV;XvCSFNAr2`mu)j@Al4mkwBPN<#v3~ns!$0Kf>xW zD>?f5PZO2Bagool#81O$T7h%;>oVL4=)SqV>~?axt}gtA1oE6={~; z(_Nn&ulhuDE%|Yu{ODfp�w8)iD45qO+d4o!Sb~lpln+M2PDjst893D^xxIg<3xh z`Qg}Voh!`i9J4Cy1&Vg!U=;VR(~1$O(D^%~=@~C>O=F&W&&=Jcid8qW(g=P#Cey)+)3eglL_9W|4 zjvV@pe5&Wjr*hmQ4vxl$msJi&JNJT$;CYs+sO&3;J?dsn#Si48Ju``es`X0<^vSWr zy+CjGQ)}|xJ~`?0T4R5THb)H_pf6on(~EZTTRC)hi4Zj7*ms|)2*)lfL^NFkAXPL& zOI41o-W}C%@Zi^Vf~tNBd5#EF==`0(uB2)CX}v%d&h8Ku6BS9{`8iMD`59QNrWftv zs)pX?AXS-3)wxwF!m-N=5l!FPTJpA4XT!AUrvIs{rCjfM&3@--kLM%m%1Kr@aglf^ z*nJLrnSyF7MAKdtrS`!_bQ*7z1;+54cGmRXmj|<9{P~{ zVP2KvXR0HQNL6x~6;a1X``GjS^ou=eDygXcWcpd1>q=RpI+dg)=r)~ww`=k z)9W0wDqJ(lN-a1?xUZa6j6j9X-x;lGPA$ok<-W2Oby_i6<=_g+a}-w}=lpg1nJ}+& z%+~|(ngi{`My)ealswvXymqadVfx>1_0@ZXQ!RlrZ$!J5`XvrTs|a4n+##Nv?eo^| zKv!7G7Z|8N{54Ebg70YrV$BF{^^@tU}M#s`~kofhX#E02q_^Vc-uQo+H->#yk4fE#L zixZ;X3kdqQliLcvS4F!Hr90r?baHOg8QRebzc_@g@XJtiO+Q0pPm7d=QT#P1RD}q% zq-iA!F2dQT#zPbD%9mpe2q!{>LZB5a_7qwQtKyI8AyNs1~|f@qZ^Vfzwk_nQqdfuw2g%j0V8>IGE9pOZ(}`G21g)AaIA z>-{0iq~||Pt*f*`w90|Ki+n1_sxK1kf2w8hk7(aU;lO@V5jcVq4$qg`KY!RDaPZM= zd7SlhQ^hB`mhnL^`{~b}tUXaT6b{smXw?tYj(mt#5hqK}luFL+Z60{{@>F>oeyg>j zP}4lUy4b_3pO3lHH@iLZ+u5>rD?e!;0Ge$ZWP*w}_$&l^|N>KqbhBXcciQTT`iI_S&9-q^G(( zZoH?rqL4QD`}>eJ$KTA}Q|3<#`yG`aTIE0`$cJbZ@!`=bQpu>}{Q}8*%gE#O9s4T^ z=`1x{PP@kKO);BWb+*fH)MX@|IoMlig=m!nl^~z$N0BcK`&pk){hf}yri=%+LT;5~ z(>vLv_KT$k1-?v9FOQR|4_17lJ+R;T!CG9WqxI9po{Ar+9nmTWYDYdqs|Zo(w4djw zw`L6uoQ^vvj~CUBQxwu0JU=YAa`wt@|N3_`MHMPRw90`>kPp!+;?aP2rIM%VhX;<2 zoFR{o^dGJ$q`R+wPPZO^_+9j}Iuq<7duI4~R=eI$ZG~u+1C=13>c_aJ2d!a)S6UO^ zQO5&YA-BpgvF1Dv_pY5|cz{~TV^*lDx^Q4f^y%~uVt$~nBhoJ(_Jh5}R)|(PP&@J= znx2_BFeHUIQketwVk_j996o0ygLVt7O0Tm|i^B#hKGBnBCsrH(#P&_y)oYC62Wm&O z%F(E4c4>E2#X*6|)62-?@4NR8sEAiv-7yM%^mX*D>-}tsAD#P(vj|%uTJ0fB-PVf^#fZWx9UfdSw(8!cd}oAs)0P_N~EgFxi_o0HMo;i!)&Mcfvpg& z`hnV!57DZsm6e)GC3BYd3@kj@SsvdU*G*AK^ZBZ>B46^hn9j4B*i_YI@A3?QN)WB8 zLM6zDXxgc8sU}ukea(NOTMxx^Y=zvaACI2&k=lP--ZfCE-*9=nb7m*SC%OeUH(X@C z)!s^%8m9Px+7Ye#f!dJ|(W)xrhj^*v?A>;O8{4PK;}hxIC<^Io&97G$jT>jPkIc@Z zs6r)(R#l-ALk0Q&ELV5Ur|0 zCCGvqnz7N0@5V~(v5t*SyL$cJcoUMtVd z`D~kQ!I`kDiq3K6@xa>UUpU)FyA!OSAAClys;ctS7|AhZ<_e{Eu@!Qws+gTsF*~+O zTNNsCj`5lUA9G&?uNd$VxBC6r84qhmgmcV)*R=J^g8QTH{H?!i^&)~>VUN(A%HESi znOB#1_O7jJAqTd?aiZ^LJR2wW4(O$KS~^cbD6JsVXs`SDIPvS)*?X3kK47i?Wxn*| zzi%1@Fe;V2(fTZm7e^aj_mscXPeGtUL~C02V!cJKoMrYbo$^>gpk1sn^u*SgwxamT z#h$nG7qn3ow!&IT*WoT0BJsaodXXisDF|$ZHJ`pW@yTnV!`~-&`%W14f{3Ql^99R# z2Cx;*U3BNCd@~W(;JT;a%F+r4BG3|D-_1}^%!w)y6?3hv!hv>ip4YS?)gBu?PcHRL z3G1yOuobRXXz$OFn~c+uOOhYhqwFa)-}P`@UCcN7(JT7!j|M0l zh(JrUcS6ym)H=m-B>zS0UHZlEaG+gWIdfJJ&s8m&@ox;HT&n4+MAz_ zQ#jBro@LMz@xSf2u4P-|**7&#L0~I9TO!1u$JUjCz4VJkdn*WRg=c;AuKt4p_JT zQt2-XIj|L8bE11iZQ^XRN7v*dKgwDnRdFrBR(S1b&L{)X$5F^f<@$6nc{aE|yF%c_Yp>4SB@y(Wml1a`0Iro@XMT%7Jzfoi^fyYXI&w2jo*Z&@Q51Lin7x!XCwl!5*PG zDr$;Y^{B+hw|B4gCKjyWEnc&Sj5a>zQKRR;U)}kjsyrTh`GSY;bJm(7mdCb_I(PeN+DHVM4(+n)BI5+R{T4qSIq7)w~YzYDoBotUw6^bZutv2B}emR$A}~5 z=0vfk@r{(NUyM)?$cJe1d}{-7Dy#;5SGA%Tm6}s>1h#djrZdQHLQ+_i3$SkQr^@FRX*Z4ey+4NZFB9IEte+=&L~zzHPMT$NUf|GtX9*$ zIak`4y191hiwN`y(b5k~-`*;Q{os1e9Ndd&mwb{O-0Sq-uC^vXei-Zr=Qbm_Pf#JE zW$#+z>5&xfUF1Ntir93ymi?dJErv&sXEHe+6b-0^Ml-;D#W5|T#G)ukt^+5#kAzD^AJ5+bQRLLXsbRbI zT&dX>j|W$7w9A%ceo)O1B0{xYQH2P!6jT+e?H02$2hSO3mlZMx^`Yr{&b2*&2(*jn zVDE-%yT!f895hlU+U1^R4vIJ8pxSP0O=WFYR3QQ_$=c3w#kJk$_+bvp0~76Xj4=mA zC~;7wwl7zdmD=W5VgyCCf{zL2$D;Xnjh3Ra&`ZMV6~FbA&_(Joga=HPX3uqIC2CTqK* z3K3{Y)^@ImT-y~6w9EC8Ie1koYr7Gu?KW3rR>i+yE8@^)Uy)i_+pY9lWNlYC5P_D0 zb5y9d+oWA*4(>&?OMN9dxYvX8;FMscwn@8(5!@$;KudBq@NNjs28thuKudI{O|x^T zw%asnQWZx7Dxpa9vgaJr!4<$SC1h<^{6GX+a@QqX+ii+hFZ;o{hIT1-B?o7Ltkfby zgsjvy#j8}snS%(lB%_^IGCUh7ejoxZ1=m-h+HRpOR6=@ zLq0^S99fQkAZ_tq5uG*yRUtZUg!hDy9Ay$m>ZqOTBm2QCXH`|={Miz*U~(oM`4Ful zkOR?aBR(rUE4V^_uvkYWJTtJW;MqiwB^d4g$V^gI{tsvC$cJcE)!ppx$V$EN-^Dtj z(?*~wM5m2dwMm$)H+uO<9kuhE$bS!>d7&SOKt4pPeiR%vJIL`gla6*NV&vaxmUv+V z5rKS&Ryinsq%CKa!P?m_#j*T*@JyI6KBqEJ^vPe?4k|%Q{M&QHf;)>PVp`%X4^5HmP#TV_uOXpXBg`^20|}O}3(%Xd*go1XVRzU#TXVh<*t{M8W(( z?TAhj;iEZ2s-l_Gj~RtNseaI$ArUm=n21gjp`o{kP8)%CvEraYO$&<+?nU+}=2n1P zT{u30*8g;W2dW)f(lmds$@bI>$D-4X|Iy38FoM?%Si2Cda3~0Dh1~Si{fDFMOWrfl zt%_~7*e-K$Mxhey1y@xHsR|$h?IN1q)T`9YZd-U!%(3OAZLYPP3?=vj;DNkzO;fs zK16HU@Y$QJbAJ_z8Rs8m^Zd#j6DVuZF2*t4C41|NRjBF0z{b1-6a*?nG|hL5`^I!g zSrGG(?xpfNfjKy%&@Sc;JukYrZ)*FL1*s2SK%hcIYue{;T`>waUFc<1#I7?3=Q-NN z8bdpA&E903{HstZdyWWHh-lfnf_gWadzX4qa&YxQyI3pfEuq3$#mW}FQg{RrfqaOT zQ6j7_3&n7hP&7ym&U3U&5u+56*uVp>Zui4pf4cWS+As&U1s= znS)nLXqOc-2d~au&pFS%h(NoDc6*oeTyQTk2j#hrcDbiRGZAr6o{ML}JXcg90xiir z7oj{C91W6#R>)|VBZfJ6Js*t3Qb%Q;E2#AqXaW*OxP04area93c;Yz4+8x_>n2G2#5gMvObeag?rcKqQ-dAr{=k=AVovSvh<+X&ON<#$lAzDHBI=t6W z+A6*2Pe0nFIF^6swS`kKs|;ds zJtw>JmuTM7^Pv$x0AkXLW znCEunQ#sHsqSHoDrpg?o>cjK7Jmz%*@~Iq@sk?bRD9?37r;VUYmD(xKbwsC)K<$W5 z8$oqYXH`_&dCee?c`brIseVu$l-^Pm)e)UG0=-3a+6bC6q!OA3l^jHcsw$c@B!Xrf z52DjXpms#3jX=AYk7}M@-_g|g;J*a>LYGte#H0~s)+yAxg))}IEW$aF)}pNr7`+O{ z*&8pn31o}tYo@LkAMlMB?ZNCqw5I8HQ{zgmM7zM$kvbx<6>`&4@C$YuPhN|&FI6pU z0799aao(lfDa+>;JyJW`-+q_N8>lu!s#;$uT{*O?`Z0L>exq4!+Ks(Ir#r*7w2~RhC<{@Be^Xhc8^dHs1VVb_GP`o#zE@c$a%XB*3ToztZ`XFuT&7I5YhAu{fDi*sg>gFwSVt7#{27k$Q<0WXct!lnl>?_u+gt=LRuK&%S_ca2arWPfR0Jx)6$kCO_)j4#mOSs$ zORDm)AFK*n;rc<-Dwk>m?Jr|9|$tNnmDyM5ge3IY`(T2>z` zRDC#WB?pf;+Qn)|`vm#I?jlph85`8*V$ATA`X~QvJ}mCUX5oyI5W6 z?M%C=b(JbyuBjsx1o9zTRyZqE;VfvS%m!HJWredt6)u3PPzhz2^e;HuP=&KX6^>)p z@!W&05Upuc;jB=Fv!H)Gs03#sS>dcug;Nm7hiF;htWbrsV4RiN8RuPD;jB=FQxK?7 zRYeuf3RO4@;#EhxR2kegk*si5sKO}-RETI<;R2xwXZ^gaic{f~)e^3QWQDUr70!Z8 z)ls3UiYiG*IKf|8KDZts{Ek}r(-KzsmTiG4OKV=fxUoe zS>cROh2!3p96Wkx7gx2i!Wp3oryx)vqGg3MLKTjq#0*t99qr=kTvj+ERN)i^Dnzub za7L)YakNVg9zC>+>mXU-j8KJB5U3E*vR)aXdc~DNa`1Q~pURQ@LN0Or^^W%1{)^?@ z#GW$(*FLza(X`K&b`XpD9|0T*ni7nE8wPc&b*nQ8a?Xvv@h{%V7n9b|J=yv@7^LbM^-+IP)qwg8IS_%CG>yjE;xXs3$6wGcXBcyEFVlXOmGjy>f;^JM;eoz# zTTxHzq5LNVjhr=&RPjh62iiqTv`gBS!xoPqk0kzrc1exo;2x*1k{o)|<`LwPr18*0 z`N47JwxXz%$K2y`1Z`&okpmHEiE847TsG(Vhy53OaRoqGB<=F7uX4~>TcND=qAhHN zXjvKTP-O^E*6P8^F!@7l1!xaZe$v+7KzY91(_HZ!5ok%%XsqR!^Vm}s$-a6)J6AiW z--v_q+z#crq6(FuC7I_kN;q1;bHy%#eb7chpkxz(p`6|mO;r}B7`BVNl7o9$=D7&vIghzJ4`M5dN{Qeemm?@EHIE=7 zkPp%H?rW0?@*T+gZ%vo^!F&2}eqbcx_-opgv!m_$wd-3;%S}^q5c3YvE{8@O62Tm- z2wU;7!<{w)lqhK06*yy*^n?G;twJ0gKzNALso*q%=s6-#38Lu@Y3d{D8XqIs7ISb5 zw2R}fszQXyhpM=bxc`}hZ3X@4ucKYEdQW3Ti}OlmlV43COKSH zhl_zrYB(N)WC3fe2KXHV4~c4o8W@r*eQQ zj$KCyN1uyU5u6|7xk35Cp6lQIYRL62wUSZEJx`Y8F^^GjHkcf48Glnv;i|uSm6xtx z-StB&8SSi)(eA7!c=gKj5+k^}AsYGISSfgP@=R#G=2X(xb`v5)9i+-5UnDpS1s;cuGCyt znVpf`_v{C^#yHlrmcbR7$V`=*=T}DX|B(;Tn)V0J{Jwn#trHavM5_ob-*|&&HG^lh z^_8ZsV-8-$pb|p3x#_N61<5n?BG8ho47~Q?${^3^9R&J>Xm^g{*+B4^hH}E> zW9NK_RO!$C2+g$;!M{BB{5e`ha7{lpq+mtvv-k&5uLcqQO*}(FK6h5*c~DV>=$8=A z9K{GHUfB<4UQ+mivl^+|@S-Y2qe5lIk!Qk==R9go{~(`=K)Z}^&?*9QP{641Y@i?* z&3|*Reh5A*q8cJ&m-6pJj0{B6-iE;|EL?ZJR6`_!^AFJ~g0hv@qFi@*j&kzDk7yOa zvstL_3dlP-9*%Y#O<8w&h0Jx=fV?x25BpHoT@k9g3J0Q91l3(Wo8Y=D=t@DkU@aM9 zq7p*5S>T>caNRYaMw#dnqTO>GuDc2cqE!UUwd{wi?d&xwq26^fP1apL^WwV8sw9HP z0)0X>eZMw%KFD=f;Xt&C;Q5cogQ_TxhaRe;?76E@RmJmPsETszN(A>4qE!T69bDKa zml%KXs#4)Fb}=gDl?lEADMD8!%(khzToqv}j7s-9g9u%Lbk`+>kP3M%LI`=xW8_}_ zU=DfzgE{z4bs7ko2kEpxu3q^7cNBAuUwL<}$;Tt|X9(~yBl!6e{>LYVte&ZdP51j> zY=!7x+u(nFB46hQdg*l?Oh!!JmQ`IsP@Wh+FdjX+h1RuSFa ziWB7??3cB->zvj4!G+g7&W>`thm_+J9|w1oW0xI2hF^PE?@?fXDz`$umppe7?fTBs zM|Fvjb`kv&B1l2K+mTf5B2~>8ts2Y<|c+&$F=m9C=Lp zcxBBRNF>DVAj0n;3gn*WU+c62bkOO|lR8*=5)+uiMIeX5t&L7Hy(!s8S)R`)D5_8i z#+arxo>akjYtTUJ-=D{cVZXnsXYA2R`hl%5#^@_!k5assy!EW|y`(DFb3~veP5bzZ zI>sw+6t_M;J5k|4yBL-9ZH`M*jS9=21(KGI6Vo@w>91D0>F3_XRv2TN_C`cCqjkTm zR)_3#Z6EwV1X`jyac#O9y&lyHd`#c`#b3}aMkVbwlr-OX@KHVe=j3tXO1`)BV&`hr zWmVV;qf*mK{oC6(xV>56;35ojqC=< zMrBG=RADPbs~ngU$cJbLA?u>gX~lVfcAdYoTH5FA)hFI*p26PQpCpN=#U@JaRX<&0 zqPK`vIJ8+QLnK1CH<^fj3E|_K%UDEUD@Ro@Yjvs$d#E}PK=H$A#oDn)=xcIR5BpMG z+;=aBQcD~J+f@;)Ciss}kP_1wK|;94gfN{tM%NG??YCG}$@`MSbm}g)LiBU{d_^m9)LJ4YJvwJ1+EMi~0#zYeMQk7NB#`{UE8cpy zlf=ei6D3C(ie2o{H~Y>r4|NL8U8*1GAtKO{rj?#N-)gan4lgVH0-W|M;J z6{_u3-n9BGZxC2}TIE0l)nnI^rY#*^&YILGoAq#T0#|DH7qmODQv=fst)l3fcVY!= zGRC9@_>hjjC<|m=G7LDNQXlrW50@jH!D zdMa^+e27+}-RJzm92iT^--D`(?iY5US$&P2mrE;toPVvO`A6r6o-tiipJ)Wz-LTGI z?=Q|w`lznR+0ooL{-K9CP&=YEZC#Zy)*G89ikvN9*Ad|;c@eE?BR&{s4;{L|_-*_t z&z9MJ&7vdbdDcFeX`)^11=_K9eHXiKHo70zZJU9J_(=`Siz~C}FQWNet+Ji*w|b)4 zu@*D}mXcCB9@1pdn@lpOrxNiWm;V85ToUsd&GrFi>UWQ3LZt)j-D_lB8; z_q0o9CD;nlnpS7OVXyZ^8XNYMSH>K39?_b%Hp@s`e^$U4^y4~(1A9S5RIZuB{`me0 zt6LUb$=X>vOPI-7bd&v1Rb5!y(ms5lh@EcEY;Rnkm3h9_13&wLtq@Jmm!#9}&O0hu z{?(P0zQQVjXib~0D=n_81x#17qfln)$rH)sY9O#pZ$dp*XZWUS2 zetZ1KH0IA$AzDTBD!Do8>poHTgN?P+^N%yVJzGMatA6x9_e<0>daF3+w*_N{d{^MZ zGW~{2RoLnWKnJT&w!TsJXF(44tO(D95Upw9-Pc)HPF1wauMJbi18c2{7-ZO1wu=Mo zgk3$2laI#vPc zh4Mr7JZFX*MurK!>8q#_E|%puBAp3e{Fx$dk04nOIopS>TfSE{PA`CE!x!;9DxzCOm0s5_B}tq@J$ z^Qu))Q>%U?eU~WKm#$^izmnHW^+R{654J+I zrZrEei`i7+;;F)+w|E|fXiZyjvblI=ZE?GOpRQa*b*GA=Pbwm@WiRmoRk-O?;ZPN# zRYcLfLR5OYukrr%(xPsT&U!Q7eb41qi_HO5JL-LDKHp38x$4JfAB+>51}`uUTsX~h zt?taV*b32_mRhuw*mPJJN9Q#ZG>7YaHo>b2>zlBBK8C7lGPw zY?PIyaz>A>aBMWKLya*;rOzhH^)7NC!Z~Jznl>rNPGimR&ECelhbvbm&@RS8+NuzN zS1DdXxT|nH2gKDft#_Zq+C8JbH{PExFObV@Wsbb}v*+Wm5j-C5$`aRFw37LxvVDif zgW1S)cZG}y=Q!wj)mzoOVc`?NV3;#%4CrnKIa!!hfeM|!2UWfCR-B!iu4iPMADg;5w!itLMS`CZXcyN(npWj-lD)4_W~-+Cc?=>P zyDy?OtwhllcFOtUcD4n7q?U|tWlk^lP;#JMTshH`{cptCIg$@p-e(0oh(JC>Yub#a zIqefCYuop;UNaDZc5#hDS8K`Z9^`$8FE6Bg+wz{j!Y=WvZeyR+}FWlwAp zW&aSrBL)%3r*eEwqt}r}@%8z?Cf{haa`((W!zBmW#q|U2&#=^IH7zmHK6+=Yfe7S7 zH0?97DU-n*2`!D38T-b09<>@EInXZ7?R15uWhSHNsU-W`f3z4xARnS-Ul~2AuVO#y z8jT3Fi>m?JW%GP-5k=!}=L<`robcTAxxMSIIB?#j{V=l~Fdinw+2fMR#vlUuRE~GX z)fP$Va@xP#xNaZ?J0ACIo~qH56M8E;kK!@MRybd2+IzX8M5m{i@H;>1U>VS)d5MVPMwBRa_7aNspvASE_pNm-;VoygFm4HLdU%;VXD1@NNA2@;Y^gNruu2(VDh#Sb{xj;ljYl zdQB}vpigQ0(RXKisbsFdL*Qtk2J(2)zuf~W$MsjrS!cdT5R)6Ev#QnUEmh^K)m3SQ zXtl4w=2kO@sP3NU59O#pZ2(kpP&{yeyS6-pdN#Egpa4@s&8vO< zH_2|JD(p8Ek!|Oz(bry?Brf-hu!euXwJiJbXy^#Vb5uyHjG9fYOeIzYI(A905rKR! zdG2#^ut}o}vUg*)#|D0URA1*_*qw>?L55z}w8=f!dX1xrV$_0)+`As9cd-?s)!s!8 zL}0&ZTK>jOjT|xW1@4bd;J$J>&?iJo4%d%#omxxnolbWQ94$Im9+%45K=Fyb&-tLN z@eSqR?a?v^b@qdE5Va#ZZ9k9?(VDihbQUr8;2I-KOmof;mjiuL5yay9@zLFxQhNlA zz=T~(2&;3T~nW5tPs1-a9NMlGIDcUOAUbUXD#1Ikgi!sU5#)b-_6wf7t(=t%`r-B!o(ap<(#w4{uEU$w_=D-{ z6fc=zld6ZDnp&(EpqUp-SvI+Kk8!B2? zt~NEYWuGrOx_EOdPY&QS0rYhhEy3Q=shhFl+l@LRP@$@-7<*b(zr1rBBJEGVx0Jmy8prJ86L zb4Am>pI6kLGpB^HFwg4>0{IY4*ZP*#vQkSP@$TA_pdipL<|aK;(*8|(o>sYJg5Y0R z71t|lg;j!fhq=~To~La|Ryh!XmgswsiFw8PU0(!}E3_9BOFDBD{?=5g57re;`+DdE zqk7xZ-cQp_P!MQWRiz#4AS!>I*J@cchoD%J9OkhfO|*-3jLvJ@loi8&4>O7#tFLe% z0xi)h68F(G$|E^1%m5hs^Ye*ZG*>Un35TZ5h(bmz%{hbpK)M%?(*@@!vs5t?; zPU)ZiNvu?bXyWiY*R|-mjFy?K-lvj8t%sHPN~()Mg@}HxiC2Bpi}D@>v#WNWtJSoT zzRGs^x_TnZs(mJ1r*!XTAObCE+83D)Sexi;<0VTp)DeLS5v`~aKNRdCuV&&kOFqWy zeiGpe;(VfDMWL78cTHY<{eRalgV!vdv-m`|37zzujRs2uUV%hzl>-sThiDbiVW7~5 zuDB$xa-w#;Qm7*C&F-XMoZm+xPzj=+d%PvUd*K)MI{)= zDhDEv5783A9Q3bGj2Im2*}u1=R7#BekBUG(M7!-JN8xn4cjar?U2>pZjIp5c zAkHTcfeI1ra?pW_K)V>zD&p_Cm;J_(VDDlpic0rRql@q{2O>}*qFn?X$Y?hkCSI0N zf_5nq9JS*@nc=a|PIYcM^5{aFTK%$*ZBdHzk&b-d8qCtvk50_PG$YuX)pclSYX&kPL_ z*vdI(OPba?DNZ!balrWMuL^!fj30H$!@r;stlEV5#w)H4Yhes8R9>ob5NH?Cn%3}H zE%8y#C=v7RdnrE@yy986-q4u??PArYvk7`Ln*VJ+{6P#NP$8me&2VbJQF~ULh|2m- zDk9J>R&7liKQ@z*2%=rAsI)iAzqM@oS4^!qT}K4+A)3y%Kg(c? zxpTZHg0bszpk0a>cb3pJ$`70JgRf5boL_i6oa0b_xb;{@yG_w9GfGwU+^&OWOLSI5 zck~xvwCJI+TBWx z6;(#NP0?;QNO};%emJU73HP*Pi8kdrMR#~-#n~yRXL7W=zo1>Ls506uiguf$z3-p` zudbj<9g22$X25DEqurutw>jF81MQ+E8SMr|yUo##zo1>Lk22Z?MY|n}c8}vBw!-Qv zqurorw~tY@BL^Z#t!qg}yEyaX0V`85+TALOcCn($Xcrvu21PsCLIjPIYe~}%^ncU7 zQ(%bkUCD>m?W1kYSI2huOlsIi$u5i-xiI}Kl|b2zf>hiRe)8I68&dQR6g2|tjl#HkTT4B z=EMGWd~#cT^}-$!fl5?AhBm7xeDh};qi#hh9EesCbxYMV){00m{*5p(XytiNyV)^% z(DUa?u%glv*n2fm^7VA0_+7yvBnR3hgj@6J zt*uIiafDhI{7yxnLPTp?p&IFJ`d4K7K3v2^eCJ=>)Ahr(OP;&+n64*|HmnJ2D5i== zC$hj$Hqm_fse=B^#c)T$wf#G(r)%VL)VeWbF_=2 z=^`WtY4_XJgMEbvw4@@C9T8~BMflhc8a1;^*;uIxm0(465p>|=%HaBe2(+Xk@E5d8 zQR!B2LUg@urKAiCoTYljQSHp#JrXBAy(r8Yq`ji}NlM)a6u_k991%Z}m&2UN>AVt-lUfKiGYxsve_S1W*aywWj?=$&b$o z(S!Uz1p0(%`toA?VfFz+ENHz(ud`>4nvyC+ARnS>Z}kFsr62Ea&_&AY-6V%U z>n#)QV&v04^rUJZ`$4J@fqaOjFE|hf_wFL%z??v|%5l7Nb)&OChX^m&UWr|d5*&Ye z_IzzltHo;_#NmE9?N(irQ{L|zp;tW~8^BgLnwqxdt99N7tA~mac@9|X$6fH0x=~AC z`gOMeMmVDBnTai>jYAjOiEM>(*@(ba$gOFo=lHDtz z*0vo(#oa+4D4rt%Eos`=frqTG7Yr5u&B&~8=`dMx9B!01fOav)Xm61Whb+&Ap`!DY z40`+SK8aX1u)2akOZ4`DvD+H8e5iO*Q1t^j(2}M-+;G?Wa#=UAvHozQ_JP5YqtxW| z0aSufazqpfBi4;7KQR6kHVTGF&4>BbqK(`+!Ld23}JM7xyp?u<&S zj12<}lWNJWh65A?#jehNOfK@JiD-IyXKhZS3sr_a{c;M*sA#SX`=0JrS|OUQcx@?d zouxeg>y=yr^`c$0B4Ho;yFG6qjF69Zin}KswHp5G&ZOjM03_osUI*=yNc*L?vOVl)skP^#0aVkQq}J@ zzBCc7BB+)a|4=Qd^kk3X2clI3&CY^nHJY83=Y1##WnVQ6+4RZH+^% zxIVhQKzr|OxN97wD!QuvaEof6R5k3lS80W4x%QDGm_QupE%K=xlLsanTzCIlkxk*i zo>md>7sxBKcHstHS?}TsKvmVG^%!FhRqEH8ud%4UNx1HOfi`6{@P<7+t|z_-ul(CN)zK zxZ=R|gLAeWd~z9c8(U$OkO&{2&GQkiGO!h*C4&AFMBw@gTOqfmy*j!=pa}V~W>Pa{ zj=~Cud+U2z&Izv8{1MMO@Z3KBM z?efYJ*K^3Ha-dyAtBBn78d+=dUrDK2KT&L(k<%RY-avhHOoaE`_FU%X@ZS2;suA9` z9kQ7*zxLCc^^Ne-TU%M0S}Edsof@SQ#do)InOm*?db%nq0xfCUraG@%<4?vWH%*@? zuJ6iY2D-)Sd-JIXv_#($y41pooUlE$`1J%au6cg5{n&nb>4)KpDzv0&Irg=+<_^zh zwqKPXI{s78yu7ua-uIY_Kuh$rVXIcwqPB0Rw*MwUWc}wAb6&5W`Xft4pe6d^`m%b~ z)zo@X1BNGx57TEg*E}4h4;iiYPqwF7%+75F=zjXUrmcKj->SMLTl70U62c4+*3;DdDJ2`LBZ#Ah zmS_Ys39HG1cWbYls``Q2KPjBWtXXfc{(chsu|A!!u8%%g`33EM}{N!}J=H z8S!VOX4bvT{<@d)sD7aKDf9B0^*Z_V?=mxD@h`2d+BZAKJf-K`r+k;+yq<58e&Tkx z7h5&H_lnuC@ihHYJDd=|Z*6W(*|~Q2pa%(}Z;m`>|4HNYPQ@Y=MC)aF&GFGA^%j!j zwT`WMQ6sL~B~v#~rPe)-NstI+vS-!-q(>5FfL5l4gUeXUofy`R!^n~Fe%h^8y4eTG>1 z2Oq9evsS#gHm8EQC3ckl=8Z5f+8x@ol9{ROB)#F+%n_M&pmnc*jpVum;zgtS<;CjmosaxnV_%Ar6SN0jo`fjR^?YdsB?Iriojk# zg><(4?GWp|KFyOquCDrl+HXy-WZo_{L0`L{{n&J^kF_tu)|7+Wy^}C-ps56(Z0Q?M?Nhi`BJMdB4v~Ie4qM`P$AA z`iNoSUbLI}bV2ieo;ZE-apo9sw2xJ~!J3qxzlaxAzAR|G* zTGlA~&i#0W1JNp?)R{Kco;T{IWc@Tj6t7djEMIDj{`1XnFDj|sA-}ogpJDoz2dwH$ z(=OJS?eC{HZ<-)l{`87D^1w*_DODNt3DNX6$DDRnHvi!0YKv74M5~B-zqGW5_exA| zb}B(!{WhPutMYig^`GHhRDzX=-r8E!+M07Zy6)Siia?(bP2V0!Y-ByCaXqG@k*HKr z+a{7u;7Ds&%&F_ijv?+F3(J}lQ@-k? zav%aNY1*)lx>*O_c$~7E_KwD1&~6i>q}k!WzWU%dnPba}#`XtxIeLCx^EuJiXr3C0 z7-RGew?4z|8SkcAzud29?wVE3>^60RJ~uwxi#hLD;!LAA6rK*V^K3EYTUCg_R?abV zYud7*x2(@E#M&j+mHn-=zSwi-eV{8AmaIbUBYZRPCHO-t=z>4gcBoSx}5zaANqWgmnrr7_^nygnk zLHno8E@yszB0--)X`* zX87~jnJWNB4DwMy|Esf=b<~NJB`s7{nDZ*)!MV0p=_c1x7Ozean6()B$VcZ{eFO17UR|kEk5~FN1?wdoJcRt5}D1(S=4%5<6!9=0Du#ZGCH@ zNbmi>?)!&SnyI&}8R_lY?GOKo2D9|9az;|@9vfcMO6s>LI$xbhVny-4{Ou;r(3d}p zP+GM}_soB`(`>!k_gop0N>#Ux{FE={qqZss+C@ure*UzUHNtx~I_9rLF}DAI{tokI z>Wj`qc+qaVKIzT8y=Utyb}`2nW`yG}>L&=SpR?dn;}3s#Ii^n&MzKuh$*Z@_E))~rZs$@kR0!d9ner#HWAH(uYpgH^4H ztYvi_T|CvBZj$IR;vav_w()wFpCi23>g<%q{>Sr%=znV*?K2+LvR0QW7qg8b@wdep z&11`_=^w685on2?1Gu7FcYb}6vUx?KC{sSOS*6r;J?AVHftEC_b67KL&ug{)HRxIf zjufgwOLX<)`)byM-AAKqc2NC5?M0S6@@M~hsD8CL`;qcb6)WP<_Lyy>RRp#gz2%<2 zZ|pEVrZywmJ;`egTK`|&?}jFci>;6N_jZ_}&%7Dwjk|EjUm)YVdcM1n-hBm6`AgKF ztzWkpG337-R-Q{clRsRRB!209(4TAAT)o^MDgrIhw^HsGv~FDXr{-^}a-iL=tuFZ+ zO?g}YW+8K&&7aMBWBu=`1-?iUosRnbSFIU(k8-uVXm>@k6#vdj)Ah5}Y7ycFA*PJ} zJvBcevbVPUnL5wZZxvP%Xo<$-Vm9mg+tI0mwBe?mE=pd-MYR<2+Gbw0p1kApg(X=IW;kM3Eok zBEAoFXiz}!8#h@|g$T4n>-LO211mm=_ViyfMd3iZJ#(x}jg6hJPg%koVLN*S&Mckn z>GA>sTiso}G&Q=`Lj9d(jG!?$QZEL_oV@iwlz5ydp;+)Zv7l*fpX4=Gh2o0F+2h0y z#g&UdOR{&3wxQm|U(hb~uE!ZC+Pf{{d+*lz1@zw3SJXcqXUwtHimpRFy+XZCE6a=7 zjMUJWBL^bTlBN}_)5rVu)T(;J52lEOyuCd8@6FZ2N=JFoF7;K+^S-)M;)FMRd>Ql7 zr>ZJMpe6cJY`w1D$=|-^$-iFZK)WKrzEyx$~&!mCa$^ zCL4N~m+vp~)Xh`FJJ{@JUhmS$v7N1_pVT*6An~{Mp4U`PYvrtP1&5j$Gv) zSOqq$2sC-Sj~I5bwORGVBtIh%ts=+|L4E{6e(0aqZ6Oh)L|=BRo1e84Lf=w#b4<_= zQYA=LAf!s~GW(0@kSZ6gB1n}%s=Ogp`sn)OWnYmh7p)>bNquNM-CD=uzM}rod8^d{GkzaeRA#<@&A1a2iir2D&orDCG_S^UNJ+x z>-s^x?)v8E@fdtZy5Qu<)^xmY3qI7b1n_Wr}K}3oO(mR55M5X$@ zJ9oD{L&@)FvU2l(pLb^GnVH?&qBZX%vKsSm6T7W%{U*1X!SSjR#)!wzTYXj@c@w(>3Pc3X(h6fHGFj!`-495tj$SpETk62 zQb^Nv;ZZjnzw|54hm>q7)!dBa*F)N;ApSTx)*MTrHl4*;7^i<#cE6fhsgGH6&A-oS z-)LvPDk|zBXZ2FWDft{rAx+<4*$3(sPi|E&Mf}gKhsVDMQ4eW)R#?*unb)Tl;#UW> z6=x3owMAMcd|5fo-cEZ;YgnwTXk9Eteasq_Ue>}SuuYJ_NHT$=8rBv^RErQOf z737*1SvFly-g{PG==F!CVeSt)) zzv9LSZ*RBaA}tftcU9`Uy07mtf6b|Nt??1{=&XT#pjztWR{gTKC))kFo1>kdmWiTG zFE}nwEo9uFo`{*4BZHroiS6~usU54&wY|8M$oEHHwpXY#mK_=t<|x$tihW{gBAe4c z%+WaXyq#@GVvC&Sx_w8%K=tX#E^aj-iD%z&#UAuz82hEKTxwy?Q})UylUd${CQ+eb zSvBxb3)k{niF|JSWqX@E@vIVQU|fu(C_BF?t44J%lQHTKIV&VE61@fdw-Ty*zE=N6 zg(P0T>F;*8eKcFPB+P-C?8$l3p3!|Q+p^NkYSZ7P)pO-4x>6n|O7%bjBhe9L-b(6( zFUz>HX^DLN-mCUOb4IZNJ;EHA`-$c^?NM8XvKLKEjZsx9sM9Cjsz2Ztx#mbd`r4!}Bgo#L_VRHu7_yLh`qer??Yd#N=eSv(z$ zVkXa&r}ppm4`ng8&ExZ`(I2XJiig{t#mn_T0wd8ANek9d=bg&yKK)K2ujqbZ|82@B z*8gOv1LLk)l8tSzMBl6HrbeOtwbY{7_D#Wra3rr0<@uLpwYY(sfcY>4^5*SHQekjJ(MJY#IC!7hq-L2fL zeDF9nHYU`8aWhutWsOTDu)*C;jjs=ctLvUrbmc!NXN5%Fayi)E0|~6+3X|Bfkf~=K zRc!~C${JV-X*v>K-&jrkF2MD~p1@zM&(Hd{rS}%oc^}MVd%(Lacc*b|Uzn+J|6wDw z_oD{k9or`Gdv)_NPucNoJAIph1V*Bj{`3Ya`~BmLBXrdZ64(kzn`^jF)FJIwhSP8+ zWrdlP&v=)uTb0I|i0^UQ7i^>+eEQtht7`&J&z+ZDJC?@o^$T@iCdG#73lTO5oXpa+&%94YPw8dhDej6ehgDX+o=&su0+19^9%dc&FO5ysZa;Tt?zzfFZ+BF zQ|_7?$|v>J^o{e}JI^La1ZIddodZazsjez=$(Gn6k>5}I*M95TMAq(Ur~~8H>HWZ7 z`t0ZIpVH=7@<-bc_1VISt_Kxl0y9LK-e!Kes`}-GO17$#68W}l_w5B1jc5HThdD5A z-L*IEN0v-v{KzCrn`h{)Ks&+jj-jWv(8u# z)IgfP$GKWbog5StUV2L+-`M23-Mx7nTl-m<12YM}d(9qOA&m`-GP4@eEJ)4!$8Ohq zG>U#y`GNg@u|)PsS((5{bat?9Rdwlxk}lhHxgMy2krZX}wi@dGS=YiVc1+~az3 z@3B3$M+%GoC)9y)>(6{{4;VL={d>;TC|$j#djHs$wvyDkNMMFY(>LE?fviPl@S}diR`{<3XkQ=is2{%x}-VoTGt zA73>w9*36a^Jh-fu7CWm{r*WhLmwUHz+QIU@ccrXOF}kk)Eb~B%JrSsZ1V*B}2U1q)F+)Zg=D~qK*0o+? z4*#~zjosw9I4Rk9{&#ZbT?82gX7IBhez`{77E#^a^q9hd)+*a;JaWTtDD^MeoO{)reQ7cO05+ zg|U$EZ<~?m8{U;Ed`gul$D^<=?k6;J=B1f)Be@pi;(VnjX=_vX;_V$AUswM=VhXJQ za+ev;#vPIgj6_e^I5d*S*uT;%bUEopb=1H}G}qo~%AYSQ%kO-6CIVw&COE^<^*&z* zsJmu*zoYkmGXK9&hkskl)G(t`13hlatIsMcJct@d__xhS^qtquzx6x8J^4ouw`rNm z3wy3_(^+;}(c?Ubo~Jus%H~lE#U=3xhr%65U|ggXrB}`udYyXRc~Y)b3`Yi}WsUMV zYO3{rPs!NV_T@-z`T%M4JiXPbd<`{U{TZ&*E{Xh2jxuSPnEq)swdna`;c>$fIr;(R%-fq&UN2AYqn|h=2XBn*xIV+@PV(o-rRe#bq{CYLHbuo8rX}V4(HcUO1{*&v6 zyfT5UfHWODmujG9g};|EC|0gHdIDR4?&mz&M12-hB;v=S3H)@)LTm>eTW$#mb)=pz z%qo?mWAaBKj?pFZvj@FKu&5Sh-;KZ6Mh!|Y=FUx5C!GAJI9oM;ESs?@L?SQ}T`zjH zjhgYauKQOa@>eOw2A_4ZumduIkrZXkBc^Uk`z~V4!UVo=cP^G3+Lz597b;~kq-75F z`;va_zolkYNhi44G-{7+Ssbli>*r-d_w{Bg=x73S$4K;!DhIvwv`nBoIZ&=S5*SHQ zu5{?A*82LHEoX1J9+-RKlO@IN`!H(N6-4+xQ8_%|50obN-mfI%Js|byFwlo`hc` z0_TtB4SR8|_q-_9ORen~*!N>?ZLf~(i(|DMcLN)1pMTMwt-5J`6BipeNl)LH5D~XV zCa_e$V~wu$W>?7Ll zODhoAiXDzJvl<*SMxVL7iS1;|c%HLtm{ws&SJvuXnZQVj@@z!1UbJTw*UW$Anxh6r zqUU8K#Oevrr^8+I<*YE11!*<3A$?l26{F3p4)q*~$+!`{DmFb)`&TBt;olE>?d(bWuddrE)z`10&JVM5i>p;G$->?JeT?!5I!M z_Cz0cs#|Rb_KYKCRBhbg!K`Nov$t=npQewAYw9Z7R_<3wU?jSmeELK^qr-`e4-{Dg z?ro<=OIcy5NF3c<=-=j(XGbO%u-xtL>2q*7^rIE=Hm&Yc@F5 zsT=88mOsi_VI~+!Q5LKoq_#b9*ZsWw7%3~vr2VkUta8z4cJIEKRbbzN>ZH%OCo4=Q zu+)^X71>`+`mz&rzY$$ez3!f)(cb~aCo|d`>w-(N_RThHzkj=*{W@-g?N*;XTGcNP zu*&Vfwf#_VxA=EOdD1sf@AhRo<7C?a z_b}S1wQZ;Fag<HHBdNUf_pnWT09ae~mm zxYR4P#qpbb8l19fL0N?mfw7RlNOV4N-M!4le+Tf7$Wi1XSKXPrna@S8g6b|2SJohZ z=;ROX^M{t+eWS<d~C)QRkI>3Q4!sE4%hAU8)Kp9k5~d^2o54_a}l=d%I@3u#^rjrtUMP`&B(heeRLEj>9a@*pP< zicyq$JNu(L-CgYUpcR*TKC3%C-KRkw6j_;LA`;|nOHa;>VOd737qY@D~e~?oxTGq(Br>%O{J<4zuX)F;qGvGK+ z*K)3Fp^n)(%vdsJmO6a&a{Hb&nzla4%}`G!A}(EV4C|LH&T{%cF$tvo|8BNA%^wGB z`lmY+1c9@Gzm!S)x4p#W-EH+LINt zom-FP8#YC%$8LY=Mh&E8q79vSoW0+sN8Q|FpZV8j_Va`Snwb@5f_|jq!Cw>jr5E+} zkgV@KNT43lbgZ_eB|q9Jr%@w)mfCp53byEITcIJv1qUlidv8kh<8d|zSl zM zfxQn2jARi`bDuZfvzk32o*tU1fpO6*7C{?M0}0ea+9HI;g}Hgzv1jvy2F68iT7=L*0`-u7 zJArY@QR0}>>%pLlvolwf=wjR`k)6|AWF6O%Cp@dxW{M1D!l&XiYfdh*ojbMWwNgmS zSs{USk~L`N)XQ8QWn7;Y?7^(aQCf7lEkf^&8X~KuyN-Bl{g%E~3TZhjBrro+gXUTz z_1j2eCC#-or&>qbl|q{CD{7G6Solk%@zbGccC0z- zy-|ZIm(EEnRZ60>V=JYKTn9DS=c(FC*Nt;Yn2ok%2}Dgz5h9lmiuRDTb&hN zD}^+D<4$wnHPSFwGMGE+y{17D=8vp_b$TP=Gzl7)v>ulNm~Zs4>Omu%wx{4Jm$$dm zy2SW)Q>31L^Gi2of~Dkoh=jy18n0HY&}!6f^O^=~dy9H0r_pH7YHjhb$L?3N!bp~a z)2s&)*wS)VwDvJ*?V|?K+K1LS*7*|51nVSLeFm-i^i{O#!}Ep zo`=>r*7*|59rfrAHzUEIHJs|8H5|r8`V}I)sS!M}91o|p53N|N^CdKL(vxB)h?Yh@ ztF36mXO|Fn?qX+&3~oD>8#t zWW4Kd#oZW}MrW;cw~eA6a#r5>UX8qtIBh`r?yr?XT9kKsDW`!1wt}n?+-H$at3Fge$VwG`td2b6kaCDWvIbP~`CpI%@f&{w`?`q8`$6Jx~MdBok%n>YYPJgLrh$ zxa~9=upP7_8{TLI!?h2tAL#g_++B6nz+T+3Y_(&|vwSS@_ql?=)fv)sA7q^zd|h}K zUbSNGdPra?)TXP|6Jz<2Yjf07^BOpMX3b`oCcGy!FcVx8(RtDSHF%rlp?p!!vFgV5 zPS(=aUJw`;X}Wv4cO=ifFF*h4;BE~ykd}$dBa?X6=QlHRonGtcJZug7Gj)Z{Y%9zJ z*C_N%;gyM=(8P}NT43lbf)NH7rs42F=m`Q?FeW&k8N9)Uo$l@F0N7N%9_3L zd`oZ}{f~~1GLb+%q!nevU&Z+O=PityTv4;{>A-ppcM1)Ri|YqPd06#R?kHc%SX#TV zjs)r86G!#Tf;Tm?pHk_U^edcsWqv4_wj!Tin+0@&! z1%Y}1y?fJ2S_fO*RfykMN)d(lSx9++BUuz+OhA*HPNh z_49-VW`Z*{eZ!k~xgKzDq*1L(^-OYiPfOy8;-H7;6-|K1ZLoP`FlW^I>sO4~&cByrK;4U&H9SJk*$(L%3G+ zoarD4e_T@!Y2jLfTx;wzbYIcMF2>3bh1WhWT&p#CmY10t7#GK2x+`UGyszbT;a*V#e>!TksBE*J|w?DMAC|;+RiQBdPkSL9XSyysotfa;>F@w4!|1 zr<+c$buq%3*lOWT+44Q6t2~N3!E(oa;>F@v~aCXuH~60gljDg za;-(nM9E`;YMV-QhmhB`_T$i%5ZA#A^`zaTI!(lT*8vL}1; zU$`KUemj9#A^mou@A4U}`JLHfcE;RszLK*-0`-u#2&dV)eVV7SHuMxD)8`l$=PQe# z4X4p!>NFM`IZ_a)hqO$f2GVaNL{^73+t}BQdTC}>m@9NLz%{Y%A2jxHyZ-L=D?u&*(hUMOIjfdZjhbTLf)54J1$xX_>%T2IJzK zC==92tvLe;j3fvr{igq%26;lOe>Pgw0||^I6NlzJ@XSA+_8Nha1mXMTG?2hnKs}kj ze6hATQ(IZlhSMMyX~myp7g=HMIKx?l(s9?}+JLgvVz#k}{x?i(4bxHu;Yg5sM$Vr0-fKMoQE zX82lGP6524K_i1jzeacgBFJ}|eOV9Y8yT$G8RuP5*wR1(>-1VZEDdszC+^V~LIdOC zyen%UfqF>$!h1n;WUw?aF3!|4K|S1V)SD)e7f?iXbz)mi!Mh0vGEaI*+b8O z-D#Rhpy!cRlzDY?7}x82SNcd`DgU+^iLM=th%_n&1sFxTr$qFf(NjC!H9}}$Cg>GK zIq^e?F|ba!@y)DwHxd{ZX}Yq1Y`ihE`)ED1oz32&daCwkN_L@vanUQZ3LhD1)IE~l z=zdpoBY}EI)3qPxl8yPbcRG&O3y%m~F+-cwbeGGlA;v{_(e=C2><7Iaxp4C=*) zbqiMObjYr?Sujp$U|jSHo&D$#U`#3<$^YpL6m#-GeTC&XUe#6B-zo{AjJ` zh0i(poR7GpnPZ8ifdu){iX?o_$>*6qpR+xuzOb1!#JIS=7Cz_Xb9F2E9AhCtezYP9 zpL6oL{(;x$Y{lHaJf;T5B}ZAu48rG}e6EinpJOZ}$d6VeMLBo78NXMsw9$UL@Hu18 zdupZz#wABtM*za-Ja%uOk^l3;9*l(q`O%6be6Etu4WG|h?m?+S1LKmTtRn!r>$gJy zpIkc9$f+!FV=N@dk5(k%b4ETld_K4TdT6T9z_{cnYdtS~u9DA*T_>yrN7>gVwjuS*bhB^3Ud2?lnS>Zg0^VQo4)I(YjPA}&)iiNh;n&!Xn?d>pA z<9uZiL^+Lp{qK58=V&AL2WI%jtOS7?NWVri4 zOBJU^e32nS%BGPXsFcYNT zPSD8724{K4MC{=-idq@USTx(@%fFM;>j)k z(Rs+FzRbUEj;J^WD@yPFBaJZ!|I4ha&C}P|T5CCO-Se0P&OS&hiv5!~qv)hG@k|aR zu#|t>j6}~QPa15T$d{$AJABQSvp}?#F=3S5`~)+>QCm?O>`yWl_spec4k_eD0^=f0 z?+wpc*I1gPE+4Tez&_*eR@%8KcZ3GU#ZjA{_7*kRXuds5{UCjn8wu1ynvQGpXX*Wu z2J>#QS8dyK-1XQJS~0U87#BxvdVkcOI!5tN>he6FEpa1(dPvhX!Z&m3)qYOmg+JRC z{^2icwBx)r_fl%B^aJSvT~@72m#m)H5r zzT@JsyY@f3cv}}sp$in{bdD_bO!8p9sCHWy5||;LE?*_WmO|Im%JT>nKYD<5EAiMn3w6m-Yqi6X7WT zCuYC$Z~I(pjeNp`oIGgy-03f65}2X?-%VP0ke|$#rGM@9ARAFMQTQCkL>w!H2RV6A z_j%AF{BeB_hOEegoIGgwJjmQf?+Xo#i?f9AAaAifOAqpT&?3l#mLAf=gDQE@@OjX_ zwrm^C=Rs>u#Mw@Gkdp@up9d|1JZS03S&;`-@}S}KV7)&}4i_47+?T5l;X#!=X!ty6 z5#&KjPp0E&f0GA|wIzfHJ%9WYEi`alf-4T;LAvuk$?$p5BFKZ59@6wIJ=))ksjZ&e z5gxP%j7$Eoj(vm&4f3Gj^Pnf{zt$ovEJeNDI=&Jf)X9T}&x0009<=n379KRngL=Hz zgVv0LadGw$9yG{F8{EtVz<(vS5lRq4kHGDl&V|>Haa!|w7_L`|ZjowAtB(l>P z{O|MX_S^ex-B&zz*(>Y?lK>4P4u2#jk4XrM+@|yHoS}0rE6&o9a~%I=elIxZX5_2r ze0#mC{N81|*a~SnA9VfES=85{Pp}5+AuR-5v68M_J4B=1Cs@PptK@omB-*p0BhktE z#IoReu95lE;5s+GN=s4SC_m8Vkyv-!B0V#(U2KK45Ecdzkv55JUsShqlFoEG=RV;_%i}7!hlYj`2hyenp9^m;(Q){52}X-C330D= z4(ERPf${>461L^fiAZovzNP5-SVq_3AetF`TkJa$Xi3l1wl`B7aUg+~qQnv!TRckq zRy+^-t@zwvPYaPXa?f7aYq!huZke+yld2TUt7mE?(2@|vc3iSE{B_^uxg8@!0xby< z*JQO_j{X*Zqo-PTVp&qlezy|XEA+%aH|(Jh&01cyNAKTky*Q?a>h<%=q=&ji*AMgr zX(8OtPuRuYm}{?Z-pSBF+9cj;QO$mIb}6UGUB@8M6aPw!dbLSqk}I3vwU?aitTvpV zlr(DYUpfwK+q8e#$43x+7=Wts0XlfAXA<{y$Eq_v$oc4~LyGtiybw)i?gH|c;Pgo7xb||TQ z-FkYI;Q7Fw_FMD+O#(*-(k5ZouNPUf{E+Tlw2S?gI)NS{ojQSbvENLh{f>H}KZ``Y z!dBRCCQ)X`qD`xoq$JQ%K!mxk&@R%SPyaK?w-gX`5LRdlJ;BT=bpl)YSq5L5`Wlq8 z_iuLj8uT*@9&tBj#wR^mAv#N#!~+%6D{O_d5c2aAvhW*oC116u(e~{oN$Cz1)MLyf zQq#azNDEQ)qo#69#{XoPu0g)m&UP-S^Tcx2{6;S z%_V%Tjefa+)<8X^g{atMwdB90Ximh)kv548HwN0f^5;-p={n~*%GY=`+j~jv+-P5! zUSS+~O<*geg;=jL*>5(#D?g+e4t+;GqyvR8kHocIk0i{y`Izoe9F;K%Ld}^0X_IJP z{-j-I+B@frL1oO?Qe4$htZOa|@Z2o)j&?F}gZQJniAfgU3L;B4?YfA3J2q#;L}MtGLF z9M?5r;UCfCLh~MftYFo)`rn24b!P@UwD%Rotp7=kwWBTnI5{mui!mAH`t7f%MNiL9 z+On~865C}0^^n#Y($_!&TlvRqDfKuqzkWDj_`G^4ViMxLY+LQfxEIve-{&OlY1=J< zBWGI}Inp`~o8u_>^!x-Q&=aIhulUNLyd;VH=gs%)g`VtvSRb1jGc(n3zPnjlUGF<8 z!q?re?dxf;uocp#hS8%-4kt0qdPoOEn9n({YBblTXjKU4fS`l0;<=CVMD07q6jMVJ zyaG_3s5OvIo$%HrO(2~*!K)=@$eKVpb%Ix9nw>R)bm|2571Abg<@{EAT+j{_pi1b%`VXel7*Agq4B(`wVp?dNIVF(#xIBdxaj#n) zXWK`$Ro^NFLU;yo#F)f`-in@&p%2eV;A{I{mA0WtiDfqMv3btR?SI9Y_hJTlZd<2K z-0G`goj33(!B$8=Q1H*WKN2}6Uk_;^o?IH|^c(+_tW~*!gBloA zFEPD(f;9S$f6A_1xq@O_e?Hqef#bkdNIy{EICx}i%(z=?@VN5zkTwY(8S!`4X#(lg z2_6|)e^{&ur2iiTjf^u(=4t}z)CoKXJg$7&B)oHO_utkjK6zjH=iel}k?8cUQXs-3 zj(2z5yV#?c0h)b?LG0sQ_5wG{PJ~lzCt=CL1KY31ZryuR`o#8yZL8eu;Uf3@V8d_AO10?#uOK5Y{A z(m2(h*1-f?Ytbw01(P5Z@`(RL$5pfK(cFg#&KWs!GY%`NA>(PSWm}woa^%8NoQ zU=1EiKO{vnG9HP(9?}89kRFNe&5UM!NT*KlSQ^tUnpyHl^y$oe~qr3;?-o;i(v+W0Gkn19JzgBB_ z6x5n~eGilb=7iSWw8 z)d)W4c%FIn@hdMJg8mauKCW>8iFB|Ia@8P&8t9=(Q1ydXXLa}doCIEx{hAEYrdQeN zepHz5M?FRNqr5vx5w1GpSi%t#y;nqaYJIQBtG#Ig&nD7Bcz65w?yFxw85u z-7AuOuLue51z!(oAs(Yz__r zt8xt7&F~5I1S>j1@DnK;y(dz<=L_^X$5vR;37)KxeD@UzuAcgONJsC)mGJJwc{Nt8 zfp)P5Bt$uSvL?r0_pOI$Tp@vaNYgb=_XoeH`-5F*TzOSlt$}v&n%A{($@Orqg(HD_ zNDEPl?sJZ%`0`-s<;v2fdn~(1BensO7uXD7E z*Sruf(H-6lbceS(jVrIlt~I>+w?0Oi?$Og-YW`cA#uaKHZ4!50eA<32`&hkW@mGLc zMZnfLZm>5?8!f1MOn2CB%wyxtzBW z+Bm0<7TJUZ>LE>WWE$jLeQvWXm$);YZE+orHP9|*XHnvh=Qi8L6L)Sx0`-shF8c#c?lk&5||HF88#b z!wYeQ&S0f|ZPY_+5)zR>J*0V*M8^~#`LFiMyhZ&Vh#V8$1c|Wf{_@EUEdZG{xMq;qS4T&r8nBczAgU5 zKV}WAGe&)iE1npw2SBNR|8cUuTnr0Z7h_;YG zOG5n8_62o&=T=#F-u!s3>GJqt4YZ5ZVaiL&w2SrRfRGnA?%ag7kU&d;SI)*`MdH~LzMfeF?XtIi1v-e_j+-}s6WT%o zEd{;n2E5Wy-PZ&zwy7cG;4DFD&pX%tyXm-z%T+Y5sSry(SyGT>aor&@T6gfA=it z-C*qcULnE#=35HRU@&%hg=7u1%V*ZV-xiFLVC?#~kl^$0TN2`T8oQ@x?B?^vE?0_J z1MM>5-=Rx6c70n&@Ud@+p2npsY6fL8|L%^CU9Lc}2HNGw{d;;rLV{!R zEeY{jbY^fmH;9g1t}|#2u*+xAuQ>>DiOygl%KHB5A04~CE%b!Xjc-Ya+b=#X{p=M# zLA(AjYx8LG|Af^)C*Mr!Q|sMmoxyv0gKG|a7r=kc!Eep~HwmlI)Qpf2Sk|9$Eqm}LTMfzp*7Gh-kS;tIxq?J z5b1!>8dGv)3g!D^n$|$Oc;6@>v<4FBA<_Y%HRwDi&`8u8XczAr1%%c>0`-tioj|*I z-zaqgTj5=xfCzK%(#S}n(XQjbR$Nu{?>Yqp9hd~hgmmfz+U0tpe-9}j!mL4KDMF)N zdxfpIPVLvM1A-1r0%JnjBxo!}XtYOow4+_Dc$x%yg#=nM2^vcg8tqyG?PC2hbpq`o zZ4xw=A~f2y2HM4nXX*rch_p%ItcG@RMopbS50N&BzJ=b6%%1#~zN7eb*>@wCzMZP? zA*h^-Bh<1~bf(VUXS}1HJZqi(RD9@tA_`UOYGEs+g;>~qywhXCId{j2&57P82~40K z(n5F|F8hZBwnFV7jxdizwEO(rX^~uGGU;<;dgZ)7)Oox3D!WhHU5Or%#9m=5q=Pst ziX#pQ^aN?sD|ghi$hUuI3UM#uxH2`~+S|d|R6MiOcx1*+9uZ-$uocpQ1|67@qaM;i zTnrC&_8nVg59p939yKr~lQ__~mQ$dAEhqGGW*Z6g1jn)I6?%eKFw#OilrFPV>DLa< zsx)a5y;eGMw2R|dh`+Bla*q5|%(;=Ne;g9%A=32RYwwk|{q0caTEX(0yg5p1pk2Ju zsIoo%guSXnKj+BUw=5)34{0IlW|^|-&-)XcwmFw?@@8kPfp*DKkl|<|-Xr3XKs}_j zSCYLtI`%D>)OoGd8fce14DuBnx#Y-Se6)N#63O(yEAJeJd0f$%3i1-_-4KmqeMOlX zbUqZHkAE}uPo#e5EJJ&Rt&kQXce>2VJLhpopod5Y<4Su)V>Cq9w!Wfh?1pIW(({$6 zL8D#mrO`gHLzYb*p}oRZNCz5pU`CF5NDD#Nhw`ou>GhS?z?e*eu5;yG=ke$j(k9{g zr6Z?VCPcHdo~dc}3DIYIb~fXnc~{ZA%kve_yG-aA4qGAZDd_)&6-JACNDD!;sNz|) zU)x=AsDUw=1kLS=)(@A~k20RRzkUR9pq^e0nDAE|Zlwv-Gvn~QlHT0TBO}3^+k<|? z`1IV)eZ^}O&+P$$9-3ZxXHa=FHD41UZ>A1LC0;jr-c>a3N^jl`2-GvZ^2U|&=G}lm zyWSYnSAm{I`HE8BEXp&0_6l2hSC>b4SFQ49(SYzqUkW;yOO!W@@|>Ytp^dE3_fa}cU@O!P2s$tc)I-`N5+XArWm^~3aiH&BUq#s4)Cu$i>C_3d>y45a8reVC zmbAM`W$hKV@<#suATTDRO|J^>F1}&J!&S8g+V!sB7#c{Rhe(?m&;IjW!sX`CIM6QU z51I%^xv)Y4^^i_o1MPYqMFrN<^ufd9gt>{__R-b^N1CzjBK-wg>&@3%J-lkX1jm;{%UE{auwQnrVtlToX ze%$OZ!8uWUHm@XM|C5gvJ!$#J+zM$SEFxYXI@_%oE|utglE4J&Ax%#RMK!c464=T= zW=laFVU8T_o=#uRz0veZJ*$~sZ7)5>S-Y*HJ#<;gM2|>fTi6QeXdG`2oo&?)mx@CI zJwe*^%C2A3oso4`i2JAd@H}pj$0FJ*Q)A^%1DxLy57}3z)ZX;Oe`Vd;Tb_)tSJ(<^ zQ^O;)2I?Ul5OiSn71AbgtjHMWY{O3Wfw^DBp;y=oCgG`sS))(;JnrP_5$zRb8D<<) z#?*JtEidQP{AB(nkI<20E2PahFj~|@nw~=GImmhBlePBacXCOO&>9$%N$h>Ihg0*9 zf9!>A3&f*WNSnm)p;?_vZQDDak7>8b%lceCgXlYEHD(;>JLZf?3(=%SedoP{<(vuc zw2Ma#^w1=F4wz{_wdf_MTAMPPytzbsg`Qv@B*d4EvpS=Pw08y;DHD$b>LD$}KdWY2 zN$n>%FMU2K(VKC!2HM3uNQk{9X4)Tq_>wd4LIPYlI+#okJE1Q)+MchcFDsaC(@C-9QlaPC&eL= zOb@)G-c{VYFBB=W$y;Bw2HK^b4)PTt=nP6egEiWeiAMtUkPgO`z6NPD1lbae5{s_K z2+u^OM$;Dc6_2a%JMA`kg!T$sAx*o~p;?tT+T)Qx50N&#qASOuc~H*`bVXS-KWeW` z4Y~#uUxV}87TDww`l`iNNCz5ppm%pc$gzVc?Dc+|j{OyYq`Skc^P(JG_k zpt;22S(|&;^onL5RUkV1*r-F5!pt)Unb9s$To(5l0w4O^| z&ruyU&{8m8DQ|V=`PK4P=U|rb<}SU<&}%KviR$?5cANnOaiH(s45uvxGqv*8T3#pg zCurB3wLJ}QHBjRVmf`h0@CpfUZuc~3t>qO*d221NEcz3)>#aVX2CcQcs;SK%rRDWJ z@CpfUh4VCMt>u+dd220KSo9}o*IPwB4O(k?byj&=4UR)wNYHU$DaZhnx7Ko{NNb>7 z@;2D}1X+e^O=~UMLV{unECrd2^440ek!cOIOT8ZP>vQ@Ha<-&qv@8>kwveE66Ic?0 zR!+{yl(%w5xH7@x3hmP93G!e)5;;#)6IwZ z2=l5&p12f;_6iBKqzP)xf5Hm;1PQbhZ5#b>SfMTS#5*_I+tdkc<&Bsa#H$?(x{qc5 zPJe=}yixf-2=owX)2rLxW^vQ3zoc!UUGM60Q=W4q&_kq6jYSjZM~?0&qivyGZfY8nnr9ITO1*J;?0jSyg~wFLfZ6dSMG1WUevIzwuN@R zc|L~5h41zyjeoAT{si@qPF(}({~Ljxcq?2CuT=AW2}_@kdWEgLb@u@gj`|i>NMJ7@ zZN?F4JwMdqV04tAT`zx#p@9VIA#G|*di7H1jib?Vg?7C>=)n~g#DN6rA#G}Ou?kwM zcl4@7yIuwuLjwuaL)z3B{#6-k#F6>h7TU#GTN6PXNT43lCV}%g(kV1N*TTvkP}@C} z{Rh3W)E`*ey}Edxo}HJ|6~K+6bID2C8+5Fs_Xc7AlW(%TX8Fh53Tb*rBN3g)%(hmv z9<B!LOkLs|$=L$6jyU@QNaEqNi(QoySL+QnJa^y)?06 z=^zf5;;4rNdV;hNAN)K(ee~5KS?cPfL~kvMum;-2IXH-e4$L@kB}1AtXkWXsaVPoc z=yY+YfgYMf*T0*n-F*tG%!N88(pYkNw6j;}3C`L=v>P%+y-;PH+*G2yOJm99vC9PN zAx+PhOz)xkp8Q8mr^^ib4q$!RAv#eFL$I0~hvm41)U0w%S1MT9htqIp7 z>LG!8NNcZb_G;wuTN_C|fmcq}K)d8&u&(IHt>zSY+)rcbA(2ckSnc%raF)~gNc(fE zMC$htXELmTc5&7gV$ST2HlL3_KknetIS6r<;q`9dA=31oqRi`T9wjv!9IS^LNSg$W zM2AP>wA=F%X~cy%TVf6Lghpks66w+I@Mtf4cU~M4sE4$^1|9DjOr⪚#`z9&@QeF z^j-b!wVfB~8q7Jhy-U}f#hE1&sE4!=G?zHLXfDZAsAC*zAZ-#fmpFrIE?HlqJK}7Qm>q}8tCT38|RgQ)r!rTCnqC#a`aXC`z`fEq}krNArOTWk5O=?nnv z;+fTJE%z1Y47}C`1lmQ~>?_(Yag9C1=fFFI`qIDIv6VLxwYR1Q?c##Uop%kU=!NK2OBsOUWdJR9 z(xwJRi+V^0vyVMJeaATO+D@V2%?w@~JTp+1VQ-`?10zJcXvy@7c8Wng(VMR?`i^RoyqX};rw`O z9_Lp<9B9{D4YVcGE86h}by07PilITd53g#Dm;3N4tZktuNShiMIqD%DU7aaga@zjb ziZikxa%|<3Qh04{4LYR$gABy)rc@ zhqEY$bG#gmGZq~own93{mYgg{Z`H#-LBh+NV)PZ(cfE{Edu3`+*2g)V<7ItZ{m{0s z71BELa5Vm~!a6nTA)R_(A#D;~F6zu$^DJktL0@4jIu5)wHL&VT{l+=Gj@*pH%a9!} z7v(CBjvQMdtu?|?CH)*(P>Dx9q@#H|Wv|Y2l)a+A*ow|(pl!y1m2J9Kc)z3LFumga z2j#ntm+x}rPRD_*kT&B$-%$@~o$vCl$f^Fs!FqHZa2+m%23^5{w$7<}kK_DKIW|8}Q2MVuWZHEt!#Hg`U>-puTU$!F2}O8`$37Ac!1WA#FyE(V`yGLA}JLdI|3h z_}+w$9PLux6;#54Dvtg5l}WtE3A{oAE$MuhYfJW(G=uBmCuoJlNmAe%s7xhJ)}*qynU_KK)W0`+2QXu^A1Ab|;_QzvL-=;vXW zzzhjv3cR8NGjgO;CuoH0=XzKJvoq8)HP9~7F$o2JS3S&(uJ>NXH~}9N3EH^I)HedVz)}XwA^yL}IUKUBVq} zKx=|p>${c?tr_}zMNA-#dYbV56L!!mq+=4K6Lx5|)Zf}-4O)?dN(g$W%~Nas6L!!O zq*D;OITN(%>n99ZgEEVtqJw%-ZHoq~uu zMP5-Brk@dI4a)TRetil(Qv>ZHjUIaDy>m|4q<%)2HE?!Dy+9+(y^D5{j!6(2cCZ!B z!Kg=1>5UubtbS#t)#BtM^3;(k?)Cn8k|L`o2j6yL4>9)@V)6KKPTqYp-9xh;ktL5+ zakrn#ozR^KoFC13x8v^FUD92;d}QQB(m=bovk)RrouSTx64UMK|1_|XKs}^|c;t2&=g8h% zPLsFOsUGb!yOUl%rZvzm?kt3;F{-2U$&l~uH|KvL({w7}E=%*NCQuJ)A*%h`!Wl&G z@-9%dhK(9Xo5ba{7wld1+ciUER`t&P&5=CQbGsZldV+fqA?o$6=M*Vd$tge9lA_GT z$c)4HwO6Qzv=Hn16miz|ZRD&Uf7e0{q)p=6grW9|(oLPXt=ZMp%k?8gYn0Pop(nU| zq4z+(c*oB8O*d!ozZKk`p*fNEs)!~~4{0H;{kzWI`|=Q{PVIsgY9MVAuXUeol{zxs z5$D40>X~bkHm|I#HP92>AqnwJx)yfJ>|>lin@zKjKs}^|n0#}ld-|dA&If;f?@qoj zC;q$iRka4%rS(yN6N#@CdOt(qW>)#)rYoJ}+?+B6Z)_ylJ<2WbrmFDpEv7S-q*vU`@+1nMCz#Hn9*%At$5yYjI+0t%084 z4oQgTN)cAy;Fd#8m2>LD#eoeFi;>_bJ=g10`EBaY{=ChXm*HP9~2?Lp=& z#Pipxt06^a%4&Tos#jMRvf3S5qzOaM@aoU^I;cZ6)2bP}OWLS`H0lZQ>DXJcLdFKl z$#+s#zWGDwLMWTXk)tOxw+DL$A>LS3M(t~mRqgpEi^|mGR;Xf@>)I>SLz>>do3pGs zcq^p#t+#B{K-wg(&K)C{KhjnmnRQR@__I%_RsYi3EA#~SCG^ha?RVw1mm8@uFKm@{ zR;>vA@L@qspdQjf{I!3lT)4ZRn!d5FjT%UsMEX0k+=}JKtMM;?=e}@gR(zcdRka3s zg1aywHjWxEe{4Kd#jounTb8(;u-&Po3DiSci21GdyFXSPr*3|g!$u9HO(NT{S=L7v z#;c7vhPo|^eVH`!qsm$XJ;8kh3J ze1phWmC9)iv`gzpu+yjSB9Cuj%YtLn#fpQ zyEL~4wHnGx9{SY&qTwT|+SPc~y41IkJQH(kuTanQs{M!}&fJ7X>chc|Q(CS(SkkTe>`1MFo?!Khem`nQZ)e%o!?O97 zkc|ZDAuYrw=SDiOjcP9suP!C0cB|+%PLnINi)J6Ri@Ql$&wCDa4y2tf%N}rSBv21& zAwutsc6#PaD|?rXHwd)r@1uBsMf<3@`?B3rliVAvyE<)`Rn|M7Qzv%yucW=Yzi*<^%D2ScMiqPw zB>YyW7xgOR>Kn31-`sNIfUeG~$BMg)FAa%w?*6KU(c+$pei^9leL1t?BzJQgv#*fw zwb>F8KhKfp6JK&WE*@cMU@N4BIQZL1S?-ONveJt^3<5pDeVY((ZaFR+ubU&^>fG7M zGbfX~a`gcn2e!gp7`;_K@~YhNS6&%6YJ@>xFCZ;M$EViHE7LxZ>6iC32*WPy`Y5yf z?qm7TTZiP zOh^mybJ%s;e}7tL$=b&t&@S%6gs8IWY^2XSIn>J)+dBNl?=Rd++AC~@dn$Uv-?s^F zv0)2jr|ZKF0%Jm&a?vRvD@Wts+i#)LHe=8K!nUi#iL`Rj%k4Fc`ro=S+j!xr0lzWzt1 zeWR6=xN~(Vz5B5C3R~fxihh6aSV?=@?5(oqj{^(>V?vsKS#Ifidv2>e@`XVioQvnL zh3K!oqR=kxsf3vDODp@%fH!6R3ojZ3dWbY#QB#ua&J7pKgv>n+0`1~1Oo%`KNbAJs zTO!AdZ|YFg7TMNbVJqBI36U@RbbH`S9c1Y|FB$~KgtQPf53RAsmB}eb-x_2PXczZX zLM(ahA!keHEVAeK%^eyc7WJz33R~e0Nr;wTB-%X=6_o9VKW`8i6VgI#c||xm1{ZUe z)#&QbwZXpxy@BTvw2S*4Au?_M)V}j?9XAb)D7K|KA(dr)j^k{ncyN&M|&PSieWuuU|&1wf-vQ)v5LOnz16x$KFbwiHR(SJ=BXuS9c(rj>F3h zwI`-msL`x_33tT$7gMxCn)c_-x;ce1hwY*Df0F1s>iyp|(07vvKi%BvlK!+k;LujP zNxnzi9sO77IJ`VsduV!Ag(u*DVif-?0_aLTsDr+7nl;wp;D!>ePNMi#vMM zVXc9BNYhVeE~)Qa{rA58T$W=JeMj0PQu7MWze!vldf9F@Io|1COgL{nydd&*$HFdO zAKo5NM{dS}8fS-ZjfBSLNYM&uAx__HX+OK}OM86&fli&J+aeur<#ym9}9gHxqrGK4PlG{z2L#Qu7MW zjY;r3&#uzb>RC3QO{99|W3)DDue|z&j>(K8H4SWqG~FxuYk@WCr&pYR{yXAgw5W$P zy`P%iS+j}Wl6I?QiFj<~Rc^FbrUrV&x#9VSl~c4r`ayeMIg!A#X==PZA-^nm^S)hW zLMNw6&)T5|rONBR@~T`~FNH=psuZSozO)K8$`~Cb*a~U-W?0WfZe=^Kvte=zg^{Bk z(qMLP4#8F{MtRS4f-0 zu?$yan{$nh!>h4t4^6Kyjt@S1#0q`8 zEJZ7%={Ka?6;fy0Ub1&wDXq|V)Jt8X!H}%h<>Gs^2F8?v2qH(XkT!|7Lx!u-ms{I! z%zWPNQMSDGY0cV^=V(>)?qKMw*o*@sx4*7ny`Jf>6s?dJqUgo8YESjGcFDfSB}R*S zscSSVS;~6*y{)jK9aC|yBRrpNEz9wacXbIS?hzlEA~>aE7FsA#pg5J_NLNT4OUyEG}M^Kgy2R`)J# z6ncdOTB2*Pdn2c1sSjn(O<5F<4DS`s4tz534R0}rbriSs31sptvL7(%@Kc#>V~%Yky_U;Pwb6G)&XA?D^U z?Hr#oP5vc#!AGTFE89;3=(Kbh=#Lf+4=vd zp(^L8U__1tS`uPXmcnkc)k4iE*i~Wnf}UXhNWU>ss<@T;6QQ~l=&Dd13A9Adk>x1s zZfjjjPCPW$&_KJGU(<6k2Q7K>kxR0};;ssFLu`fFIbG*P7Q64=x+nXTGUGr3Ez$4% z{1ujWNBkt474N1nS4X?J-x1>9w=cV2O&lR_>=;{7MylgDmumFJ%|HP9~Z zujo4Omn54eu9ABebyK)^!dAHd6r%Zrc=_i0Ps(biMjCM-ftG|gyko!Y`RP>IOeItcVOt2EWRCG_5 z$`v_V=0T+}s?nt0eR-(HBzFMZ!TNZQ*$QbP`c@t5)KLv>_Rm-6iXiIw|Nj4u16%ob zgfAIHV!|r{$6T7g{$jA_i!}Mxymuqsy+8pxmx^B+hOXb}2PR>Zf ziQ|n{NDHxy?%j2!$j>H=9PRpd<=7HEo$&V!IsM0pZsAY58yeUOX(8G-ujN#KdZj(L zT1hoAQ%-k5^PT#9EE-tAExUcSj>Gh7cH?vM`(hpBor>L@n*)oxZO4qzabPQ?>8jn< z%{hPato@{HF7X_o9@6wJ?DUuAr8(JU=8w!cuoY_4FI$&v>D&=HoN&HsHrjo>UuHLb z>ti|&)2mU<>Ajz&XUI1`@9JdDn$KPS+$TB?Y=yKCJInnl({E}ccdhAeM2-Ynq9=r& zEbDBo{HQbSlfUG&%0EUDb7gjUwC{QHVx;EA``Rm0V@!Hi)^GT^EL**+(=Ja&cl5X; z+AC~@G|g8XsyMxqN;%70ZIT!{>LE?{&oAwfpPhV5KDxfU5jnO(ZF-XYLLui|+lEf# zCXS7EKPd8TeiMf&Y6u6y^HwsRs=5{qcBOpSA6!!r9zr{(xc zU7YjV+(@%Rxm><-uocpDXY|-PyYJ*DocE_*G|nLEAx+Q8Jheb}&bd|okl5Xb99yBb z5L*j=Y3JMag7aCmA~xC;MH@u6RVkn(hYIUBj8;HX z22gF7{J8gzvO-dKBXT6rk`QGcZejnCINI5BmojudtOti%v^B+lwc*ak_0yr!aEVLt2Qz*DJ}D z1Amu$H+MH8$5w{6xRkMl)gk8ur_-|O7TS&9Gdn&_hN?Oa)2n;`9E-%I$)G-ezmt=6 zXGPL46X{+KjS_5yH2qp{$t~`PkFU!@hq@b)BY~EL=rQY{TdwkWXKE7TUEdgk47`S1Om@5(=7qusf?SA=ZxloQ-C3GCv3Te7CIzFBKQQ^z-=*{j%{+tQ*eLiUbSr6t7ICxX4(C(pOJs$?&#Dg@?mJvlKk2$Y=t!ameLEE)Sa8pIQjls zC^2%>Lz-6S@U!-b<-f`d1$!8gV=L4a;@c8sRlSoT=R!BzM!Sy;x)qA2Clz>#6r&D(E!L zv|jdZnb#UIE>Y(`A6&>`&HZSn_R7>)d40eAOyOub-du3|$Z}U!s5C${%$6Pk^8M!4{3VB^wvdtOQU`6jiEh_$gve_(=)=(1oiXz z#V+sFT4kwhP2O@Sp~TN-9H>W6o{i|CUY-7@`)l6I_UBY@&r!8@=xibVgh&uMS`uQ+ z-Q3Q{xfWWrA8qCA|GJWO>M19lBlqocv}lQ*h);LbUNY@`#8EwszCr>m(Q^P>`Z<}B z(#lWw9h4ZMPjFvh9}2Pb>&(s@tIAvbs&-Il3w=jgh%P5D+c$@ui%iYYOQ8nRCeh$@ z8mH);0W#mVHVVfNdV(_s)fq}(wI}^`z+L@x4}(BGq=l$@Erav#JHN@%FUBjJ0njea zeDn;%5=+VYTpsT@vS4j0tJV;hMf<|JCFJnd?|TLj!4(xK!;8`(E~Ts`Qe7 zB(C)631&D#?0S2feejn8D#QHR3fEMO32FMCSGRih-!FVG7nka%Py=a`=(G0wQ1z4j z)z0^iNzCrh6U-m!Im;H0+K)BMuEs5Er7({|J*4URk~!_HY%MOz$?JP5)Ii!KmW<6T z3*}C)4lM7WFn2~zaL+&$;nJ%jZ|%D!FZS(j5U7VVJp;Mo6B++nZuJWN+8FMB&@S$G zsh)JrmMaDgR+WpqXX8EtJw#fF%EOAt9Gecy)=%{{G>|rlz4>yfr^{wi$G$A3aL0?D z;7(tNA=Q7E&$ei(4zyk`ac_w+Ax*zv-(-sHvtzZ~ysW>WfwW0%fB$hcXX`dOtafIF zRSxt7t2^|IQ?F!H^Jd@{qoTUH!hyUv-N6MANQ@2KtVcgm{H2sh2yhwCX`6^^aF3 z1@*+{B_BKw8P(`a-WS4ynyvimAk(ocsr=NWA1&+o9!51dVn1@MI$|q7 z4%Uvgk45;cu-~E@v1+gEiC-Ojn0zDaYb*6^>Q%xc zSGMcd6FCmkt5~&HwuP;bj$M0APWZES)T>yvSN6)UC$d+jMy%Q^+rm~z$F9AyhQC@S z?}ga4*W?=h3KxwdR_>`t?MP!}Kav?UijAt-RVR)3Ix>$q9d@j(QcV_R3!Q^+avg z(1=xg)wZCOLC37UvWA}_CGUmUwb$etepVBWBUbH|?fUgZj>GgSR_&E-VJoC#*Itto zes&i1Dpu{4z4EJr?3JkztMDaYb*6?=_e2jGL+G}zRKkJXi5v%sfcKv!H$6{T+27`0cng{_c|U3+B>f7h727h>05lWX`py=WY>xNYjVP`Ohvu=kZP|d zlGR?1kJIl8)B73r%G8Kedu3bL%CFopEyN2{d+koO*BMZI<;eY3tcP^$+G}zRzls-) zqi2lT>kFX4o}iu(#i{n%gleya9)3`JZC2z#D<=H#IC(Efg>F0*tJ(C@Jcm_ zShZIs&=brbV%J`oz*!CH*tJ(CaCSC{ShZIs&=btgV%J`oz?BT?*tJ(Ca78wWShZIs z&=Vsgk6C+V0<#ySW7l4pz%0xpV%1)mKu>TN7Q6P!1ZJ#A$F99Hfp&2p9lQ3*1ZMY0 z$F99Hfx8rwh*f)K0zJXnN$lDy6S$*8I(F@q3EY{QM6B8?6X*%n& z;uB2A_KNRX`UF=aQzZmGzw5VR+CPqJ#PSL?xc2H3{O^WWhKBDIKOGy3U^49RbHUr` zEwubpF+L-V-ufC*g1&bXymJ5vw4{k}lruHZE+6~a(YEA~q9c9I`4f&1?WRfyj?gFY zeE>+)I{|Comqq`ZY(3Mms~Xg^qFZZM&d}%dEg@`$wC@%FKkUpLT;6>(k~748mAn@o z#PR6qe`S|PCR_K4bT>4RMm=9cM=oyA+mqPVGj!H`PxuYG{xQGfz$7s8Sag)w_f9{j zc{O?mWW^&ABS*U!6YUM?S?A)POtRL~JDq-ixuW|=#vGwcg&%mrUZI{4=gz<4tokag zWdC9j{9a#Qk7@djNuB%h*s4iZI=cUX1lq;;jL3sg!dH$@JYFYyefVR6-s4r{zI-R` zYt|3VyQ-l*D!S=T2yU$48n+Fk0*%Q-jCV&vedlT=k%RhTn?4@?&B> zdXhZGxI%*8<%~3~YNT<3G}gh`WdiMDd`4dd2RWhA9u2>yg zA#G~-t-8{R?6=}~!uiM1_iV=+SJ=BqM+qKRZ_~J%0ON|I#r`ohPSm37qs*&T&X!#r ze9xWVioHT_h4_hxlSJf7Mqn$yccVGO*Zba)dlrnbCJr0nOq){N?RRrnh(AF+lkj>g zoP7PD@9nxbnm(CgEfM0x)&9=1OO0j4jmpNE8fRyu{qqt1MTDy_=5v3$`H8km-->qm zjsLt}nZz&e=XSm;{;FL2{?pFPpGvypZoU-aZ_8pUq)m+-$BVn~jekkoMLnbgf)31; z6KRt;a=5Frvd=^*JO3=vE9?c6@KnOA(QZsexBaan+AI1dd}QX^=`4=ijH6!skM{Js z5n1`C)=p?>X1D2M$8_Y_3TZPAj288frZYIHf>Yz{Qdwz9Rj0{_0`5N_tkxPBlSwS< z*1-Awue7RH_Pr9lLfRxS@^#r{B+raoI$C;{L8NT!qWaj3WAC$b?97GE%8uW4aK5Sa zZDjh`+!mj6Y=yKL`TSNFBDIU()4hv&NSg%q57H)a@~H|=i60BA=iWbIukCy>l4Zqx z-B;KPCUJgf0q4-$jvBmffy6kFHVN#j`*-6aIln8T`-k3mp?`mpM~NBvqFM#)RqqHj zxJW1GE4x9YKfS$``wCkj9Yh}HkvO>0jL3%Bg|!CiAsrBO5O%Ofkv55A18>{8U+t=H z?fAty_}rYxru9X%SJ(?C(fs9g_V&Sp)t-(!U5o>1lkoh~akN~$JZb99iaHK@FUp1y z^hN>hD>L#F>1SCB$Ba|iFF#_}YW8K)`VT8>udo%;X5`pEsE0KD5@x8GJ^tBI>bFc~ zC2C+yCV_EmAG<5QRPM^!cY5oL{`Fgq!}RLFZN;4q6Wrf5~LE2{tY{SJT)*>=~4+D2ffor{~9sJVS2TG zML+q;)F)N$Sp^-t%i`qfqF;>1Uu$nv`Cvo-O}6L z%(-4vhuu#kdWF4U5^OyBH|%5^eIRt8Rc7rKy~iok?xX13o-B?oo8@|EoaVG zD?+a=FQ_BOR!Ea|&}g*#!%+IG`Lzb>A*~7TKj!&B+9Wo9bIZ-Y?V`MUpoi1vR-aI* zex&8P8<3QRZFpiRs+zw^@`J$ew>1|*7m(6*Un33>Kdi7H|{!}J4ppgM50*bqn9Bf~}A?<3Qh04{7=?z>s0;=>9(P@h4v}-Y0`GnFOg&4E)E8 z1K+S>dbMD~U-pqKKUle}p2pi@&@1$oYT;Xcv)`**-ELLCr$SG#6`m)0I`)gKPOo!m z?e(9UZ=gW}EeUb^sRQ<7Sx4B@oAgw8*3d4Fd?D`TPv?xN-PXR;rmf)>5@?COoAF)5 z{^I7l_PTaG6^?MUi&vTuO^#l%ljh8{uV!jzc!dO765>|Ua{Hf(>+Sb@_f&Y@p#h!dVUN;#xxAMPB!{on`kv`+nc{ zhF3_SB_U=_Ze(9M_Om^GQcs0*E!xGko$4h+=GgZ>Id8w8yMy5s5@?Bj2Wz{qPYwIs zPWyIGh3gX9#cY6fMMFE;M-p$@)4u9pc!dO7qB~g4x>(9X?8rKjyL#`aX0 z6{B6;Sx{9i`>g`$LWsUMT z?LS&}HoQUtEzvh8%g>XqJpYZIDQi!K`x>;1yGc49SHtpn(KB}cOPvj`kU&fHZ0&RF zWW!S*+wWrTc5(Mg&kpu_U!E=Tz1{ugE{0b~pe1^r%#iP8=}d3g{j2m)xR*t{ zSWTd@JJ^*cU;EttBzsrGD zT@0^~Kuh$*)|pH4z{Tu#n$_JE)-TX5-r1n{ux$NZep9@&Jv&cV!z+V;niKtw;)WaY zn~S;ZE6;T`G|(>Afaoo0pS|Ry>o!B)YqB%4s&XlJ*4$wst`3g*v81~o$H>rLs$XKI zkbdFl+HE;#Y96~>kuE_^pDU@@3Tb+3GW|%W)Zpo|c;zM`thb^b(n3^P(cjrq=SO*J zW?r{l(MQ}?jaF%|F1=X5J@UosQ0~_z86MIb9k!m9J3ek}SGd{D@CrRanx5VnGQinY z=ZGA&`@0Z&f_g~P8O+_rxqddMYCQjOH~)+*?)|QZwO6BG$m}+M;#jB-d1Y#pt9e3Z z%{$kgHo24H-%Xf2_CSdH3R@v9#Fa5^o%;8)tKt`OTj&YuAuU9sPH)Kk{}ixG{V?3n z@b9-I*At@miwVvXZWXog==1KYt1d?(Q~%R(^lE-F^4yyHp%BGkdQ~cZy|i+DY=1Sk zhoOP3kfx^-7FtfVg_YFVyq1N&qaM=qn@C-XI_3L3t(L8s>hAx1TO{FnPK!rkvC`j0 z_Jng=Wyvd3*jzq(!2yu5E%=sW5mEkylk>+F(W4_0TsUh6(q zv_)iav9j8$*Yh@ryjiuJwVb>%HJ&=&K+b+Sjq}8S_KJVUqR989bnjv-r0IQRgoJPM^s31x(hYrk#-6{Ux1oWpkQQQ5^?vq-@h_`B4cA!cJL(}#*I+_3 zD^H{Gs^dF{U3*`L_C9dP_d6q&W|*4gFRoPK%Qscb(UN|^ah1sw;rLYm&6I4PaH zm@rz6=w07N-%$@~`sT|w4_UiP{b5%e+uP9Kw-fsPW)hM0VfkpQ;c8Nq1c`RfkLw%y ztW#-g(v=sAx*zVJ2Q)FT&I>A^!*j%45A*=^zNPf@7m*T zuDAbrxVNE!y z(aX@lelv*@)jFsQ1JbB{P3uUsTWEhFYrC~5v~~O>%k=8YhcDT=mcMPcFWz2d&+&-W zXU;Mm2ev|*zD4)z4m)naIQx%dy$k|-0cm=6@OW>P?xT(J8TEGXh7Eo;JJW?S)~26Z zg&rcWOpPyF(l0s`Z((O?)n1jFUD9e^zpM5NTOm!AiG^L%s;|D5=|0|QW90ZOIMP&^ zc=5QsW@mzZVq-5u1ADFKDlpSE*n% z%z05ie}S!#raIi7b9RgF7p+&`?PU@s;JqK5k)fWc(PL!| zr+LXa_E=HDLAw|e_Ms3tKKRjId*-BdIZHnW?IMAeg!rt^FlXwsiPp1~m)ZDCI}&I~ zh(R?fI_IaSb*e_PIXITk6TEKdn|f`w*q9|zAG5@?B@!0w*kIni*U{p*n@ zjmVKeOG3O}bfrBZ?N9dJdF>s%?$8sQkLe9G`yzJ!kssLAnshhfKmsiZ(Wc*9cEJke zom=;7IXKs%U0hda=k;zsd(Td3*Bsf;!C4Inv_!wXT&bip=*Htt#x4aInujmQp67;K~Irmvh%OAJhGW{G}$&f%xv=jb!q8&O_)CvD(8IdD_ zmV|h=|D$e|>G$m27rHu_i=Zc%snMQucv0)?srT%U&UH27KmsiZp*}n74!e5OK2xHb zgLxa;#T-?LtLx(3p>yB0zs*0w@CpgEM86)^jxnSTg#%eg19&3A9AN0QS&(vc%G@_Wl8;2HM3voDdl& zMdbU7Kd~p&?&jeB3|rw|lx`QCY%OaJ>~1$K7yXSxe+P*KTB1?X_n^$a>@9o$NK*st z;=Y}B+e6RG1<$s%PiE<+e?gL;XyiE&TVefyDtFVSNO3)%osE9u5Y>^u-95bp>YMBG z&EnbZ*L#^7XcsFlG$(p>pG2tp@H44?#p4V;*Xh?}_!&R!Js4^!Ree&GjoAAXh- zTOl30?!y|sSA2{#J*7u=pS@J~`2^}d+{&+b4ES?`;URsyhUz}n%C>eosQa*2=n2yF zPI9XI?54U;O{n{@hTpq7nk!t^E4Mm*kbHv4HA6?Wpe43+g`X6}Cb; zTK9RJ>OL3GKdAe#hCimx?o)y4K69b&!>#=K#T@d= z)cBF=K6|L{a}nx3>=m{``a#{NKGc0!!=Fp|7-{nnzg5z$N_C$_Q1@ZG*b3>` zbsyI7S57`gn!dq9b)URc_sI!$A8zGWBfg}!GMO4rUphngqp~~yoqJICVXv?i($Tt4 z399>?tni@j!y10hz{g0_ZyZwH$ECVYE~xvkhQI13*Q2pZb)N!M_vs3CAGYh)FJ3)A z!H9`|$GztOtI~>WP8`&I*e?2xbhPesiRwNzpzgyOetyNrNYk@wRQG9G`VTu3)O}dP z&ybSq3E@)RrwG-3>OGC`8Y3P(r(B-nwuHJ5Yxp^Cay`=U>OPgB?!$Kd`bG28bPamd zD2_>p8dUdrj_N+IL*0k%Vk@NStwU7zsdaOwogeBxO!zy9CrHPx`>=+;k4oMPvFkpp;qPmb>rqYS*praE?>YGx>DYB2*6{aj$@OSI=+%8jLfwb$`t^$+PEIgl zqRcYiC3`5OOZr+$hID-G|?- z>env@(%aunjen@_^DotXj<LQ%zYGdpZ6bbn)`_5I%g1hjK&Ok?8cze z-)n;BY3?I3^u0eT51-V8xlb3&eNLvikMPy0iu`?9SF5AWX%P;d_g(HXn)?V}red@) z?_%z=9&?{FXzn8jovLKf_^sb{p9I~%IwH4wbkp2NsC23#&#sKUF!$+%xzD>a_Yo@g z6-T8pKYM6Huz1Tmxn6rU&3&>6)(~AE=02BU?sGt|rnyfR!5aGKK7wFPc+dOiK3N1u zrGM^|MezFj=RSg9O*qf{=RR2k?_mGjM-a@HE46>_lSOdW_RoE?2+oiGxsM=N6Yhij zbDu1NE46>_lSOb%^v`_+!J2T-=%4#!5!}`I=RSg9zT98?=RR2kcYyx6k06*YzghU_ zK7wE>ey8%!eXu_oAl3p1i@7N9_^p|WD)$P=b!rsg8A|U!9VvA1XJ-O z#6S1RBKYmzKlc#?^VPYJR3c+KT=zq8!YNgF?Z!I@md9v#cjb!U`RxmWVH;f;%(vyqJ8OIX^sADLV>{Oe2Q@4WZdrC# z_;%eJwXacHC*M3mDcP{bOnu%uxM?5zy_;-)-4uWlBv@shhZw=xe8-n`= zo$Vl)?-2_hs$IRHQ%T01b*BXX`tsx84+G8)k3IUl+E?~J*lNX8D?k2Y?T`yAONfR( z?Sc!cZwh7(81Eq1CPo`md&8c=(n;S0t)6vdFyFylch$U%--t;pe`91_Zto?#gO&Ki zsYi~utGfG)L#9 zSo_V4VBaz09R%CNXmrT0Rz-bheG;5Kc!Yysz8{actMS**{-Pw~!b7i#W}m+)2&zVe zOHYg&U%$Ss)rzU=Dwa0xdwshS;`qrX>a^gNpzqb=9R%CNXw=#s^P*GVUJ+~^$7A&~Yt_-G2Y3-GfZ^(VtosAFN(qLY(~Npy>AI z=LF5J8}A_4CPw40+eu^>AnrE8`8{E# zdK8~aS9Q`AB}9jPZj4U+ynWDPg8Q4rY!jo6X}gxdQE@g_hOL(L31+Se z!tYw$UwAv}WD!DDJau17#c13^eqvW}fBmV!m;>->Hzb46F5>Fr>x0q9*GG$QJ=e;( zciPT^XvLaDJ*OAW|HbY?qSc;5+k{_tA02HQILJY;JVxVpOkhLXjg|2oB|B6G^ZnDl zlMA;E+f|YweuBTOujD5eP5;Dd#ZdDv#0lgbG+a247FW z@@4%`PN|shDT7a^_1Le+=%~feHu1Z#oDnRK(Xbp=f48_#GzFG3g8AONY*4!XxCa2M zm+WjA)F4XEIJ#dNB}^q~U4Ogg(VY5It>r9(5zGlUeqlAff+Z!(HLjSi*m3n$9W@eR zb?Y9ZgY6~D6~TNNjXM*tx+UUwddYG{FkkW8`@=hxWZVa<=U|T<1Iy(nS4LfIv@?}N zOp{h(bw@<}<)t-Ogm^*aF&d{buv)(UT8eh1V!ph)@JY(BdRJYW@S{?+D}ps-G~RI# zg^wT_5s9&`!QU>rCda;F4KWvmclShWVMoOp8G_)|WVFpC(cC1LI5HURB3gp~ZrJew zWat{G44+NNaERTu*tvJF3anNVae`o*Tsy`huJ9EgmpC#sGP3e;TOEGtfE64IU+GE- z6?>O+7v{ULdN!gYEDm=NY!jpL+fK0hhwh_;4`I2kt;k@$oV)NF3XA&$KSAuyfaSWj zs+GiR7VX59BZJW_FUi!?lU*BYMi#!T3Fj`G8G>rw!Rr5F=iUX&HHQm=`MO$7zbc60&O$uRelx~b&jq1zl|}pOxll1*_B8gnr=AOfso2xV zaGrWD2#uvI+F#FwiurPWG{#rYm9Io%7VWR+LdASJKlbW48ud9`>o(qEc%4%wU#9aeVJr@L1NyId1<*Vm{&?=KfJ9#(l zkcEo*^6v82bLA`jLl*6?=TnZk*6|f<=&$F3(EK4X*wg-cE(ndQtUP0U^;~60Jx@u=PrLe&my!M$oKvATs4t;u4}Hj%U{n0!F*kbX3-GJN%1sI(fCBYgGz+QTL~zG5%<>$xB_ zz4{R#QFgujhhbD)zL$o(n>w zFN^lqbD?6soFD!5T=_~QX3_q7E>z5y^P|6>3xcUQKlJh-}`~{OGUef{-;=D$bAioFC8oxgfM!X3bX$KnyYs?clqnNAT+MBXn#EyD(1_%%U{oxuS8-N?Zj1D&xK0ksvO~~=R(Dr zaPIQg^DIKEfqdUz&s7tt=ep*ayZrTB5X{%r%2&??p_MEv&tK1lO4eL8;mG&bb3thR z$fEuAT&bkW$g?ZMSI>n?t3f$pQ^WVc;dt+yK=bzBHJjx4ioJl7>J63QeVF}xP4jj^ zXvPs4>}lM&TeJ&*x#iSgG0ocrp|P8lhrjhQus(QeV12ZW=Its&>bb~Zzu~iGF~6$A zyuJVNP4jj^Xe4IQK){B_HdMwR(!5=$n6Fl9k!Otf3I4La(sdRDQ?aL!ukd~j>m#w8 z5gL72G=5hfR=G;bFw z=F9mJe-{Tvs0BeWU_Cu6q2>i4kj@6)_pwUT-+ zYry#tkqE0V#LV)@lI2nX1i^e=t){^01&H6zXx=Ue<}2%@`4RUlVf7o>BiGTqT@Xyg z`4KaHSY3yRf0E|yf)FpLhK$D99junG?KE!}1oP$HgWJ>^pq}{Nhsh<)6a1 zOEA6g#^s5xSVKk|^W+2dLC?zi;L1toIx-mTB7F5+Jj$8~Lh7!>m|gSWziV3svgT|D zBeWU_C)hD&bbvLFWzEO!J-u-I-n$F(6Xq+v(%glc9CIteC)V|i9>JO)F>-F9qI(jF z%$L!2%>%4?Bx}wx80{kFbUH11r|R42Dy(^{uWu*}`~5Df6>GwgZ_I_8n*}qD{yu7j zHD?6NW3(~PztcB5X79@Q3#{O^ua7D;bWbd2v@4_Gf%>R>Wql+o$h(NqE&^{krT_BI z9%Ns!7nEB5%{x1a5xl!x1g|+Gcz0PuKEdT3%UKiln=6AYX9Rn}MX1*HOP&|s@o}N$ zn|ImoTSOlJ$5%e?wsLNR{)EwG2n!R0{ABF@ch!gtM*lcMsKOC%TIoWi&%fxiqww0= zf4EwSVsYIa-#vfI%dgs>Fx5R{_GoL>(9n!Gst%MiLV{}5B{NI(q z=rTlJ5qGrz_4BI>Pg$*4lRy8mMdKA$Cf|2uFoJDjv_+&cHl48R`TM8Mvoe_P<-_-A z+;MU8{Zs}}`Ir$bkI@+!6eY};BPJt*5G;?;DFP4WQR0gj7a@M%I`5tui7Q!;_hux| zvYLu^5gdt({&56T$$Feu|Ccg(t_)eJy;dhw;@!>9JZTY(b`dOt(Laumm8$+W;Va&4 z_uk*F43_80V7`q0afGbYb1h!Ad}W^>x&J?sXOid2V7?CeM-j3f3+Ju1d}R&vndP}M zB;t-bFwun3KaOBc80{jOCpS`J+(^;e3AJ*nCsiN4VXfTWDs^P`8S@gn7vLUQG^=!~ zk9Q7>C{?vGbUH7Ia8JgOQR>w_h|;Vt!d)D_mtm<`lTt5Q(h6t7a^EMyeIEx=dN(LT zr+12C+$qxgB`Fo&YwWWtqjZ8Lx7+j%i=`^P6?qW2XAt22mE1MZ8+5gDuEM@zFW^l$ zxib;q&V=5Fs}Y1y;f>zPV03Z{a3|iM<*r((o3t`YeVawQh|;|!Sr46yS_EsteoLon z5$^jq2$sj_bgCBP){BE+zOtI?Y5ZOh{DiwW5$@vH835iOtX53Lo=)%kM7ZzcAT)OM z1gl9#>8@Htch#&6=39Cbww}gZG`Z;%i{%;(%2zdHbUI0uTQ3fR`Ih>wk_@?22$_K55c`3c@-tPG}-h-uQQbUtXKoe``dqti1l zxku*gDCWz%%bxtmO{Wkyog4(qV|02d!?*NmS&{nCiWy8kK=J)6~=I_4EWQzztKqw`A>Ld9EF$Nvgz^ zBSRx2D=$5}v%b=m5-RpC=PvwKJgk=URO}C%+a-Pkp>dT(C#RPG#q3ACt7|J%%$IW) zZmTD^ibLEg)|+Qm25ZP@V@k7ddq0t7Xk=vNC7Jp@>{{HX)?0ekyQ~T4E_?D5z~(XIF-=o(q-c^Kyi*p3Auk`-;8bujhi`h+(w9o(n>w zFDuXKuhLqpGNd~bJJ@gjdM*f!t1Q}I&xMNl%6h1${qZyP%&T5kI8v$ww?=usW?CS>vt$g)d5ZSz|`Pdj=Jr{(mxl(a{OwR|MdM*g9GFi00o(mQ8<=y44=gL=V zUl#4J=W?#XzG4mi^;{5|aYP2A{qZyP-$G1BjgkyThE1x zHR0Ulujg5WRs;FIzn-fmQqOhGHFx>zxgeOYtCg>w3qmVdR-V6}3ze+7YQmB4ujhi$ z`jJKZ>$y@%m62yxhOeFrl~#jtgq-T*yf%{aT3t0cuVG)Y7mS&Y>Bk*75&xXt&jq0w zM`SSCp6~{ryQliKg3#E_%1h5VBRc1_2-bxCh8=}7&fz%UKC0=Q(<0a=MjJB&Hr$8v z?XT$lTr^?6TB*e*W4gmnt8l(OiQdlz!Bp&N{I)Et9)k1jr|A7$EtlBMqSLeOh|abx z74zl%Xis<}SRae!8V$-|G* zixIzD>HS;~%vV-Z^P@3G!)nH#|dwZ%3xoq*YPPaIMt7Fs$Y*2UO5@V39pr*ag{}vpX#d& zM!S}0PxW!aYqetUve(N`^%Wr}aVn3|_-oTR)qen|`W2;9ecYL_b}(PgUFE0xI1{#7 z$qApzV|4kczRHlZLPfg>Up*I(vL=Gi+=ah0@znRh7M$vDES>7B3`S@*5KiT%`nbuF zTCRM>SDL$wS%Xvk7jUXCYc6NBxXED=%-7WlH#wYBeU-sz7m+>H$4w3^gEisEFF(~+ zgq#VhJVuwF>f>I9l_4j`igsmWPxW;d$r-ewT}0EFNqVYZ<}3C>6TO_o@t$Ds^6qjG za#F2p&IsmY5%~m{oa(FYtO@(gmBIOg5$pvQ!TK_SIk^bt#hUQixCq`wY%TA37s0+_ z1aoo`{1fKOd)`GHzT=?ctj#MM{G8Jay-cXXTkW;j=j!dc}vlH8uDp z{@t=+W%UR32N&fNPoa19y_a_`PAE>u&3U9vjXcZu@iy^XuXylBQ=_}_@1B>=sqSCj zv5bn*saAPJd$_e`kHRhg>|%K_-%Af^U1*Y#Vt{B@+_UD%Hk~YjsTiHoTN!KzQ?YDg z4mhz*JmXheif`Rr=h(sW7>!S_ThuFlY4g-z{}ryU#0$-r; zyViWTd_(p4t2-BE4Va42_$!+?ToUI$T^1b{%&aNiGq?KPr#e~$dz#Vs3r+3D#5KW- z(Y;j_1x7Fx%SJ~wVQRFks#o~Z(BAR8FFe}6@tAJbyYiQ~Ug}q2?Qpd^bJWsk{o|v< z*Z#3PH+@Er>Q0LfPPJ0Y87+Uec3RZpo?c<$N!M2_&z12|ecO2Fl%e73t9v(mv2afH zzx#JBlfkl$dHVcI;=68I9^Ck|3#-{e=F6OnX*h0baLlKNg}2V{9k07{dBf(XlW1Rf z@yrIl9hILg3x-d=B$NnK3uOiMS@s8`(fdr965MlB@9?=ky&UhdJVxWM4vqe86#a0G zmBAJ=l|GAXy9dM5KbjiI9^^eSf7!YQ-L>8d5|ZB}Exj5enKgsH*H zRlVXJ$cc<#4H<2tJw~)gpCj5iJ2PL_)|l&$n;O-9dRTk|vJWFz9-}db8?`ie|MAiB zqW{~S+dRFZq2kC6HYc)HjJ7#3oOaXlX!ZdYR?mK9X2WTVlKR0h#%N3?>f46MyYZd> z+q;2fFxo||Mx>8HWy8wkRl4Rx^)%aud*K)THdyn+HG(iKL(!5&^*PCKpT9RSTC`zY zJg$ChaKgnss~_s0Sk6?gjP1AV6TiKqF8&6Yfe}o__0fr|m=Qh=6RpJJ1ecF}nOdkg z6It36!L^8~c+V%?RR$wi9;00uTnCviufHpU5iF0tO2x1pZ19W0O0$fD?XH=y5bk2=UQ1dUzQAYO1S?}eU2^1%YS~4sA)}31f`0cf^t;;zRumY) zR4f~_aP+%N(eHkR+`ec+=iIdqwke2r(J4tMZtZZjsxI}reb?^Jeb%~5PT%O5iqXcL ziGFwY-Mzvhsv7%>~)0e)l(s z#ORQjHM<_@nA3M>red_+AK_oCw&Y}g@Xld*j5cNv`rQs|UJJIN17K?z?IN0Q85qn* zzxzF^+OD;oaym6&YhA>zZrvwbh<%r^PM4!!~OvN$nB7%nw&b8jY!g_b=sLr|5y0)&7 zyuupd(+beyf&^3MzB0a zBU7Ui9F9sLU+8tK2j6pWPI8pINBymHMNT47p133O%yg{-T)NhywBQsz+n7#?iPh?N9e;94d zFl4wj$Z%7U;pAPW<;;UEf;D7x`Ma|sm`b0MT`PHAdS1!x=yhx6oZs1cS0=(Zld!Al zYL%TjpKw4|s})l*8h1HS(WK{5X0yOeJr6sx3YR9M$F-^t`iBanS2lf83*kwOkP0?&@eQckSqj)oYHP_xUT6 z3H>v5ovl_(#b{%s&PvZK{VrR}@)(W#iFji<8*eN}9+*t%RbQr(w_=rT_h5wm7s?)# zwdFl=!L0V_3aU+*M&XSGaTQKMT*;)M-9a7F6;vwWq-gZJ{k9Z;eqx(Y_6P4Amgic& z5Yw&`(et)kSLJw@(Jo>e-f>>XJI>Cll9_&RPscK?SljZMzWRju%9KJm*$fvTyM>bB z(Cap==#s2CTgx`teI8(+hjNZ1`_AVd=44Fv6hOSFv8x_sPWZGNyyIZv6-vfp3$t1& zC!y2-+?>doxOOOgHYf6Wa8x$YXAw-rG3_GI>oy#ETT(yJ>lP*sPVx$CXfs17J+Jh; z>=UM9v@3(NGs|N%?qA`3^Ca}VA7Bs4lw7kK^JTO#tMUFn1wHR35Uv zyjc2Oq0$P#d|6w3CKBGXrRSA?mk}(F(Z)Q5x6}oAOZ^h3eKK!b^_OISuvUyVX8U^s z17y*#4p~&DfYT7|9EtMGXxyN~8{`taLAF0GIWbWgjCK*((~NV^O>!b@!uHt=7oLf? zyYow@8H!+=7+pT6-q0nfI5H7bv@7F%^zFzc@t5P0Iknb7neQpuMKncL-p+TmesJBD z9i>&<(&rOYGT+rKs=HRa%YJhaoR^r2y^wHM8I0g8!Dv?o*9qp!esg6og5@#VmBBTY z`Ld@|8F}OqJKxo+#_|~L%HR%w`SRMhG8n-cGCD=zAs?a-EnE5efDu(iJlmqg@%O%qcIH$LJK17p>6i7LlPFY!^;w7lF<-Y=aI~ zsxvZA5%tf`DH-h|(6fgl(7Q{|zzC*d`%OFoNYV+8Fdb@gwMe zTA}wrzmQtaeAzxswowWCq92`uYQPAV$7o~ZZ3S;FMOkx3Fkg;0>)m|fV>hnQ0~OJg zm&F)9ff!v<4(A{8FM5wO+LKw9u0@^ou{=h*vp$x= zXcy57Z}h(}z0s?5srvdXm4PGQo%OK{M(DF}a?iZB-_o(DXI{*gqtcjDFdcjl@6H=> zZty{4r=m^=nJ=U9S2j!2!Qq$=vJ6JMh{Is@cUbeqnCbIWi5^ zBUm1zF$>3A>MFdY%JhS8N-|%uNq1V)nb)S9FRbQ!k1UVTP3LM4AJMykWiZ-B@R^rN z*ELs7IP%>SEJm)%8#Jsj@|rsCC15qUwd3`Q`g6oH3)%sZ9&@@l3CD}#A4f;puKD}#N-e0lwi`G0gd Bf~Eif literal 0 HcmV?d00001 diff --git a/wam_description/meshes/wambase.stl b/wam_description/meshes/wambase.stl new file mode 100644 index 0000000000000000000000000000000000000000..f7d513212369b72fd708c21e75851cf4138669d0 GIT binary patch literal 49084 zcmb`Q36vE@((e-lM3zQb)F+^h8{p0eDBWF^2ne!>BA|kxtd2_KHUhF=2BqClMAQMn zQDEE!1yOpbDimCB!39NR6I4*g1yE7MQND<%%#_eoe?B@$sV$dHNj9A_D^m3H=SQ`}&#s+cIIyrVzA>m1^6&ok;p6U@f3H-N zwUd$u*VdFz_ug7FtlPOkRJjz=Y{mX$bjx~m!qcBRDqvex>7^RByi$&c_>)!x8;C9+ zTaBEAXkaO%MIn>wWc0{&wZly-=a;iB9|GcTx{G6+I z1$TG9Q#5?SsARZxQ3FdMt<*~=j8EQry?^{m_tNF82gIxDnN`8WDXYXQUxU0NkN8hUU)KE7;K0s*XO%))sn<7Mo&5IVNAZHP#bxLT z>Sbw=1pj38?$0&{=XQBiG<4go!Q44>vh>ojT%3uef7=x_>~Uwr=K$>@?FfdvdY~TC zK7kr|ZhWFSwd_^Y!vDT(UBO3(E)Txh{l2s=c^9w+_Rw!Dqmp5-PM^6l_-=pNx>yQn zr8bT`H#z397D?Spzc0fUMLncNf$XPkRcHFTpyrcLi6?kAa}$qleJ7Y+?HM7E&LUWd zbTazncCQDgzLaVpT_wSgS97F&;u9K8_m3}1y1ej9!692l1W%0qU0RnSUBKsrTi0(Z zc8Pv6ta0|^#ld4ysni2YA+1!c8|oz0`(Bz{kf~RWEsA{Re3?($(y8oDwndfQfC&{jCXuEDe1E4 zwDxyx|IgX{iJe)jo=?C2uUXME7fneXe)Gn{D_@#lxR~Y;CXn`t&xg*88_gM=v^(ag zay-vS`$Sp?sft$*>|RtQA3rtfd&xm^){xFkymU&NXxT}%gg`ns(Pw~; z+8$h62&8ipCq30O`ej*4Af21At;@X+=`4bNk$pap_KAZYtr@NyJt?_-YQLa=oB8E+ z)~Ef7&U3`k2hXNGW()k2NvvJ_i9OFgy}9hZU`zigN$($`71&=? zC9T7*!H9cCL=%eBm`E8$#B&qt`5MfpKfYI33TdT|+InxexAo}c?Tc=S&=b@{TB+|# zo9fLwyC-G$o)TQRLIPvb^E*PpVu@^WgBc`5L*r!cs_6-hR}%`jZ7MlIO1N z5TPfihqO{}+*G6oAF?{`cr zymjMU!Dan_k6yd%D$zhaq?J1Kw!!+y?R(<^oragA?@0SZkli(+9K@} zTQ8fUH=i;qVDBiWj%np3>kstA9;Y+W`q7j0p%finxT+uLAu`^$wzd=>qos;^b8kli zqXg0(p>^9U;?i#QWLC4K*b}UiPoO#yXvrt=6SRwMn47>-*kf`NSPJ`FZURf;NXt!N zDU2Ao2`q(?FE@duFoOHU+>^d5v}X`YVaAc0z;lCiZUXIMhT{`0rr#R$I`>bB3|I>D z;M@e(32C1=p~33l=yvIBfOc^ulbb*fk@ktR|IglF)El#<9%vWWqPYq55NStbXw+(4 zZR6faZVfDj9{NPBM<(glhSrs6X7@#w9rC=l!-6{@O8qu}l8%Sg4KtG$<$pS+PWaP( zjRPi7&ss|3RW*v#Ti%zQqKy5738d}sQ-bPFwdNmMJNN%Rp!p->PfR`J*!ODtr`PK6 zwYTGueVZ0+Id5O^_BHoL;8hl#8kfIGgW^X>^PrSMJzpa&&42qlMM(R^&+kss>))># zcNp}HZ7cE0*0!>TNLIPvf9kIe2h$GW;913GsDX9zi3*jBrl|ii&*SX7nGNJP+pGRHSI4hTE|Q#~ zd~{yC=C~lnQb<=Qa6M=yE2K4!*hM|0eFAHXv`?Hh>BO+vf{Dq`jfR!Yn0H&@B}4P# zZyE$Kwt`O_HTkTPCwrI0fA4UeR}Z9pqQb9?rWhX4E~lJxoH_lP51@8pirebkA%i8q z;KqRUJ`OIF+|8c-<)$f_S=f))R^|$rFAj)McOCutRd|a?>=%$3AI-U zBPxVmBA%ePO0_)n<(U42k8K`URlgE~HE3*#C8bRC(GYz?jy_mh6Bz<-1*Km8;l!~1 z+=+UB+cV0!Ry>X3t|57MCGm#<}SE^)U0GhIvpl(5{)IjK)PeZcygMTaJ=Pupk2(Il&VJd&!<^u{j?@!Tx(0187GTY>Qkz9ue{Y^)6tKV zVors$uQA}b@w#kv|8Pv}ymDL*V&BDHsnn$r5<#eOjr< z|6ZiOKX`Rm=b9OOmCUVDkw8mIH9hZKUG(=Bx_Jzmu2FR)7zs45@?Bf$+0uz z4GTu=IjxQ=Cqi~7cwZFl;;gOISh^}oS4Z`!lWG)NTa^j4q*Tox?~8^|J-9Ug*m|Ib z{XJV!>caEuB>xz7sb03BUODyKfO`smf}UU&rPS~BSI0k%FVgi3e=R_DB+!ylXIyk{ z@|O=<=r7_Q%BbH;PhkzTiy0@KbIOi~HtM0T{P3d!w1os(QtBUf4o>QSwKx3omilGX zL)__J`-HtAOx z)Ud~I_0q9Vy#C_O(neFq>8IO_2yssJOQqg2&6fBlBYl?%TMzy%AKOy+dzD#6IpUL) z1z3VhpD&aaIj}`Bf3P0$zv=ZN+lok_C7-x-%qu}bzelq263icb0&SruxHc3b zlX97);k1=<6`9W(mO|Pm&?}^~h*W}VUOe*S;D-SVq#o!yW;MRXjmNGIF1R2iP!DOJ zIA`TMLEkU_EgDE?5mkDHbZ&zErCLVZR_HrsYQ}u(TvB}ar`)<(1X`++kb0m7TJnj7 z$8HD?3`lzkwlvZ{VQh&8(zyxTv%=c)Xky!T%v+sIf;B_}E!om?RX?k(Y)hN-A#Lar zEn2@Byzs{&`2wF4LBQMt{z6cgMV>@m}RJ#rCP${wfvs%NK> zN!{1q4+_+(aBFPHJAroXaoSc` zb7NO}BA2qQfO_0YX&m7rOMq8G|34AZGb~YY2J656epEa$cPF`tMnES2RIBcww_ohx{)CK@>V!^KOW=l4SIU{B7e~j0E%<3lN+T8dVUY?b<5Ct&1AG z9^AQOrqmo;L8cMMHs*}{i_v-hvUy1*F*r+5P(zw77QV%SJv|kVO z9rci=tKnzA5*{Fp=Z7>dLk+BxPhdS-jr*8;hSY;s!ZcQ-9==!o4)jS%sjYr#Iy~PH zQV%SJv|kVO9rch_iq3h==X}odJ4#Ul>*Nzy4_wjXy4LsVl^@0@+snGgM~q$CzT@#5 zBpPsk#ZpMSdSv*V8zMdD>Apr*yE%dmG6~ieY1C8d%Dej}chVTV`I)ID=oPktPdr;( zl=R%VN+N^xm+N7VIbPvfT_Rj!B3#CnVgmK-@0q6YvFo*Xs;kV5TxZP?0O3pdj z#nnAsOD!6gw79ifSpAG`0sBjPGHEX{dqAv*G+oW0e)UqOf&TaB^Gi_!X`jf{?GQE? zJwbQ+{{4LJ)wJU!8t4hG?&(?)jlp$?jnXySTwI0(>LIPv?&kG$=P7;l59>BYNT6NZ z51?yz-TLZgjT-1Vr*_Wgm_a*t;uV&{nL(*B6ya(NDbn|?%9J93dPuuSt)uU+Xpgf2 z(!Pe7KX6tH_#EIYV=PHOcCkIYsn*W+AB=t_n6h=Y5IC10O;=2+P0;TI=^TXwma@mJ z?dsuX9NxL(PtX%nC*##JnsL_AjI(WbI^$RZ?IJC)#G5~O@0B&su4!qbVP}JnX*S^6 zS`8#PqFPIIU9D1V=e<|fK)a@o84Vk$S5l-#TS#!UvzC;q9Cvv~m^IL@87oG^M$wxn zilQwfIIdVrbg_eC;vv+!zl=#^BJa1e2HG`|!D!fcHIU*J+CqZkinZjT55}vs9uP$_ zK1%MBQ0^mr7j2;@_L#j@Y9K|?JC@|>Io+$}A9~D&p!!E?-$lC^kLl6Zuf`|ky?TUg zhSn@aTS%ZKidQs8tsh*Z55MoUf~SX3OniT))C29}Y^PNIoIXjNBM#MLN0yeNEhNyA zQXkQLzJuab$ES3`_7!QC!8Js?m>JMr7T+ZC#(tx8qd{RA+Cl;?(RF6ZeIBB?`^c5s z+P6A!bx`nmS`V~~V_vBx>sE&!_bJkIdcRnTwva$eN{zUvuU=8Rfqv(lp(XeU+Qo?B zW=@%Fc~vww{9SrnwKK1X?&|$(#Pbra!jyWVxJVD%xGL=>W);V6g{6>Is+?j;*YfV+ z8tUz4T@y3mt->m=2gxJ;$t36%YTzo2+KTe_VJ2@!jVcJyPOYn3! z0#kF*u=S{{N4o~puNG0B*lG3rQY6qWdh5KBn)7;@YAZFL`aq}Xn}>gvn)~$_S+_$> z89-9|r}y&>AzooAq@9M;+^CBN>LIPvTpEMhD5qZ2{^Bz97fYeGufaRb7xYZe;LpCT8aT}^bNO#efgalSi#cq!UK0xc=^b-J$A3x_u@ zFndd)fp&Rp+TAv#ex{7-^DBR1o!Q|;`2!VF} zduD9j{w(z?w1os(qVYk!{R8sqLF!kghl>W<_3yGdFC9_IUg}q93kkH8j#|5yVMeNG zpj|VX&2FuYSAD4`qAeuQl8ZheM@MUmTh|`jcxC4m7vZGuqAeusaoVqpS9 zZX({aIjH?*+E(a^Sru2|6%we2wC@!XXxFU5tI#mtMjM27nn5~zo?Bj~^<&@S%#`Goln8Sx5B;l7_EGOS^~n@9-s5NSuyf%^_2A&|}@ z$Ugu0V-P*T5uBDy|Mm&26Vgfzsxv_!@gU{x^kc^z-+^t9Ij&&Or}=!}cs*xNxA4p< z-?ryZ==-nao^6aPNYhRcX|#Rte3{jdz*6>@wdvb>Huu%9pPiSyeC4e6Y?sFee}bOi z=t{jBx2Id&eag2bNT6M${kFnUG_%p`!5MemA?L=|sQzM}zT}R+$&b5>^SMPimatb? z3TdT=_vove9NHkcf5G%pB+x^oeXp(`wk|k$QtHWXrSAmKwZ2`v@-@!8r$<=#%kjzk zpD)hm@1tUZy~0vR`x;nt)I*xG*QWJ#hdKR{8q=4Tq6XH$JP zSBrgTuh0|JqxHwtokByDB7u5H)2>0&`biJ+YTEtF^ZDDp_^h!8+Qs_O6Fm3yi1Vne ze%i9Q6baNrns(KC^i2+@GdO#}^n4zvJR7hE+Qn$66!ns%AN7(wyNgSaKs}_D+P`mn z^4;!k@j4n&96xyGWDT^7(N3w^oBJkae3T%8dPvi^k<^)xEP5avgVq*n*kc~&7`v$N z5;6S&i3}NAiV4)Szh_!TEqkST)UrB#kC)T~?P9c3Y9H17V2ULxXw)KM?OHvKF{uXi z-b~tq{U~a_?JX;!(vx9yK04jeSI?tS%k56zS|?tiCrHbvO=#3=9<@lIhe(S*&MWhs zaN>#iMmah5H6EJLBX08Lc>U{Zi}Sh1(Ra{^S6B+^w9Zx49QBY^>R}omJ?He(L!Mk- ziW*oapD<%k^Qh&qM&G3;UZE$bC!?0fITNKwpdQlntPI5xOX?4ElyY(LlR6 zU(r>v89lLD$oR@11}JZd?<()U1$2HM5>N~vZP+dHSdq!bC%Lt4fl z&r#glOK?_0+SjN!hZ%k6%+jFAm&M{0&QUlsRFvlo0H47^J*0gCpA5rNsGXZYJ*0gC zZK3ZtGvp?)6rVvmcjYFq6!$ATulPjEsqY4tw7l5$U0aHKyPYL+6IiGJod(*)80>3& zas8&?q^9W;ZdeKW1?-JuYqYa8}#GgXw$8{_@Sb;Mp(sm9qwxLOQnw*2yRSNV>*7;vI#_{_&m$mcsh^ z8r=J6{UL32#FS0JZ!7b%+D)l8JG;ld_IHdvc+_bWay_tpkoGmucho~#sfU&w7r*wG zvho&-C)#?52Kw$36)JAOM103@Z1uew_Ikhg;;%l9ZvX5Sz3c6g;Mn)B3%DLw3h4?3 z?up#{C_@$vv)amPH=p1hP7zs3A&q)I!J~-cxe!R_CU~UM%pwHRxe1N{w7L@l>D&aK zHKcvwwOd-n2fsBpI=OU$*SeW2 zTB!+L>&6c?IX*7Fc)UL6v6;cRZyuL(j&||eVwF0iY4v!-gzeF(mrwKv>@i5w8fW8= z(Z(*<#kV#etD8+eJE*<$P0>KR{1p!h9=vuy`?xhZfp9j(7wjSFaH>1fm!saHtnChqOiCR+T+PojZzZsI?SPmQkc z{+kd;=O(`Ty%j%KAm7-FbZ!E_2^eXghzs+BckVwreru8RMAy1>2Hn~8iHg?BX!|{x zJf~7-8Bx|Rb@IdgNc+SWqeet?m!@YB^^o=n>`O@d#Ksjb1&dnd#bYN)EO9lbG3Z*_Cn{9@)};(N zqO4z9*Ke!M-?a^wJn>m{B0I;`4#6 zOBr%RS-*JYYb<~6u<(giH$`*z_!?LW>D(HWEk%@(OAhA~^PBYu=aqGe#?P0$B%=IE zW*IDnv{GA7YZcDFZEo~iG=Z}WM_{`lo!cwQuec}5`#*dQ%KAde`pQk#=QOYs(z!J# z--#%Dm9>aZQ1%*9_F8DNSMkJTug)u^=?T!JYuGd1QONGANTgiWPPq4NYi(u+|nwfOeQdyj3Z22Nu7KR^orvLeSdq*?L&D&MDHOGuY3*4 zeL~880+ahV4J?Ipg+k>qh%reWPjOc~p1Z@@+*#gP zFf)Lh8>D?=$$yG?cFytyX(2K!z#9CG_>{>AfpyB#a0GuNKIJ7sAe}{!M5@tne}B$P zgg`nsQMbzo&P#+qIyZqeN7^SSdkrXi4Ndmy&WD*lvd#@x!TzM*zr){6#p8o=!xi*C z1@X{7gOu+El<$Tn-{o9H>|!aT#eODL$!N}fC}$A6Cif9Nq^(E%ukRI>LRyH7{9UQ< zq8`#pQ5GIh79N@`+||Qm09kcPt<&G6<9kI}SU_)*kUIG_r@TF)ygf8|d!cPBEQNHc zL3w*<@^(jfsYcCBquHhfMj7+q3q)qU<%M>@_smYhYs{mO|RE2l|eBNYlH7 zR=gBZo*0@u(P@~qn$*K5DC>(U>kCZQ7uZ=1J)vC7?G#Ja7gN?3n5@qcX3Z%YNGnA- zTueD!U~)J|pk2zA+`g|;l##`hkp(6r3v32}r6><_JFJqC#gvf+CL?o%S#66~NV}{0 ze8oLu*Zq9`%pP-G!My=@RX?Vy`u1u@z=XMi5io(YyQ)w7gi4v6Mj^12J$Baz-4zpa ztw0F$1owd4RsE2z>f8GOJPo#sv|N4VYxJ6~(c3HTLZDsTHFDSJ`D&lNsxJh3h%`M> zm0oezbj96X4Hp9K;y#nRey-{IxxGd>`8aMf=y)%ryupg?4dg%3VK~Yj;SPD<)aA zyMC_e`nkOtE~U^e?q#{_=bEmc+bixupdQlh`Z-^Tvsc4~K)bki=B}S>x_)l2xC>#f zv1HNi`gus#&+XN4DTQ`%ht*v_mn+rgDv1#0x=I%9uAfV9x3;+V*<&6b<~p~G6?grd z$Dl$DB(25C+Qk^`u2d(>X?&n9BsgC2*-SO)ZV`^V z$-{JC27ZEeF@n?cwRFeU+VpObjLqoTmObX)j;kel7J%*wyO8d`I{E%@OZXGcESbP; z8EK~>BMJ#DWslQ(@JLF3+-h4gR^D5pcYDdP@0GcaOs>(hCu;^A6tgWXg|xNL|N0t8 z;O>r6zf#T5qI+2Gr7?&a=sVK6HF&>_-Z++3C&~bp<>?}t)fR0oF6A}HQ)kwadZ6z} z)7|6LuUgO@5PhGYo{t22h;(kRcz>7PY9?O!8aNN~+NoP!ZSe|AA+6LRy7!|i-TSfa zw&nRqpod8NUh)6zs)+ZHS&w_7uVKcy+>v75sU}`wDWrW3b8f{h>LKmVwWxu0@`(x+ zKX2!qZ9bb^58tbWboUOo)oXVzFEwwIlX_q&q?Kw%cel}h*1j+0z%VuoTjih0`5$C3N>r-W{{rBY_?wEje{!@07K+IF{IBZYx~lIzlo4 z)Ih=>rxDJ0l}zb9tAy2ghlM{uySR5EaX0BjardO5-?m2r?IKOzAVBBia=Jh9(vOQv zx!rm9gEi1D?zT{-Pv`u2nxj4}ot}>xNT4O9{!MqcHKO}0cWzr;$~}(vWLN|3;{FV+ zQmMDMqkB1zov}P0Z6Se{==;Lye$ju?9j3MD&NCisyi>#)Xcu>Mgov3q(B$cSw1os( z60bCS)ranT<+#NASFC|{aSzDdtCkG?VsSp&LIN$hd)1N|&rdJqh|GI^tbulM7L_xo z`3zpLxi}wfA%T|My=uwjC(UY)pP*fyqwK8hW@qlZHUkLRD>JKw+}jOda-WKE>t;?V zg@l=XDdb^!*ruI%}97~uennk<$LwdWl#Txe5 z&N%i>xQ^gat4!1vyGYn$wxrZNng>_V+Mxa&>5N0OzKkd{Uy1MRp?!C*jM{|q-I(TD znQ<(Ec9E9sl{0{ZG60!zDBlqcw974R-?mH7RHs=+^0}FDtOgQ%HmxO>`y@lnj6=Dh zXrNv0G4}nul8bVFm7H#79BT^+?pM}QMSO#`fwT|zb}q%|!`Hx7DvtwJ=XS?ZNV|QX zgjcDkjs#lD?G=x6t`mFZYfxs%S$OjKZRxDW?ap3dDWu(wSF)3yF+p`CI1*V)xxK>J z?rRK4S1d_CGY@i)W3R9j(vn&7swi1&=0U5D1V>S8$;}3`62?!^F3v<;k2GKBBfB=> zH=o#JZe4#pXoyS>Le7UJ*bcpK-8Q^J{ItlF)6Zch1Zq?i4{Ko?Q#)<{O`FGwf zUZE%Eih%K|!5w+Yf*)>;m;BjH|9kJtL5q=ng}^!?O^rWjOT6a5-1y8J`g%Vg z7wkW4pk2IgO{p2B@5htsHA%WRZbSX5Z@~UDfgU2Q)Ul(6#K*q0CtfpsfTw}9PjFvd zdey1P$6=uPn9nt9peN?4oH-vKyxA;%xm&{|GoqKKep|@rnhC5E(n_8EXBaIQSvxti z$7P-d(mt`|iqpbN1XcryN_FDvpN6<@(o5mU{q>VO zCw1V~jcn_pU2{d*5HlzKHJo{s&mig{E$1WT^YIp)57a=~Cun?V7$1=x zALt47UA|w#cr~HrlVRVY~Mvaq^0kMw(nADr-8Ijyw~zjJ?@!l@t<{N z3`X3a_?)9BG|u_{8MyN7+M_+HOuh+b>R_2fD>!0@GE{_1)B1*Mxe|+-Tt;2)mOFQdV zo?IQA@X&#BCQK=rOE79H_1}a0Bz2e93{O6&zDHmw)TZkyWBVi*EgBj>{d^5e6oQ7F z8y*3+)s@6WsbvvUkx3=~OwCmTS;H37+yU#uw*X??gN1$CEm$tvr_hr1;Ht99y z&$z>b2f{two(Mi^^7nwf!crK6sUyxlDfuRTD*kf&>7E7>Xo<4d?zI#C^Tha;8b3k1 z7=x8!kJvNzialbAy~0vl2iD}?L%TR+pZ`2wNdpPAq*Rk`55>FM9hWq(eYVC=&@P_~ zZo5>2&mNyeK7-Ul3c07SS6GVs6rYonc!9oK{jSH)N?wSYdm2cfC8ekrM%){@C*mi* z-HLgIzIFfM*#Y->?(H0%xp%Nv7^#VNF<&X_w=wr$?z^aggl~yz9zxB_ZOzdx)yYM0 z%9gI%8F2sog8DAnLV~oNC8em}hTMO-@8TzDm(GowSEQGO&`ToQORyBiV5O+vhTMO- z@1h10)EAs3>ATwYUHk;?VholMrC~%x+_(6AU@7XiE`m$n)wb`V1`<>^XNlet)9yIU z{g?YLeu8!}221qO5Pc#(@9Y(pqJHZlxKh+_HTPfcyQqN#^#f-~qNwKnYoe(81npwf zmJC@_h8&m-nbmEqbu$CTe0tMg_r98Yyov2nitB-Pjh#w*HuIQI!n-tGv~ zce7}vC~prbZ`USo=a?a-(5}f#jRxiIA?5Abt>ZE{hkfrOdojaM|6hdig7T-0fxU5qRA?UZRo zrcEx&d6d|~QW#h0`}*kpJ~F4Lxv0}X!sJB8D_#*%E~-r~>NI@26>&v!(THbg$VH8< zic%OQBo_@S7u6;gbs8A2_?Y_~_XVjrXW_Qyg|_Bsm+Iu=isYgZ<)RvLQL%*t=R?+# zg)B(S-Z2 z$wi$85_I;QC8a+8+t{T2)YHQyUv&;YylG`H;)r@t%|6e?ygK6k#C_@Acixd>{=HJC z9(7Cdee34&oYCin##UkFQb;S+u-U|9{)er@U6YS5n>1!+Ft}R1=$b#Ci&4+lxUBia zWMOIRkUg-UFoCrFed<*g(pdFjYgx@1y8(YgoV%i#-Er%JlcQN$8Khf8g_l_kKPv zSiWeQoDb|{NYnezRj=g6t>1_5of~;xA?*{NU-ET)bG6}mWSeix-+iZN@SlM%hz5>r z)Klt@8=EBCj{K{he)0Mc?IP_H6ZahxKTc11*ZB7GsP4J<6kh%O8qwf0YGV}Y(S67- z&Wpc3?^4}n+Ls~PMcOAwBLt0dtHI-hTGhnC3O&|VYW+9Ebi0$k3DGVcJDST_50#>} z3Zbnc+g4OtH#7KpRFBZs1MO0s9PJZ)zTuol_MFpMi&%$87wXCR(DrK*D=XqWo2qkV!RgQmz3&ZEdcV@+0yJaV`-xm8&M z^^~G9s7GvX75+?P5bYxE6BMsB#jDuFEA~XjIcgwH&wrHPplQ^`JZgj z#S%@igriT!+A{IO)d{_&J2RV4)D*8I`cRCDD8dDm3A9At!$KPWqIk83Vj`;BQrvE6 zNvR_i57JY9I}n~X_v-SZD_2GrOm$Jzoew-ubk9WHx58l!^Mc~Mk;!3Ct%hsr#26}>HlkR8ul!&Wt(3eynQiufVA*ua!~{v`b#O2(Hx8 zt*6Dkt{$s{hyGcJ1nMEJ)YPNb#|uw65I%ZM$7I-~X~CV<=i9b&cBysUOhivFU;atF zrr>J5^t`bAp{6~9l6%r~j(WaVd#5!_Hh$S#&$@I}A!;D)6SJ2MO4c7Z5H8(SSQhM= z7qq)K?Iq|5^~Au&F{OT});4*(W?Mb@^{)z$Ks}^st}Pps?E3ORIOkti7GP$9w6Bq# zb^be}adg^I%OeWMN=5m~1eU^{pPRr^*z$;VLuiklX8ANkU&em2A#Et z&beryUF^rc2AzY5`c)QzmV5%$Q3EacUQrJ(r!goR=n3|GUxWHC{4*%XKXxs%f*NRt2pe3I`btKS| z%+B%9hItXs&L+x8{(*LVuV{8oXm*ajr`Z_^w2QRNwF%9&3D31A_K601h_qxGN#?f$ zaYxEBPy=b7pxHSYx2IE5Z(disVo5VH=wqlSb8Sp>Z8BU9DKt@E2<&5cW|g|_t`ic< zGLi{@)#d03(mpZnqh@6^*CwCQTx;e#(ZJD#dbIwiyCkNZA?bX~4!bH60%@P1xi+M^ zHu)#bwN#2%5JF%yKt1Ut8Oj+F&Kb}y(mwIv<)4H!*CssIQf+w!AsQHoP)~A(kaC9P z7s?sXF48_hv$NjtW$)xBnw_x}##+>qxmMF$oA6vq=Y!WA;uS`1q-pj$dVNS)M$B0T zY9Q?sZOaB}nw{f^Xm+Na=rVm8Q7*qmJ-QQc*&t0hL(Dk?+C|zY%o-==HI7-!1iVT? z0xi*18CplR8u(S*l2-Ic;K~ANw^mDd?QGU$qJeg?MPv_v*MrIHvLD#_XI^tA zXVKc(tSv)M3(0FXdEq|*pTYv+X5&ip@GKZyp~rDM)_r7!TcJ6WG6ya#{; z>LKm+0Bk*Yug_{YyW|z;r4<^y&mbCP*Ab}adu8@A?D^ocXxqx!rPk$q*Jzmi5@{=H zA4i~`?-li{gx1csU-3SiXrNu{C7it)4L;xe=Q%p(?2#o<4{7O%3HQWvs3&qeu{UNF z?`U6x+9bp6!nr8EN3p6WnbSMT)6yw{Z+FCJk@5LqDW6Fx`Zf~tW=gh&dPt{bErD+% z#qSxw=k|Sq-z8$-Gm6i@pFnl=9lw7-h)l|5G*tgE&6WQ1+jd>Y|8O?9FvG2k~IyZs69qB3w63b|OiXWdWM-P3k&=aJqBt!$B zyvL{QQO{{)d4+Tqkx99X=J(*(_w8cDK@X*@Bd{Jw=O*|qI`)0L7`sp}^`|PYkj^5U zSLQuoF~>ynM2#GqCvD`|*D!DT$|{9VZ3^KukU+iM8s=?sqG6u3lVkG?MHOC|H(5no z5A)oe93$=50|_jJ+CE|4KbPf+c^0G!ugsh9yY6YR%Q))5>z?VB*MPFX}M zVdAcRKPS?;2_EP4ZsL&r#pf=uR~qvWcj-;TLLi-+z~0Vr*V0uIB$mcq`_wN!y^0?C zUZE!(qbyw|AsYA$FFrYodQKzDE2OiCOvhNarT1XI4e@HX0$2&P|~2Nc+V90FmIe9smFU literal 0 HcmV?d00001 diff --git a/wam_description/xacro/.wam_j1.urdf.xacro.swo b/wam_description/xacro/.wam_j1.urdf.xacro.swo new file mode 100644 index 0000000000000000000000000000000000000000..c20cc44b5015db357a8c3c15572928edd753427e GIT binary patch literal 12288 zcmeI2zmFS56vroNNC*K01rmzHu+ZM_+RmMm)7mK_5h4*GK>|V))_6U(=e)m|ojuzJ z2?YX)hK7;`rJ{fiB>n`1geW02)C7qV2~ogzW_NvF=f@$ah-Rg)cm3wg%$v`9JJ#uD z=)ZRP3hlZbg6nZYe)onie|-E~a`S0IW?8JQM_#jK#Ix{7H*y05dNR$uIg1Cmh|PV( z^H7RRi8S#RER?CS?zP-Pj>fLB96hr2ummiD`w}SBc*M84A&(bHKxOU$z zw$T!>1S|ndz!IGgdB*~=2J1S|nd zz!Is!&LPNp)@GZ6Yj?PRH3nGo02TaW0B`LaM*{JzJfSasl1xXw+enS zO>)H&)o%sf-OR-FKo=fPSt3Ffy~0ODsLwB&E_X54UG`FuD4MXC_Z)o$a<4ToCWm^f zNLZ)}hF~f;xR@YTF2Q>IR4p@%mC5#?3MY@@KjM-1s))0QUtL?Q)0}yI9H*iKJSLzz z8ju++5w8eyI%07ql1a~L`M$G?7aoy_g`!b9=d$N)wcQ z-g=@5Ph+m+@^G?MTg>w*9gB#U)t<3%#wL8%yW_~OcI4(naLdhA%6xM_oXr)Fr zP2}~&&5B;Fvm&tyrddCz4~%WrWokzkTw`$na|f`%+ZTC()R1~q6Uatx8f_Q_ud$pA z8Q{6yZA@8zXuxX~YKE$_T&?Mngq?0vmuyCyaUn(G^R@5>`{lcs#To;L%t&@&A(= zSr56&S)S8<78SZ+k=~u|&N+NE3N~o21lwgYYt(JIaRlb1d-+?{Y^K>=H#Swcql@o6+W}^HJG@UNMA6u~0TR} + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + wam + wam_control_gazebo/RobotSimWam + 0.001 + + + + + diff --git a/wam_description/xacro/wam_base.urdf.xacro b/wam_description/xacro/wam_base.urdf.xacro new file mode 100644 index 0000000..3091252 --- /dev/null +++ b/wam_description/xacro/wam_base.urdf.xacro @@ -0,0 +1,48 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + true + Gazebo/Grey + + + + + + + + + + + + + diff --git a/wam_description/xacro/wam_bhand.urdf.xacro b/wam_description/xacro/wam_bhand.urdf.xacro new file mode 100644 index 0000000..f9bec07 --- /dev/null +++ b/wam_description/xacro/wam_bhand.urdf.xacro @@ -0,0 +1,22 @@ + + + + + + + + + + + + + + + + + + diff --git a/wam_description/xacro/wam_j1.urdf.xacro b/wam_description/xacro/wam_j1.urdf.xacro new file mode 100644 index 0000000..556b2b7 --- /dev/null +++ b/wam_description/xacro/wam_j1.urdf.xacro @@ -0,0 +1,56 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + Gazebo/Grey + true + + + + + + + + + + + + + + + + + 1 + 1 + + + + + diff --git a/wam_description/xacro/wam_j2.urdf.xacro b/wam_description/xacro/wam_j2.urdf.xacro new file mode 100644 index 0000000..0e67dcc --- /dev/null +++ b/wam_description/xacro/wam_j2.urdf.xacro @@ -0,0 +1,56 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + Gazebo/Grey + true + + + + + + + + + + + + + + + + 1 + 1 + + + + + + diff --git a/wam_description/xacro/wam_j3.urdf.xacro b/wam_description/xacro/wam_j3.urdf.xacro new file mode 100644 index 0000000..40973a7 --- /dev/null +++ b/wam_description/xacro/wam_j3.urdf.xacro @@ -0,0 +1,56 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + Gazebo/Grey + true + + + + + + + + + + + + + + + + 1 + 1 + + + + + + diff --git a/wam_description/xacro/wam_j4.urdf.xacro b/wam_description/xacro/wam_j4.urdf.xacro new file mode 100644 index 0000000..c357a29 --- /dev/null +++ b/wam_description/xacro/wam_j4.urdf.xacro @@ -0,0 +1,56 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + Gazebo/Grey + true + + + + + + + + + + + + + + + + 1 + 1 + + + + + + diff --git a/wam_description/xacro/wam_j5.urdf.xacro b/wam_description/xacro/wam_j5.urdf.xacro new file mode 100644 index 0000000..8a31b40 --- /dev/null +++ b/wam_description/xacro/wam_j5.urdf.xacro @@ -0,0 +1,56 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + Gazebo/Grey + true + + + + + + + + + + + + + + + + 1 + 1 + + + + + + diff --git a/wam_description/xacro/wam_j6.urdf.xacro b/wam_description/xacro/wam_j6.urdf.xacro new file mode 100644 index 0000000..e40a5e1 --- /dev/null +++ b/wam_description/xacro/wam_j6.urdf.xacro @@ -0,0 +1,56 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + Gazebo/Grey + true + + + + + + + + + + + + + + + + 1 + 1 + + + + + + diff --git a/wam_description/xacro/wam_j7.urdf.xacro b/wam_description/xacro/wam_j7.urdf.xacro new file mode 100644 index 0000000..246a7a3 --- /dev/null +++ b/wam_description/xacro/wam_j7.urdf.xacro @@ -0,0 +1,56 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + Gazebo/Grey + true + + + + + + + + + + + + + + + + 1 + 1 + + + + + + diff --git a/wam_description/xacro/wam_table.urdf.xacro b/wam_description/xacro/wam_table.urdf.xacro new file mode 100644 index 0000000..ddb7493 --- /dev/null +++ b/wam_description/xacro/wam_table.urdf.xacro @@ -0,0 +1,30 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/wam_description/xacro/wam_tool_plate.urdf.xacro b/wam_description/xacro/wam_tool_plate.urdf.xacro new file mode 100644 index 0000000..1530ea9 --- /dev/null +++ b/wam_description/xacro/wam_tool_plate.urdf.xacro @@ -0,0 +1,45 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + Gazebo/Grey + true + + + + + + + + + + + + -- 2.12.0