From 43895cce314bff38af32a0c00046a19fcf7a7cef Mon Sep 17 00:00:00 2001 From: Salvatore Marcellini Date: Mon, 18 Sep 2023 23:43:04 +0200 Subject: [PATCH 1/3] new omnidirectional tilting multicopter model --- .gitignore | 1 + models/NDT_tilting/NDT_tilting.sdf.jinja | 1236 ++++++++++++++++++++++ models/NDT_tilting/meshes/arm.stl | Bin 0 -> 50684 bytes models/NDT_tilting/meshes/body.stl | Bin 0 -> 161084 bytes models/NDT_tilting/model.config | 11 + 5 files changed, 1248 insertions(+) create mode 100644 models/NDT_tilting/NDT_tilting.sdf.jinja create mode 100755 models/NDT_tilting/meshes/arm.stl create mode 100755 models/NDT_tilting/meshes/body.stl create mode 100644 models/NDT_tilting/model.config diff --git a/.gitignore b/.gitignore index 42b07155c1..0737a57b6f 100644 --- a/.gitignore +++ b/.gitignore @@ -31,3 +31,4 @@ models/standard_vtol_drop/standard_vtol_drop.sdf models/tailsitter/tailsitter.sdf models/advanced_plane/advanced_plane.sdf models/quadtailsitter/quadtailsitter.sdf +models/NDT_tilting/NDT_tilting.sdf diff --git a/models/NDT_tilting/NDT_tilting.sdf.jinja b/models/NDT_tilting/NDT_tilting.sdf.jinja new file mode 100644 index 0000000000..61b1a8a1a7 --- /dev/null +++ b/models/NDT_tilting/NDT_tilting.sdf.jinja @@ -0,0 +1,1236 @@ + + + + + + 0 0 0 0 0 0 + + + 0 0 0 0 0 0 + 2.5 + + 0.15 + 0.00 + 0.00 + 0.15 + 0.0 + 0.05 + + + + 0 0 0 0 0 0 + + + 1e-3 1e-3 1e-3 + model://NDT_tilting/meshes/body.stl + + + + + + 0.001 + 0 + + + + + + + + + 0 0 0 0 0 0 + + + 1e-3 1e-3 1e-3 + model://NDT_tilting/meshes/body.stl + + + + + + + 1 + + 0 + + + 0 0 0.05 0 0 0 + + 0 0 0 0 0 0 + 0.015 + + 1e-05 + 0 + 0 + 1e-05 + 0 + 1e-05 + + + + + /imu_link + base_link + + 1 0 0 + + 0 + 0 + 0 + 0 + + + 0 + 0 + + 1 + + + + + + 0 0 0 0 0 0 + + 0.0 0.0 0.0 0 0 0 + 0.4031180930624021 + + 0.001829 + 0 + 0 + 0.000448 + 0 + 0.001461 + + + + + + 1e-3 1e-3 1e-3 + model://NDT_tilting/meshes/arm.stl + + + + + + + + + + + + + + + 1e-3 1e-3 1e-3 + model://NDT_tilting/meshes/arm.stl + + + + + + + 1 + + 0 + + + + 0.14 0.15 0.05 0 0 0.785 + tilt_arm_2 + base_link + + 0.5 0.5 0 + + -2 + 2 + + + 1.0 + 0 + 0 + + 1 + + + + + 0 0 0 0 0 1.5 + + 0.0 0.0 0.0 0 0 0 + 0.4031180930624021 + + 0.001829 + 0 + 0 + 0.000448 + 0 + 0.001461 + + + + + + 1e-3 1e-3 1e-3 + model://NDT_tilting/meshes/arm.stl + + + + + + + + + + + + + + + 1e-3 1e-3 1e-3 + model://NDT_tilting/meshes/arm.stl + + + + + + + 1 + + 0 + + + + 0.14 0.15 0.05 0 0 0.785 + tilt_arm_3 + base_link + + -0.47 0.53 0 + + -2 + 2 + + + 1.0 + 0 + 0 + + 1 + + + + + 0 0 0 0 0 3.1415 + + 0.0 0.0 0.0 0 0 0 + 0.4031180930624021 + + 0.001829 + 0 + 0 + 0.000448 + 0 + 0.001461 + + + + + + 1e-3 1e-3 1e-3 + model://NDT_tilting/meshes/arm.stl + + + + + + + + + + + + + + + 1e-3 1e-3 1e-3 + model://NDT_tilting/meshes/arm.stl + + + + + + + 1 + + 0 + + + + 0.14 0.15 0.05 0 0 0.785 + tilt_arm_4 + base_link + + -0.5 -0.5 0 + + -2 + 2 + + + 1.0 + 0 + 0 + + 1 + + + + + 0 0 0 0 0 4.64 + + 0.0 0.0 0.0 0 0 0 + 0.4031180930624021 + + 0.001829 + 0 + 0 + 0.000448 + 0 + 0.001461 + + + + + + 1e-3 1e-3 1e-3 + model://NDT_tilting/meshes/arm.stl + + + + + + + + + + + + + + + 1e-3 1e-3 1e-3 + model://NDT_tilting/meshes/arm.stl + + + + + + + 1 + + 0 + + + + 0.14 0.15 0.05 0 0 0.785 + tilt_arm_1 + base_link + + 0.47 -0.53 0 + + -2 + 2 + + + 1.0 + 0 + 0 + + 1 + + + + + + 0.32 -0.36 0.11 0 0 0 + + 0 0 0 0 0 0 + 0.005 + + 9.75e-07 + 0 + 0 + 0.000273104 + 0 + 0.000274004 + + + + 0 0 0 0 0 0 + + + 0.005 + 0.128 + + + + + + + + + + + + + 0 0 0 0 0 0 + + + 1 1 1 + model://iris/meshes/iris_prop_ccw.dae + + + + + + + 1 + + + + rotor_1 + tilt_arm_1 + + 0 0 1 + + -1e+16 + 1e+16 + + + 0 + 0 + + 1 + + + + 0.32 -0.36 -0.035 0 0 0 + + 0 0 0 0 0 0 + 0.005 + + 9.75e-07 + 0 + 0 + 0.000273104 + 0 + 0.000274004 + + + + 0 0 0 0 0 0 + + + 0.005 + 0.128 + + + + + + + + + + + + + 0 0 0 0 0 0 + + + 1 1 1 + model://iris/meshes/iris_prop_cw.dae + + + + + + + 1 + + + + rotor_6 + tilt_arm_1 + + 0 0 1 + + -1e+16 + 1e+16 + + + 0 + 0 + + 1 + + + + + 0.327 0.35 0.115 0 0 0 + + 0 0 0 0 0 0 + 0.005 + + 9.75e-07 + 0 + 0 + 0.000273104 + 0 + 0.000274004 + + + + 0 0 0 0 0 0 + + + 0.005 + 0.128 + + + + + + + + + + + + + 0 0 0 0 0 0 + + + 1 1 1 + model://iris/meshes/iris_prop_cw.dae + + + + + + + 1 + + + + rotor_2 + tilt_arm_2 + + 0 0 1 + + -1e+16 + 1e+16 + + + 0 + 0 + + 1 + + + + 0.327 0.35 -0.035 0 0 0 + + 0 0 0 0 0 0 + 0.005 + + 9.75e-07 + 0 + 0 + 0.000273104 + 0 + 0.000274004 + + + + 0 0 0 0 0 0 + + + 0.005 + 0.128 + + + + + + + + + + + + + 0 0 0 0 0 0 + + + 1 1 1 + model://iris/meshes/iris_prop_ccw.dae + + + + + + + 1 + + + + rotor_5 + tilt_arm_2 + + 0 0 1 + + -1e+16 + 1e+16 + + + 0 + 0 + + 1 + + + + + -0.32 0.357 0.115 0 0 0 + + 0 0 0 0 0 0 + 0.005 + + 9.75e-07 + 0 + 0 + 0.000273104 + 0 + 0.000274004 + + + + 0 0 0 0 0 0 + + + 0.005 + 0.128 + + + + + + + + + + + + + 0 0 0 0 0 0 + + + 1 1 1 + model://iris/meshes/iris_prop_ccw.dae + + + + + + + 1 + + + + rotor_3 + tilt_arm_3 + + 0 0 1 + + -1e+16 + 1e+16 + + + 0 + 0 + + 1 + + + + -0.32 0.357 -0.035 0 0 0 + + 0 0 0 0 0 0 + 0.005 + + 9.75e-07 + 0 + 0 + 0.000273104 + 0 + 0.000274004 + + + + 0 0 0 0 0 0 + + + 0.005 + 0.128 + + + + + + + + + + + + + 0 0 0 0 0 0 + + + 1 1 1 + model://iris/meshes/iris_prop_cw.dae + + + + + + + 1 + + + + rotor_8 + tilt_arm_3 + + 0 0 1 + + -1e+16 + 1e+16 + + + 0 + 0 + + 1 + + + + + -0.328 -0.350 0.115 0 0 0 0 0 0 + + 0 0 0 0 0 0 + 0.005 + + 9.75e-07 + 0 + 0 + 0.000273104 + 0 + 0.000274004 + + + + 0 0 0 0 0 0 + + + 0.005 + 0.128 + + + + + + + + + + + + + 0 0 0 0 0 0 + + + 1 1 1 + model://iris/meshes/iris_prop_cw.dae + + + + + + + 1 + + + + rotor_4 + tilt_arm_4 + + 0 0 1 + + -1e+16 + 1e+16 + + + 0 + 0 + + 1 + + + + -0.328 -0.350 -0.035 0 0 0 0 0 0 + + 0 0 0 0 0 0 + 0.005 + + 9.75e-07 + 0 + 0 + 0.000273104 + 0 + 0.000274004 + + + + 0 0 0 0 0 0 + + + 0.005 + 0.128 + + + + + + + + + + + + + 0 0 0 0 0 0 + + + 1 1 1 + model://iris/meshes/iris_prop_ccw.dae + + + + + + + 1 + + + + rotor_7 + tilt_arm_4 + + 0 0 1 + + -1e+16 + 1e+16 + + + 0 + 0 + + 1 + + + + + + + base_link + 10 + + + + rotor_1_joint + rotor_1 + ccw + 0.0125 + 0.025 + 1100 + 9.84e-06 + 0.09 + /gazebo/command/motor_speed + 0 + 0.000175 + 1e-06 + /motor_speed/0 + 10 + + + + rotor_6_joint + rotor_6 + cw + 0.0125 + 0.025 + 1100 + 9.84e-06 + 0.09 + /gazebo/command/motor_speed + 5 + 0.000175 + 1e-06 + /motor_speed/5 + 10 + + + + rotor_2_joint + rotor_2 + cw + 0.0125 + 0.025 + 1100 + 9.84e-06 + 0.09 + /gazebo/command/motor_speed + 1 + 0.000175 + 1e-06 + /motor_speed/1 + 10 + + + + rotor_5_joint + rotor_5 + ccw + 0.0125 + 0.025 + 1100 + 9.84e-06 + 0.09 + /gazebo/command/motor_speed + 4 + 0.000175 + 1e-06 + /motor_speed/4 + 10 + + + + rotor_3_joint + rotor_3 + ccw + 0.0125 + 0.025 + 1100 + 9.84e-06 + 0.09 + /gazebo/command/motor_speed + 2 + 0.000175 + 1e-06 + /motor_speed/2 + 10 + + + + rotor_8_joint + rotor_8 + cw + 0.0125 + 0.025 + 1100 + 9.84e-06 + 0.09 + /gazebo/command/motor_speed + 7 + 0.000175 + 1e-06 + /motor_speed/7 + 10 + + + + rotor_4_joint + rotor_4 + cw + 0.0125 + 0.025 + 1100 + 9.84e-06 + 0.09 + /gazebo/command/motor_speed + 3 + 0.000175 + 1e-06 + /motor_speed/3 + 10 + + + + rotor_7_joint + rotor_7 + ccw + 0.0125 + 0.025 + 1100 + 9.84e-06 + 0.09 + /gazebo/command/motor_speed + 6 + 0.000175 + 1e-06 + /motor_speed/6 + 10 + + + model://gps + 0.05 0 0.04 0 0 0 + gps0 + + + gps0::link + base_link + + + + + + + 100 + 0.0004 + 6.4e-06 + 600 + /mag + + + + 50 + /baro + 0 + + + + /imu + /mag + /baro + INADDR_ANY + {{ mavlink_tcp_port }} + {{ mavlink_udp_port }} + {{ serial_enabled }} + {{ serial_device }} + {{ serial_baudrate }} + INADDR_ANY + 14550 + INADDR_ANY + 14540 + {{ hil_mode }} + 0 + 0 + 1 + 1 + 1 + /gazebo/command/motor_speed + + + 0 + 0 + 1000 + 0 + 100 + velocity + + + 1 + 0 + 1000 + 0 + 100 + velocity + + + 2 + 0 + 1000 + 0 + 100 + velocity + + + 3 + 0 + 1000 + 0 + 100 + velocity + + + 4 + 0 + 1000 + 0 + 100 + velocity + + + 5 + 0 + 1000 + 0 + 100 + velocity + + + 6 + 0 + 1000 + 0 + 100 + velocity + + + 7 + 0 + 1000 + 0 + 100 + velocity + + + + 8 + 0.0 + 1.57 + 0 + 0 + position + tilt_arm_1_joint + +

20

+ 0.0 + 0.5 + 0.0 + 0.0 + 2 + -2 +
+
+ + 9 + 0.0 + 1.57 + 0 + 0 + position + tilt_arm_2_joint + +

20

+ 0.0 + 0.5 + 0 + 0 + 2 + -2 +
+
+ + 10 + 0.0 + 1.57 + 0 + 0 + position + tilt_arm_3_joint + +

20

+ 0.0 + 0.5 + 0 + 0 + 2 + -2 +
+
+ + 11 + 0.0 + 1.57 + 0 + 0 + position + tilt_arm_4_joint + +

20

+ 0.0 + 0.5 + 0 + 0 + 2 + -2 +
+
+
+
+ 0 + + + /imu_link + /imu + 0.00018665 + 3.8785e-05 + 1000.0 + 0.0087 + 0.00186 + 0.006 + 300.0 + 0.196 + +
+
diff --git a/models/NDT_tilting/meshes/arm.stl b/models/NDT_tilting/meshes/arm.stl new file mode 100755 index 0000000000000000000000000000000000000000..943fde0e3020cea62dd7a63d6de59f86b4625f70 GIT binary patch literal 50684 zcmb822b2^=_qUfIW<`=Hs0i!=29h8!u+uUH29QCr7*T>Eh~N+fWCaPzioS~Eq_6=2 zU4$hJGA$~ivIfiwf?xtfiDE$ItJ^)*{q*kezW>j2_SnbYedcy|Ro%L`s%Grc_2x*8 z)?Kf!(Wp`VX7wA^Z`81P4b}1Hj-4|XEn0N4#{c&}$I7Iob^CCvm7jlFB2EAEarJ!l ze&uB5k?^ne zbL`7Od+2xN5mZtW;zPHfZQ7iKe_a&mH75uCiUgI^g!s^(Z%a>+_8{S37e#KnGY8{? z1eMf;_|WgkHe-;4e_a&$=h_@^GzSSPsR{9+ThErBBF{m>zm|BVpM&wrBdDY%;3J`3 zWRdW%-RCf|(z`2%kk2(rY69=71mV-k_E`UtAFt%?I)w9nl1geqd?Z`YmggYhU%UNk zX@BE`gtW6!QWN4M*%KWfB>Zc4d@R1o_#h$u)hMY6@sS)+jt>(4wL8wQFK2v^ka1^} z)P(p*Mh3?R3IE!}tEI{IAmPRjS4mAIeMn3cA891~Yd7wiyY-@|Lr5GnN@^nct|YdX zAbeUshn_#oTlZ!I_pYF%Cd7xt5$P$;bAa$a*PRDV?+FqzFBv5@AwKly%UtXDAmLvp z=W}m-kZ|VLq>`Et9}?G-Bg&o6lY~#Zd5Ia#LBh{>cDR{^Lz566GTS8MRhFMw9NOex z7i{vgnnRm{1eMf8flo+eKz?-ypIhMgbDsk~9KwH&QxW2W?}~(fU9ic2Z{mXlmDGgz zNZo>m@VNz>{MHm7B&hiQNQe*iT@wDaZV#_diw_c1QWN4s_bG1-lJKt!Hu1eMf;_&}siBjI1` z=kR6;@j-%0YC?QS9ML_+eGYtZdL9$tPWK1fhWO~6N3e30<3-RE$t zKKO75`COx1=nxVIjgp!WANt89wwEA$T0e)L zKg?SX5>!$X;zPHfSp&!-;a|J6n&~}3Lgpo-q$b3N?ulkCBa4K8ot)3T@j=3wUz18| zLVU=3lJ_O;LBhXw^AaMoCSG4;g#zKUub)SsV()L1s}7k!1)fe!MzVEW#xn z=znF|B>d>ZeD08YSDp_(2MIr}B#ERO_c_dy)5?Df#eGmA;m4KYK1k5YZ_VO9sF3jE zN^u_~Xyy0H;y$PZ2*j~qo0IUP&mkwjGNU=z=Ki?T?TpX$<4W=8AVDiXN)#v9m)I+v z_vX|I#R)1ToOb%31g+$~x%E|XA5=(4JN<8hR`TB53bMElDgh#pQwK&AK1*8De6GA{ zx85!8g9-_0r~ggR%56cDA>*zrf7I>>tXcWve}}H_NKo;|;ErOeQKusO$iTJt;y(PI z5&T@gzx_9YR(|^zC#aC{d+2{7Xyvzmae@j7zlZ)ef>wU}7bmC$2(Q2WH^T47JDjy} zv+@#bbH6X?_Q2=*J+!zF614JrVsV0fiM`T!Z_XT?B(mJTm1R*O;j}D?WM>Q#w37Gc z<`TtyP$3~L8z4L%Bxoh?&EL(?=2-6C>)x71Bz1C@aD79DzR)r{_M4|H0P3W-p`GS#r+{3LNfxe7UF ztz7Q-AVI6`V^^phqT?);YfC4!4)!32Algl2_Fe_q~uLmKNsZoHlcuD@xoIiPvsktuk|#Bz+{N&d;6L>@=q*@(F3R_xwV&^Woeiaow~rb(%hY zf%6J1)H`$I8*)mp4-m;_%G14 z!NB9=?6qfQw~~NDB{dXXxEs~6izyb>Q<-Wy=6d$xoZUDvER6%veNv1qKpowoITn)Sur zYuAyW)vKlEs2zVvgcBd{R=m?*QL&VD>F!u_DkK>BV$o{fwX+*vTHU%}U~C-;T5WDT zS9O~#F;RS!Ti4FMtb289YOPt#sgPi-j71N$ZfgIyrHR%1>zV6F(CX~z^VAdjB#MfU zqh*`g`p;4=)-EP?3JeutTsM$ta?qyEUU}6r>&<# z;^JHLREI({4;BvmD)WV>9<{c2E!Bbqt;#oBs;(Gs2yJa^YU8TtQ!N+=8Bu>-G*g{% zz>UGNXye-+wX;tAv~gzi+&C2y-STFtJGKZR?eTt_QFgEE`zLBHK0QQ&R!h&DrOI5G zrwNI>w@e#p52`&Z@$k_0aVjLLUN%eR?w0vOd_2)`u)U=A%EX^XA|VpA>Qp#ORqB$H z^s!*YAiGn|^@$6Ae=JUg#NVIHQmxJxLVUCs+S}fEbbn&fjFBM{w7UJ-*{WLJ;-rto zyL;J9@{c7p+&MQ+g~SYkte*Y$fTbZ4w7O&WT$NK`vW(8-LUzGj z4eU4bHpi)uC~eJC6}k%{KDO!4AEy0S@eLsowCd7szFIwGVe(ydf3l{1_m;Nyz9&DA zQz0>K(|k3gsu1GiIsKl7>-TkTI$8|E!BD4?FDHqNzjUQNh~_;k{`qCUg=}^ZIQNt3W;95URE7Cnej1S=Wi=? z9#^n7ttAOsv3iL`@3{SZYjoAFcH8UHHc%n)<-f0}A$lCTefMmgza3cH&b~O2){+FR zSntH5-8D+OMiUS4pInF{q!x($8Yoe72x z)U2&${?Kh<={B*y+?v*s1g%(w#iAAe>0_O>@B758&S@K{kjPoHT2+{8=0V-3EZw&f zvpz^`NrG0a;bPI35<{%+Bk~j9bxqqqg@ko`p&Hd&G5~p3dTdyFj3gfXD6J(4TCq0N z&oSi@>)80tiAZ-n&QUdzxbTfabxsFabrv6bj9U-sJnq(QdYprx6|2`+v{#dHR$-eL zHm=h?sE`=FuTX8W$D%^r2&}wNPh%uWs5OB0;O&uNJDF<;;rLD}Ri(8XjsAo^tZ9I2982 zjx1DLFMB2FV@;b;mYzexA5{DyM1ocsZ41?%+l7!E?#4@pTG1=#gd6;LG){%Y>$_L0 z&;K@c?TChht(mn~hD$%aBSeB$k1klPIxJk7^s%A!{np6tUxa`AZC{)UiJs@LR;%7H zb?wzdds_uZ_lIx4W?P5^t%hz|rLJ#p*5UR{ztw6r<_zn{`rpK@8*^2`JYW)JK_t= z`uMSW)*HXC43P*}J-kxA*4nJ~ef({GtJiNKYf<$L@fZ{mxwjUm&aKxbpW{>g`J=R- ze=l4RB0;M$XBMaxSwhHj{5Ykub^E&=t=Zdh;#5e?edA>{rLU=LXY2PgPQS0$?wK4S zL92g8zpOSsV^$zP8hJFl_nLdG+67O=sgRg_)(SPSi>Wyiy1hfX-J891dx!+B%6_z5 zZF$hFK;HB1+VDp|53=4F+&4~z#FA#qROQo6t(K$v?Nr@=Cx2fvM1oe8&snA(s$?p! za+4ko_g_2GD)m{tI297}J1teuj5R*)k@2U;;piXUX+eTk!Rjt|;hxM%4?b$mxp>=p zDkNAZ#-cw>tC)UM|GBmF+N-mx@9u^dY+_{a_uC}G-CwzK`tn^r*A#*Z3C6BibkgQZ z={rtqwYWGzD@N28A0!yNV$pu;+w{I4 z4wQ9Kn+gd=qTr4@6%vdqL4pbiMu{Lng#^cZkf1_>BiJF#&W}xngue^qw8x{j<-WhA zf~-0R2wHIj$D-eM?q2)j%(I;qq(Xw@F&1q*@Z8#OoN<9eP$9w5rPqC)np>;m%8Cv_ zg@nI@CC_oJ{NuF_wy9KtpjB|xPAp7+(T-Gh2r4AF=A<+IS#uY^yTQFHDkS{Z zFIlm;-0YGBt+;j;i*_7-`I7MZ^PRh*LV_!LvFO}-eU@}8JkuelknndJ<*p(l`Y&19 zwj@C-u1snl;YV{{eltHudI=R0TrZ79e|w^7&e<~tI(J2dgullscQxb5Yjc_&8c>3u z71w=rw$!gn&hKAzb_gmYxEih3knbOuvus~ehoC}&Yvek!Tr@Bz`m9S(A>r>}%X2(- z@9Nw)E`QsJJ|t+xwSK+(I^fLQPfFkK+!YlP+<}Nit8O?mxBfMK9D)i7ekw2(_$Nn%c%n_^+y>Lm zapouzwBj16-h*sjDYt!t$xEasQX#<=&sencnu@vaKReeUsF095biZ#PcUA6i`P@NA z&&v@XBxuDIPrU+J_3Ye--s#~GR7i0BG8U~p@66mEPWE;PDkPlNbWT&rT{VfXU9z>; zT&G`=pcU6IW6{T}T$p>!@~<5qR7h|&G8S#LqGIlMFYIv$DkP-myXUXuu8to(J@=Zt zlO+gRaWzsCpC8ECc42wvIjE4}+M?croUtcoT~0-Zph808ihCAI?rO#5Z|A&z*`*~2 zT5)Yr=M1@Xa;vp!>O2P(5?m>aMcaSVJ0~*vOveWm5)y;mvp8~BH?(VkAzpRJf1FPtv`l(}>)YBi-463JLDe z#iAEJla>4S-wjIK6|K167K^^xa!>Ae>%($3%BI2{Gy0B259RgAl|Lb-E_(`$o zt?j4eJn(+=5_d&{`&6;$rh$!eewvY4f}j<5onq0O&s?^oWB5jgpu&Bl;9ZTl>B%|` zx;*Bz2Ne?B5sF2t#2VK*yTK5L;QB7tVGotssDABl)-01nt^QY*O@#zkSamf~)IU8` z{cor5lAsmWOQp9Tul?TornSWf6|Q*llccx*Ui;+8aSlO+1lKa9x2L7Q{r4*+2wHJv zG8QfW)=fG0*0|SckAQ;JNcz^5*F&??<*)d=;%a2hoaL&;woS?2K5*j5^z;|A9U`E> z2iF;6Q9WYQ^~fzj(2A>uv8av;wRLoG2r69n3;2%e$WvQKpb|bva79m_dil@5+D+aa zQ-YusSM+qna?ba)c0D@LA*k@|NARxxeg3MvI;$>lA~h8fJZlnMlkvwvcEs=b*%5y? zGdp-r-=;#s-P$A*(G!`eQknr~nixX5x_`86`2`VJ~J-y-t6%zgqU2%d634gy$ zh|VAVmjCn4GwRCtphCjmJu6O7A>r?ZmAEVKJau-&KW(V5y|dND2`VJ~bA+-KEWWSG4j^x)mp= z_-ECM-&N+QaaN;d6E;3v_h{(rcMH{T6Q#l`3XJo;dY{w%t(PKwSKahJ=SzB@v+Aqc z<5bwM{25N}%F;d>H=B^T^Uu8@60{QE0|&}Jr})U$`<#pQKIcVMKZ;W!;m?WU{^PCje38jlip{!C2v!l3JHHk6(8Z>9=1N}_CmO8 z)uIpyTFoe0ty(sg3_yI0)B8m8^?uQ(cNfH|knrbS@$q?1KkHcf&hV7J>q8`HHRb3k zb@Z6*bBd3qdcSME-uFtho)@P=!k?+d$B)_Ft&IG$twuW*he*(B(Vkb;wXTO zZzubAS9X{fr$WM?=fy|WUnAD_N7Aha$4m{8pjD3rD^<QS z@zHX41*_ImwdOxBt7Q{p*HU~e(C=xYeqSHtZCp=wUU zAw*w&W@3mwGjZ<^N8=pZj1s~5<2F48(`=R4yXHuU3JDoE2jwQX5ET+KZZck%np1o%*JoI+)@N8={P#$l1g$uu#-c@f z4DL_gndtJt;Sd!PGHxFHN6zAij{ zAtB@DireH&k@z^M&lH`j&lEjf{z#kzt(bl2?*iyC*y2dK{lLycAu1$f+*sep*(mX` zOP`I>fA;1XhvOt@#hggTD?J9cjL)>!^ga}#LPEyP&)IUuOMINC&v@x)u`{Y2j+3Aj zGd2BP89fHq9q(jc{nNn^6%sOT)(n!fYT`q;g{9lXes%t#I0;%Ye~d-f=`mRGk9+M8 z?mrl!LPEw(=gD&BPJHM-6<(pw+&ysVp*RUzF{{<9YM&H@@3aQnbNBulqC#R-+A{Uj z*K&4He0;CZ4t}W54&FTfV4MW4m}|$PgLd=|Z=OENezxDQAu1&PuDVpU9AJDrtj|E+ zr_Vt4y!c?81g%&B=rb&NZ)KjpO`j&;^Gk>di8Jfusm3jhkEQx7XIFieGxW!{?Trt8E^6aseJ1tru%F`mEL!<%1LC97 zpjwGf){e1j?ED+2ShFJ}8nj)kD$F%LZqjFKSL?I28>=6{N!jcOt^8FA@iBSDe-gC@ z4720sq_w0%Vs>Bsy@`6JUrpC%goo-g!ZQ#2f)l^l5nB0cC*otN^oyYue04JBTBee2Ycf`jng=Ot2`){+uXa9@S(Lv(QL-SSU z?`8}>tz``R{8# z)8GCQC*rdswDMQ<#K)cWI@oJ2xyU}b^aq@}4-%#K%vJ;InE7Lveou17eOK=yob1nz z(8^z1be`k9yX~-bBJtDqFYxVwATjB{EY)$ld{a-JqoHo^)w^*Ee*%?x~FBs)SYe|1=V{Pe?EyXleA ziGu#~@vW2~@yn2z>ilu?T|)6OTgQ=CbUb><__$BU!__)2zPI^?cyYp5`K#*U<5&G0&5x80Pn~#6hzdVf-omKfa{5zz zjMZ^{oR04o?e7vNK`YkkI(yaaQEJy?;g3gj2~i;-t$Ftia+Xtke6Q!HLwcUd{&#O3s}nU}4-f9wJw%0s^vVhsni^-5o@XsR-*(&5Gfsk5TpNf**X!}o(K-?C z)2U~O3JDoqzr81?Kjk^z)cL|oI&TUxlH96z{{M~U9wBnjWEE?DGs#Vp-R_E$>hp3Q{XxHjZQ%4=t`J4W;){nS1 zPJ&ikv4};>%)iXOFylt6{onV5sF0ATUHgQoqx3V_`dO@<-TKB!(2DCCIwtD*WB&fz zthrzI2~i;-v(Ko1O&z7%!q#nK^=x>5oCK}75)z9h^gMW=$^%wp<$WP4BxFwf;~i5+ zg>_xndJbgf%1g*G^qF3nkeBN@vFw2_sK!^$nncF+|kh7f9uMX<^<~v>Ibp86l zI0;&DeI^#IrSp=X*N(BC>+xWS3JJ+kGV+X%M|GVxTGwlzEFBytK`X8x=}4{fs}4KI zS>g1-Au1#!*J`lV_$btCKK=FDPm5ah<0NS1uP0~gCoj}_V#c;dt$p*GhNzH`oH1jv z@v&O3`7F|FKLt~FuO~q(f5lsTOw#%8uIZz!D?Z!bf(i-AeLua>_>i-;AL_NAg-5Q% zN!jcOt%8+sfzI1USc9#p^}{%g8zfj$2hKn`zjEX53_>so)eH+fe{H(7z_Ai>Hzux}6`XvJp=-j%;EUld`L z%DWBvphALm^r;D2@tJ~m<)2|Fim>M7-3EP7A;GHn)C8^gOu@VI&wCU_SV8h`gFdK` zV2yiff>wN{;9dD=V~QfI2YI(aA5=)NVm&oMD?U?@@Xrwy1*$vVZIGbCdXV+!sR>%~ znTiqK>93+db;r965>!~-v6?(JK`TB}knqo^6$NTF|Abia$UueF9jnQp4-&NEGX)9% zEMHNe^5WeF2`a4BSR0<2pcS7fNciU-ivo2N?>0zKVdce2@6-gX_)I~&w8R4KgMAVG!o2kV_v6SR_Rzq;eh>9mLQdtGh|nwmr2 zh`HOK4=SuCSiPK@pcS7fNJ!sxf8opR?WTg@-3AFNtPNO;oSL8&pD9SlsC9qs%Z&`C z9^l;u2`bF=Sy`N#pcS7fNJva{e?`oVq9(iN-3AFN%-dNfoSL8&pQ#w({eM^78OP-6 zyxSl_g;_YW{!`;e$R%(2CDgjPQO%&do*5 z{weR)BlOJ$pF{FCLr6a7?~L*}_*t}){L0_wB*D*>%*ph8$z=UqWD-6G(eG)Ju{l#pDpu&}Z`gTqmX6Vy~C47+Z&)mw}mCqMH^5j%V1a|@C8RS`t z6SNAh>C1c4Cl2LYpGAeM^7QSTbK53YtPaKvYXcb&N*C!1#^oc_` z{b^C*nl*jv-%c3vWF7q{CuIZgiUe1q^;w*4Pt?gg+}ppsXWVvG`%c8AylyA;I%A&aVhs@=Jo+Nt#d8XzgF~oUQ!Yg8b&7A^gue6(KEnD#E9;BmTTn+y|A^ zL~$P^{Ojz9A9suUppu$M`fz@6QQj4MwSUdu`z=l|mZT<=>X#V7Ms-P333y@?ub zFOlbPdLk9Jjem`|D?aL`CbA>O_ls+;DCUC-KX=xc`6_t%|Uv=9u zOVxZk4C4AkseCFV4osM*`gNbJ4vo42#JDN7>QW(b@{_r$OSw7f*S%2?{kqi3r$XYJ zGv=yc+vcdFpLGTC^WwgBsgO9Y-W=6t|& zcve0Y62Cq)L-l!Jp*nJ94-h}T`F$=G60>GMuj1D&Qs-3c4C2IBZ|71W(P8^^b=t{A z>hinVgBV|b0D%>MeXh-P=Zika13hMCZhFDy{m9YUmju5TRjJ@~Mz0y8k&f zX~>JJ%kc&vUOBUFT`DAcWIm@(%zIJo=#>sa?urTt|C*6O16iqw8m-NLuf6bM`1s{O zoqQ_%TywW8&MXf?Ke_iDqL46eB>VT%K*)1YAz|Kn=7>MtdC-Yhg)>jfr$WNCY(nh= zp?gUN6%wZR?E7jv2;CDisE{x{v|9c)5W2V5r9#4tf@Y<+g3u$%8y}*OFeB~YrSE{y zqqa5`68;Egn|FOGGmiwVOvETx`KopO9E6Ud zUQ85)go&=T>hA%eBefTIMIm7#_+{rD2GOlyDKEB*Lc+`vJ6n`0))T3aFf-Af{bv;; zsE{zToy@^<>ZOUL|Ll*ZuiZ$6v*^;nQ&s+wiOJa+L?#sy=9ApH_Hgqi)~vQo>_)%8 z79eOfwdYi|dBa52x7?NbuBuL~Z+$efzI~$UlrR+%=K0*&`GxcATaD}1x2Ii_9Uy3R zqS92=Ep3uozFg+>mul6rzBs#fDmvG6ds6*VZnFA) zz>V@8cm5UbT=uU-r88StR7jY<>*fqoUpX3Xe%Z0a%MCIE1g+|KdqUNEeX^RmyQB6| zCx1)0VXG~P=X1MRR7jW+}hMGA;c2 z+0zpB`stG|P)L|@?&c-Wj~gGJbistg=rw}^1g)N$FpPT#qeO>*y{QY?{NYKj8nW+Br&{X52(x#1-R=t_I{pGP16%r=4ySdM@w@*uS z>RdKlRX+y_T0Qd04&wHhwb@xxJ!c<6@{L0M} z$8@c4-|*el)?^)bNziKSfh_fD-Di@q{kb0-*`Ic5Y|Z%M+AtLoCbx4l%WFqAv0ImG zV%6322MJo;{aKbeVm*_bqpE$_#C|R0R>D+Bm}@t)gpZA>2(dE0=l)qqk8?anf(k#^ zJd>M?;#~y@TA6p)wTsN>XpaOH5~gk3>=kVuAZTU!La7JRv=8(vn+gfj$J~4ueK$bR z%Jk_9br0&?2jj!0Lc)v{H$%o43=p(3V{>1tZ?zAMbDIhYGv?i#8nGlm(8|P^=cj+F zeIQ=hR7jZE?%GsHm>BHl?TGCGf>tKxpEE)7_RswJ!=^&Q z%q4E7k2xwp(8|nqNgw_^Xj36!=0rEs$6OmAXk}(?_g!H=x2cdYbGus`AZG{=v@+R; z+vdniY$_y7j^b7m$bA9?txOi>_Fd#xHWd;k*K+F*|?9O@)NXecc)dIdy^rtxR_A#zf@p2`VH^4)0b)s0{)HtxT2S#&*;n z2`VH^E#lTusBt!upcSj7K;@PB(hFtOSDOw+q+YuD{W9vg2M$GKEj0RUUDf`t>Ln|$ zjZ{dOPjc@{S6!CAGpW1+1g$FcsjDW}y+pZBuB$FfKfP352`VJ&)+nR4zjZj`zFl2) zS^5o2!O5|=5JzA& z=R}4&`OKxt?TNbTvUG2h%FCugVq5)E>dCy{BFXxEYI#fdc&WSs1g#dopRSH4E>rG^ z(p6Vjk1DCWY$_yvoqsYCzVDBSJ8E^+71kqHDz5-Rt6Oicty(v_T)B}!S6yKp9i;NI zsgUS5awz?x_*02dMQeLZa8;!;yaN$|!GE3+b6Hq${rgL95Y! zS67!lQ#a{DS6v(R>?xI(O@+jqWxqt;z3MdO&d$2(O6VC{Dz5-RtHbA4Q~6`ANWLpw zbtQBbAeEO*g~Ute?vHFbQBJv8hOW92I@6HKD?reyu+>HC`;J#7+gw*&37ySIZ;4u8LU)Z z0fJV8j#N@t&S{v8CA#Xeb(SoZmraF4s~dJj{aukvE|ph;1g$DptfU?v z)hHPgb=76-Y+ov`1Qims4}TLWd)B$ittNEUW$TJUDz5-RtKXiesFsv&oQ&aum! zB9&Ky3W*Nto5-PF=PI`<(p8tOD0|Dy0s3x$pp_W~?&=`Mhed^i87s-v4}S~>2wIuZ?5+-CoLf{#m@)6J;vkj; z2wIt_aGqV?pjnxm>BG?sv))q2wIt0!d)H2{9#cc zVdfHVbCFms~2%89u)K+wv}+U~o;d~Q)8Vdi#swH7%;fS{Gh zKHN4(USd%pVR96A)fu@@fS{GhqTIfV{K}$2!sJ@+>N#?_06{C04Z33xd7?#ygvl9` z=K%a%G(gbGWVLQALB4BIAz^Y~cQ*q$b(jRLOm^3GF65f z+fjdnsgN+Wh`YOl8YhzktynGT|A&Ir#L|CuV?C>}ChJuFVHJJ6pEHxOh6@r@NL2oH zh!toMGKrH7)&TZ_`-@30kqH z*1snMf(nUw69=o()$UK`KHm;4Z|Of<>1>Gvt+<+?*Wo}=A(7kTA@#?N{gXLdpP!C~ z^iWG?#Jj6_)fB|g*HD+yY0bte`jL4`#3mIKvI zeFr9U>Sx{=AJ%_~ES-gupcPlCVo?%QNL+OP18QRPLCM-+{5hwE^=S3ADpal%5J?YNB;D&jKDe^t+;9!i;|#1V(g@T>hg;pPWq5%kUNv- zAVDjxemc+L5mZPVo!v(*D>pRxuB0vG4NH5FpcPkfo%ZkuDkRpveXsiIt6|ADmp&yu zMfw#9T5&bn=~o^>g~Y1r_oxFCMkM>Lj1B4WGCoMqimU3*`0xlSB<_3ZZq@ww$mAH5 zF)kxl#yJUEad*HO=N>_Y#NaV^srt1aNyZY1RT6`cR8GRnQlhBta|V+nqT{P$6Obxdh%-U?+}N<{i2j00}B2%zJYQw0U5EkXEKIxS0$I zDkMz%y9D}fU}uz8rcb*W83`&ROh0xBjKRQuEv?MhbTdm5R7jZd=n{w}fqiFMnHb|{ z$RwzcFmc5t5EBFY=d?1h(#`ZqP$6OBqe~#R2hIV|%EWxPVj)3=go*Pmp=X?Q`IGbQ zBxq%3yOIPI5@x>g?#j%yfs-7xGIOx^kgNX&h`y(-mRrKqDw z(8}~mcXvs$F`1_%Bcnnh=h=4Z_X%xM)KMg8Wk#2~yChkq%u|wCQX$c^#!X5cZ=0fy zB0(z?CEVR5$&O{7k_?#&iLS$MP&X{PAw?ZUf>tKlxw}h}<;y%JnLZT~RTsBakH>CG zQAd%Wm5JK!?vhk1GEYgxLWRV%HA&_)oN0FeFnSERzVr>X2B*tuN zt!i}ZkfM$vK`S$hy6*~etxbi*kxwo4QtOT>>L?PlGTDIJ=ExarDkRpF3acM0bxKi3 zk)V~yYTUky+{dOuVr7q3YJZ}0iaLq}txR_2jzQ#bHWd$fCAz}P^v$Lrn!z5^B z-l3NPcmx#^=Dm4YhN*;fg@ozHUe;$; zCM*)PGGo)rEIon>2{RtO?A5HWSR`m=VvLs|dju5{Ca!o{xLGN(NYKi}N-xv*2r48@ zeDtabv*Klupp}XFUd7@OR7jXOU$QD9K`S$Nl_aQ;F!PmnS7zq4NYKj6!QPX51Qily z-u2$D$p9=8v@*Gb*Mc5Fg@nl;yk2558H)t1OitwWM310C!sJ0-Z#Nm4MS@l)xAR7n zM^GVQ@;PtRn#|H7K`WD^dXd2+sE{yusTX}rh8!kAE0b$`5zZs1kTChR7e!5`A0|O7 zQ!{vx+9RltFm-}A8<>hElLW0;`vj_@Oe!Q;?*xdARJdzp=#q656%uAI%$uFflP5^f z%Djb=brcm6W*5-QGE565NYKi(X308=3JJ3}>19i%C)y-vWqM`FI*JMjvn%UmeP%@2 zBxq$uSIIhx3JJ5j>}9VeGT0<&WuipMI*JMjvrFz};U>b_Bxq%#UCBC%3JJ5@?^P2f zQrjeGWukV;I*JMjb85jrUQhH0DkRLQ9MNOukAVDjW z^?Q-pBdCxtr{28Tz*H<7NzjVbOR$cjLV{=U0z@VWS{dKo%xUf_lL`sr&zqgilZQ#r z%Dh7_1MmncB+PsBvJBILVG^`5eZk9QJc0@d)BawzWO|}Sf>x$adl{KWP$6OZv6uCk z5oM8}l^L5}X6X@BNSN{HWv?bOSR`m=VvLs|dju5{Ca!o{xQTEU30j$0>1FyJL4|~g zk6txlBDF<=Rwm|q6^lnuAz|Wt$*PD1t<2n2lAuDu%vauBg_A3g771FJIoNx0kDx-r z%)8#(4JTJpEfTacxrEn(9zlhK$sfF45>BoNTO?>@aw4xMdIS{`CJ*v@dpNnWZIPgr z$?d!mGfk)Rc8pFmZVNreRKotXJ`G3V^L|GQe*5&nXi z|KF3pMq-&?%%VcVzvl0k$gjhs`rehCNi-)9-S1!}e=*DXH7hFSS_qzQbe_Ze{VQW7 zpG7NkUGjH7sF-UxjmcA*K_A9SK8sf7y5z5sP%+nXs+6ZqgFcLvd={;E2G%G3icQR* z!qd3?B%kP!(Jq4u37!}B3AM0VfS?smG5f?{C;R15;dyHM_K9{MJd#U=1W$bXM0C;k zIwWYtbLc*C(Ff~tsqjQRKglPC=FboKAi*>HKC$+~6@llVm1)i3uiTVhI4h3|34Zs$ z_wi`6tN=kPej~ys(g&$JRQTNt`u2&?>9^ORLW18O@d+8{Bxq%>gTGC+`NPNZs2Cse ztsQ=n@8jGnpA0-X3G;lx-=?ZG`HjGH(8|2G;BQl{%P3WsifIq|-c{i{y_K|_FWa3+9^ z7X_kBLO=$Edl_;j6a`Tx1%#jPdTQ^d>RHw2#e3uZtbz#9v_=|(M1>id-DJ9-#KeG8cX)M zYv#f8jx0usYrE$^-5I%L;OO3q`~0x?v73(@88`9h-l2zA>7P9~w|B?>=k_{nBUX@r z79~ooI&xCXsnfpnidDO}oPR{I)%a_=N~qRH-~5%4pKLy__i!6F?kLacPG0}B#g|`R z+Es}Xcc1ySk<+g{y7&0R9~$w-zxBEkK0UX%Vcf-zP_4}$`o_q*>mAVBXk*ye^Wx{b z?>lL);yXv3-&KhcTdZ;N$QlQIp|`~i*BY@$cTzd`O+~TRrx!aywHmLTGP3;K1AD*w z-G3SJz=Dm+C4ZV;d||I|bXB6nVXvMtviRej-Ve5ijh#>2v79x2-C~so=Q={QcK-ag zM!tO7{NBF*dyNqnuR6Ot`0@$G7borQ2-TXp#pxs8UHqTD$G?obdUV`@K@&SR)`g9oo}OQ> z`^!_B|32;R6)I6;vju04ti9q(y&dnq+K8R+IidW`8n4d$`8NOI2-VvBp)*Ggoq2Gt zam6`CoHe|toOfzD^YkO%vO*;}@y5l+_HH>8Hfmyp5i^xQnp&X0dhl_*_C~y`3qSG7 zii1y@;Rw~j^S$}%&-bpIio3#-Pu}#@?n&$1Ia4J{pcMYF`w6`@pS{WmlzUv3Ja`VdENWCBHdrLb=P? z`#3_i-e7Ha(&I<;HvR%^pd}tWe%1NW z9r7w{z{5TC*(1uCAGp>Lss+!t`lUzrwtMa@BWf>Nn%`}zBqzT6_mg_R8i$rxd+I&{ zG_~Nt-CZ?#S87AGR+)RWfAS`uTqR1ZvHM}Zbek+)B~R3`(fh%y-Q3-lw4VQHc_J5AE$eTtN?~glc{4=Dob%EzIu*FRGH9 zphpdU7ew&XN+3-w(5^Qq*c&LJTDV)+;}q<1RH6h*!S!kddo?9g3#IOQ&VoIsN|Zot zy56~9@2rGsU21JNjTz7qIRa3L5@?la%z)O;QHBz#g_iF|G6hF6N~jjzG&fpmab0LnjH11Ls>NFbWDp#;*@!rjuICsd*Y z(#;=i*6aOjIJ1!x)WY>y`)<}dVvXga5R_=XNFV*=K=1osA8$R5l~sHW%}cd#eZjc{ zy@lT&ji5vcq%WPad+$$|Z9j?)C8z}(SKYr`Z$)o3f)dRa>0f?&UhjRkc1E$G1hrt} zcN6CI8h;p#phWXUI`!vySt&s+*hr&{ci6b(FU8#Q!P_qmEs?DO?TW1uBb*;^{*K;t zFK%HqsDw&#VxYNdXw#kcEB8$*4}7RucK)_FjD46FXllK&aq7qoSFO`~a>K37M)$!< z<=MY(mM{NxaZ@EqoNB}_r>#=k*lFVIa{e(B%7>@TafE7Nj5>4K+j`&o=ZDP3HtWtV zZ##NIxpbR3VJu2XPOSZjakY)PHbUOuJvVnBSZy^&AYW=>o^a%9YuP(EU^bLcNlrYl)=S>TOtTSY zEX)fuwLstd?KOJSKG94z0-=(exa5@QY8&;FH?6F?N+3-wl)^=Ot&Vpvl~o{Ak`s#$ z`D<;XuED};u&V^p)Ix2pJMPalai_Jbi+|lLzVO#-?!4WFPXr0t)%t&UWAFZ@vqn7e zJ!`we4>gPT{%vtrB})AB-=~ahbl_^e%a7Z^o@1P~#0!p@Q0zNnjw4h{@3tbYH{w$R z{yB2uzBAYBEqvRpD=91FOD!$+*b@8dBPUk*<@&vi4(+X^&XF&*w7tca*w?Od;^G}P zusZ*7vJqOl=7lu1K=Un#HUgoNoGAW#!`?NImZ_}5TdM@p)Iurn{f}i82$kf-QUBby zH)o)0HsF0eW!~qJ>E4%srk47#PWz<^v&%0ZJE6R_>HU=wpSO0k)n7L0&AR6nvjH!< zt9jAq%!_JXs)bfb@7if!dC#PB(Id_B#%I0X&50L2w`p(QGW5=4`F7+>Egf-qLM1uD ze%_B{lt7wV=+!tz@q|ipf+LQ2SB3RzVU3LMHtve=Jm@>0Tcvm7synAA4}?l`;*X2| zQ2Ua43|H6~uB!yn)WY5V;-Xc0Yn}ibN~k0!nzufdY+&pYY$$;=wa}l_UK}m;5vql> zd-A4@0K${2Lud@lGiyUN}z7;|MJ$hayKE>M{Fe|R7-0!wyRj@Y(GlC-uJhh)q7}*9g>Yc zLbZ@itt78=N|Zpkz3KY>dM_+I#%zp5s20+xm8|~e*~K|un@}FN=bWZWlsNR5c_SBH z_Nm^xZ=G*8ZeDeEvFzjtC?yo3; z775f1N93_SqK6})T1dOOf%8|CD1kP{nMG`gvF(yjEu=Xwi9~FPlqdmvoFR=(s20*` zWSO@_N|Zpkai$l`Dtb5)s)ckKS=Kce=A0@~0yXRAwFT$3N~qQn>p9)rx!~McB}$-; zapoOHmIdeMN~jjnX=ItVT}qTd+vN&E95ck$PC~Vi=K4b%$%HjBl_-I6P+B9ay=Z79 zs5SOQXeHdQL%OdY3@uS5N+756&)BQC-#QDDPwXR93+dFK>pQ3tB~Y`|-dglpx6MjE zF}#CHs20*`TypGq>(x$}P&8)E>8eDDw|C}^y!_DndYA714zmH`0wZ3_2-VV2RHwcF zJ(G&N9%&W_JiFM9uarRj@3G-Kdq-dQqnH~x4C-HIfGO}wNTQ0H~YOPOB7{A zAFR*h36x4(TQ zb7#=h!aUl&=U8ZY6zD5sSp~nVlAL&;vvcpdPqxfc zUon1mx!{Be_cvOy4cO)9_gShHOC!eUQ|7Fy+$%cu9A`xkbw-gMif^2R5cW%D1^${i(|FNjY( zKD)Q=B-qGT?ntN>-Y)KJc|s*Q!F{Ue8N!H638bk7FX8s?;y$NJa)Nto(MDXqqK^W- z-Mcrl(|;3tpy^jUp^}`~^2p74&leL@Sq1N-1k%((DbTOPvWotSlAJhc-sZjIp2YZS zlGXW79%~lsy-@8mkU+lFQZG>vzcXUV^NYJGQDQ4=F^{h|v)4FbC$q7wwZ!vJno!)c z+Z;!z7Fs3!N<~~}#4l!7I}McN#OHV0v-kBsV!T_wgVA4+K)%$%+eN?P36@x_O^-W>@}-J_fqkj{|elSeN~&j}lcd~yK$ z5y6Yn+j&C0T235z%|LJJyq!n!qRb04wbXaT8jN0)elREg=esj{-8aF;Z+RWQcHbTMLc7~uU=f-Rf!VcvDSXizI*icUvjM3cy{&K<#}J5P+a`6IgU^* zyesr}74ah@zQ1SXMJdUNbYd&_q9l+nweZf<+eOb1{H{uJBAq1vM_jRdQ?xS=gf(7p4zQhAYW>!f2@dq8?lZN zDp5keR_U~_wyy`yJ9$FU*>{d3R15DTJ*saddFir^p*C3}o=^#BCD?j=D^UVzYN7sF zBA!r5PNbG-{b0ddKN5R>IN|f*|(Pk3`XA?@O7S@?K1Mn?TTOZOq z>#8lr6DrAxbQ-rFCx(`&1k%*f7SrE$+4^!KohshPzW;dnsb=xhSE{y40{K!)+n8@9 z`IB>eh1%rX5TB5zR1>aiD3u$W2x4qOfT0%?Y z_(~;8XzK~1rGn!tB~%OTiesWMOD#A{RY^{ymZ*CyN@#n<+AGIIzCN_|X>Fq1*v34e zlAK^Y`T9@-X=;px;%A5?W8e?-umCN~jh} zI{952Qx_Z|t0X5kytFn^gB+KJQC~cZqmrCRbzbikh4HQu+A^@-&XH_5w-ir* z>S;`P2Cio7N^v+-RPq!O`XZhdQM#YtDI_IS3)j=Cv(6?k#^o-6(yyOjzQ`%9I_qo# zV|DIksJ+)uFkj@X4pQ~0_cp6h_Phi#gd|P#X z<#|u27TPgaiet|i=LS5D2`$=t{RHzxznfN_bv6Od$upbKqP^EoFkj@9R-NmfGdu@8 zXPTv?6Fa!hnN0M%k)Q-Vk*iTibCqi41hrs;Yfk+HC7LhNEVq>t)PfC`LO(%?=8H6I zbL9lJV1sqjPf()yBAs@T^ZHPNTCkDMe&GBS*AtN!>mWaW#gYy?CI#0lK~SQ^b~Zvz zyE3-QS#Xa<3Dv@NmUP(1DY%cL5+zo#Qx@s1wRf=KJE(+e;W|q?oY^k;o~uL&-Mg;{ zp7K^gwQ!v!9ae-3t_W-Spy%WovOZJT^D4ONtP&-V=4y0BaF;A6sHM+j<10In!ksvk zXue3(KUM_2XiiW|OCgRKLT`XxpZ;9)ReLKZ_#DV7?Hkl1nP`I&%@=8wbXX%RxHp0E z2YWKTLvN$e7%J^^p&@)T)EHXWJLrbPdfWcj4LzivopE^YzWZ;A>2J^ZZ=0VBF+?p$ zm?kmz_9J?4*!H?a1QXDrWHjQC7ndbs2=|l|prM89yY6^&@7|9hUPgUa(FP@?mAK&7 z%M%f8D1kJz0)58(-ugX6jmT}xttGq@CHDB-ibO;kN+1m_(3>8=p!e~M@l||nBNCMG zPDp(77svND{1?8}&k0I$;ulv9^^Od&6XZFDphZbeoc6~r_ukf&yF%#(f|8uL?v=0h zmTa7rRUjzIiPP@-dhdrPAX12Bjh2XCWuunl#M?gd&E6%`e>4g~Nlv_Phm(8XD6Suc zpd=^mz2oHG(VhSCgx%M|9wnm@uiSX!7z89a0o#xN<>pZcN^%0vcgNp{Mp4CPpD1nv|Xg&KqJsLqtPM}Tix@9@qUDbJkpcc|- z)31IMghm9iXcU7I5omB+iU>5wb*320qCgBG8xKYa(j@GQ?3hzuM4(8hmW@jW(;9$A z1X76-_MP~k`~Eye1X4n^talzvYXBM%NF_?x_wIx4JNg(AND0-ldHZ1cy5GLlj}d`X zqJ(|7KbXGm*N8w$sFuYB7<4fQVniS%RLlCoLC*AjL?D$YVKEK{UF?Jy5l9KuvYvA= ztr}=VAeAU#u^I+l42T#JND0-lUVAXD8fZiymE;6tPWXsGN+3-w(4$8LQbM(Gx7;!F z5rI^q1WIA_h(JoH7D}BvWA{!P%>i2&57v;E7!9ofr{F3DtssOgnK|M4%|i z3C8+~o|+MXB7uCV1rP4-N+SYALbYrSz(0A62&57vEH08S-53!_3DvT-3}1sWB9Kay zu=q~CmBffZN~o6Y-Ada@LMK6Y$jhatdj#i-AaAJ7p`WQIZqxJ9?ZvdGYK=lqi8TS8-QPPzyG=2G~zfqWL17)_3j6<8x?Us)g%Z{p`0vi4sV=lYq{K z64ZhXuHyFFphWXUnx|n_PEZRrxEkG0P@?%Fo%-{CDluM3 z>xoLJBq!V#hcP0M5=c|azQ-AKUp2;vKq^tfzHl6LUrxq|KuV|Rgx3#%i{PQixNmv3#GvCm||Hq5kp8NIl(WPeIy+vkfxS>^*@-R^=xiYpi29u zdfB#fx++lu^`Bx0S(Jj3Q3{k$EwoBTF9R)hL{&< zYM~Uk=j{oVE5;ys)bgWcFA;aTO~P> z_U`gNig|&i7Tzw7KH^&&`$0-_f+K^_JG(I)3FJ#H^v)ayc|s*Q;l@6&5l;52H$a+x z1v&9cf@mWUD#;1P6N;mZJ|f&<9h(Sa2HG2&P%WhC?cy$Sfe1}1Q39iL=SAabTqRTs zX?i;!bx0*j*ts0(4K(VI5~^kAa=cHBQHNBb1m;)tV?OGT5~_tXylu#|L&Hfr>`%wbV{ z(y5i?bxw&As2lcIu|8s*lTaI<=m~QHc`pu4z8# zq7KPBfoI~F8tK&9>(UM5c9kfBy5Xq5zqKifxyKY9a0B zQLqu)E+tC99%o_EMjxSCNW1wU-r6vRQ;8BNH_j$wS@jXBg|wU3B5o8T-A0KL@Lg{1 z9HS0tUaDm=DE<6AMjcX#5@=(b-TSCRN~jjnZk+)mfG{Fci4thLTsw=Sj6OoOkp90{ zyp+H=D6PZQGvQF@7^}0D=%^p#>s04Ts3a%S+`!%_%$?&%pLv0%7RJ}9&XrI}PNcbk z#xPX^X=>>@ijQHc5+!sz?_-!Mp;{PUr#jadrYgw^j_3WjT?wSAg|Tm{bDbNgBqunY zk7MevE~*65)Iuxas;Vbck`rleP`8rcue4=o8$)fT5r7gZ$q9PC;7ic1f~QsjX=+ zjZYrlL6zhLPX$_?OKcG(kfxT-Si`Bw7+XXoO4w=2!E}mMV~Z%ET4=|dj{Xv;vFvlOjOPpBj( zIO6oJL&q=-XA26KS2nVgkl!R!SgEE&CdD&_xl95wldHgs%05 zn1C@VmlCRl`cL0fBaRm%f2kxV(z;LGuEN@q5=c`EwduYMcPsRi2zeSHNF|Mjnk`r#_4ttP&1oEX8#-+U5U?UPL$qC+Jc%$5^8uJ28EsU>Iebh6^ zP`WC~36`{v1E~bk)Y6r(_(sJM0KGHb51z9_JElkVgi3P4trWR2HS+>ZEwp2L)c6j@ z5dbAQ;Z_Y|oC(bfX=IsqJ*AE^KmAWP%X4$dQ=~0LM1ujRt@legn5(_NK*^# zm>#v?Q&W-?X`Mm+uI7a_wa|`}-&H~-Il+DI*h-?O)^Arn+o|=-JNWLABzvK()m>2S;mVGTfIC`uwl_;V9*vBJNLbXtvj6dLG zo~a}!oG*!fR|%x4h1z5sh1jlw_fbhs(2se)s|3>2LhE642T!OZC+NYw-&F!>YQaCI z=diZxJT)ab!8`2t)Fjl;!=tA9$UQYBIl+?l@k=x>_1YGjPDTJ46<8%oc;Bv(hm}w* ztT}PS(f`)62f#bXHyH0qI&+uLgel1hzMK7TEeZ7ocvsSyyLtv0-gA}Y1m9*KH%bYl zsbyct52k1f8ku zpb|(^3-1bJXLv#-IpN;(_zo(8G_~-qr02-rT1s+)ci8{dl2C7ecO}(F{?<~G6D;Xa zgE2ac=7lu1EEbyd1{xhkB}(YKS;gdFbQmR63vVrZpDMz*#Kw)1oJjAvy-@{Mqckt| z23QwoFB;z3NI=51Fc4f@!ga1?jonI6gN(PN?adP^$q7dE7`wHDrk1`po={0nFrtT# zx1CHw%?oL2X(@!~aK40X3C}?vg*TY>?+KOU1U*K-FJWGwsf9O~&*ur1L`LqTk!pd5=c`EwaL+-CsdLX zY&~K0>RJi&(iVeO!cna!RFV^^UDYiytd}UEtq(NUHDaBI89nNmGi=lcR|;^Q^Y(s% z5+#u4j=;(ZYQYBAWcvw9G+(5-1F>>~TCm~vCa~fapPUlS7isPl_S;Z`TCl;LzkY%e z%@^sk&smT9;$100E!arAmKq}kd9l{=(;_TsA0q_>B}!PlXW3oS7%57q7Ou0TeT)>9 zC~>dZNT)wFMv4-uh3hP7A0tI2N?2SZIg@I;$OU7hD4|-o&XV^3m7)?Q^wffns^Uu2 zdRC#VG*sdTl+L0&9T^f=t}!gZEH z?A1aar4l8OcBk&qbB;<-3pueA`fX66`6A6TIx8or1sg1dNW@Ve=a!nU+FLoH&%xPi zKS7D+i!@6baabBd5AU$3*l^^pGZ9GxQGmXU_&$wIQ`)XGQcyoZi6e~W^*}UW<2@sP zT>%@EfQaeZHsT5O6EQZC67?M>;`-B%Dq8RUVVBPlViSoLt}~vH#T+z(!~f7|%-Z$37sxbW&VOU(-ewQ!yBgg{(+nG%#Z!f0Oaw3lE0^~=6_&6dUH+YSU9 zlz@n7JVzZ*s46QZC~*Yt&=FSe#e@I7fAt)UO(a@)4n}dQY$!oVcn+a?y&@ic@T}(D z&0~TMN+Yx4KR(!?1Vl`m4aTym?n((t9APxCSHwT>yt6xX?L&hNNpt9lLy7t)DL6aK{tjJ*NajOq&fxRq7`wafH#lUJ(n{J+?e+%3;9< zB_LwjY#=%mqd+wpN>Jhmqj|luVXn8FdDD*9<6WZ!L`>J$8Jo)9z>I*z5jC9%+|?OV z4r|he5+Ple6(eR<&p`rD3khwI=Jiy%sC5lTP~r%qdA+jnNY#G?8EX|sX8 zgt7D*LrPHM2%~wuvQhVH!3HHDV%lt==d5A^-f;5<+x_#+jbh@p`v-y&M;QH&Z_V#r z5~2w1a@+C8~l%NDQB4KG>uWVqnw8Oi97~XSAK*Y4!;P|nhpu`bI^LnSf;HEn+d*w5;isiR& zSXkVk5yoz7G$vm;F2!yeVY<`a{+!=jcFWWI6z9DCErqRYMu`$g^A5vZHO3;S)o3go zVLE#bk!Zdk(sRI1$Fg!n(n2XXB8|dDqWOa0XxSo#bno77hrMVqfzX&bpJvnN+3a_p%)Ry~f3BEWgwI?v>4Bf(=HFQvzxF z;7)tpt8SeBwmW7wH~9U+K7v{r$F0*o`INPWuUPi;ne&$}3Qx|+ahk72WwUkB2i9Lc z(R!S}pK)TS55|F00%`U>o%R<#G;{dKEzkJy126Uy)IwWG(cUf@x6kx9z4hP~E6zPJ zv=T}*UyaJvX-|Ci&&$?c`pk;2Y`+MtJx2IaLSw9T+J|lVm*E?a-n4tiX~!2TQ9>i8 zb=vp+^sUR6S%1Fm`p3g3#%O3tAe}}4Cv3fRc+b~%?SAH|g?$9IunWW(Yn4yj?6gjI zzoiS{MWaOXHBU51y3;=Or(4f>?9(6ber?Bv8IiO!##&`#)18m#zV_0BLM587dAL@x z@x_DInz7SqZ|?r#niDc2X@O>KcG}Z+UH!5+k`amKi*zE+-}Rgg<{bOuX*RAl@00RU zEsbW@X`lVV^#j{jOI-WR6AP6nfizpby|w$@@cnbve0t{0*^BxJYQZ+so%RK*PPy!( z7wp?yb=!sEt|-xbH8xqNz2gDD8UF1SyEPyBttV7VBc=tPc$4_V=$-Ao8)39B)IU9H z@QF9kC#pmVd(THwJTmi%Gw2hQP%T`iw+lXTfId+rN|?VINpaQ8CoZE;R6@1P^Nl#4 zI3PYTNwd}1ONjA(UE~igai4x}d>w$mQjc<+H(yL@KFwDV4M zglbvrK519~^XHk%x8C{7A3o}zCl)F(j~ZLJ+U~T?Q(q{aI^M4*Qi*ihe>(Yn%QyYX zJu??wyQnbVC-2?T5x!kY2T%Q8@zm~4NTAf24!yy!^aesCEv={EsR!t(^{&iQM=yaV zPd2PK*hG4RDDgzH*J*!z`z6D_vN7C2cAU3lZgeL}9IezNWL&q22TWjyo zN|+b!odn8|Gw)9OABSH%{5M+zc(bhmXkMy?G@q~2zUsDXrY(7Xaz|+U~TiwGT*Zj}j%U<;$vpy-@@5MnyukU?X`3duykrw>C*Uv2>7cbEj?I=SF%T z%?l+>E%PxF*1bF+A#C{aT1u+uibJA;1Ld~J+k41!)wZCA6q zdlx;`-1VdX37;76R|z~H>EJ~N#ES}%w6sJzZCiW2DXzUrxof_*%Gu(YY^QB&uiM47 zS0zLXL~140M=fU`rB9AMbIu_2neu)xm5(RVGj-b5*AB3+RV~;{vk4`vKOd0(JeFck zq%i|lAmduNlsn3bT6l7%s~VIw{V2(aG){yKB`9%(+2i%fMx39UbxJ_Qv|UeQYTM12 zq68(5Fq+qGR`mXDbdM!UKu`-$&i$6KE2DcXQQ`=r6Ja|)m&?vilz^ZXY;fPGdU7Qw zaRlygtR1W<33pX%!3OugDjTxr6(x=^8=jDzxF`WZE!g0mUS&fGN*rM{uUCZZK}HD( zYQYBfJV)KNj1or}?T8`S8I2MU)S`{JU)x87f9+ACPA5WkctgHQgmhh2{GXr3kP>)W zNO)JIc|DZXknC-T@*zPj);a$fsNo3I8YC<$(!5^TkRA6>&m^b?8)%9AFQLYe5|qG3 zBrMJAm5sW!mzoy{YT-KG75kbqG9D6eS?21sh|YLW&Yc80`r;=@ca( zs0AD7&#QlZv(r?YC_#xMjOO)lVrvsQu@xmCs1=^0{$ILqDr|}p7;T6DpHl*N7zsOh zHbqXJMM=0T()Jvf8;p9oElM0=HasC`?xF+)weTEiN6~6ePw7R8BaH4R>a&AU0)kqw zk>)tGL4p!T)OUzeh*i6ad#REa?<$;CwCib(0~<y?dbo|#)rxb9!r+l~?t z)Ixgu8;|Vmeo*yabd5$NMB<61gQRWc?&qfuk3VbQ;^#xFW9}UD!f29ONOPuF-POB{ z_+=oH#1lHZvlXuyvf>s0cLnnSt{a2KJ71m4uywc@T!&LF%m=s%3<930IxS*reZ#WW z7bQwyPL)=KZ9Q>7))OP4TA1l^b-2@h>u#%lc)_F7yW>|JSEvLtNUj3=yRv=f<=l7H z9bW9pas2}GTD-y4DGS@%UN+j^wi4K(ODhw$e}2Pg`{$~K9lEqKVSDs9=^j0;tCpW_ zpML8doA3mLN|f+x0BG%Tq;GAPb&GZkzl*amXm3o1b~R)WJauS^lsE!!K|J;Hk?D5~ z#PyQw{op$Rn$K6iQTMis4?Q{&CsLxsw|t$S<2mHiizApX=rr2~5j~u(y+n^=YceTa zow7(?REg*Z9Z{XpNJRA1W z5@?ASe|Vx=Lmp*ZVm6dW>1r)Jjh5or$A~!IvGPeowcehHIKIk=L{~cv)u<0GQHeNi zGaHGhc2W`%$BAY`iIlF+^~KR^LkW&jQC5kl_M;LJ$Gc`jiIh&Kf2$f)B95cYMk1Du z@OnkWal6@|1b3Cv)d|Wtn@FdMaaZ*`!xLst=O5uLXE;@y5!6E44+!d%qt_P1sj}&RW_8M1U3?}bcEL{BF+aTFA&s%4W9n(Cn)j6(h**-h&U6Lyg*Qk zHqvZ6C#qAvN>u4Y#2I~ULy0O~mDMPxit8t@P8Fwo`Amt3>kJuzva0BG`Zv`_I8|%} z>Hz1BHD9E8y&~dzNk&i$WrY?q%Bf)S9ZZwp@yA6rv8|*nEuEXIugh*-KeT7d;61R!js4TygI!zTJP)$<_jC_6Du33 zcTN)6NJMoSX0+bf6U-Mj*e6ytQtzB3u#t%BoXlvwvnQA@Y_LzPY^2^fNnj%p)rpkR zdS_2CU)W$TTG>dwbCSSDA|_wyiPSrLf?DA@Twkk1>Mc{g!JZ>hUt9S;^z^C)8|)LS z=TL$YPfWg&*DE6RwJ9$U)PfE6qWuIVo|t?kuUACsol{;Qs0ADBMf(X#JTdu7UayGM z*QUHcP>VKFUz-zE|EfflPDJXRwSP@oEUVPlDuJi1`d1~YQbd#YO zoALsY=<59+t#?imPgL)GB;3~ndH-5{&zt(->N(KYhIKf5!qJJU7me$1Vnd0fg*#+U zxs4=&7JBFUt_GP7gxFAGY1Fd%7#zz+l0b|3+StdhK#C0|k`{=58{z9^c|yGtK2usX zNFy0H7K!)HJ4{3x$#^1-WYYMdDqSUHEE1j^`N9UTS43JhNO`Fio`d6ueu5HDRHrXS z8_A@+KqNXJm!y$Ql6bjx>@*u#t#r?RB(~j3<~cY;gQg*+?UqB!P`YRI9b4jbuE*d|`v*hss78$s`GEB%(Uy zKiWvf6U-MjIO3>mq>)ULz(yjL4tgSuOFTiX@EmSjq6GYTH7-f{278W3;}UxgAyPVx zII8DRLdGJ4iC8+w>lKkkGAS?I3AOMX9C7p$lz3w4Ag@+WAB8^LQERwWf zgX5J{AJsZTlCZ33&l71};t6WO23pK$>kLT(8;P)Y#Sv*-;t6WO21gv#b0|RxY$T$3 zS4JDjq`W{R+HAX3gEaO@5>Hg`d>qL%QqSpoXZFaT*(X-dp#&w`hjRolT3?&;QZ3l< zJ!k4`lf)Cc!;96A)Yp1~`N9VK#OgVepaeD&k@lc#BCQ(4yg(#6?>SRnnyq zo}d<kdboZf z^?gdDGa40J@DG5T6hPz!YqZx>HG$u2;WgeQ+Zbvlt$JxA(mJ;8iogMDH@K?!Um zqB^%0&v>P{ACeb{M5i9EvXOe{B=JObZY`cXvlpt46k;|~|C+S$9Jro(&YY|n`o!+Qc(vh~a_42ioz2kN__0LXO#1WFE`LsBFfi%ZHo}h$Uq5h3v zxuJB&Ca47(Y3`VKf)Z+lR$>H8q2GoQ)B=q(*BQJGN~jg;26ts6jw*6X{v1kBE8L-s zeY}l0-jRGkV8p=)G-DIg0)Y_+rrQ?{| z(j1q@yBZ1}OC+F`pzTh3$v$_jIC$QX|^cdU2ol9bD_s!>hFYM?mY2{m-@Y zqDIUlfs=BS)TibGQGbaRa#;~#H#m_h2chX+v zcaA#0s}d#ZZ`WE|+;FWCdvqribKg{yYkhjLBUG!7hu-?#@BYh(2NrBpEcw&)@(X)? zqpK1n>Mz4uKiD2Nc0O^(V%GR|%T*qn>j>4Vzdmd28>01Gyz1=Y;L9hJU!1hJBUB3! zVl5hb>+vt+t{xqCU~zo=iSAiXZQ50d67@G`t&>}b2(*j+|Ht%0Zte~r@%zuPPtPyb{pBg$f1h^u3Y92PfB)6m@$RefCwCZoZTJ4Q^R~LTb zm6->hG{X_9h3B*Q?XByk;;!)IlQ%uJdD1#}&QysKCB}&w1l3Ncx02^rS3;#5|*kbQ*I6}4RGs&&P9|1Af z-l#9#+bq6x<|&R)ExeodPj;<`KY+W!TYKmgdlip==e(v$l&DWMw_be)HsBe)J85q5 z@adO0Lbc#yEY5yw!*Q?y?{nqgXN%q@OPeZDqCP3zI^o>D6**-Dg9t@$Ynxv1ChBi4t{e zs=Do3YcJW_l~65<;(}BD>5VG+Mk%3M_zxcU)|Py0RicDNqw$`hq-Rh5~@}Ii&E-2OZJ>9Q3ADT@tsodT(WmoLbWdaqD4tN_rQA0 zfR@M+fJ&68zrd)+3~22fWhkLq^;Z{ZBvW!Eql9YJ|EQEkOI?nZRH8)vokkjwbvYta zLbdAuc}krYyUaE!b_OC0gh2I~IphO9z?Vr0_ zf4Xe@QEVtdE!eRCn`y1+jYd$S`66xqM%#Mdt({S9C_ydQu>Z|zHU2OfL5b#zbn4IZ zvQmOtu#x&&`8UDP64@HiuGlIu!m)ooXbHLa@s1j4gCMd{9`5*4^Nxp z2-U(E)&8NP^}T<7$ZTx0?(E{WqbC$gx0w^hqLk#s+MgI#+mQbZa|H6G7DmqYUl6U` zci7HsD4~*^SpAIG2J!y8e|8AtcIE||T9_x;e^1yuIAAv9U&g}RfRdbeV6B(D4g7CL zn6Z#RzSIJ3|6I|U_K9Y)5eSv!#3iRZSKE+(KItlfG__C)_AiWh2UA($zf!s?$%(~> z{I#}G*I;Qi=m^l%LT#=)?$0%Gr?sn#f88v<@YibYyxoOQ1PR)e{nL2s{-v`+^0pBnJb zkrVfwxn67G+iqP+Ss`C)X{pDS7)ntj>R& zY~a6AT-!yy)B?@7z_)glRFV_+zd5Zr z16{LG|NBt!$aL>ZKvPToSp0{h;?}13S4!0XeAJqC&n;%-6>EvRniqY}yr|}-T4dvg58dU$e`D1nhP%Po}d zsDx@E%~J2Q&5M?onisv)yr@c)xZ$XI;zdEw?<%2MPaHjOaIFj9)jI9?pIGUxm@vD% z;MfV}`?sIdRf!Uq`_MmD#PvpO@exm`7Si?)#J1M=b{oT4uU6Lo8P-*a5}3nn`}Qqc z_us$HN(j|L+Wrr;_0AV|G{XAxvi?`A6)I5zbJ5j)+_K(aWrS)WZT|<^TCvral8xYZ zRiXs!J$U%Otqs~=TnV9CNT)S`x~zg1Rf!TPx3n_x%LgZwKeFEWnWw8(!WMVxk@I37 zuC*C@&XRqtN|b<&G|I5vxny6fglcJR_SZSvj}mw$_K9N?s)clFC3&4wq6F&3{?E%+ z?k1%A2z{;QrCM5>v0cSFXZukCIoUt8wI14Hhh(FVP%WfWE6MAe5+zV>_FsFg7Zx64 zHpU`U3+dEKR)6#C@|>?tD3056PE#dH9D2;W!HX{YRO{Wh&Nmx3uR6P2cJhScfPFln zTDo@DY1@Bimdl@P7UN!C+*FAY@JjZdnym!`u<@Dhr1F`kn#HZJctW+1PAibs*TRby z)<@a=JV}&*4^DG68}F7jV+rHkyoGbTi&99fJ@;3XK#K(Gh9mM=A7PxRd8roCZf@ZG z6(vfbjd5lXTViaxBvcD&&PyT@TOuV&z#eBvV-u={G)IH+$)mrbLp5?@YMnH9E;)Bri4tgIoOy?lWy$%u5~_uC8d>IT zml7q=cDaHO#|*KxlTayip z^o>iH@7p``248;YeXUFPe}~xsae)!9WrS+!D5}%m|DH+ZU5_-&1D;*%##c(9{`c7M zovowJy3IypAZ{??;fzo%q|-RDZdYL}suCqo|7rAE_ngr)u!lqqat4Vq{KB&zYMnP; zdd@(oBqumG?0?Uh7iemsKJ33*TSt8OZK(!>FHuQOaBdjpgXQOsolyLwsQM`81)5s- z+IV-Xzid*^2Vb)BuKh=Dm_e#U34NQZ_nb3GB~%L~&3DtkQCdDo(+BG_c|s*QLGRjM zx-3!9)Y512gi3NE`CXfzm!GoLLCnvUK$==w3h_DOd(L(R8yx9riS!fN`bdCgZ?|%S zT3T-L$)jgrzIYDy?cT;%b53~9H$L(Xo0;A|qO(^&OI1luyt>uI)`8pKzLL2!Xlh{| z?cVby=bS3Z3Fk`+`Vu9Orq%(r4wvSG=6wqKE0rj5yZzI+^N9t0q7tfw^%>`P3;JD^ zt$@yp(XO4l*5WJB{{)4 zLnMM1)x40V7HIlPPpBj(()`1EPLx&fqDml5EtCR%Wh|>es3a%spSxSveX?bqy8i$3 z;+h?+l{@AInp*Y0oVV`!`r1b9yXNfTyC+R3&faxSQzc5&|GnON;j%#xcTFn3@>sK2 z_`+gOSnJ#5bGrsDw8|-$Pj5Z9$G5jZZX-=0B>HJ4!TP5TAH_c5B;7u#vCa zkx(tXUEJC7gi3OP`&7|0gb|q%NK*@5!tLEPbq|t~oZuc?v=P^@=%bMDcJJQIPXA5p zfu>*agi3N^%Of{yJzq>rWfevlN+3-wlmh)qEUQ4MBqvUqw|VQhCo#U7WOe?N$C~AO zFH}1X%nLNN)Js&v?~GXT{Nk=kl-SBz%;W3LY&A~U$!u(EE%E%5CY1N=HpdaFg;q(w zQW4h~@r&8jP6H)5@%i2MY<>NY81L5aVCZo)FQlo3w~Kzo6Dr9GH>Qr>M+u~m~3$7n=83Vctgx)k3RG-pAHU zieK1z$w@C&{)&>ENb4oJzaoKrsfD+TekHzxVFsy^oZy~!^bFBoF)z^6f|uy?K7mk4 zPH?|I*l;WK>aV!+j~R>eSCLQ&>?x7vI65m*LT5rcLyAuxy(m2=Y#j2*0qjQvFG_Fc z2|O(&IdR}M1Ffm^b{@rxk^oID^ zDp5kuCxaXZg;qB;SJfRZYi4w{0=3bO}sYiturH=_^756z+ zk`o-;g)v;oQJ)g(oprs;`(5?5NG~~Wx7Hp@76wmEkLn5aoH=pMQ@gc}U9@l%PtCkQ zQw#M^j~ZJ^^wgB(#2p%Tzau=V&>q6E^^LjAKuJfV`D zNG;L&!IJ%;5=c{PhxzklZea6|lCuewDB)Y8%_d6DCX`SutTS=W;9H`$KBRfpRa=ZF zRFV_v8?1Vq7+RtdNK;E&On=*D>&uDs4c0#P{m08sHOrsAQng(Y$d_8$#(XQupPb_> z)F$69PpAa65~(HT{)%~lrWR_GciZ2tD9MS`678)m`POP)NKeek;_{jN%s(0U4fx1`@yLbXuR$?w{j zy5tC1B{`AmJg-6KrL~C~&VA!?~q+`cqG1!ZUC+ zTUUz1nWBQHkkA+Lw20FE1WzF;p<1}kmEt(wjdKI;0x13Z3FeE@a$0rP*#ySw+|7U% z?Y(}2`64H-E%(n2xbvg-UO&NnaaU>8xt@82*#ydjduh<3z1L4LU*yD<;_56X_wMv; zrP}iZR-Ml{VM1~B4s)70!F=zvwVEGnHmzQDzS4FxK5J(=r#@G$u<$gd(w@Mo^ZB;w z{L1s5P%X4$t`x_fGtLco8WUQy_xcIui+(q)I_qo#o|9)bp+$SIpJ2YoiEGQzi-zZb z=S;JdbYchBIg{xpD1lGpY8293rCK>bE!g0iQ$In8=8H7TZRG^DV1uR5Pf()yBF)-d zIYBMhVBPc+lxV(4r(NWFBopgH32MOxPk2=4uehFwyjTbM`74%m*fA-&W(k54CAPB> zGWT05f_p4Vs1~lXq{BW=$$cD^D6xv2vPf^Oy@Ms+K_yfR*IClx%y!B5TqR2A-hD;z zl(!P9h3hQoup(S?MOe!RJtxf*7is#(il7(G32JF6#4$tY4bbb;pKHEqZ{-A^137W6zn`E)^F^8^9s0qNdlMLc zuqV?y^fu}!H$(Vl2vIdGB2a7F|GFW>kg-@ltq>L1t|R^J`v28J6pu(y0$K@+$fgEQ=fG108#V={Oh(M8`gm*&1qMx)}M4(7ek`oqfrB(eS zTV7U_~>ol;niPtZ6ZZsV6AO35$5sV#Ie(P?8fCVW-6y zbe^CjCoFPLi;?j>LCI*u=n;WHgnw>DOO!f??J*+)1xaoL&&Sw?{;nv=36$aJ5rHVl z3A8sxwDvZXpcZJsD(7zbQRHBBLZ18 ziV^#_Jw^l?88`80Mg$t+I#Y~gQ6h$rjR&IyX%hBDcFd_SB2Xk$%f=-mX$?Rl0;xm^ z`%Zks{!K7_e;y+ODWO`{JCCF_0F4Nw5+&?=_YwQQ!}J|}j0mKJYT3MfBz@hl5rI^q zgnhR^viRejQ6d5x~>5rI^qgvB^OWV{qRAw~pJLba^t z9N|pgM+8!d5*Djr#KnM!5rLFYE$g*M(yD<*1X4*(Fy@4h2&4qk)B$sF(Qx>ss;a;cH**#Kv9wtjP=tO5hxPKms;@P?yfWs)bT_ zJ!gyvq!J}io33|`5rLFYE!*>wF@r_~Qi&31m1)eN5rLFYEwp?$l8F(4lu#|aX>PO> zBLb;J3B18>L>40gDWO{M7;e-TBLb;J2_2*Qh(JoHmX1-w?ovE60Z+{@r;z5l7>M+> zQ?`;CB{|`~qsPfJo^Fc-@}(B;miFSF7tek~i4sV26?f$XwP1s5fc*p|nlI96eb=5m zK8NO|TDZ>D&wd+}D1o#)3FvGnK`q$eDsI0GN;F@jc^YQr1hrs;tI_=gC7LhNsXx!l zN(pMgMjB<*JMLVqjdiZA662M$o~VRMa>9LaSn!KOC6K0;eUCHZzG{pSfmEV|ec?Fb zzMPB^fs{}!j5zuIkBa>9L)3mf4ipb|(^3pBqY+jdS@B}$|lEVaFtX z?SyxN(K?XkDc`XPmE;8XpsSr~iLeo^gQk|=t>4>Li4yh&=t%ma$|7vUy=^5_3+2W= z?`k)kd)q3>3GPAn*E#b7O)b`6bZ=V;)k3RGyJWhzt&*Hbdv|#s#k@dM3vU-kAMve?{U9Yd!I44eo!uCY1oEX8 zdS{M|BoY1{!rp3DvT5Io>D6s6#4I0`n{S zF&}kE3DrWH-Y&eg@uZVVl)yZZzH4kkwUACX5b!i}n|LeXUI&bx0*jz(yL$ zXw)GkR7-2KzXsWUl)y8w?;4v>Eu>Q`$?KdFB~Ul)uVQ_~Iwzr8TAPuGbD1cm(hcKwl_-I_;i$jA?J_UbLfXwg zocEzb3A8cJUShk7ZI^^t;Y>X7E8S{8%S&(CAjA(beBHpbb#k2<7;Y9Z~`8889} zBQljJfws%FvpCA=BUB6N|9izt35TD%C>c{w+H5*z9X4`>KNltJ) zAL=}=Gbn*HwJ^R;b#CuqBvg_UX>On~OqD>ITDp$nW0UT9Sq^YH~+25{G%kTtuIr`fb3FJ#Hw4T&T z@_jW*a)LWFv6ZYqJpH^~(RZOX-E12pfIz4Ov=W?O#a0qMHS+>ZE!3v_CJrNjK&T`q z(mI311dP$Flt7wV_BH6p=n=D2qJ*yXhM0gcDwh(fh5Aq5R3nZTBY&wRC(^o4-LAsg zk`hQ$3$^LK4RQCkfs*e6~9G~EitaDQIZpG$)~nNUeixK#tZA7LJ)1k%((JElkN_tcc+L|SK1zpHs6O)a$JO3_i>gQ4a^vAK4L{CjZwNRVx+gInQDancC+Y$LozL1W2Azy0Q z*U}@S#|l%466%kAJTfIz3$@Ak13u=NN^-*alIVApK$=>pO~z4(?J9U5mE;8dnD@I% zAWbc_9!7WYgi3OP9^Cs~C6J~T{9}3!YrD=>2_%{2vQJNRh)Uq$+M^dx}jZLKzCG_3&@voFnExap??%-o= zsU#=Zdi*=61k%*PyTT|Ho={0nuuc1SPzj`|g?ELqGd!V^oN(`XdJ6|i?)uu2a~w#x76yWAOSsOptg%}OYLM}kw7q#k zB{{)}9%Hw5(A3iR#uF;Z2}bnr@s^Z8np*n)`*=$#Q9{4d@$r_FP%ZUizO1x-kmi?K z`b?fsNlv8GxH`L20%>aLGxe7)%O@w&sbY-?qCND0-#8_Yh@ zM+8zyPS9h7{ycgHC6J~TJOlf7PpBj(lJ~Ju2KEQTY(fd7sfE2lj!}G_YYRu3Ee3VN zcI*k2N=RsnK`Y^?HjH;;yHZI`q;^%?2qQdFXZ z#YK`cskVz;au-<%)xvd_wEwRZl_;U77JO6{SEA-ixKgO4;G?Rj1imB^mgZiekE)Ur z)Y4M0{zIaws021hAf5I(K`^RHPEbor!T)!SN;F@jd5WMS_}?`-K`mdp`VTHD(R`71 zCm=8a2&=V_utebpxx4x)hj&<1ZaDJS znTVtj45^??M zN0qI2|FFyF2+@p03)dMP$YKs0IBkj&l<+x7^LnR!%HKAg^3BKQlowvTW~q6Bpcbw( zIuM9UH&KETM;OiPo%Zs}zrM*gui3KPeA|IwgAx!ijpwLi%T#5h1SO8Z9Xi6Qy?pS$ z_phFVacV>h&%r1zl?^2*3C|%kuUEvQ51!S%yLn8oK?#VMHXDrM(oaz02%~wuB6ivQ zh!vC1JTcgy1Vl`mjT9Ybo5xyHl%T{BM)P{7z4nKe`0}8EX|uryJN*PDjxd_nE8;&Nc~|k=$9E4lC;<`E zcn*mn)MzL{i6d}_jyPe`4#o1*-djCKEeUtUwAo<%qUx@cpu`bogV!r!{aZg>yy1=~ z!h22$h?q7T8gHr5P=XRi7|rXIjRor-TbwoJuwa7{5HW2w80)E@pu`bI^Lj-fGS|$T zcDx?%8YLiNy1vfXRPfcFfW#3sod`U~8B-2x(uNWtU6&OjW;Gg0;AtVD4br@x>SNp; zPXrs3@W}&hHc&T=<5krM2}&Gc&%x`J4YZQs)81R)IVb@U({>##kTd zW$S|jfuIC7B4KG>ub$%@)wraOpcZUkjKUa=jfN7Gz(yo2&Fhs7jFxtI_YcE+P6>#Z zHX9s2_7jvi!f0Oav=`iT$0o0QW>&fU_6-Y*8#Kt+ZH>m{&BvwKZG%jA+S{M=n@w(c zdY|%~x4)&ZmCYzo0%_i1bys5%)M_-A4lSR0h(Hf&_#Q;?sLc`H*NHf$>pnS?^LKn35^wJ zr>W*%a?>`aj4yY1X|F;hN@(P_PW$xh*PF5XI~wI)OZP8Sq6E_PD>na_`ptp;uXv$* z!S4^~BdDd3-#YD8mb|p=EnmH@`}y9Xg-SGEoK#>0qE7qo&;EYk?5e9aojrXlTTS| z;EH8GUon5_qVVL59H;qeR5n`|ePI0=6RpSj`xz&O`d}P5C6H$C(`kR8%IPTygG+p_Ndg`D#?QPJ80Bf1bYf(r0FVW&1^F?J>fa z5*lNz(>`p=zYN@X^rp=_PCLF(i4qzyt<%2mr*ECH%=+_f*FPRUF-AjE0_ijYIAQCh z1AD%7nFB&D9uX&;o(w+9HKizuyW1s$b^J_aU z%!s6=G1e*@o9=u>^R<^26e`ht&BOJQjV~Uw*7BWBdvo&-*PM_MNeeV*|}t zk&H+*U!)Up{;ua-IOo_O-(1DWO?j!7MlTEey<+CBmy0FcX%Fr4z3)Hqm7mRg@w!EhP%YeTY9)uh;pu^)ZJwXG z=~f_;LPIQE7S?oS(SO4?pnKQQD`OCK)_0JOvm6%73 zEnIDP+UBV@5KkTN*AuBkI_*E5{Jt5Re&wDOi>_T%nD3MKZs{Q3E~SH~{=Rr>cPAuJ z>P&~;U_g2UA(EEXQ}EQo^wfG+=BcBXz>_B%)*Da@Q(d%fi| z4!^Ct=Iw`uRzisqu$O%M@mpOrW6`u1yK|Qv;0V=18KxfRqFryfdFzwMmlwUf7y4T1 z$(9a&%VrRp*$l!HgR2~W8cf)e#3$wzL^G-aWch$Z0 zqJf8P)nEXt26DeSk!D`sdh()yA6&m>`H`(Ef)XY02B+B_=CyMl`*8W%T^|TGNT?Q` zgV#Ilo!?Rpym0nF+1(j4$Rtq$ekIL0zuJAz)IDsLdSsZTCPKB~?YK73X}@R2!_#g# zWmb96`5R)K7$xw#Tq#i7op$rS+Xud6>m}!0y{5aXobYP^alJ&I1Nl-5rOtG|YLFy3 zk=6i?y6=Q#@4sbM`Lns!{YGB|q%h9mbgSo%YOK9~>B1uvhu{oz@Pc zaCzEDpzlg|W$PuE$?8YUOSO<@PM!9VkH2>F+`*m7S8tw-vWodyNxM5tb#66yqtxIC zB}!OrN@P`QCBxE6BB5H=VkF+HZ;4AIp;}fSJ=*THt+fwJYmX8otmVt9fxS_~@12Wv=nu%aZ~RjmaZ-2bX@7YJ(M zI^GrjmykPa5G9T<+7ohSB1%9|E7-O@PyYK*qoD-60VIyV9XdizazshEE7JBH@Lkov z55Zq4L5U;G2CrM}=*L=@%ZZdI0YNQ12Rt?Z6RFWqf)Ym<&FfWt$XT2y0YNR;K<~_d zgK9LCpu`bI^E%(bc%~>yKu`-d+$kiyggk{5C5|xK6LQiiN*2)KWpZLGN zaYTKG->(0EQ1((KFWwcjSRZL`JMO+3!P$=^%m%Ml&vDH&bIS?W{R?~BQ38TmNN<1R zk*(bi`cZX0u@MQ8cw*@YXA`OxZ^JIA~*nxq!eoat3}^)4fR8HgnD zgwF14#cR2&c*Xx+!F+)0#-Q=eSLZTp9d0?-;ZzIr0j>grfG4U>i`ZJ!+p4!LcyxMm{EFiWm0$+RRbYQtw(mTH`_8(IbJVAQE5hoe>dz&w@U&x|5mq9O6Yw07sMe6< zxMV1fOU#B6DP66F$I+4_;&{hwB%)exPedGFnGGdUy4q=|Mtx|BO2l!S*+@jSlM;z^ zM%Zj9k%vCM55E_-%x{Tglt3{N1KgAEFI+aiijiq zjGz|U6-WL31SNQm|F5w#0k-ri?)xy3j1bleh(#C=c05l4vrCxZ=w0jH!XPlio*0T^ zE7q_Xk0GRDhY71KOYAtNjDSEiPeM3^vJ3*E_u_laP7IjcEVhvmP=+E#GNHf{IeohS z-M@1eKvj>rO!x2W^L=OOKIiLmz9O2v_45y0%Lr+i4b4T|M$T~{8Ht_gNaW0GiIA4r z&@9YtkdVY|6tOeazdMmLNL$+x7^XR&do>jbtSf3-DGx|o@-FjAWU03&1dC0jku|yPI*}qjEeJ!IARtJ`E%bux|R_|ulQQ+5^C1V*OKs9RNp4wcO+-2OGMG- z6a79&l(($w_7ZOJ&UGzn*|U;QbQ|TJOEMCky|d0ckA$vkHsllCM)~uSn2jPl8)lt% z9tmC7Y{)0Njq=VVF&jmAp3FM$JQBLD*^p1{HsH@oVm6BKjFffWc_egQvmu}8Hp-uu z#B3CC;H;4-?>rLH>i04DS`y`7>$=_EK$NfbvCq~Gsbx0g6a79&NHP)!&eFd-QNFgW zWrVcMhP>!1A<0M_I7|QTM0w}BmJ!l28}g#7gd`(z;4J;S6Xk2`T1H4qHr9D(dP@@i zyNL3&tAu>J-BbBm5|XG?PWV$OqP(*|EBEK6r8-};=Ou~Fd(y|h6vQZM#DjPd<{a!8=iPCB% zoNuyG64TOkTkMnTjLSAil$H^L4a6m5sidWQs#SxEeTG;h%dQd@QIX6@*nOCm*-*sM z?*r=$CE<1L_ej*L!AMBUY$)Pz8zdy*b?vwQJ&0UqsB2NH-^UP_R3y_%RrCJ5ZnrlO z6_<=e(G@>EE5GxTLOSC6SihhvJ7-LXwg2wbyl#OkK-}qAPxI8x_fv zWF&mGc3mVh5}V_aT4!KnQP(wlia2_yuxc<8(z0izh+~zIgx9s-`gbQPE~#r#%WT-F zU2iQ(NHP-bJ_e%VlDbweRcM(FMI2r#5|WI>&RqZQL`5=nEhD65HWYEJ5|WI>&RqZQ zL`5=nEhD65HWYEJ5|WI>&RqZQL`5=nEhD5Q8x@x<6A_DmaJq%vFYgtL8Wlv$rbJnUsN=BmIL5Gd>wRJ5c zbX~I{54TE4G7_zX8+>hDtCwn{=PX}KZ&}whT3*ykRlas4q-FOZpSVg$!t2^^{ks$8 zIqO=~G8^)VtAr#YQ8^l&;2J<)%ZQ@AwbvRz`P!0<#BxRo)&SBA8&SS?*>jSRPaTQM zneqE5&sowIlp%ZQ@OC%TRDwIvw|?_KMB?MRfbZMHY~+LD-!B7BrcUpt&qQ1fM<8(KDv z#U=W8zYp_+{R{|5Ov}8Q6YlNSt)2nVY>==>#!qfpE)@xB^%5fX8Eq&kl9pZ9ep`&96KFOQ(lWy0 z5}k{a#1TsDx5W&Wb7j9}d(E>_6t+ZgWJnwBA=I_(x3uiHMv1{jFO?*nXuh_uk>W}N zv1$W^M${iqNXzWWGYmv8l_aJmPiDV=x@Sc~UUaarav#!CsT2W>PdB}OD~a7l&&K|# zOGQF)(2p;bw5(K$mRAW$OpAootTM32`ye5$PB)LE=yfDA#%(qfd9Njo^a0CC64x>< z60&{x&^=yr$Gx}RaPH*l#XEoLkFUGM;{2DtZ))_*e(xLexBk}mr@wKZH=nn2ba(#p z+nzkLe=p)4fAb4ll#qDa>;HcKg3E50{`#}ta$XVt@}igSkf7EH*Z5|4p~r;P!`sew1ul?5a z9`}0^h==c*g^w)lUdhuN!1>yx~yzG)H)xLetxXFj-CqCnZR%-{Q z_3tdzOD{SJHF(98#08)I@ch{)pD;V-@ZDkKuiy5u@y?<3xx0UC{@NRkpFQ>KGZ0_> z`rQvwa@F-8pWp3%H=f=984ue~s`q^3j|LkgzP|r6^KTw=-0XMn_&C_u|0hpCySidZ zEw!stpZhcr-~8n1Ta>6Je)&Vs+EA(+pSd;IAfcB3s4qVoHh%5OlMeE^Q;RL8TH@7j zdH+Gy?Pve^NApj<`s(R-|M>wM+SOZL{K2DaB_z~#U-Rf+MXCP#El(cW6}8mzt#?(a zKJx7Ub5L5=4`k!#ZvKt)$~ODpX^;3cO0{nv3EkfZ-}q7V^KaeZu0tQBmRkPnpZ(_` zKK73LUP6hU=>NX*=!Q~#;&,HBvw8|~`OAN2=EvX$7lq;_?a%l0;miH|tvF{tx> z`$(uAKYi;9u<_BI%h1~Q?W30Z&0X*IeGvD3@Vl}{nM6JH`U_7)+hu)x>{fR~+ugU1 z1p9p5`7d9yz4O3(e{w#3&(F**c>XEV&phB?=3l$$nrZ+2A3iZZ<}_@-}ftDYkuVb+ST`-c&~w=mTW)oWp@E_+{e$!QkjH=?2W{i-tv0~c`a%^ z_jf)u|Kz)mYxl7Y8z;Z&g*%jx_|sE=F#o_SztQf4#LX_c{XkIbIY0XB{QkE)c6Qb? z?++W--T90yN=Ur(rQe%>dhw6bk+|R^x8ET#XkGlp`Rk6~KRfunhrz~WfAz$z!;p}8 z$2b0IzWtr=Oh@85|K6@;5By9ZF=U%i!35j!l|6B9>eB`<% z;uXL0uP-G*ty34*%+KEUgZ6YE4I5U2ssn3%s!jV{&uu>lt3gUgRLzq3{E3$zBtb1b zxBu}=|A;<#!c`yMqJ)I%X(X%$Nl;7A?ayxZdDyTTq=ba(X(X%$Nl;5qdVc!HV8d!~ zkVK2I>#CkcqSfG;B&bz2_@QRw1<$|7p8eUkKv@SIB~JRQYv*_RU$=^}1jH^SBy=V3 z=bH#>-TGzM%`biIt!7R<_uQ>L`?IflP(q?=)B5=)f?999MHxQuNF{3qS}>> z44VjQJ>-SQF0MXsQmc<3&TZ7WW`hzEYSUS&wFI?JKkvqi+dbi?aUbo@x9!iK6(uCp zH@!YK5!CvBAHT_B`%}k9eY6_fwm++LN=Rso@piR|pw>h7|Lo%GH~&nutJV@H_GfLE z5)w65TL0KYQ0vq0JaO^3e>yh$N9$1&`?Ees2?>q)*=yGl)H?kyPFmdVtH(q?ZzIFR z{_MMul#pQj(8sH_1hwAqb0;re|B_>Byb`fZ2?^OYe>K?Hri6q_=mehCKv1imp?NhD zl#r+=Z3Jp?LV{Xq3+~lOP(ng2#tF2<2?=VcO}kekK?w=9d?(POCM2k(zUf|#1SKTY zgPpK(B*u~n32N0CV}6hXB_wJj3PNMzgaoxTR%WS^poD}*)Vy^h-<8pf&Q@zUqxyi`qFJAGwQ)W(l_$g2S}%I- zO&9Mx>Bci(zxwFiKEG>!_LUe)NO1M*@S#lvwLW;ylNQf>#<4SBRlE1)C+yjuohL&H z39iWmfD-Yn;=06 z3AIWm(Ap;?sHJ}6Z%jx~LPEXE3H0*`32LeT+dG}1pHC|?+RUBw7`=*k;$7ajLkWrXHX5--f?A?I z7L|=tE`IQqBzA`^A)jI0$IpK8DO;3~s2PB*e#pk#FM9P+64YYrDdN5V?&wiUNN6VG zt2nap_=7LpB0(*->9TRxQ-5@j5)zt``D&DG-1b3F-6BCP_RX?!=vEhOQ9?p9OJ7x! zjTip#`8y=2#ZjqjoPE)SJCu;98M3YQ$%fSj32JeyEaID&zwIC;Bs9|>@8c1lc=%Bg z)S{Ot8;`s0#XFRc(2B)aA2(d{l7XNWeOKA|?o=b%V~9mt{^J;nl8`-LHPC(B@b{N*@mkc<{dr6+V)wnjk#}wq z67}3{^+Uwj&wKF}uSG4@tj`TZ9RKRuoJk1@)xWRehQ9?rP z*jJ-OwEl6B1hv#}e6A+q3Fo|IixLv*%|3$^G2Q=xElNnJ&-*%@h?DR6_JN?5#u%Ro zi?BPVghY*9ww}0&pq9o;pV5<`goMW6@jiaxu@AX~1hq8gYc0cLhUP!g8<>QIe92gY zfBgqf9tdj5cWH&iZ8Sf4loAs1iDOHA;B)@V4hd?>2m4Bqp4AKA^}FevO+uo4JA2gD z{xb%GT8brn#Y;9WyX`x7C?TO3WgHn=>@yJ5QcN^POV4}sac5FOf^k>oe(YK9U}QQi ztX0NrVs7m{;$$-A85u&TZCM&k$L9d&nbe zHbz3vZOA;^L#|pUs1>uYxzFx&A67e6s?3_4n}@4^XQ_}!)@m>_GdmG02=gKHY!A6= zouF2%2h4q)L8UtTQUCKOpJL347S_A!S+QLq|EkvqiI}%7d}NS~=iKiwzn%1dWJ)8?b2A1xwUiC(zxQQIJ$Go7geoU&r$u``bE__ONE@&-Umsj zjSX3>d&qn31hv$TeVsw2y4!hoIY^26imeo^FBS54yA2W=yL=5mHjpFS32JeCtQu^& zgIn>|YGKiKymy}W-<~1Zu7pg$y_P$;6FELzLL%Obx0)r3hX!(29g~wO2(K63=;vH?5kcc8&83}5|d+zphE#8$4t3lO)wLY~B`(4k?=A0s|1}Py?^+e(?PdILi z1hw?seC{k8zj?2FD-&>T5)!J}k+2%%wWy`%=Boy>VKqnz3Dwg`SPhb(mY%e)e#nN^ z;2?>%WY<+ajf7=?lAu=ApsnJxtwDX1hX0u2cdO@&SK7bZxEsWgWl8yrBpPi* zA=WcTqKJ26yaKUJ2?<@v$C6D1wIaUmV@zfnT5i-fB_yiF*jUo?eJs~tg`if<6Joq- z**lg2VL4tCN=T^1_*k-upjOOxV!UeEJC?~|xoXPG=n@iYV?LH_BB&MfwivHk_Kszw zSk9gDOI(6cO>Jz*dRZZ;74y%96D@nkGHWb%P>6|Yv~vGtEl1hryiD*8uc&{>Y~HYFtFSG=EZBB&KBY|+mx zH_=81%Z{dm1Y?xU9b6%(6)T19J}g>-ja^De$hP^!k)VWxO6UacTzQr&QC~en^PD6o z;dSdt8-W_!BS9^-68D@WC?TOX<^)=z@?IAvp_W>^drlIRkWkBa0zFFky9<+0OTE@T zCkaYOs0TX{*@iZjC=YpI5^B}xgY4)|P(q?cq98OTDxbQwxJOT^rBO6Xl>{XuG@|C6 zYiw6uc)t&7$s6R;O@a~<@+Db=@=?lf@AW|~d9`dMNemLiKJswc66I@^r{CKZwaN!a zYfpj_66L9*M=1i>B|$C464`5$poD}XjvN^*Ke0zkB&fxhD02t*T7KeHnl;+$8E1|0 z?l#7&c<*e)xs;I5m4-LfD+IM-Epy>SybbRsY*0div*N>tHWAc{HQB}RR)4SMCr&6K z!FhY;C$13GidE;uke#sG@)MP7&?O|ef{^(PD+IM-#d|SiS?sp_MCD9$2??%i*qer) z(YQiTE8YSuhHR1DmY=BHk1ip>m6yYZBEMvXpjNzrSPWS&SGD{^<*;-K39Z8onKdf} zwc_2&V#wY(x8)})7pF@|jB87g@3TTsE8Zb3hAgD*mY=AcqAnpZu6RYJ(+WYYc(b(_ zvZ=OPexh=tx`YH**fKwHg`ifvZ(9smVfKYQ<#=@o39bQVe&Py2t$1&^7_!?YEk9A& zZCye_Ynej^-3mdic>lQ=vh*e`KT$b%T|#19<&3<(6@psv9(UpEqI&aV^IA&Q5gXqk zFP7I^MLU5~?aBrT`>i`4GBfQyl$p6O39qZC;6&sn+S45fYN-Z?4AV|fLPE9aL}VNG zFE5gymRjPFDccE3NT^jh5!r^;+Lc?oFbTEPqlS#%PEbNZy~_#oTIC2YOhPS<3`6F! z^>bw|FHAy0ql6O}eFlPB8sYri1PMw=XtZ-8vJGt%RnGRpB-GMKJ!F!1f)WxMwVi-B zQ11D{B-E0}@%K0+C?O&5qc_#*)s#cu-w9Dmo>T9gi=c#ryr>hApJ?7$dja~JDrzYL z7;$z$dn_s&_Ksc>yF-?c z&#>+Tc>w+WGKrc2*y@LDSgrxDMJ=|TB9PC}TL}rxeS8&1Hd=n-4zEQm_JXp3yo}!3 zNoWq|t5LGi@)MPp(Ftm?Ho-QRMw7N64#Fn49MS@z449W&_)fN^_kf=2$_Ndp~;U&sd>jbsNXh}~OId?r; zBB9kbUr!X#@)MPF*9mGdQmgy0XGIAKt^sZ)sHH0nv1o6*l#q};Up3HuwEV;!64cVO z@|ao#ayffUO`@Kgt$v6&`+3JIqp=gzQl0zUKm>A9``mzp>fcv!M6~=w<)n6kT54}T z#}UD{YZ4M_$G#dR!t!@{Eo!OX_*_jy%TL^)goOIJ&mcu054q1ENvO~JI-H0rk9pit zUW-~9V|*qo0{PT^CQPEnF63jQCDaOMXx*EN%mN`hA6kgnZ)I5?g+v^7K1F zE%{(yDblmTeuKVJM525AArZeL-)GX! zPwY96?OpS%ouAm>PPZA$w4I;Wb0A6gT!T(TR#;w_M4O9DUvSwCbD!h1H}0K?^AnSx zR-0K&+xdx=tJVp-n<`b$(wnvO6P4GOrL9tpM9&0FqRsC6Z(lV~sp9;^ycV_ETz%Hg zPn>5SSua(bpO{av%^;`k{KTFE$n%A8zj{7GmEvilE`~af?8}bRp)VjV%BY2#hJGA6MI(a`gRpLso6?MsO@GJ zYcEygy(U2|wfxLz>_nWOnEgODEXu4>MJ{J2B9}9J6bZFmUyV|I#QBLyP)q$Iv!lC> zI6txX36toF+Un5yQbo>o+9092@pT`SD$Y;LaY^mURy?Ye@XjNDH|o5fpV-^05o*W2 zmLVH)eqs{TQjf|E?0)BQeq!%YCQ%=>nfLlqMP7K?Ai+LgEiukdoVN25l{+|X=O@lB zx^LM+({_GhA6JTq^Al6j-i9a9-o8)U`H9W1L=I%Xk2pUu32L>sa^1H3T0N^cKQSdF zWN#$m{KO=v)!r3O+xdy@J}hRCjW|CsB_!J0_h~ynvE2uWI6pB7YPENs({_Ghe`8uU z;{3#vkZ5n;r|ta2o>^B!oS&G)pmp&Vr|tYifAgF75$7kSghYG$K5geG&OPeWoyYl! zNl>f3gPykY6Xza_iiqeV?}T6PJiMKQRevwRh>$c79@ex)xK*Mx38mZ7EuY zwZwXEHm?;C=O;!@?YFGSY{ymSB;x$UB&en5=JRvei1QPBO__v*>U<>P{KO=vrRU}= z6S5KKC-#~$35oWGzt_`9#QBLyP)kqRS6E~t&QI($)g`#D>U<>P{KO=vRW)cUMUlN@ zZ`|$t#H<63A1&UUw(}EXECFHXC#HmiuH^lE6G5#OUr*cli9M?)vv>O0ZIqCx+O&Qi z`93QIwc0#k+Rjgmu_Us0`WbYTkWg)Amc_)VIB_wrMXfg9nYQy2V=Rg6oqm=cB_ve; znJuzyRGhe2*TVSG=55nKH6Pd z_KxKzTHaDhNT{ECeQYAA)z&p;?fk^3k5+q@y<_=_mVcEJ5*n|(U2P($)mC(7?fk@O zSFIIV_KxKzS{_+SNYuD%{bLhBt+p~XYv(6M|7bl*r;FM7i76pLzneM2meDv6)M_hi zvvz)B^z$|{=sYsZ>q`j<#t(hGT1!x?trX7M`H3}NiLmn%Q$j+veO(l#vaHEoDwB{< z37x>R8VG9DGc>P8f)Wz-q>Vrg+WCo5ANvRYsjRYmUu3C%}Xo;5h+S`>$sHHaT zUX27LB-HYqK##Kg-QGV;LM`=8_i7|4A)y}Z1V#qSL+<_DB-E=CmRNRlj6NS4 zh#HBIPi-UIKu}9#WtPhFsXIXl35}?E=NhRkFT9VtCZU$b{Cv7eP(nf;Cu>k1$MV~| zH|P>X8S-7(N|G2PAmrh)CCYPJo__agCZSgO;ArhhP(q?Sb@Zr-MFEyiO@dmAC9>Bh zK?w;(962&fESj-si3GJ66ZQPWz4j)#=MHK{XDf}I(Y1HC({_Ghj8~=|gq?<%5)!&n zzNubIP^+zFPTTp3v9q|n4d1iBI6pBZB*uB|CW2aRg>~A_PmI0DEe~MN{^I<^l#t*& zy5}dZC8*U_il^=T#Qv_hXB+OeoCaklq=W?512z-XYOCkdc79^);ceN5yY?67C#Hmi z)~_;?V=Y0g_7-5;&QFY$)Rrx>YkzTmVoFG8Eh{rp))LfeZ!>1?{KTHA(of~Os^!Wk z>m?;5#uXORUPn-?y_K1@^Amf<&0#wY@m%|h^Al4-f-5?k32L=BLbG;$Vt@17Pf6Qu zxl77IN(qT^HOjQt5!7mLwr1`8#GV1wvkkXf4wka1QbK~OUz-VPwfAkac79^dNT@cQur?L# z%Fa*hb#4-BsU>EnY!Z}^P^)yp`bP8*%dPEg*Cf(t>p;!K4=nZ zX=KREW%YB*T<#--Nl0jva027iKu}8~TxMWvgtH9nKEj!Vgho3jFp3TYwKP&^Cb`C4 z%Ovk3wMj^5)OG^?V<4y{kCPek@*kEF-#yOqI~I8#C*TJMf?D#NdheW`(=z+J=QIfk zc~K|Kmxn(e2x=(;$Q=qvP(nh{fD?#IY)?av8B9VgMKZb5LUD=hwCItHNk}NFaRSkj zou8NlwG@%%juAy<+mw({bmj!&L_0sR$8aX07URbpMJ+$k&QHwsHqvACYGbawb&qVr zThM&ycNz zgl00CGtr+_oS&Ekwb%>FM&xB={~)0mS>}Fp8*zSO64YXEE*p_wlKq^7W|o=5(rv`~ ziAhk4qf*(3JeeG?NYtD`V)mTCs zCLtkvzG@&M&QHv^mRfpN9)*jDT+WQCNz`+*)ejMIeqs{TQl0xg77>w?nsWmZs()X_ z5fSGnCP6K=P|q9?Vb6*Z5^Bf38YLpmPs~{nwbY|L*FZ#^pO|ws66)u^D@8=)A?FN| zg!;U%!-dCYV2N}CC4 zwck_O9tlcFJoL(^Oz*vIxgVCj)Bfj({j&R@WQmv$gab=Nqf_g`XFqm&{zdk#XxRoO zOT>I2(gun4JGJh0^G8lkdE|}O*q~&Im=8qSAkluO*15NM#Ps-AUf;7q$7e;!5-}f$ zv_Yc%POXPt`LO9{PW=8F8&^MObkB--!PGTU$Y!|$%KLCF#^ABeO;!b&AAdxjT0 z?b~Z?P_jhK2O@2du%|06YYVr&(KpxFpk#@d4@BA^VXZ`3)(d{+O_s40Z8r%@mWcU4 z9C5^ZlqA;L@!M=nO>gYAVWUfy2&0Qwwn3u*j{93fP!cvo*i$INZ=>~d5^?8UE9$9; zEEOe7gw&HcAwcHb_{hq-D>rjc_wl9LFn4mIxc|ibxwI?CDC&+Cm$ti#Xzlw-QN~ z2phGFNE^JCwGwGrFK8a8h_pe;5@Ft_h_pe%TD!EuKNgWTC|M%RI~S2QNQCF?T9K1l zMB1QaiLjWVh_n$gLzj?<_~9oI)QWgzBwES(c$K4!-MPjqvv=cK zUWt}^E1|^hLvb5zZ?-|go?9DN7Om2%CH5NRwWwwFv=Z<3Qc=RFpH~`7)!J*u=dE2$ zF*nGZ^pR-SN(qT(FR!$jpjIobjiPJroRW6uHlBAa+TLt~M0?Waan{)2wW!r<*8Jd_ z9z{uOB~!(?ywc`Uk+3T%F5OH}YuqlVBSY?+AYu2UxOB9^Yf;Odo1)B-pv3A% z<1Vi>5|ogz`rkNS<$X}g+E^QRt3HmbyK`#A@2Tl!sTyVeqhG5_NLVizO4YROzmcF; z{9a>&5)#e(hl7l#pm8%&31X6$xs!r;u}zu~d|_C!Mn*UTL!p60J5j%bVO}nCmgx%lzxiblB*>hW&(f3kOV)dc51zu@_Ylvi7GKSuZntuTsy-;wur@U)yVtMC9en{LPPu_&!e7AhjY}Xy)&u zM8x-TY}ap>=!x2!vGt|GNeI1EBvd#4?oKx1`#83Hxwq=bRh!zo&8iRHIrdcd9z{Y= z*WbR%MtmP9dla=)H^aFGllVT4?ew0SM6JZ$L9Z{>a<3(!-<|`hQpNXiY+rkC4Z07@ z@hcl_i8u+Nw<{7F89c8~HpWur*$GqAV(+SU72n6PGb?(}QOmIWw5oHK3TF=VK1f1s z%rnnaDx7Q332LbwdmfpH_&$!EmoPJlMjXooTVE=i&(Lj<(AecUUb2BRAUZ)Uj*s=M z;`=zZpL1r}6tS;p+JF1r@OCBa^q$1`acrk|myn2^PpxK2#P@NMpjPaNnE887-A8;M zr%&y}N`&?3G#~;`=yBP%HK^wWn+O46+g5$FaTPz4fVOSWB$uW;sP7;`=zZ)4N@3 zTYJNMJFYq>5#Ps2f?9fRo*N|_@qHZI={+?G3Dx;X#P@NMpq8GSXNAc|d>_YldQVM4 z;&9aYNW}MXlAxBJ^qbl_`}M5i`#84Kd)g(quIhXw;`=yBP^)Utvh-RwVj1`SzZmuB z_J7I)LUn!X+wKoyM%h|L}ITiJ(?wH%7aPUD$SN zg!WW-35oK9(b{cy{|Z5^$kL4dVg1i~ReVdx_J(%}3C2OW|9pj@R%Dw-KaXAUeeWwJ zBpA=-Ui}qgigP zL4pzz^`wnJo!hsBqCU2Vct@?oqYM(1@VaU-PM{^~42YRYsHN8KQ3eT0NT}sIfgYu^ zEM_L5mU^v686+qnp&sl+?A5nj@j8=ZW)f=E=!26&Izb7E8i|6io%c4v*|&sjcYkYF z{aZqIno)~I9zE5_m!(RA5?)s$YTmiVcAa?A?}J+M2KjW8poD~cN!FlzlzmIc_UiZg zpq6}Bwvr?U3F1U~xNM2?we~F`+pFK(6}8F-M{7@l5)$R9qem%bux|<3Njj}QwudNO zQAYOKBq-r^6>;RqV0-l~_Sq#tEyhH-SAP=U60(yO`${8c*s+f(#;e$aWrTf8$oA@Y z2?@^C2O9%Ht;qPD4LidoZLhv|hII)Et|0Vp3E5t<6@prkxjY+oxJ}|)LY9ZzB_zhx zkJv@GLQpF*u=}b=?!4cQZwXmGb(fIfYRhJVT9HXU8+IIS$G3zmFT6`ga1F@zP4qpA zD+IM7BYrmQoZOCY30Z!7mypof;;=h&g`igC@6ViwJ)`Hww}dQDze`AH&2rdfx`jH`p22x`UtkD0G0 z#$M#z_?D3E|L77DT#d}V`YQyrVz=lAqu^(sVMC=XU zi*E_p?wT$kp%vj_H~9)dt=LyIb0YS*@5Q%-Y?n}%kQi5lHxbl|{ZTVtL)I<`o6}RW zj@Y=PYGx7=`t1ZtW#1CA9aRHiTDo&zJtsj4udAov1nR@SCDfmlNvNe7^fi4Fl#ozu zIuU#It(EMNpq5&q@2Da{2?@1IC(u9aTSC3FQU30Z1SKTYyPQC;wQmXaK4=nZ zX=Ly>iXC% z8nuU$Tg)5Sw}krGZW3zA6poD~?8Yg0}zC}y+ zEukL!n1ou2$b82-2}(#PIvY-C>X9W0YB7Gy{hX8dmQb#$kshPh7u-@s)C|B@KV&1mC6x6+Ew+Usu(z+j zohG4~jIZLzMtn;s+ZDCgrppHQDE4>QBs3%Q)hOABZwY1ppceaP*}z`Q{%)Iu=Ayo; zCL8fBq3q|>;uupl%sW#;qGrh0m)hS1kf0XF%FzZTB(yd#-bZ{(D92rDam+6p*uy(B zZ$Lt89AkaNw}jGvP>a5+Y{a*O(yNi6M=iphE+r(ix-+)K_?A$5XKFDrC>z+fJ+o+n zM6EfoN5!{u~(UZ^^Jl;oqODNX>s3rfQ6Po%y`U%c@=_?Z?DUnwF{zMVZPz9p1vOVm + + + NDT tilting + 1.0 + NDT_tilting.sdf + + NDT tilting coaxial octorotor + + + From 623c1bcd0b0453033914510f55251906bf45242a Mon Sep 17 00:00:00 2001 From: Salvatore Marcellini Date: Mon, 18 Sep 2023 23:44:38 +0200 Subject: [PATCH 2/3] added omnidirectional tilting drone model --- worlds/empty.world | 9 +++++++-- 1 file changed, 7 insertions(+), 2 deletions(-) diff --git a/worlds/empty.world b/worlds/empty.world index 08922a0c1f..e196ed972e 100644 --- a/worlds/empty.world +++ b/worlds/empty.world @@ -1,6 +1,11 @@ + + 0.95 0.95 0.95 1 + 0.3 0.3 0.3 1 + true + model://sun @@ -9,9 +14,9 @@ model://ground_plane - + 0 0 -9.8066 From 77736f4d7933bb20216734108100548e5efe32ea Mon Sep 17 00:00:00 2001 From: Salvatore Marcellini Date: Tue, 3 Oct 2023 19:46:23 +0200 Subject: [PATCH 3/3] Added small tilting quadrotor --- .gitignore | 1 + models/tilting_quadrotor/meshes/arm.stl | Bin 0 -> 50684 bytes models/tilting_quadrotor/meshes/body.stl | Bin 0 -> 161084 bytes models/tilting_quadrotor/model.config | 11 + .../tilting_quadrotor.sdf.jinja | 876 ++++++++++++++++++ worlds/empty.world | 16 +- 6 files changed, 901 insertions(+), 3 deletions(-) create mode 100755 models/tilting_quadrotor/meshes/arm.stl create mode 100755 models/tilting_quadrotor/meshes/body.stl create mode 100644 models/tilting_quadrotor/model.config create mode 100644 models/tilting_quadrotor/tilting_quadrotor.sdf.jinja diff --git a/.gitignore b/.gitignore index 0737a57b6f..32e5a2ff47 100644 --- a/.gitignore +++ b/.gitignore @@ -32,3 +32,4 @@ models/tailsitter/tailsitter.sdf models/advanced_plane/advanced_plane.sdf models/quadtailsitter/quadtailsitter.sdf models/NDT_tilting/NDT_tilting.sdf +models/tilting_quadrotor/tilting_quadrotor.sdf diff --git a/models/tilting_quadrotor/meshes/arm.stl b/models/tilting_quadrotor/meshes/arm.stl new file mode 100755 index 0000000000000000000000000000000000000000..943fde0e3020cea62dd7a63d6de59f86b4625f70 GIT binary patch literal 50684 zcmb822b2^=_qUfIW<`=Hs0i!=29h8!u+uUH29QCr7*T>Eh~N+fWCaPzioS~Eq_6=2 zU4$hJGA$~ivIfiwf?xtfiDE$ItJ^)*{q*kezW>j2_SnbYedcy|Ro%L`s%Grc_2x*8 z)?Kf!(Wp`VX7wA^Z`81P4b}1Hj-4|XEn0N4#{c&}$I7Iob^CCvm7jlFB2EAEarJ!l ze&uB5k?^ne zbL`7Od+2xN5mZtW;zPHfZQ7iKe_a&mH75uCiUgI^g!s^(Z%a>+_8{S37e#KnGY8{? z1eMf;_|WgkHe-;4e_a&$=h_@^GzSSPsR{9+ThErBBF{m>zm|BVpM&wrBdDY%;3J`3 zWRdW%-RCf|(z`2%kk2(rY69=71mV-k_E`UtAFt%?I)w9nl1geqd?Z`YmggYhU%UNk zX@BE`gtW6!QWN4M*%KWfB>Zc4d@R1o_#h$u)hMY6@sS)+jt>(4wL8wQFK2v^ka1^} z)P(p*Mh3?R3IE!}tEI{IAmPRjS4mAIeMn3cA891~Yd7wiyY-@|Lr5GnN@^nct|YdX zAbeUshn_#oTlZ!I_pYF%Cd7xt5$P$;bAa$a*PRDV?+FqzFBv5@AwKly%UtXDAmLvp z=W}m-kZ|VLq>`Et9}?G-Bg&o6lY~#Zd5Ia#LBh{>cDR{^Lz566GTS8MRhFMw9NOex z7i{vgnnRm{1eMf8flo+eKz?-ypIhMgbDsk~9KwH&QxW2W?}~(fU9ic2Z{mXlmDGgz zNZo>m@VNz>{MHm7B&hiQNQe*iT@wDaZV#_diw_c1QWN4s_bG1-lJKt!Hu1eMf;_&}siBjI1` z=kR6;@j-%0YC?QS9ML_+eGYtZdL9$tPWK1fhWO~6N3e30<3-RE$t zKKO75`COx1=nxVIjgp!WANt89wwEA$T0e)L zKg?SX5>!$X;zPHfSp&!-;a|J6n&~}3Lgpo-q$b3N?ulkCBa4K8ot)3T@j=3wUz18| zLVU=3lJ_O;LBhXw^AaMoCSG4;g#zKUub)SsV()L1s}7k!1)fe!MzVEW#xn z=znF|B>d>ZeD08YSDp_(2MIr}B#ERO_c_dy)5?Df#eGmA;m4KYK1k5YZ_VO9sF3jE zN^u_~Xyy0H;y$PZ2*j~qo0IUP&mkwjGNU=z=Ki?T?TpX$<4W=8AVDiXN)#v9m)I+v z_vX|I#R)1ToOb%31g+$~x%E|XA5=(4JN<8hR`TB53bMElDgh#pQwK&AK1*8De6GA{ zx85!8g9-_0r~ggR%56cDA>*zrf7I>>tXcWve}}H_NKo;|;ErOeQKusO$iTJt;y(PI z5&T@gzx_9YR(|^zC#aC{d+2{7Xyvzmae@j7zlZ)ef>wU}7bmC$2(Q2WH^T47JDjy} zv+@#bbH6X?_Q2=*J+!zF614JrVsV0fiM`T!Z_XT?B(mJTm1R*O;j}D?WM>Q#w37Gc z<`TtyP$3~L8z4L%Bxoh?&EL(?=2-6C>)x71Bz1C@aD79DzR)r{_M4|H0P3W-p`GS#r+{3LNfxe7UF ztz7Q-AVI6`V^^phqT?);YfC4!4)!32Algl2_Fe_q~uLmKNsZoHlcuD@xoIiPvsktuk|#Bz+{N&d;6L>@=q*@(F3R_xwV&^Woeiaow~rb(%hY zf%6J1)H`$I8*)mp4-m;_%G14 z!NB9=?6qfQw~~NDB{dXXxEs~6izyb>Q<-Wy=6d$xoZUDvER6%veNv1qKpowoITn)Sur zYuAyW)vKlEs2zVvgcBd{R=m?*QL&VD>F!u_DkK>BV$o{fwX+*vTHU%}U~C-;T5WDT zS9O~#F;RS!Ti4FMtb289YOPt#sgPi-j71N$ZfgIyrHR%1>zV6F(CX~z^VAdjB#MfU zqh*`g`p;4=)-EP?3JeutTsM$ta?qyEUU}6r>&<# z;^JHLREI({4;BvmD)WV>9<{c2E!Bbqt;#oBs;(Gs2yJa^YU8TtQ!N+=8Bu>-G*g{% zz>UGNXye-+wX;tAv~gzi+&C2y-STFtJGKZR?eTt_QFgEE`zLBHK0QQ&R!h&DrOI5G zrwNI>w@e#p52`&Z@$k_0aVjLLUN%eR?w0vOd_2)`u)U=A%EX^XA|VpA>Qp#ORqB$H z^s!*YAiGn|^@$6Ae=JUg#NVIHQmxJxLVUCs+S}fEbbn&fjFBM{w7UJ-*{WLJ;-rto zyL;J9@{c7p+&MQ+g~SYkte*Y$fTbZ4w7O&WT$NK`vW(8-LUzGj z4eU4bHpi)uC~eJC6}k%{KDO!4AEy0S@eLsowCd7szFIwGVe(ydf3l{1_m;Nyz9&DA zQz0>K(|k3gsu1GiIsKl7>-TkTI$8|E!BD4?FDHqNzjUQNh~_;k{`qCUg=}^ZIQNt3W;95URE7Cnej1S=Wi=? z9#^n7ttAOsv3iL`@3{SZYjoAFcH8UHHc%n)<-f0}A$lCTefMmgza3cH&b~O2){+FR zSntH5-8D+OMiUS4pInF{q!x($8Yoe72x z)U2&${?Kh<={B*y+?v*s1g%(w#iAAe>0_O>@B758&S@K{kjPoHT2+{8=0V-3EZw&f zvpz^`NrG0a;bPI35<{%+Bk~j9bxqqqg@ko`p&Hd&G5~p3dTdyFj3gfXD6J(4TCq0N z&oSi@>)80tiAZ-n&QUdzxbTfabxsFabrv6bj9U-sJnq(QdYprx6|2`+v{#dHR$-eL zHm=h?sE`=FuTX8W$D%^r2&}wNPh%uWs5OB0;O&uNJDF<;;rLD}Ri(8XjsAo^tZ9I2982 zjx1DLFMB2FV@;b;mYzexA5{DyM1ocsZ41?%+l7!E?#4@pTG1=#gd6;LG){%Y>$_L0 z&;K@c?TChht(mn~hD$%aBSeB$k1klPIxJk7^s%A!{np6tUxa`AZC{)UiJs@LR;%7H zb?wzdds_uZ_lIx4W?P5^t%hz|rLJ#p*5UR{ztw6r<_zn{`rpK@8*^2`JYW)JK_t= z`uMSW)*HXC43P*}J-kxA*4nJ~ef({GtJiNKYf<$L@fZ{mxwjUm&aKxbpW{>g`J=R- ze=l4RB0;M$XBMaxSwhHj{5Ykub^E&=t=Zdh;#5e?edA>{rLU=LXY2PgPQS0$?wK4S zL92g8zpOSsV^$zP8hJFl_nLdG+67O=sgRg_)(SPSi>Wyiy1hfX-J891dx!+B%6_z5 zZF$hFK;HB1+VDp|53=4F+&4~z#FA#qROQo6t(K$v?Nr@=Cx2fvM1oe8&snA(s$?p! za+4ko_g_2GD)m{tI297}J1teuj5R*)k@2U;;piXUX+eTk!Rjt|;hxM%4?b$mxp>=p zDkNAZ#-cw>tC)UM|GBmF+N-mx@9u^dY+_{a_uC}G-CwzK`tn^r*A#*Z3C6BibkgQZ z={rtqwYWGzD@N28A0!yNV$pu;+w{I4 z4wQ9Kn+gd=qTr4@6%vdqL4pbiMu{Lng#^cZkf1_>BiJF#&W}xngue^qw8x{j<-WhA zf~-0R2wHIj$D-eM?q2)j%(I;qq(Xw@F&1q*@Z8#OoN<9eP$9w5rPqC)np>;m%8Cv_ zg@nI@CC_oJ{NuF_wy9KtpjB|xPAp7+(T-Gh2r4AF=A<+IS#uY^yTQFHDkS{Z zFIlm;-0YGBt+;j;i*_7-`I7MZ^PRh*LV_!LvFO}-eU@}8JkuelknndJ<*p(l`Y&19 zwj@C-u1snl;YV{{eltHudI=R0TrZ79e|w^7&e<~tI(J2dgullscQxb5Yjc_&8c>3u z71w=rw$!gn&hKAzb_gmYxEih3knbOuvus~ehoC}&Yvek!Tr@Bz`m9S(A>r>}%X2(- z@9Nw)E`QsJJ|t+xwSK+(I^fLQPfFkK+!YlP+<}Nit8O?mxBfMK9D)i7ekw2(_$Nn%c%n_^+y>Lm zapouzwBj16-h*sjDYt!t$xEasQX#<=&sencnu@vaKReeUsF095biZ#PcUA6i`P@NA z&&v@XBxuDIPrU+J_3Ye--s#~GR7i0BG8U~p@66mEPWE;PDkPlNbWT&rT{VfXU9z>; zT&G`=pcU6IW6{T}T$p>!@~<5qR7h|&G8S#LqGIlMFYIv$DkP-myXUXuu8to(J@=Zt zlO+gRaWzsCpC8ECc42wvIjE4}+M?croUtcoT~0-Zph808ihCAI?rO#5Z|A&z*`*~2 zT5)Yr=M1@Xa;vp!>O2P(5?m>aMcaSVJ0~*vOveWm5)y;mvp8~BH?(VkAzpRJf1FPtv`l(}>)YBi-463JLDe z#iAEJla>4S-wjIK6|K167K^^xa!>Ae>%($3%BI2{Gy0B259RgAl|Lb-E_(`$o zt?j4eJn(+=5_d&{`&6;$rh$!eewvY4f}j<5onq0O&s?^oWB5jgpu&Bl;9ZTl>B%|` zx;*Bz2Ne?B5sF2t#2VK*yTK5L;QB7tVGotssDABl)-01nt^QY*O@#zkSamf~)IU8` z{cor5lAsmWOQp9Tul?TornSWf6|Q*llccx*Ui;+8aSlO+1lKa9x2L7Q{r4*+2wHJv zG8QfW)=fG0*0|SckAQ;JNcz^5*F&??<*)d=;%a2hoaL&;woS?2K5*j5^z;|A9U`E> z2iF;6Q9WYQ^~fzj(2A>uv8av;wRLoG2r69n3;2%e$WvQKpb|bva79m_dil@5+D+aa zQ-YusSM+qna?ba)c0D@LA*k@|NARxxeg3MvI;$>lA~h8fJZlnMlkvwvcEs=b*%5y? zGdp-r-=;#s-P$A*(G!`eQknr~nixX5x_`86`2`VJ~J-y-t6%zgqU2%d634gy$ zh|VAVmjCn4GwRCtphCjmJu6O7A>r?ZmAEVKJau-&KW(V5y|dND2`VJ~bA+-KEWWSG4j^x)mp= z_-ECM-&N+QaaN;d6E;3v_h{(rcMH{T6Q#l`3XJo;dY{w%t(PKwSKahJ=SzB@v+Aqc z<5bwM{25N}%F;d>H=B^T^Uu8@60{QE0|&}Jr})U$`<#pQKIcVMKZ;W!;m?WU{^PCje38jlip{!C2v!l3JHHk6(8Z>9=1N}_CmO8 z)uIpyTFoe0ty(sg3_yI0)B8m8^?uQ(cNfH|knrbS@$q?1KkHcf&hV7J>q8`HHRb3k zb@Z6*bBd3qdcSME-uFtho)@P=!k?+d$B)_Ft&IG$twuW*he*(B(Vkb;wXTO zZzubAS9X{fr$WM?=fy|WUnAD_N7Aha$4m{8pjD3rD^<QS z@zHX41*_ImwdOxBt7Q{p*HU~e(C=xYeqSHtZCp=wUU zAw*w&W@3mwGjZ<^N8=pZj1s~5<2F48(`=R4yXHuU3JDoE2jwQX5ET+KZZck%np1o%*JoI+)@N8={P#$l1g$uu#-c@f z4DL_gndtJt;Sd!PGHxFHN6zAij{ zAtB@DireH&k@z^M&lH`j&lEjf{z#kzt(bl2?*iyC*y2dK{lLycAu1$f+*sep*(mX` zOP`I>fA;1XhvOt@#hggTD?J9cjL)>!^ga}#LPEyP&)IUuOMINC&v@x)u`{Y2j+3Aj zGd2BP89fHq9q(jc{nNn^6%sOT)(n!fYT`q;g{9lXes%t#I0;%Ye~d-f=`mRGk9+M8 z?mrl!LPEw(=gD&BPJHM-6<(pw+&ysVp*RUzF{{<9YM&H@@3aQnbNBulqC#R-+A{Uj z*K&4He0;CZ4t}W54&FTfV4MW4m}|$PgLd=|Z=OENezxDQAu1&PuDVpU9AJDrtj|E+ zr_Vt4y!c?81g%&B=rb&NZ)KjpO`j&;^Gk>di8Jfusm3jhkEQx7XIFieGxW!{?Trt8E^6aseJ1tru%F`mEL!<%1LC97 zpjwGf){e1j?ED+2ShFJ}8nj)kD$F%LZqjFKSL?I28>=6{N!jcOt^8FA@iBSDe-gC@ z4720sq_w0%Vs>Bsy@`6JUrpC%goo-g!ZQ#2f)l^l5nB0cC*otN^oyYue04JBTBee2Ycf`jng=Ot2`){+uXa9@S(Lv(QL-SSU z?`8}>tz``R{8# z)8GCQC*rdswDMQ<#K)cWI@oJ2xyU}b^aq@}4-%#K%vJ;InE7Lveou17eOK=yob1nz z(8^z1be`k9yX~-bBJtDqFYxVwATjB{EY)$ld{a-JqoHo^)w^*Ee*%?x~FBs)SYe|1=V{Pe?EyXleA ziGu#~@vW2~@yn2z>ilu?T|)6OTgQ=CbUb><__$BU!__)2zPI^?cyYp5`K#*U<5&G0&5x80Pn~#6hzdVf-omKfa{5zz zjMZ^{oR04o?e7vNK`YkkI(yaaQEJy?;g3gj2~i;-t$Ftia+Xtke6Q!HLwcUd{&#O3s}nU}4-f9wJw%0s^vVhsni^-5o@XsR-*(&5Gfsk5TpNf**X!}o(K-?C z)2U~O3JDoqzr81?Kjk^z)cL|oI&TUxlH96z{{M~U9wBnjWEE?DGs#Vp-R_E$>hp3Q{XxHjZQ%4=t`J4W;){nS1 zPJ&ikv4};>%)iXOFylt6{onV5sF0ATUHgQoqx3V_`dO@<-TKB!(2DCCIwtD*WB&fz zthrzI2~i;-v(Ko1O&z7%!q#nK^=x>5oCK}75)z9h^gMW=$^%wp<$WP4BxFwf;~i5+ zg>_xndJbgf%1g*G^qF3nkeBN@vFw2_sK!^$nncF+|kh7f9uMX<^<~v>Ibp86l zI0;&DeI^#IrSp=X*N(BC>+xWS3JJ+kGV+X%M|GVxTGwlzEFBytK`X8x=}4{fs}4KI zS>g1-Au1#!*J`lV_$btCKK=FDPm5ah<0NS1uP0~gCoj}_V#c;dt$p*GhNzH`oH1jv z@v&O3`7F|FKLt~FuO~q(f5lsTOw#%8uIZz!D?Z!bf(i-AeLua>_>i-;AL_NAg-5Q% zN!jcOt%8+sfzI1USc9#p^}{%g8zfj$2hKn`zjEX53_>so)eH+fe{H(7z_Ai>Hzux}6`XvJp=-j%;EUld`L z%DWBvphALm^r;D2@tJ~m<)2|Fim>M7-3EP7A;GHn)C8^gOu@VI&wCU_SV8h`gFdK` zV2yiff>wN{;9dD=V~QfI2YI(aA5=)NVm&oMD?U?@@Xrwy1*$vVZIGbCdXV+!sR>%~ znTiqK>93+db;r965>!~-v6?(JK`TB}knqo^6$NTF|Abia$UueF9jnQp4-&NEGX)9% zEMHNe^5WeF2`a4BSR0<2pcS7fNciU-ivo2N?>0zKVdce2@6-gX_)I~&w8R4KgMAVG!o2kV_v6SR_Rzq;eh>9mLQdtGh|nwmr2 zh`HOK4=SuCSiPK@pcS7fNJ!sxf8opR?WTg@-3AFNtPNO;oSL8&pD9SlsC9qs%Z&`C z9^l;u2`bF=Sy`N#pcS7fNJva{e?`oVq9(iN-3AFN%-dNfoSL8&pQ#w({eM^78OP-6 zyxSl_g;_YW{!`;e$R%(2CDgjPQO%&do*5 z{weR)BlOJ$pF{FCLr6a7?~L*}_*t}){L0_wB*D*>%*ph8$z=UqWD-6G(eG)Ju{l#pDpu&}Z`gTqmX6Vy~C47+Z&)mw}mCqMH^5j%V1a|@C8RS`t z6SNAh>C1c4Cl2LYpGAeM^7QSTbK53YtPaKvYXcb&N*C!1#^oc_` z{b^C*nl*jv-%c3vWF7q{CuIZgiUe1q^;w*4Pt?gg+}ppsXWVvG`%c8AylyA;I%A&aVhs@=Jo+Nt#d8XzgF~oUQ!Yg8b&7A^gue6(KEnD#E9;BmTTn+y|A^ zL~$P^{Ojz9A9suUppu$M`fz@6QQj4MwSUdu`z=l|mZT<=>X#V7Ms-P333y@?ub zFOlbPdLk9Jjem`|D?aL`CbA>O_ls+;DCUC-KX=xc`6_t%|Uv=9u zOVxZk4C4AkseCFV4osM*`gNbJ4vo42#JDN7>QW(b@{_r$OSw7f*S%2?{kqi3r$XYJ zGv=yc+vcdFpLGTC^WwgBsgO9Y-W=6t|& zcve0Y62Cq)L-l!Jp*nJ94-h}T`F$=G60>GMuj1D&Qs-3c4C2IBZ|71W(P8^^b=t{A z>hinVgBV|b0D%>MeXh-P=Zika13hMCZhFDy{m9YUmju5TRjJ@~Mz0y8k&f zX~>JJ%kc&vUOBUFT`DAcWIm@(%zIJo=#>sa?urTt|C*6O16iqw8m-NLuf6bM`1s{O zoqQ_%TywW8&MXf?Ke_iDqL46eB>VT%K*)1YAz|Kn=7>MtdC-Yhg)>jfr$WNCY(nh= zp?gUN6%wZR?E7jv2;CDisE{x{v|9c)5W2V5r9#4tf@Y<+g3u$%8y}*OFeB~YrSE{y zqqa5`68;Egn|FOGGmiwVOvETx`KopO9E6Ud zUQ85)go&=T>hA%eBefTIMIm7#_+{rD2GOlyDKEB*Lc+`vJ6n`0))T3aFf-Af{bv;; zsE{zToy@^<>ZOUL|Ll*ZuiZ$6v*^;nQ&s+wiOJa+L?#sy=9ApH_Hgqi)~vQo>_)%8 z79eOfwdYi|dBa52x7?NbuBuL~Z+$efzI~$UlrR+%=K0*&`GxcATaD}1x2Ii_9Uy3R zqS92=Ep3uozFg+>mul6rzBs#fDmvG6ds6*VZnFA) zz>V@8cm5UbT=uU-r88StR7jY<>*fqoUpX3Xe%Z0a%MCIE1g+|KdqUNEeX^RmyQB6| zCx1)0VXG~P=X1MRR7jW+}hMGA;c2 z+0zpB`stG|P)L|@?&c-Wj~gGJbistg=rw}^1g)N$FpPT#qeO>*y{QY?{NYKj8nW+Br&{X52(x#1-R=t_I{pGP16%r=4ySdM@w@*uS z>RdKlRX+y_T0Qd04&wHhwb@xxJ!c<6@{L0M} z$8@c4-|*el)?^)bNziKSfh_fD-Di@q{kb0-*`Ic5Y|Z%M+AtLoCbx4l%WFqAv0ImG zV%6322MJo;{aKbeVm*_bqpE$_#C|R0R>D+Bm}@t)gpZA>2(dE0=l)qqk8?anf(k#^ zJd>M?;#~y@TA6p)wTsN>XpaOH5~gk3>=kVuAZTU!La7JRv=8(vn+gfj$J~4ueK$bR z%Jk_9br0&?2jj!0Lc)v{H$%o43=p(3V{>1tZ?zAMbDIhYGv?i#8nGlm(8|P^=cj+F zeIQ=hR7jZE?%GsHm>BHl?TGCGf>tKxpEE)7_RswJ!=^&Q z%q4E7k2xwp(8|nqNgw_^Xj36!=0rEs$6OmAXk}(?_g!H=x2cdYbGus`AZG{=v@+R; z+vdniY$_y7j^b7m$bA9?txOi>_Fd#xHWd;k*K+F*|?9O@)NXecc)dIdy^rtxR_A#zf@p2`VH^4)0b)s0{)HtxT2S#&*;n z2`VH^E#lTusBt!upcSj7K;@PB(hFtOSDOw+q+YuD{W9vg2M$GKEj0RUUDf`t>Ln|$ zjZ{dOPjc@{S6!CAGpW1+1g$FcsjDW}y+pZBuB$FfKfP352`VJ&)+nR4zjZj`zFl2) zS^5o2!O5|=5JzA& z=R}4&`OKxt?TNbTvUG2h%FCugVq5)E>dCy{BFXxEYI#fdc&WSs1g#dopRSH4E>rG^ z(p6Vjk1DCWY$_yvoqsYCzVDBSJ8E^+71kqHDz5-Rt6Oicty(v_T)B}!S6yKp9i;NI zsgUS5awz?x_*02dMQeLZa8;!;yaN$|!GE3+b6Hq${rgL95Y! zS67!lQ#a{DS6v(R>?xI(O@+jqWxqt;z3MdO&d$2(O6VC{Dz5-RtHbA4Q~6`ANWLpw zbtQBbAeEO*g~Ute?vHFbQBJv8hOW92I@6HKD?reyu+>HC`;J#7+gw*&37ySIZ;4u8LU)Z z0fJV8j#N@t&S{v8CA#Xeb(SoZmraF4s~dJj{aukvE|ph;1g$DptfU?v z)hHPgb=76-Y+ov`1Qims4}TLWd)B$ittNEUW$TJUDz5-RtKXiesFsv&oQ&aum! zB9&Ky3W*Nto5-PF=PI`<(p8tOD0|Dy0s3x$pp_W~?&=`Mhed^i87s-v4}S~>2wIuZ?5+-CoLf{#m@)6J;vkj; z2wIt_aGqV?pjnxm>BG?sv))q2wIt0!d)H2{9#cc zVdfHVbCFms~2%89u)K+wv}+U~o;d~Q)8Vdi#swH7%;fS{Gh zKHN4(USd%pVR96A)fu@@fS{GhqTIfV{K}$2!sJ@+>N#?_06{C04Z33xd7?#ygvl9` z=K%a%G(gbGWVLQALB4BIAz^Y~cQ*q$b(jRLOm^3GF65f z+fjdnsgN+Wh`YOl8YhzktynGT|A&Ir#L|CuV?C>}ChJuFVHJJ6pEHxOh6@r@NL2oH zh!toMGKrH7)&TZ_`-@30kqH z*1snMf(nUw69=o()$UK`KHm;4Z|Of<>1>Gvt+<+?*Wo}=A(7kTA@#?N{gXLdpP!C~ z^iWG?#Jj6_)fB|g*HD+yY0bte`jL4`#3mIKvI zeFr9U>Sx{=AJ%_~ES-gupcPlCVo?%QNL+OP18QRPLCM-+{5hwE^=S3ADpal%5J?YNB;D&jKDe^t+;9!i;|#1V(g@T>hg;pPWq5%kUNv- zAVDjxemc+L5mZPVo!v(*D>pRxuB0vG4NH5FpcPkfo%ZkuDkRpveXsiIt6|ADmp&yu zMfw#9T5&bn=~o^>g~Y1r_oxFCMkM>Lj1B4WGCoMqimU3*`0xlSB<_3ZZq@ww$mAH5 zF)kxl#yJUEad*HO=N>_Y#NaV^srt1aNyZY1RT6`cR8GRnQlhBta|V+nqT{P$6Obxdh%-U?+}N<{i2j00}B2%zJYQw0U5EkXEKIxS0$I zDkMz%y9D}fU}uz8rcb*W83`&ROh0xBjKRQuEv?MhbTdm5R7jZd=n{w}fqiFMnHb|{ z$RwzcFmc5t5EBFY=d?1h(#`ZqP$6OBqe~#R2hIV|%EWxPVj)3=go*Pmp=X?Q`IGbQ zBxq%3yOIPI5@x>g?#j%yfs-7xGIOx^kgNX&h`y(-mRrKqDw z(8}~mcXvs$F`1_%Bcnnh=h=4Z_X%xM)KMg8Wk#2~yChkq%u|wCQX$c^#!X5cZ=0fy zB0(z?CEVR5$&O{7k_?#&iLS$MP&X{PAw?ZUf>tKlxw}h}<;y%JnLZT~RTsBakH>CG zQAd%Wm5JK!?vhk1GEYgxLWRV%HA&_)oN0FeFnSERzVr>X2B*tuN zt!i}ZkfM$vK`S$hy6*~etxbi*kxwo4QtOT>>L?PlGTDIJ=ExarDkRpF3acM0bxKi3 zk)V~yYTUky+{dOuVr7q3YJZ}0iaLq}txR_2jzQ#bHWd$fCAz}P^v$Lrn!z5^B z-l3NPcmx#^=Dm4YhN*;fg@ozHUe;$; zCM*)PGGo)rEIon>2{RtO?A5HWSR`m=VvLs|dju5{Ca!o{xLGN(NYKi}N-xv*2r48@ zeDtabv*Klupp}XFUd7@OR7jXOU$QD9K`S$Nl_aQ;F!PmnS7zq4NYKj6!QPX51Qily z-u2$D$p9=8v@*Gb*Mc5Fg@nl;yk2558H)t1OitwWM310C!sJ0-Z#Nm4MS@l)xAR7n zM^GVQ@;PtRn#|H7K`WD^dXd2+sE{yusTX}rh8!kAE0b$`5zZs1kTChR7e!5`A0|O7 zQ!{vx+9RltFm-}A8<>hElLW0;`vj_@Oe!Q;?*xdARJdzp=#q656%uAI%$uFflP5^f z%Djb=brcm6W*5-QGE565NYKi(X308=3JJ3}>19i%C)y-vWqM`FI*JMjvn%UmeP%@2 zBxq$uSIIhx3JJ5j>}9VeGT0<&WuipMI*JMjvrFz};U>b_Bxq%#UCBC%3JJ5@?^P2f zQrjeGWukV;I*JMjb85jrUQhH0DkRLQ9MNOukAVDjW z^?Q-pBdCxtr{28Tz*H<7NzjVbOR$cjLV{=U0z@VWS{dKo%xUf_lL`sr&zqgilZQ#r z%Dh7_1MmncB+PsBvJBILVG^`5eZk9QJc0@d)BawzWO|}Sf>x$adl{KWP$6OZv6uCk z5oM8}l^L5}X6X@BNSN{HWv?bOSR`m=VvLs|dju5{Ca!o{xQTEU30j$0>1FyJL4|~g zk6txlBDF<=Rwm|q6^lnuAz|Wt$*PD1t<2n2lAuDu%vauBg_A3g771FJIoNx0kDx-r z%)8#(4JTJpEfTacxrEn(9zlhK$sfF45>BoNTO?>@aw4xMdIS{`CJ*v@dpNnWZIPgr z$?d!mGfk)Rc8pFmZVNreRKotXJ`G3V^L|GQe*5&nXi z|KF3pMq-&?%%VcVzvl0k$gjhs`rehCNi-)9-S1!}e=*DXH7hFSS_qzQbe_Ze{VQW7 zpG7NkUGjH7sF-UxjmcA*K_A9SK8sf7y5z5sP%+nXs+6ZqgFcLvd={;E2G%G3icQR* z!qd3?B%kP!(Jq4u37!}B3AM0VfS?smG5f?{C;R15;dyHM_K9{MJd#U=1W$bXM0C;k zIwWYtbLc*C(Ff~tsqjQRKglPC=FboKAi*>HKC$+~6@llVm1)i3uiTVhI4h3|34Zs$ z_wi`6tN=kPej~ys(g&$JRQTNt`u2&?>9^ORLW18O@d+8{Bxq%>gTGC+`NPNZs2Cse ztsQ=n@8jGnpA0-X3G;lx-=?ZG`HjGH(8|2G;BQl{%P3WsifIq|-c{i{y_K|_FWa3+9^ z7X_kBLO=$Edl_;j6a`Tx1%#jPdTQ^d>RHw2#e3uZtbz#9v_=|(M1>id-DJ9-#KeG8cX)M zYv#f8jx0usYrE$^-5I%L;OO3q`~0x?v73(@88`9h-l2zA>7P9~w|B?>=k_{nBUX@r z79~ooI&xCXsnfpnidDO}oPR{I)%a_=N~qRH-~5%4pKLy__i!6F?kLacPG0}B#g|`R z+Es}Xcc1ySk<+g{y7&0R9~$w-zxBEkK0UX%Vcf-zP_4}$`o_q*>mAVBXk*ye^Wx{b z?>lL);yXv3-&KhcTdZ;N$QlQIp|`~i*BY@$cTzd`O+~TRrx!aywHmLTGP3;K1AD*w z-G3SJz=Dm+C4ZV;d||I|bXB6nVXvMtviRej-Ve5ijh#>2v79x2-C~so=Q={QcK-ag zM!tO7{NBF*dyNqnuR6Ot`0@$G7borQ2-TXp#pxs8UHqTD$G?obdUV`@K@&SR)`g9oo}OQ> z`^!_B|32;R6)I6;vju04ti9q(y&dnq+K8R+IidW`8n4d$`8NOI2-VvBp)*Ggoq2Gt zam6`CoHe|toOfzD^YkO%vO*;}@y5l+_HH>8Hfmyp5i^xQnp&X0dhl_*_C~y`3qSG7 zii1y@;Rw~j^S$}%&-bpIio3#-Pu}#@?n&$1Ia4J{pcMYF`w6`@pS{WmlzUv3Ja`VdENWCBHdrLb=P? z`#3_i-e7Ha(&I<;HvR%^pd}tWe%1NW z9r7w{z{5TC*(1uCAGp>Lss+!t`lUzrwtMa@BWf>Nn%`}zBqzT6_mg_R8i$rxd+I&{ zG_~Nt-CZ?#S87AGR+)RWfAS`uTqR1ZvHM}Zbek+)B~R3`(fh%y-Q3-lw4VQHc_J5AE$eTtN?~glc{4=Dob%EzIu*FRGH9 zphpdU7ew&XN+3-w(5^Qq*c&LJTDV)+;}q<1RH6h*!S!kddo?9g3#IOQ&VoIsN|Zot zy56~9@2rGsU21JNjTz7qIRa3L5@?la%z)O;QHBz#g_iF|G6hF6N~jjzG&fpmab0LnjH11Ls>NFbWDp#;*@!rjuICsd*Y z(#;=i*6aOjIJ1!x)WY>y`)<}dVvXga5R_=XNFV*=K=1osA8$R5l~sHW%}cd#eZjc{ zy@lT&ji5vcq%WPad+$$|Z9j?)C8z}(SKYr`Z$)o3f)dRa>0f?&UhjRkc1E$G1hrt} zcN6CI8h;p#phWXUI`!vySt&s+*hr&{ci6b(FU8#Q!P_qmEs?DO?TW1uBb*;^{*K;t zFK%HqsDw&#VxYNdXw#kcEB8$*4}7RucK)_FjD46FXllK&aq7qoSFO`~a>K37M)$!< z<=MY(mM{NxaZ@EqoNB}_r>#=k*lFVIa{e(B%7>@TafE7Nj5>4K+j`&o=ZDP3HtWtV zZ##NIxpbR3VJu2XPOSZjakY)PHbUOuJvVnBSZy^&AYW=>o^a%9YuP(EU^bLcNlrYl)=S>TOtTSY zEX)fuwLstd?KOJSKG94z0-=(exa5@QY8&;FH?6F?N+3-wl)^=Ot&Vpvl~o{Ak`s#$ z`D<;XuED};u&V^p)Ix2pJMPalai_Jbi+|lLzVO#-?!4WFPXr0t)%t&UWAFZ@vqn7e zJ!`we4>gPT{%vtrB})AB-=~ahbl_^e%a7Z^o@1P~#0!p@Q0zNnjw4h{@3tbYH{w$R z{yB2uzBAYBEqvRpD=91FOD!$+*b@8dBPUk*<@&vi4(+X^&XF&*w7tca*w?Od;^G}P zusZ*7vJqOl=7lu1K=Un#HUgoNoGAW#!`?NImZ_}5TdM@p)Iurn{f}i82$kf-QUBby zH)o)0HsF0eW!~qJ>E4%srk47#PWz<^v&%0ZJE6R_>HU=wpSO0k)n7L0&AR6nvjH!< zt9jAq%!_JXs)bfb@7if!dC#PB(Id_B#%I0X&50L2w`p(QGW5=4`F7+>Egf-qLM1uD ze%_B{lt7wV=+!tz@q|ipf+LQ2SB3RzVU3LMHtve=Jm@>0Tcvm7synAA4}?l`;*X2| zQ2Ua43|H6~uB!yn)WY5V;-Xc0Yn}ibN~k0!nzufdY+&pYY$$;=wa}l_UK}m;5vql> zd-A4@0K${2Lud@lGiyUN}z7;|MJ$hayKE>M{Fe|R7-0!wyRj@Y(GlC-uJhh)q7}*9g>Yc zLbZ@itt78=N|Zpkz3KY>dM_+I#%zp5s20+xm8|~e*~K|un@}FN=bWZWlsNR5c_SBH z_Nm^xZ=G*8ZeDeEvFzjtC?yo3; z775f1N93_SqK6})T1dOOf%8|CD1kP{nMG`gvF(yjEu=Xwi9~FPlqdmvoFR=(s20*` zWSO@_N|Zpkai$l`Dtb5)s)ckKS=Kce=A0@~0yXRAwFT$3N~qQn>p9)rx!~McB}$-; zapoOHmIdeMN~jjnX=ItVT}qTd+vN&E95ck$PC~Vi=K4b%$%HjBl_-I6P+B9ay=Z79 zs5SOQXeHdQL%OdY3@uS5N+756&)BQC-#QDDPwXR93+dFK>pQ3tB~Y`|-dglpx6MjE zF}#CHs20*`TypGq>(x$}P&8)E>8eDDw|C}^y!_DndYA714zmH`0wZ3_2-VV2RHwcF zJ(G&N9%&W_JiFM9uarRj@3G-Kdq-dQqnH~x4C-HIfGO}wNTQ0H~YOPOB7{A zAFR*h36x4(TQ zb7#=h!aUl&=U8ZY6zD5sSp~nVlAL&;vvcpdPqxfc zUon1mx!{Be_cvOy4cO)9_gShHOC!eUQ|7Fy+$%cu9A`xkbw-gMif^2R5cW%D1^${i(|FNjY( zKD)Q=B-qGT?ntN>-Y)KJc|s*Q!F{Ue8N!H638bk7FX8s?;y$NJa)Nto(MDXqqK^W- z-Mcrl(|;3tpy^jUp^}`~^2p74&leL@Sq1N-1k%((DbTOPvWotSlAJhc-sZjIp2YZS zlGXW79%~lsy-@8mkU+lFQZG>vzcXUV^NYJGQDQ4=F^{h|v)4FbC$q7wwZ!vJno!)c z+Z;!z7Fs3!N<~~}#4l!7I}McN#OHV0v-kBsV!T_wgVA4+K)%$%+eN?P36@x_O^-W>@}-J_fqkj{|elSeN~&j}lcd~yK$ z5y6Yn+j&C0T235z%|LJJyq!n!qRb04wbXaT8jN0)elREg=esj{-8aF;Z+RWQcHbTMLc7~uU=f-Rf!VcvDSXizI*icUvjM3cy{&K<#}J5P+a`6IgU^* zyesr}74ah@zQ1SXMJdUNbYd&_q9l+nweZf<+eOb1{H{uJBAq1vM_jRdQ?xS=gf(7p4zQhAYW>!f2@dq8?lZN zDp5keR_U~_wyy`yJ9$FU*>{d3R15DTJ*saddFir^p*C3}o=^#BCD?j=D^UVzYN7sF zBA!r5PNbG-{b0ddKN5R>IN|f*|(Pk3`XA?@O7S@?K1Mn?TTOZOq z>#8lr6DrAxbQ-rFCx(`&1k%*f7SrE$+4^!KohshPzW;dnsb=xhSE{y40{K!)+n8@9 z`IB>eh1%rX5TB5zR1>aiD3u$W2x4qOfT0%?Y z_(~;8XzK~1rGn!tB~%OTiesWMOD#A{RY^{ymZ*CyN@#n<+AGIIzCN_|X>Fq1*v34e zlAK^Y`T9@-X=;px;%A5?W8e?-umCN~jh} zI{952Qx_Z|t0X5kytFn^gB+KJQC~cZqmrCRbzbikh4HQu+A^@-&XH_5w-ir* z>S;`P2Cio7N^v+-RPq!O`XZhdQM#YtDI_IS3)j=Cv(6?k#^o-6(yyOjzQ`%9I_qo# zV|DIksJ+)uFkj@X4pQ~0_cp6h_Phi#gd|P#X z<#|u27TPgaiet|i=LS5D2`$=t{RHzxznfN_bv6Od$upbKqP^EoFkj@9R-NmfGdu@8 zXPTv?6Fa!hnN0M%k)Q-Vk*iTibCqi41hrs;Yfk+HC7LhNEVq>t)PfC`LO(%?=8H6I zbL9lJV1sqjPf()yBAs@T^ZHPNTCkDMe&GBS*AtN!>mWaW#gYy?CI#0lK~SQ^b~Zvz zyE3-QS#Xa<3Dv@NmUP(1DY%cL5+zo#Qx@s1wRf=KJE(+e;W|q?oY^k;o~uL&-Mg;{ zp7K^gwQ!v!9ae-3t_W-Spy%WovOZJT^D4ONtP&-V=4y0BaF;A6sHM+j<10In!ksvk zXue3(KUM_2XiiW|OCgRKLT`XxpZ;9)ReLKZ_#DV7?Hkl1nP`I&%@=8wbXX%RxHp0E z2YWKTLvN$e7%J^^p&@)T)EHXWJLrbPdfWcj4LzivopE^YzWZ;A>2J^ZZ=0VBF+?p$ zm?kmz_9J?4*!H?a1QXDrWHjQC7ndbs2=|l|prM89yY6^&@7|9hUPgUa(FP@?mAK&7 z%M%f8D1kJz0)58(-ugX6jmT}xttGq@CHDB-ibO;kN+1m_(3>8=p!e~M@l||nBNCMG zPDp(77svND{1?8}&k0I$;ulv9^^Od&6XZFDphZbeoc6~r_ukf&yF%#(f|8uL?v=0h zmTa7rRUjzIiPP@-dhdrPAX12Bjh2XCWuunl#M?gd&E6%`e>4g~Nlv_Phm(8XD6Suc zpd=^mz2oHG(VhSCgx%M|9wnm@uiSX!7z89a0o#xN<>pZcN^%0vcgNp{Mp4CPpD1nv|Xg&KqJsLqtPM}Tix@9@qUDbJkpcc|- z)31IMghm9iXcU7I5omB+iU>5wb*320qCgBG8xKYa(j@GQ?3hzuM4(8hmW@jW(;9$A z1X76-_MP~k`~Eye1X4n^talzvYXBM%NF_?x_wIx4JNg(AND0-ldHZ1cy5GLlj}d`X zqJ(|7KbXGm*N8w$sFuYB7<4fQVniS%RLlCoLC*AjL?D$YVKEK{UF?Jy5l9KuvYvA= ztr}=VAeAU#u^I+l42T#JND0-lUVAXD8fZiymE;6tPWXsGN+3-w(4$8LQbM(Gx7;!F z5rI^q1WIA_h(JoH7D}BvWA{!P%>i2&57v;E7!9ofr{F3DtssOgnK|M4%|i z3C8+~o|+MXB7uCV1rP4-N+SYALbYrSz(0A62&57vEH08S-53!_3DvT-3}1sWB9Kay zu=q~CmBffZN~o6Y-Ada@LMK6Y$jhatdj#i-AaAJ7p`WQIZqxJ9?ZvdGYK=lqi8TS8-QPPzyG=2G~zfqWL17)_3j6<8x?Us)g%Z{p`0vi4sV=lYq{K z64ZhXuHyFFphWXUnx|n_PEZRrxEkG0P@?%Fo%-{CDluM3 z>xoLJBq!V#hcP0M5=c|azQ-AKUp2;vKq^tfzHl6LUrxq|KuV|Rgx3#%i{PQixNmv3#GvCm||Hq5kp8NIl(WPeIy+vkfxS>^*@-R^=xiYpi29u zdfB#fx++lu^`Bx0S(Jj3Q3{k$EwoBTF9R)hL{&< zYM~Uk=j{oVE5;ys)bgWcFA;aTO~P> z_U`gNig|&i7Tzw7KH^&&`$0-_f+K^_JG(I)3FJ#H^v)ayc|s*Q;l@6&5l;52H$a+x z1v&9cf@mWUD#;1P6N;mZJ|f&<9h(Sa2HG2&P%WhC?cy$Sfe1}1Q39iL=SAabTqRTs zX?i;!bx0*j*ts0(4K(VI5~^kAa=cHBQHNBb1m;)tV?OGT5~_tXylu#|L&Hfr>`%wbV{ z(y5i?bxw&As2lcIu|8s*lTaI<=m~QHc`pu4z8# zq7KPBfoI~F8tK&9>(UM5c9kfBy5Xq5zqKifxyKY9a0B zQLqu)E+tC99%o_EMjxSCNW1wU-r6vRQ;8BNH_j$wS@jXBg|wU3B5o8T-A0KL@Lg{1 z9HS0tUaDm=DE<6AMjcX#5@=(b-TSCRN~jjnZk+)mfG{Fci4thLTsw=Sj6OoOkp90{ zyp+H=D6PZQGvQF@7^}0D=%^p#>s04Ts3a%S+`!%_%$?&%pLv0%7RJ}9&XrI}PNcbk z#xPX^X=>>@ijQHc5+!sz?_-!Mp;{PUr#jadrYgw^j_3WjT?wSAg|Tm{bDbNgBqunY zk7MevE~*65)Iuxas;Vbck`rleP`8rcue4=o8$)fT5r7gZ$q9PC;7ic1f~QsjX=+ zjZYrlL6zhLPX$_?OKcG(kfxT-Si`Bw7+XXoO4w=2!E}mMV~Z%ET4=|dj{Xv;vFvlOjOPpBj( zIO6oJL&q=-XA26KS2nVgkl!R!SgEE&CdD&_xl95wldHgs%05 zn1C@VmlCRl`cL0fBaRm%f2kxV(z;LGuEN@q5=c`EwduYMcPsRi2zeSHNF|Mjnk`r#_4ttP&1oEX8#-+U5U?UPL$qC+Jc%$5^8uJ28EsU>Iebh6^ zP`WC~36`{v1E~bk)Y6r(_(sJM0KGHb51z9_JElkVgi3P4trWR2HS+>ZEwp2L)c6j@ z5dbAQ;Z_Y|oC(bfX=IsqJ*AE^KmAWP%X4$dQ=~0LM1ujRt@legn5(_NK*^# zm>#v?Q&W-?X`Mm+uI7a_wa|`}-&H~-Il+DI*h-?O)^Arn+o|=-JNWLABzvK()m>2S;mVGTfIC`uwl_;V9*vBJNLbXtvj6dLG zo~a}!oG*!fR|%x4h1z5sh1jlw_fbhs(2se)s|3>2LhE642T!OZC+NYw-&F!>YQaCI z=diZxJT)ab!8`2t)Fjl;!=tA9$UQYBIl+?l@k=x>_1YGjPDTJ46<8%oc;Bv(hm}w* ztT}PS(f`)62f#bXHyH0qI&+uLgel1hzMK7TEeZ7ocvsSyyLtv0-gA}Y1m9*KH%bYl zsbyct52k1f8ku zpb|(^3-1bJXLv#-IpN;(_zo(8G_~-qr02-rT1s+)ci8{dl2C7ecO}(F{?<~G6D;Xa zgE2ac=7lu1EEbyd1{xhkB}(YKS;gdFbQmR63vVrZpDMz*#Kw)1oJjAvy-@{Mqckt| z23QwoFB;z3NI=51Fc4f@!ga1?jonI6gN(PN?adP^$q7dE7`wHDrk1`po={0nFrtT# zx1CHw%?oL2X(@!~aK40X3C}?vg*TY>?+KOU1U*K-FJWGwsf9O~&*ur1L`LqTk!pd5=c`EwaL+-CsdLX zY&~K0>RJi&(iVeO!cna!RFV^^UDYiytd}UEtq(NUHDaBI89nNmGi=lcR|;^Q^Y(s% z5+#u4j=;(ZYQYBAWcvw9G+(5-1F>>~TCm~vCa~fapPUlS7isPl_S;Z`TCl;LzkY%e z%@^sk&smT9;$100E!arAmKq}kd9l{=(;_TsA0q_>B}!PlXW3oS7%57q7Ou0TeT)>9 zC~>dZNT)wFMv4-uh3hP7A0tI2N?2SZIg@I;$OU7hD4|-o&XV^3m7)?Q^wffns^Uu2 zdRC#VG*sdTl+L0&9T^f=t}!gZEH z?A1aar4l8OcBk&qbB;<-3pueA`fX66`6A6TIx8or1sg1dNW@Ve=a!nU+FLoH&%xPi zKS7D+i!@6baabBd5AU$3*l^^pGZ9GxQGmXU_&$wIQ`)XGQcyoZi6e~W^*}UW<2@sP zT>%@EfQaeZHsT5O6EQZC67?M>;`-B%Dq8RUVVBPlViSoLt}~vH#T+z(!~f7|%-Z$37sxbW&VOU(-ewQ!yBgg{(+nG%#Z!f0Oaw3lE0^~=6_&6dUH+YSU9 zlz@n7JVzZ*s46QZC~*Yt&=FSe#e@I7fAt)UO(a@)4n}dQY$!oVcn+a?y&@ic@T}(D z&0~TMN+Yx4KR(!?1Vl`m4aTym?n((t9APxCSHwT>yt6xX?L&hNNpt9lLy7t)DL6aK{tjJ*NajOq&fxRq7`wafH#lUJ(n{J+?e+%3;9< zB_LwjY#=%mqd+wpN>Jhmqj|luVXn8FdDD*9<6WZ!L`>J$8Jo)9z>I*z5jC9%+|?OV z4r|he5+Ple6(eR<&p`rD3khwI=Jiy%sC5lTP~r%qdA+jnNY#G?8EX|sX8 zgt7D*LrPHM2%~wuvQhVH!3HHDV%lt==d5A^-f;5<+x_#+jbh@p`v-y&M;QH&Z_V#r z5~2w1a@+C8~l%NDQB4KG>uWVqnw8Oi97~XSAK*Y4!;P|nhpu`bI^LnSf;HEn+d*w5;isiR& zSXkVk5yoz7G$vm;F2!yeVY<`a{+!=jcFWWI6z9DCErqRYMu`$g^A5vZHO3;S)o3go zVLE#bk!Zdk(sRI1$Fg!n(n2XXB8|dDqWOa0XxSo#bno77hrMVqfzX&bpJvnN+3a_p%)Ry~f3BEWgwI?v>4Bf(=HFQvzxF z;7)tpt8SeBwmW7wH~9U+K7v{r$F0*o`INPWuUPi;ne&$}3Qx|+ahk72WwUkB2i9Lc z(R!S}pK)TS55|F00%`U>o%R<#G;{dKEzkJy126Uy)IwWG(cUf@x6kx9z4hP~E6zPJ zv=T}*UyaJvX-|Ci&&$?c`pk;2Y`+MtJx2IaLSw9T+J|lVm*E?a-n4tiX~!2TQ9>i8 zb=vp+^sUR6S%1Fm`p3g3#%O3tAe}}4Cv3fRc+b~%?SAH|g?$9IunWW(Yn4yj?6gjI zzoiS{MWaOXHBU51y3;=Or(4f>?9(6ber?Bv8IiO!##&`#)18m#zV_0BLM587dAL@x z@x_DInz7SqZ|?r#niDc2X@O>KcG}Z+UH!5+k`amKi*zE+-}Rgg<{bOuX*RAl@00RU zEsbW@X`lVV^#j{jOI-WR6AP6nfizpby|w$@@cnbve0t{0*^BxJYQZ+so%RK*PPy!( z7wp?yb=!sEt|-xbH8xqNz2gDD8UF1SyEPyBttV7VBc=tPc$4_V=$-Ao8)39B)IU9H z@QF9kC#pmVd(THwJTmi%Gw2hQP%T`iw+lXTfId+rN|?VINpaQ8CoZE;R6@1P^Nl#4 zI3PYTNwd}1ONjA(UE~igai4x}d>w$mQjc<+H(yL@KFwDV4M zglbvrK519~^XHk%x8C{7A3o}zCl)F(j~ZLJ+U~T?Q(q{aI^M4*Qi*ihe>(Yn%QyYX zJu??wyQnbVC-2?T5x!kY2T%Q8@zm~4NTAf24!yy!^aesCEv={EsR!t(^{&iQM=yaV zPd2PK*hG4RDDgzH*J*!z`z6D_vN7C2cAU3lZgeL}9IezNWL&q22TWjyo zN|+b!odn8|Gw)9OABSH%{5M+zc(bhmXkMy?G@q~2zUsDXrY(7Xaz|+U~TiwGT*Zj}j%U<;$vpy-@@5MnyukU?X`3duykrw>C*Uv2>7cbEj?I=SF%T z%?l+>E%PxF*1bF+A#C{aT1u+uibJA;1Ld~J+k41!)wZCA6q zdlx;`-1VdX37;76R|z~H>EJ~N#ES}%w6sJzZCiW2DXzUrxof_*%Gu(YY^QB&uiM47 zS0zLXL~140M=fU`rB9AMbIu_2neu)xm5(RVGj-b5*AB3+RV~;{vk4`vKOd0(JeFck zq%i|lAmduNlsn3bT6l7%s~VIw{V2(aG){yKB`9%(+2i%fMx39UbxJ_Qv|UeQYTM12 zq68(5Fq+qGR`mXDbdM!UKu`-$&i$6KE2DcXQQ`=r6Ja|)m&?vilz^ZXY;fPGdU7Qw zaRlygtR1W<33pX%!3OugDjTxr6(x=^8=jDzxF`WZE!g0mUS&fGN*rM{uUCZZK}HD( zYQYBfJV)KNj1or}?T8`S8I2MU)S`{JU)x87f9+ACPA5WkctgHQgmhh2{GXr3kP>)W zNO)JIc|DZXknC-T@*zPj);a$fsNo3I8YC<$(!5^TkRA6>&m^b?8)%9AFQLYe5|qG3 zBrMJAm5sW!mzoy{YT-KG75kbqG9D6eS?21sh|YLW&Yc80`r;=@ca( zs0AD7&#QlZv(r?YC_#xMjOO)lVrvsQu@xmCs1=^0{$ILqDr|}p7;T6DpHl*N7zsOh zHbqXJMM=0T()Jvf8;p9oElM0=HasC`?xF+)weTEiN6~6ePw7R8BaH4R>a&AU0)kqw zk>)tGL4p!T)OUzeh*i6ad#REa?<$;CwCib(0~<y?dbo|#)rxb9!r+l~?t z)Ixgu8;|Vmeo*yabd5$NMB<61gQRWc?&qfuk3VbQ;^#xFW9}UD!f29ONOPuF-POB{ z_+=oH#1lHZvlXuyvf>s0cLnnSt{a2KJ71m4uywc@T!&LF%m=s%3<930IxS*reZ#WW z7bQwyPL)=KZ9Q>7))OP4TA1l^b-2@h>u#%lc)_F7yW>|JSEvLtNUj3=yRv=f<=l7H z9bW9pas2}GTD-y4DGS@%UN+j^wi4K(ODhw$e}2Pg`{$~K9lEqKVSDs9=^j0;tCpW_ zpML8doA3mLN|f+x0BG%Tq;GAPb&GZkzl*amXm3o1b~R)WJauS^lsE!!K|J;Hk?D5~ z#PyQw{op$Rn$K6iQTMis4?Q{&CsLxsw|t$S<2mHiizApX=rr2~5j~u(y+n^=YceTa zow7(?REg*Z9Z{XpNJRA1W z5@?ASe|Vx=Lmp*ZVm6dW>1r)Jjh5or$A~!IvGPeowcehHIKIk=L{~cv)u<0GQHeNi zGaHGhc2W`%$BAY`iIlF+^~KR^LkW&jQC5kl_M;LJ$Gc`jiIh&Kf2$f)B95cYMk1Du z@OnkWal6@|1b3Cv)d|Wtn@FdMaaZ*`!xLst=O5uLXE;@y5!6E44+!d%qt_P1sj}&RW_8M1U3?}bcEL{BF+aTFA&s%4W9n(Cn)j6(h**-h&U6Lyg*Qk zHqvZ6C#qAvN>u4Y#2I~ULy0O~mDMPxit8t@P8Fwo`Amt3>kJuzva0BG`Zv`_I8|%} z>Hz1BHD9E8y&~dzNk&i$WrY?q%Bf)S9ZZwp@yA6rv8|*nEuEXIugh*-KeT7d;61R!js4TygI!zTJP)$<_jC_6Du33 zcTN)6NJMoSX0+bf6U-Mj*e6ytQtzB3u#t%BoXlvwvnQA@Y_LzPY^2^fNnj%p)rpkR zdS_2CU)W$TTG>dwbCSSDA|_wyiPSrLf?DA@Twkk1>Mc{g!JZ>hUt9S;^z^C)8|)LS z=TL$YPfWg&*DE6RwJ9$U)PfE6qWuIVo|t?kuUACsol{;Qs0ADBMf(X#JTdu7UayGM z*QUHcP>VKFUz-zE|EfflPDJXRwSP@oEUVPlDuJi1`d1~YQbd#YO zoALsY=<59+t#?imPgL)GB;3~ndH-5{&zt(->N(KYhIKf5!qJJU7me$1Vnd0fg*#+U zxs4=&7JBFUt_GP7gxFAGY1Fd%7#zz+l0b|3+StdhK#C0|k`{=58{z9^c|yGtK2usX zNFy0H7K!)HJ4{3x$#^1-WYYMdDqSUHEE1j^`N9UTS43JhNO`Fio`d6ueu5HDRHrXS z8_A@+KqNXJm!y$Ql6bjx>@*u#t#r?RB(~j3<~cY;gQg*+?UqB!P`YRI9b4jbuE*d|`v*hss78$s`GEB%(Uy zKiWvf6U-MjIO3>mq>)ULz(yjL4tgSuOFTiX@EmSjq6GYTH7-f{278W3;}UxgAyPVx zII8DRLdGJ4iC8+w>lKkkGAS?I3AOMX9C7p$lz3w4Ag@+WAB8^LQERwWf zgX5J{AJsZTlCZ33&l71};t6WO23pK$>kLT(8;P)Y#Sv*-;t6WO21gv#b0|RxY$T$3 zS4JDjq`W{R+HAX3gEaO@5>Hg`d>qL%QqSpoXZFaT*(X-dp#&w`hjRolT3?&;QZ3l< zJ!k4`lf)Cc!;96A)Yp1~`N9VK#OgVepaeD&k@lc#BCQ(4yg(#6?>SRnnyq zo}d<kdboZf z^?gdDGa40J@DG5T6hPz!YqZx>HG$u2;WgeQ+Zbvlt$JxA(mJ;8iogMDH@K?!Um zqB^%0&v>P{ACeb{M5i9EvXOe{B=JObZY`cXvlpt46k;|~|C+S$9Jro(&YY|n`o!+Qc(vh~a_42ioz2kN__0LXO#1WFE`LsBFfi%ZHo}h$Uq5h3v zxuJB&Ca47(Y3`VKf)Z+lR$>H8q2GoQ)B=q(*BQJGN~jg;26ts6jw*6X{v1kBE8L-s zeY}l0-jRGkV8p=)G-DIg0)Y_+rrQ?{| z(j1q@yBZ1}OC+F`pzTh3$v$_jIC$QX|^cdU2ol9bD_s!>hFYM?mY2{m-@Y zqDIUlfs=BS)TibGQGbaRa#;~#H#m_h2chX+v zcaA#0s}d#ZZ`WE|+;FWCdvqribKg{yYkhjLBUG!7hu-?#@BYh(2NrBpEcw&)@(X)? zqpK1n>Mz4uKiD2Nc0O^(V%GR|%T*qn>j>4Vzdmd28>01Gyz1=Y;L9hJU!1hJBUB3! zVl5hb>+vt+t{xqCU~zo=iSAiXZQ50d67@G`t&>}b2(*j+|Ht%0Zte~r@%zuPPtPyb{pBg$f1h^u3Y92PfB)6m@$RefCwCZoZTJ4Q^R~LTb zm6->hG{X_9h3B*Q?XByk;;!)IlQ%uJdD1#}&QysKCB}&w1l3Ncx02^rS3;#5|*kbQ*I6}4RGs&&P9|1Af z-l#9#+bq6x<|&R)ExeodPj;<`KY+W!TYKmgdlip==e(v$l&DWMw_be)HsBe)J85q5 z@adO0Lbc#yEY5yw!*Q?y?{nqgXN%q@OPeZDqCP3zI^o>D6**-Dg9t@$Ynxv1ChBi4t{e zs=Do3YcJW_l~65<;(}BD>5VG+Mk%3M_zxcU)|Py0RicDNqw$`hq-Rh5~@}Ii&E-2OZJ>9Q3ADT@tsodT(WmoLbWdaqD4tN_rQA0 zfR@M+fJ&68zrd)+3~22fWhkLq^;Z{ZBvW!Eql9YJ|EQEkOI?nZRH8)vokkjwbvYta zLbdAuc}krYyUaE!b_OC0gh2I~IphO9z?Vr0_ zf4Xe@QEVtdE!eRCn`y1+jYd$S`66xqM%#Mdt({S9C_ydQu>Z|zHU2OfL5b#zbn4IZ zvQmOtu#x&&`8UDP64@HiuGlIu!m)ooXbHLa@s1j4gCMd{9`5*4^Nxp z2-U(E)&8NP^}T<7$ZTx0?(E{WqbC$gx0w^hqLk#s+MgI#+mQbZa|H6G7DmqYUl6U` zci7HsD4~*^SpAIG2J!y8e|8AtcIE||T9_x;e^1yuIAAv9U&g}RfRdbeV6B(D4g7CL zn6Z#RzSIJ3|6I|U_K9Y)5eSv!#3iRZSKE+(KItlfG__C)_AiWh2UA($zf!s?$%(~> z{I#}G*I;Qi=m^l%LT#=)?$0%Gr?sn#f88v<@YibYyxoOQ1PR)e{nL2s{-v`+^0pBnJb zkrVfwxn67G+iqP+Ss`C)X{pDS7)ntj>R& zY~a6AT-!yy)B?@7z_)glRFV_+zd5Zr z16{LG|NBt!$aL>ZKvPToSp0{h;?}13S4!0XeAJqC&n;%-6>EvRniqY}yr|}-T4dvg58dU$e`D1nhP%Po}d zsDx@E%~J2Q&5M?onisv)yr@c)xZ$XI;zdEw?<%2MPaHjOaIFj9)jI9?pIGUxm@vD% z;MfV}`?sIdRf!Uq`_MmD#PvpO@exm`7Si?)#J1M=b{oT4uU6Lo8P-*a5}3nn`}Qqc z_us$HN(j|L+Wrr;_0AV|G{XAxvi?`A6)I5zbJ5j)+_K(aWrS)WZT|<^TCvral8xYZ zRiXs!J$U%Otqs~=TnV9CNT)S`x~zg1Rf!TPx3n_x%LgZwKeFEWnWw8(!WMVxk@I37 zuC*C@&XRqtN|b<&G|I5vxny6fglcJR_SZSvj}mw$_K9N?s)clFC3&4wq6F&3{?E%+ z?k1%A2z{;QrCM5>v0cSFXZukCIoUt8wI14Hhh(FVP%WfWE6MAe5+zV>_FsFg7Zx64 zHpU`U3+dEKR)6#C@|>?tD3056PE#dH9D2;W!HX{YRO{Wh&Nmx3uR6P2cJhScfPFln zTDo@DY1@Bimdl@P7UN!C+*FAY@JjZdnym!`u<@Dhr1F`kn#HZJctW+1PAibs*TRby z)<@a=JV}&*4^DG68}F7jV+rHkyoGbTi&99fJ@;3XK#K(Gh9mM=A7PxRd8roCZf@ZG z6(vfbjd5lXTViaxBvcD&&PyT@TOuV&z#eBvV-u={G)IH+$)mrbLp5?@YMnH9E;)Bri4tgIoOy?lWy$%u5~_uC8d>IT zml7q=cDaHO#|*KxlTayip z^o>iH@7p``248;YeXUFPe}~xsae)!9WrS+!D5}%m|DH+ZU5_-&1D;*%##c(9{`c7M zovowJy3IypAZ{??;fzo%q|-RDZdYL}suCqo|7rAE_ngr)u!lqqat4Vq{KB&zYMnP; zdd@(oBqumG?0?Uh7iemsKJ33*TSt8OZK(!>FHuQOaBdjpgXQOsolyLwsQM`81)5s- z+IV-Xzid*^2Vb)BuKh=Dm_e#U34NQZ_nb3GB~%L~&3DtkQCdDo(+BG_c|s*QLGRjM zx-3!9)Y512gi3NE`CXfzm!GoLLCnvUK$==w3h_DOd(L(R8yx9riS!fN`bdCgZ?|%S zT3T-L$)jgrzIYDy?cT;%b53~9H$L(Xo0;A|qO(^&OI1luyt>uI)`8pKzLL2!Xlh{| z?cVby=bS3Z3Fk`+`Vu9Orq%(r4wvSG=6wqKE0rj5yZzI+^N9t0q7tfw^%>`P3;JD^ zt$@yp(XO4l*5WJB{{)4 zLnMM1)x40V7HIlPPpBj(()`1EPLx&fqDml5EtCR%Wh|>es3a%spSxSveX?bqy8i$3 z;+h?+l{@AInp*Y0oVV`!`r1b9yXNfTyC+R3&faxSQzc5&|GnON;j%#xcTFn3@>sK2 z_`+gOSnJ#5bGrsDw8|-$Pj5Z9$G5jZZX-=0B>HJ4!TP5TAH_c5B;7u#vCa zkx(tXUEJC7gi3OP`&7|0gb|q%NK*@5!tLEPbq|t~oZuc?v=P^@=%bMDcJJQIPXA5p zfu>*agi3N^%Of{yJzq>rWfevlN+3-wlmh)qEUQ4MBqvUqw|VQhCo#U7WOe?N$C~AO zFH}1X%nLNN)Js&v?~GXT{Nk=kl-SBz%;W3LY&A~U$!u(EE%E%5CY1N=HpdaFg;q(w zQW4h~@r&8jP6H)5@%i2MY<>NY81L5aVCZo)FQlo3w~Kzo6Dr9GH>Qr>M+u~m~3$7n=83Vctgx)k3RG-pAHU zieK1z$w@C&{)&>ENb4oJzaoKrsfD+TekHzxVFsy^oZy~!^bFBoF)z^6f|uy?K7mk4 zPH?|I*l;WK>aV!+j~R>eSCLQ&>?x7vI65m*LT5rcLyAuxy(m2=Y#j2*0qjQvFG_Fc z2|O(&IdR}M1Ffm^b{@rxk^oID^ zDp5kuCxaXZg;qB;SJfRZYi4w{0=3bO}sYiturH=_^756z+ zk`o-;g)v;oQJ)g(oprs;`(5?5NG~~Wx7Hp@76wmEkLn5aoH=pMQ@gc}U9@l%PtCkQ zQw#M^j~ZJ^^wgB(#2p%Tzau=V&>q6E^^LjAKuJfV`D zNG;L&!IJ%;5=c{PhxzklZea6|lCuewDB)Y8%_d6DCX`SutTS=W;9H`$KBRfpRa=ZF zRFV_v8?1Vq7+RtdNK;E&On=*D>&uDs4c0#P{m08sHOrsAQng(Y$d_8$#(XQupPb_> z)F$69PpAa65~(HT{)%~lrWR_GciZ2tD9MS`678)m`POP)NKeek;_{jN%s(0U4fx1`@yLbXuR$?w{j zy5tC1B{`AmJg-6KrL~C~&VA!?~q+`cqG1!ZUC+ zTUUz1nWBQHkkA+Lw20FE1WzF;p<1}kmEt(wjdKI;0x13Z3FeE@a$0rP*#ySw+|7U% z?Y(}2`64H-E%(n2xbvg-UO&NnaaU>8xt@82*#ydjduh<3z1L4LU*yD<;_56X_wMv; zrP}iZR-Ml{VM1~B4s)70!F=zvwVEGnHmzQDzS4FxK5J(=r#@G$u<$gd(w@Mo^ZB;w z{L1s5P%X4$t`x_fGtLco8WUQy_xcIui+(q)I_qo#o|9)bp+$SIpJ2YoiEGQzi-zZb z=S;JdbYchBIg{xpD1lGpY8293rCK>bE!g0iQ$In8=8H7TZRG^DV1uR5Pf()yBF)-d zIYBMhVBPc+lxV(4r(NWFBopgH32MOxPk2=4uehFwyjTbM`74%m*fA-&W(k54CAPB> zGWT05f_p4Vs1~lXq{BW=$$cD^D6xv2vPf^Oy@Ms+K_yfR*IClx%y!B5TqR2A-hD;z zl(!P9h3hQoup(S?MOe!RJtxf*7is#(il7(G32JF6#4$tY4bbb;pKHEqZ{-A^137W6zn`E)^F^8^9s0qNdlMLc zuqV?y^fu}!H$(Vl2vIdGB2a7F|GFW>kg-@ltq>L1t|R^J`v28J6pu(y0$K@+$fgEQ=fG108#V={Oh(M8`gm*&1qMx)}M4(7ek`oqfrB(eS zTV7U_~>ol;niPtZ6ZZsV6AO35$5sV#Ie(P?8fCVW-6y zbe^CjCoFPLi;?j>LCI*u=n;WHgnw>DOO!f??J*+)1xaoL&&Sw?{;nv=36$aJ5rHVl z3A8sxwDvZXpcZJsD(7zbQRHBBLZ18 ziV^#_Jw^l?88`80Mg$t+I#Y~gQ6h$rjR&IyX%hBDcFd_SB2Xk$%f=-mX$?Rl0;xm^ z`%Zks{!K7_e;y+ODWO`{JCCF_0F4Nw5+&?=_YwQQ!}J|}j0mKJYT3MfBz@hl5rI^q zgnhR^viRejQ6d5x~>5rI^qgvB^OWV{qRAw~pJLba^t z9N|pgM+8!d5*Djr#KnM!5rLFYE$g*M(yD<*1X4*(Fy@4h2&4qk)B$sF(Qx>ss;a;cH**#Kv9wtjP=tO5hxPKms;@P?yfWs)bT_ zJ!gyvq!J}io33|`5rLFYE!*>wF@r_~Qi&31m1)eN5rLFYEwp?$l8F(4lu#|aX>PO> zBLb;J3B18>L>40gDWO{M7;e-TBLb;J2_2*Qh(JoHmX1-w?ovE60Z+{@r;z5l7>M+> zQ?`;CB{|`~qsPfJo^Fc-@}(B;miFSF7tek~i4sV26?f$XwP1s5fc*p|nlI96eb=5m zK8NO|TDZ>D&wd+}D1o#)3FvGnK`q$eDsI0GN;F@jc^YQr1hrs;tI_=gC7LhNsXx!l zN(pMgMjB<*JMLVqjdiZA662M$o~VRMa>9LaSn!KOC6K0;eUCHZzG{pSfmEV|ec?Fb zzMPB^fs{}!j5zuIkBa>9L)3mf4ipb|(^3pBqY+jdS@B}$|lEVaFtX z?SyxN(K?XkDc`XPmE;8XpsSr~iLeo^gQk|=t>4>Li4yh&=t%ma$|7vUy=^5_3+2W= z?`k)kd)q3>3GPAn*E#b7O)b`6bZ=V;)k3RGyJWhzt&*Hbdv|#s#k@dM3vU-kAMve?{U9Yd!I44eo!uCY1oEX8 zdS{M|BoY1{!rp3DvT5Io>D6s6#4I0`n{S zF&}kE3DrWH-Y&eg@uZVVl)yZZzH4kkwUACX5b!i}n|LeXUI&bx0*jz(yL$ zXw)GkR7-2KzXsWUl)y8w?;4v>Eu>Q`$?KdFB~Ul)uVQ_~Iwzr8TAPuGbD1cm(hcKwl_-I_;i$jA?J_UbLfXwg zocEzb3A8cJUShk7ZI^^t;Y>X7E8S{8%S&(CAjA(beBHpbb#k2<7;Y9Z~`8889} zBQljJfws%FvpCA=BUB6N|9izt35TD%C>c{w+H5*z9X4`>KNltJ) zAL=}=Gbn*HwJ^R;b#CuqBvg_UX>On~OqD>ITDp$nW0UT9Sq^YH~+25{G%kTtuIr`fb3FJ#Hw4T&T z@_jW*a)LWFv6ZYqJpH^~(RZOX-E12pfIz4Ov=W?O#a0qMHS+>ZE!3v_CJrNjK&T`q z(mI311dP$Flt7wV_BH6p=n=D2qJ*yXhM0gcDwh(fh5Aq5R3nZTBY&wRC(^o4-LAsg zk`hQ$3$^LK4RQCkfs*e6~9G~EitaDQIZpG$)~nNUeixK#tZA7LJ)1k%((JElkN_tcc+L|SK1zpHs6O)a$JO3_i>gQ4a^vAK4L{CjZwNRVx+gInQDancC+Y$LozL1W2Azy0Q z*U}@S#|l%466%kAJTfIz3$@Ak13u=NN^-*alIVApK$=>pO~z4(?J9U5mE;8dnD@I% zAWbc_9!7WYgi3OP9^Cs~C6J~T{9}3!YrD=>2_%{2vQJNRh)Uq$+M^dx}jZLKzCG_3&@voFnExap??%-o= zsU#=Zdi*=61k%*PyTT|Ho={0nuuc1SPzj`|g?ELqGd!V^oN(`XdJ6|i?)uu2a~w#x76yWAOSsOptg%}OYLM}kw7q#k zB{{)}9%Hw5(A3iR#uF;Z2}bnr@s^Z8np*n)`*=$#Q9{4d@$r_FP%ZUizO1x-kmi?K z`b?fsNlv8GxH`L20%>aLGxe7)%O@w&sbY-?qCND0-#8_Yh@ zM+8zyPS9h7{ycgHC6J~TJOlf7PpBj(lJ~Ju2KEQTY(fd7sfE2lj!}G_YYRu3Ee3VN zcI*k2N=RsnK`Y^?HjH;;yHZI`q;^%?2qQdFXZ z#YK`cskVz;au-<%)xvd_wEwRZl_;U77JO6{SEA-ixKgO4;G?Rj1imB^mgZiekE)Ur z)Y4M0{zIaws021hAf5I(K`^RHPEbor!T)!SN;F@jd5WMS_}?`-K`mdp`VTHD(R`71 zCm=8a2&=V_utebpxx4x)hj&<1ZaDJS znTVtj45^??M zN0qI2|FFyF2+@p03)dMP$YKs0IBkj&l<+x7^LnR!%HKAg^3BKQlowvTW~q6Bpcbw( zIuM9UH&KETM;OiPo%Zs}zrM*gui3KPeA|IwgAx!ijpwLi%T#5h1SO8Z9Xi6Qy?pS$ z_phFVacV>h&%r1zl?^2*3C|%kuUEvQ51!S%yLn8oK?#VMHXDrM(oaz02%~wuB6ivQ zh!vC1JTcgy1Vl`mjT9Ybo5xyHl%T{BM)P{7z4nKe`0}8EX|uryJN*PDjxd_nE8;&Nc~|k=$9E4lC;<`E zcn*mn)MzL{i6d}_jyPe`4#o1*-djCKEeUtUwAo<%qUx@cpu`bogV!r!{aZg>yy1=~ z!h22$h?q7T8gHr5P=XRi7|rXIjRor-TbwoJuwa7{5HW2w80)E@pu`bI^Lj-fGS|$T zcDx?%8YLiNy1vfXRPfcFfW#3sod`U~8B-2x(uNWtU6&OjW;Gg0;AtVD4br@x>SNp; zPXrs3@W}&hHc&T=<5krM2}&Gc&%x`J4YZQs)81R)IVb@U({>##kTd zW$S|jfuIC7B4KG>ub$%@)wraOpcZUkjKUa=jfN7Gz(yo2&Fhs7jFxtI_YcE+P6>#Z zHX9s2_7jvi!f0Oav=`iT$0o0QW>&fU_6-Y*8#Kt+ZH>m{&BvwKZG%jA+S{M=n@w(c zdY|%~x4)&ZmCYzo0%_i1bys5%)M_-A4lSR0h(Hf&_#Q;?sLc`H*NHf$>pnS?^LKn35^wJ zr>W*%a?>`aj4yY1X|F;hN@(P_PW$xh*PF5XI~wI)OZP8Sq6E_PD>na_`ptp;uXv$* z!S4^~BdDd3-#YD8mb|p=EnmH@`}y9Xg-SGEoK#>0qE7qo&;EYk?5e9aojrXlTTS| z;EH8GUon5_qVVL59H;qeR5n`|ePI0=6RpSj`xz&O`d}P5C6H$C(`kR8%IPTygG+p_Ndg`D#?QPJ80Bf1bYf(r0FVW&1^F?J>fa z5*lNz(>`p=zYN@X^rp=_PCLF(i4qzyt<%2mr*ECH%=+_f*FPRUF-AjE0_ijYIAQCh z1AD%7nFB&D9uX&;o(w+9HKizuyW1s$b^J_aU z%!s6=G1e*@o9=u>^R<^26e`ht&BOJQjV~Uw*7BWBdvo&-*PM_MNeeV*|}t zk&H+*U!)Up{;ua-IOo_O-(1DWO?j!7MlTEey<+CBmy0FcX%Fr4z3)Hqm7mRg@w!EhP%YeTY9)uh;pu^)ZJwXG z=~f_;LPIQE7S?oS(SO4?pnKQQD`OCK)_0JOvm6%73 zEnIDP+UBV@5KkTN*AuBkI_*E5{Jt5Re&wDOi>_T%nD3MKZs{Q3E~SH~{=Rr>cPAuJ z>P&~;U_g2UA(EEXQ}EQo^wfG+=BcBXz>_B%)*Da@Q(d%fi| z4!^Ct=Iw`uRzisqu$O%M@mpOrW6`u1yK|Qv;0V=18KxfRqFryfdFzwMmlwUf7y4T1 z$(9a&%VrRp*$l!HgR2~W8cf)e#3$wzL^G-aWch$Z0 zqJf8P)nEXt26DeSk!D`sdh()yA6&m>`H`(Ef)XY02B+B_=CyMl`*8W%T^|TGNT?Q` zgV#Ilo!?Rpym0nF+1(j4$Rtq$ekIL0zuJAz)IDsLdSsZTCPKB~?YK73X}@R2!_#g# zWmb96`5R)K7$xw#Tq#i7op$rS+Xud6>m}!0y{5aXobYP^alJ&I1Nl-5rOtG|YLFy3 zk=6i?y6=Q#@4sbM`Lns!{YGB|q%h9mbgSo%YOK9~>B1uvhu{oz@Pc zaCzEDpzlg|W$PuE$?8YUOSO<@PM!9VkH2>F+`*m7S8tw-vWodyNxM5tb#66yqtxIC zB}!OrN@P`QCBxE6BB5H=VkF+HZ;4AIp;}fSJ=*THt+fwJYmX8otmVt9fxS_~@12Wv=nu%aZ~RjmaZ-2bX@7YJ(M zI^GrjmykPa5G9T<+7ohSB1%9|E7-O@PyYK*qoD-60VIyV9XdizazshEE7JBH@Lkov z55Zq4L5U;G2CrM}=*L=@%ZZdI0YNQ12Rt?Z6RFWqf)Ym<&FfWt$XT2y0YNR;K<~_d zgK9LCpu`bI^E%(bc%~>yKu`-d+$kiyggk{5C5|xK6LQiiN*2)KWpZLGN zaYTKG->(0EQ1((KFWwcjSRZL`JMO+3!P$=^%m%Ml&vDH&bIS?W{R?~BQ38TmNN<1R zk*(bi`cZX0u@MQ8cw*@YXA`OxZ^JIA~*nxq!eoat3}^)4fR8HgnD zgwF14#cR2&c*Xx+!F+)0#-Q=eSLZTp9d0?-;ZzIr0j>grfG4U>i`ZJ!+p4!LcyxMm{EFiWm0$+RRbYQtw(mTH`_8(IbJVAQE5hoe>dz&w@U&x|5mq9O6Yw07sMe6< zxMV1fOU#B6DP66F$I+4_;&{hwB%)exPedGFnGGdUy4q=|Mtx|BO2l!S*+@jSlM;z^ zM%Zj9k%vCM55E_-%x{Tglt3{N1KgAEFI+aiijiq zjGz|U6-WL31SNQm|F5w#0k-ri?)xy3j1bleh(#C=c05l4vrCxZ=w0jH!XPlio*0T^ zE7q_Xk0GRDhY71KOYAtNjDSEiPeM3^vJ3*E_u_laP7IjcEVhvmP=+E#GNHf{IeohS z-M@1eKvj>rO!x2W^L=OOKIiLmz9O2v_45y0%Lr+i4b4T|M$T~{8Ht_gNaW0GiIA4r z&@9YtkdVY|6tOeazdMmLNL$+x7^XR&do>jbtSf3-DGx|o@-FjAWU03&1dC0jku|yPI*}qjEeJ!IARtJ`E%bux|R_|ulQQ+5^C1V*OKs9RNp4wcO+-2OGMG- z6a79&l(($w_7ZOJ&UGzn*|U;QbQ|TJOEMCky|d0ckA$vkHsllCM)~uSn2jPl8)lt% z9tmC7Y{)0Njq=VVF&jmAp3FM$JQBLD*^p1{HsH@oVm6BKjFffWc_egQvmu}8Hp-uu z#B3CC;H;4-?>rLH>i04DS`y`7>$=_EK$NfbvCq~Gsbx0g6a79&NHP)!&eFd-QNFgW zWrVcMhP>!1A<0M_I7|QTM0w}BmJ!l28}g#7gd`(z;4J;S6Xk2`T1H4qHr9D(dP@@i zyNL3&tAu>J-BbBm5|XG?PWV$OqP(*|EBEK6r8-};=Ou~Fd(y|h6vQZM#DjPd<{a!8=iPCB% zoNuyG64TOkTkMnTjLSAil$H^L4a6m5sidWQs#SxEeTG;h%dQd@QIX6@*nOCm*-*sM z?*r=$CE<1L_ej*L!AMBUY$)Pz8zdy*b?vwQJ&0UqsB2NH-^UP_R3y_%RrCJ5ZnrlO z6_<=e(G@>EE5GxTLOSC6SihhvJ7-LXwg2wbyl#OkK-}qAPxI8x_fv zWF&mGc3mVh5}V_aT4!KnQP(wlia2_yuxc<8(z0izh+~zIgx9s-`gbQPE~#r#%WT-F zU2iQ(NHP-bJ_e%VlDbweRcM(FMI2r#5|WI>&RqZQL`5=nEhD65HWYEJ5|WI>&RqZQ zL`5=nEhD65HWYEJ5|WI>&RqZQL`5=nEhD5Q8x@x<6A_DmaJq%vFYgtL8Wlv$rbJnUsN=BmIL5Gd>wRJ5c zbX~I{54TE4G7_zX8+>hDtCwn{=PX}KZ&}whT3*ykRlas4q-FOZpSVg$!t2^^{ks$8 zIqO=~G8^)VtAr#YQ8^l&;2J<)%ZQ@AwbvRz`P!0<#BxRo)&SBA8&SS?*>jSRPaTQM zneqE5&sowIlp%ZQ@OC%TRDwIvw|?_KMB?MRfbZMHY~+LD-!B7BrcUpt&qQ1fM<8(KDv z#U=W8zYp_+{R{|5Ov}8Q6YlNSt)2nVY>==>#!qfpE)@xB^%5fX8Eq&kl9pZ9ep`&96KFOQ(lWy0 z5}k{a#1TsDx5W&Wb7j9}d(E>_6t+ZgWJnwBA=I_(x3uiHMv1{jFO?*nXuh_uk>W}N zv1$W^M${iqNXzWWGYmv8l_aJmPiDV=x@Sc~UUaarav#!CsT2W>PdB}OD~a7l&&K|# zOGQF)(2p;bw5(K$mRAW$OpAootTM32`ye5$PB)LE=yfDA#%(qfd9Njo^a0CC64x>< z60&{x&^=yr$Gx}RaPH*l#XEoLkFUGM;{2DtZ))_*e(xLexBk}mr@wKZH=nn2ba(#p z+nzkLe=p)4fAb4ll#qDa>;HcKg3E50{`#}ta$XVt@}igSkf7EH*Z5|4p~r;P!`sew1ul?5a z9`}0^h==c*g^w)lUdhuN!1>yx~yzG)H)xLetxXFj-CqCnZR%-{Q z_3tdzOD{SJHF(98#08)I@ch{)pD;V-@ZDkKuiy5u@y?<3xx0UC{@NRkpFQ>KGZ0_> z`rQvwa@F-8pWp3%H=f=984ue~s`q^3j|LkgzP|r6^KTw=-0XMn_&C_u|0hpCySidZ zEw!stpZhcr-~8n1Ta>6Je)&Vs+EA(+pSd;IAfcB3s4qVoHh%5OlMeE^Q;RL8TH@7j zdH+Gy?Pve^NApj<`s(R-|M>wM+SOZL{K2DaB_z~#U-Rf+MXCP#El(cW6}8mzt#?(a zKJx7Ub5L5=4`k!#ZvKt)$~ODpX^;3cO0{nv3EkfZ-}q7V^KaeZu0tQBmRkPnpZ(_` zKK73LUP6hU=>NX*=!Q~#;&,HBvw8|~`OAN2=EvX$7lq;_?a%l0;miH|tvF{tx> z`$(uAKYi;9u<_BI%h1~Q?W30Z&0X*IeGvD3@Vl}{nM6JH`U_7)+hu)x>{fR~+ugU1 z1p9p5`7d9yz4O3(e{w#3&(F**c>XEV&phB?=3l$$nrZ+2A3iZZ<}_@-}ftDYkuVb+ST`-c&~w=mTW)oWp@E_+{e$!QkjH=?2W{i-tv0~c`a%^ z_jf)u|Kz)mYxl7Y8z;Z&g*%jx_|sE=F#o_SztQf4#LX_c{XkIbIY0XB{QkE)c6Qb? z?++W--T90yN=Ur(rQe%>dhw6bk+|R^x8ET#XkGlp`Rk6~KRfunhrz~WfAz$z!;p}8 z$2b0IzWtr=Oh@85|K6@;5By9ZF=U%i!35j!l|6B9>eB`<% z;uXL0uP-G*ty34*%+KEUgZ6YE4I5U2ssn3%s!jV{&uu>lt3gUgRLzq3{E3$zBtb1b zxBu}=|A;<#!c`yMqJ)I%X(X%$Nl;7A?ayxZdDyTTq=ba(X(X%$Nl;5qdVc!HV8d!~ zkVK2I>#CkcqSfG;B&bz2_@QRw1<$|7p8eUkKv@SIB~JRQYv*_RU$=^}1jH^SBy=V3 z=bH#>-TGzM%`biIt!7R<_uQ>L`?IflP(q?=)B5=)f?999MHxQuNF{3qS}>> z44VjQJ>-SQF0MXsQmc<3&TZ7WW`hzEYSUS&wFI?JKkvqi+dbi?aUbo@x9!iK6(uCp zH@!YK5!CvBAHT_B`%}k9eY6_fwm++LN=Rso@piR|pw>h7|Lo%GH~&nutJV@H_GfLE z5)w65TL0KYQ0vq0JaO^3e>yh$N9$1&`?Ees2?>q)*=yGl)H?kyPFmdVtH(q?ZzIFR z{_MMul#pQj(8sH_1hwAqb0;re|B_>Byb`fZ2?^OYe>K?Hri6q_=mehCKv1imp?NhD zl#r+=Z3Jp?LV{Xq3+~lOP(ng2#tF2<2?=VcO}kekK?w=9d?(POCM2k(zUf|#1SKTY zgPpK(B*u~n32N0CV}6hXB_wJj3PNMzgaoxTR%WS^poD}*)Vy^h-<8pf&Q@zUqxyi`qFJAGwQ)W(l_$g2S}%I- zO&9Mx>Bci(zxwFiKEG>!_LUe)NO1M*@S#lvwLW;ylNQf>#<4SBRlE1)C+yjuohL&H z39iWmfD-Yn;=06 z3AIWm(Ap;?sHJ}6Z%jx~LPEXE3H0*`32LeT+dG}1pHC|?+RUBw7`=*k;$7ajLkWrXHX5--f?A?I z7L|=tE`IQqBzA`^A)jI0$IpK8DO;3~s2PB*e#pk#FM9P+64YYrDdN5V?&wiUNN6VG zt2nap_=7LpB0(*->9TRxQ-5@j5)zt``D&DG-1b3F-6BCP_RX?!=vEhOQ9?p9OJ7x! zjTip#`8y=2#ZjqjoPE)SJCu;98M3YQ$%fSj32JeyEaID&zwIC;Bs9|>@8c1lc=%Bg z)S{Ot8;`s0#XFRc(2B)aA2(d{l7XNWeOKA|?o=b%V~9mt{^J;nl8`-LHPC(B@b{N*@mkc<{dr6+V)wnjk#}wq z67}3{^+Uwj&wKF}uSG4@tj`TZ9RKRuoJk1@)xWRehQ9?rP z*jJ-OwEl6B1hv#}e6A+q3Fo|IixLv*%|3$^G2Q=xElNnJ&-*%@h?DR6_JN?5#u%Ro zi?BPVghY*9ww}0&pq9o;pV5<`goMW6@jiaxu@AX~1hq8gYc0cLhUP!g8<>QIe92gY zfBgqf9tdj5cWH&iZ8Sf4loAs1iDOHA;B)@V4hd?>2m4Bqp4AKA^}FevO+uo4JA2gD z{xb%GT8brn#Y;9WyX`x7C?TO3WgHn=>@yJ5QcN^POV4}sac5FOf^k>oe(YK9U}QQi ztX0NrVs7m{;$$-A85u&TZCM&k$L9d&nbe zHbz3vZOA;^L#|pUs1>uYxzFx&A67e6s?3_4n}@4^XQ_}!)@m>_GdmG02=gKHY!A6= zouF2%2h4q)L8UtTQUCKOpJL347S_A!S+QLq|EkvqiI}%7d}NS~=iKiwzn%1dWJ)8?b2A1xwUiC(zxQQIJ$Go7geoU&r$u``bE__ONE@&-Umsj zjSX3>d&qn31hv$TeVsw2y4!hoIY^26imeo^FBS54yA2W=yL=5mHjpFS32JeCtQu^& zgIn>|YGKiKymy}W-<~1Zu7pg$y_P$;6FELzLL%Obx0)r3hX!(29g~wO2(K63=;vH?5kcc8&83}5|d+zphE#8$4t3lO)wLY~B`(4k?=A0s|1}Py?^+e(?PdILi z1hw?seC{k8zj?2FD-&>T5)!J}k+2%%wWy`%=Boy>VKqnz3Dwg`SPhb(mY%e)e#nN^ z;2?>%WY<+ajf7=?lAu=ApsnJxtwDX1hX0u2cdO@&SK7bZxEsWgWl8yrBpPi* zA=WcTqKJ26yaKUJ2?<@v$C6D1wIaUmV@zfnT5i-fB_yiF*jUo?eJs~tg`if<6Joq- z**lg2VL4tCN=T^1_*k-upjOOxV!UeEJC?~|xoXPG=n@iYV?LH_BB&MfwivHk_Kszw zSk9gDOI(6cO>Jz*dRZZ;74y%96D@nkGHWb%P>6|Yv~vGtEl1hryiD*8uc&{>Y~HYFtFSG=EZBB&KBY|+mx zH_=81%Z{dm1Y?xU9b6%(6)T19J}g>-ja^De$hP^!k)VWxO6UacTzQr&QC~en^PD6o z;dSdt8-W_!BS9^-68D@WC?TOX<^)=z@?IAvp_W>^drlIRkWkBa0zFFky9<+0OTE@T zCkaYOs0TX{*@iZjC=YpI5^B}xgY4)|P(q?cq98OTDxbQwxJOT^rBO6Xl>{XuG@|C6 zYiw6uc)t&7$s6R;O@a~<@+Db=@=?lf@AW|~d9`dMNemLiKJswc66I@^r{CKZwaN!a zYfpj_66L9*M=1i>B|$C464`5$poD}XjvN^*Ke0zkB&fxhD02t*T7KeHnl;+$8E1|0 z?l#7&c<*e)xs;I5m4-LfD+IM-Epy>SybbRsY*0div*N>tHWAc{HQB}RR)4SMCr&6K z!FhY;C$13GidE;uke#sG@)MP7&?O|ef{^(PD+IM-#d|SiS?sp_MCD9$2??%i*qer) z(YQiTE8YSuhHR1DmY=BHk1ip>m6yYZBEMvXpjNzrSPWS&SGD{^<*;-K39Z8onKdf} zwc_2&V#wY(x8)})7pF@|jB87g@3TTsE8Zb3hAgD*mY=AcqAnpZu6RYJ(+WYYc(b(_ zvZ=OPexh=tx`YH**fKwHg`ifvZ(9smVfKYQ<#=@o39bQVe&Py2t$1&^7_!?YEk9A& zZCye_Ynej^-3mdic>lQ=vh*e`KT$b%T|#19<&3<(6@psv9(UpEqI&aV^IA&Q5gXqk zFP7I^MLU5~?aBrT`>i`4GBfQyl$p6O39qZC;6&sn+S45fYN-Z?4AV|fLPE9aL}VNG zFE5gymRjPFDccE3NT^jh5!r^;+Lc?oFbTEPqlS#%PEbNZy~_#oTIC2YOhPS<3`6F! z^>bw|FHAy0ql6O}eFlPB8sYri1PMw=XtZ-8vJGt%RnGRpB-GMKJ!F!1f)WxMwVi-B zQ11D{B-E0}@%K0+C?O&5qc_#*)s#cu-w9Dmo>T9gi=c#ryr>hApJ?7$dja~JDrzYL z7;$z$dn_s&_Ksc>yF-?c z&#>+Tc>w+WGKrc2*y@LDSgrxDMJ=|TB9PC}TL}rxeS8&1Hd=n-4zEQm_JXp3yo}!3 zNoWq|t5LGi@)MPp(Ftm?Ho-QRMw7N64#Fn49MS@z449W&_)fN^_kf=2$_Ndp~;U&sd>jbsNXh}~OId?r; zBB9kbUr!X#@)MPF*9mGdQmgy0XGIAKt^sZ)sHH0nv1o6*l#q};Up3HuwEV;!64cVO z@|ao#ayffUO`@Kgt$v6&`+3JIqp=gzQl0zUKm>A9``mzp>fcv!M6~=w<)n6kT54}T z#}UD{YZ4M_$G#dR!t!@{Eo!OX_*_jy%TL^)goOIJ&mcu054q1ENvO~JI-H0rk9pit zUW-~9V|*qo0{PT^CQPEnF63jQCDaOMXx*EN%mN`hA6kgnZ)I5?g+v^7K1F zE%{(yDblmTeuKVJM525AArZeL-)GX! zPwY96?OpS%ouAm>PPZA$w4I;Wb0A6gT!T(TR#;w_M4O9DUvSwCbD!h1H}0K?^AnSx zR-0K&+xdx=tJVp-n<`b$(wnvO6P4GOrL9tpM9&0FqRsC6Z(lV~sp9;^ycV_ETz%Hg zPn>5SSua(bpO{av%^;`k{KTFE$n%A8zj{7GmEvilE`~af?8}bRp)VjV%BY2#hJGA6MI(a`gRpLso6?MsO@GJ zYcEygy(U2|wfxLz>_nWOnEgODEXu4>MJ{J2B9}9J6bZFmUyV|I#QBLyP)q$Iv!lC> zI6txX36toF+Un5yQbo>o+9092@pT`SD$Y;LaY^mURy?Ye@XjNDH|o5fpV-^05o*W2 zmLVH)eqs{TQjf|E?0)BQeq!%YCQ%=>nfLlqMP7K?Ai+LgEiukdoVN25l{+|X=O@lB zx^LM+({_GhA6JTq^Al6j-i9a9-o8)U`H9W1L=I%Xk2pUu32L>sa^1H3T0N^cKQSdF zWN#$m{KO=v)!r3O+xdy@J}hRCjW|CsB_!J0_h~ynvE2uWI6pB7YPENs({_Ghe`8uU z;{3#vkZ5n;r|ta2o>^B!oS&G)pmp&Vr|tYifAgF75$7kSghYG$K5geG&OPeWoyYl! zNl>f3gPykY6Xza_iiqeV?}T6PJiMKQRevwRh>$c79@ex)xK*Mx38mZ7EuY zwZwXEHm?;C=O;!@?YFGSY{ymSB;x$UB&en5=JRvei1QPBO__v*>U<>P{KO=vrRU}= z6S5KKC-#~$35oWGzt_`9#QBLyP)kqRS6E~t&QI($)g`#D>U<>P{KO=vRW)cUMUlN@ zZ`|$t#H<63A1&UUw(}EXECFHXC#HmiuH^lE6G5#OUr*cli9M?)vv>O0ZIqCx+O&Qi z`93QIwc0#k+Rjgmu_Us0`WbYTkWg)Amc_)VIB_wrMXfg9nYQy2V=Rg6oqm=cB_ve; znJuzyRGhe2*TVSG=55nKH6Pd z_KxKzTHaDhNT{ECeQYAA)z&p;?fk^3k5+q@y<_=_mVcEJ5*n|(U2P($)mC(7?fk@O zSFIIV_KxKzS{_+SNYuD%{bLhBt+p~XYv(6M|7bl*r;FM7i76pLzneM2meDv6)M_hi zvvz)B^z$|{=sYsZ>q`j<#t(hGT1!x?trX7M`H3}NiLmn%Q$j+veO(l#vaHEoDwB{< z37x>R8VG9DGc>P8f)Wz-q>Vrg+WCo5ANvRYsjRYmUu3C%}Xo;5h+S`>$sHHaT zUX27LB-HYqK##Kg-QGV;LM`=8_i7|4A)y}Z1V#qSL+<_DB-E=CmRNRlj6NS4 zh#HBIPi-UIKu}9#WtPhFsXIXl35}?E=NhRkFT9VtCZU$b{Cv7eP(nf;Cu>k1$MV~| zH|P>X8S-7(N|G2PAmrh)CCYPJo__agCZSgO;ArhhP(q?Sb@Zr-MFEyiO@dmAC9>Bh zK?w;(962&fESj-si3GJ66ZQPWz4j)#=MHK{XDf}I(Y1HC({_Ghj8~=|gq?<%5)!&n zzNubIP^+zFPTTp3v9q|n4d1iBI6pBZB*uB|CW2aRg>~A_PmI0DEe~MN{^I<^l#t*& zy5}dZC8*U_il^=T#Qv_hXB+OeoCaklq=W?512z-XYOCkdc79^);ceN5yY?67C#Hmi z)~_;?V=Y0g_7-5;&QFY$)Rrx>YkzTmVoFG8Eh{rp))LfeZ!>1?{KTHA(of~Os^!Wk z>m?;5#uXORUPn-?y_K1@^Amf<&0#wY@m%|h^Al4-f-5?k32L=BLbG;$Vt@17Pf6Qu zxl77IN(qT^HOjQt5!7mLwr1`8#GV1wvkkXf4wka1QbK~OUz-VPwfAkac79^dNT@cQur?L# z%Fa*hb#4-BsU>EnY!Z}^P^)yp`bP8*%dPEg*Cf(t>p;!K4=nZ zX=KREW%YB*T<#--Nl0jva027iKu}8~TxMWvgtH9nKEj!Vgho3jFp3TYwKP&^Cb`C4 z%Ovk3wMj^5)OG^?V<4y{kCPek@*kEF-#yOqI~I8#C*TJMf?D#NdheW`(=z+J=QIfk zc~K|Kmxn(e2x=(;$Q=qvP(nh{fD?#IY)?av8B9VgMKZb5LUD=hwCItHNk}NFaRSkj zou8NlwG@%%juAy<+mw({bmj!&L_0sR$8aX07URbpMJ+$k&QHwsHqvACYGbawb&qVr zThM&ycNz zgl00CGtr+_oS&Ekwb%>FM&xB={~)0mS>}Fp8*zSO64YXEE*p_wlKq^7W|o=5(rv`~ ziAhk4qf*(3JeeG?NYtD`V)mTCs zCLtkvzG@&M&QHv^mRfpN9)*jDT+WQCNz`+*)ejMIeqs{TQl0xg77>w?nsWmZs()X_ z5fSGnCP6K=P|q9?Vb6*Z5^Bf38YLpmPs~{nwbY|L*FZ#^pO|ws66)u^D@8=)A?FN| zg!;U%!-dCYV2N}CC4 zwck_O9tlcFJoL(^Oz*vIxgVCj)Bfj({j&R@WQmv$gab=Nqf_g`XFqm&{zdk#XxRoO zOT>I2(gun4JGJh0^G8lkdE|}O*q~&Im=8qSAkluO*15NM#Ps-AUf;7q$7e;!5-}f$ zv_Yc%POXPt`LO9{PW=8F8&^MObkB--!PGTU$Y!|$%KLCF#^ABeO;!b&AAdxjT0 z?b~Z?P_jhK2O@2du%|06YYVr&(KpxFpk#@d4@BA^VXZ`3)(d{+O_s40Z8r%@mWcU4 z9C5^ZlqA;L@!M=nO>gYAVWUfy2&0Qwwn3u*j{93fP!cvo*i$INZ=>~d5^?8UE9$9; zEEOe7gw&HcAwcHb_{hq-D>rjc_wl9LFn4mIxc|ibxwI?CDC&+Cm$ti#Xzlw-QN~ z2phGFNE^JCwGwGrFK8a8h_pe;5@Ft_h_pe%TD!EuKNgWTC|M%RI~S2QNQCF?T9K1l zMB1QaiLjWVh_n$gLzj?<_~9oI)QWgzBwES(c$K4!-MPjqvv=cK zUWt}^E1|^hLvb5zZ?-|go?9DN7Om2%CH5NRwWwwFv=Z<3Qc=RFpH~`7)!J*u=dE2$ zF*nGZ^pR-SN(qT(FR!$jpjIobjiPJroRW6uHlBAa+TLt~M0?Waan{)2wW!r<*8Jd_ z9z{uOB~!(?ywc`Uk+3T%F5OH}YuqlVBSY?+AYu2UxOB9^Yf;Odo1)B-pv3A% z<1Vi>5|ogz`rkNS<$X}g+E^QRt3HmbyK`#A@2Tl!sTyVeqhG5_NLVizO4YROzmcF; z{9a>&5)#e(hl7l#pm8%&31X6$xs!r;u}zu~d|_C!Mn*UTL!p60J5j%bVO}nCmgx%lzxiblB*>hW&(f3kOV)dc51zu@_Ylvi7GKSuZntuTsy-;wur@U)yVtMC9en{LPPu_&!e7AhjY}Xy)&u zM8x-TY}ap>=!x2!vGt|GNeI1EBvd#4?oKx1`#83Hxwq=bRh!zo&8iRHIrdcd9z{Y= z*WbR%MtmP9dla=)H^aFGllVT4?ew0SM6JZ$L9Z{>a<3(!-<|`hQpNXiY+rkC4Z07@ z@hcl_i8u+Nw<{7F89c8~HpWur*$GqAV(+SU72n6PGb?(}QOmIWw5oHK3TF=VK1f1s z%rnnaDx7Q332LbwdmfpH_&$!EmoPJlMjXooTVE=i&(Lj<(AecUUb2BRAUZ)Uj*s=M z;`=zZpL1r}6tS;p+JF1r@OCBa^q$1`acrk|myn2^PpxK2#P@NMpjPaNnE887-A8;M zr%&y}N`&?3G#~;`=yBP%HK^wWn+O46+g5$FaTPz4fVOSWB$uW;sP7;`=zZ)4N@3 zTYJNMJFYq>5#Ps2f?9fRo*N|_@qHZI={+?G3Dx;X#P@NMpq8GSXNAc|d>_YldQVM4 z;&9aYNW}MXlAxBJ^qbl_`}M5i`#84Kd)g(quIhXw;`=yBP^)Utvh-RwVj1`SzZmuB z_J7I)LUn!X+wKoyM%h|L}ITiJ(?wH%7aPUD$SN zg!WW-35oK9(b{cy{|Z5^$kL4dVg1i~ReVdx_J(%}3C2OW|9pj@R%Dw-KaXAUeeWwJ zBpA=-Ui}qgigP zL4pzz^`wnJo!hsBqCU2Vct@?oqYM(1@VaU-PM{^~42YRYsHN8KQ3eT0NT}sIfgYu^ zEM_L5mU^v686+qnp&sl+?A5nj@j8=ZW)f=E=!26&Izb7E8i|6io%c4v*|&sjcYkYF z{aZqIno)~I9zE5_m!(RA5?)s$YTmiVcAa?A?}J+M2KjW8poD~cN!FlzlzmIc_UiZg zpq6}Bwvr?U3F1U~xNM2?we~F`+pFK(6}8F-M{7@l5)$R9qem%bux|<3Njj}QwudNO zQAYOKBq-r^6>;RqV0-l~_Sq#tEyhH-SAP=U60(yO`${8c*s+f(#;e$aWrTf8$oA@Y z2?@^C2O9%Ht;qPD4LidoZLhv|hII)Et|0Vp3E5t<6@prkxjY+oxJ}|)LY9ZzB_zhx zkJv@GLQpF*u=}b=?!4cQZwXmGb(fIfYRhJVT9HXU8+IIS$G3zmFT6`ga1F@zP4qpA zD+IM7BYrmQoZOCY30Z!7mypof;;=h&g`igC@6ViwJ)`Hww}dQDze`AH&2rdfx`jH`p22x`UtkD0G0 z#$M#z_?D3E|L77DT#d}V`YQyrVz=lAqu^(sVMC=XU zi*E_p?wT$kp%vj_H~9)dt=LyIb0YS*@5Q%-Y?n}%kQi5lHxbl|{ZTVtL)I<`o6}RW zj@Y=PYGx7=`t1ZtW#1CA9aRHiTDo&zJtsj4udAov1nR@SCDfmlNvNe7^fi4Fl#ozu zIuU#It(EMNpq5&q@2Da{2?@1IC(u9aTSC3FQU30Z1SKTYyPQC;wQmXaK4=nZ zX=Ly>iXC% z8nuU$Tg)5Sw}krGZW3zA6poD~?8Yg0}zC}y+ zEukL!n1ou2$b82-2}(#PIvY-C>X9W0YB7Gy{hX8dmQb#$kshPh7u-@s)C|B@KV&1mC6x6+Ew+Usu(z+j zohG4~jIZLzMtn;s+ZDCgrppHQDE4>QBs3%Q)hOABZwY1ppceaP*}z`Q{%)Iu=Ayo; zCL8fBq3q|>;uupl%sW#;qGrh0m)hS1kf0XF%FzZTB(yd#-bZ{(D92rDam+6p*uy(B zZ$Lt89AkaNw}jGvP>a5+Y{a*O(yNi6M=iphE+r(ix-+)K_?A$5XKFDrC>z+fJ+o+n zM6EfoN5!{u~(UZ^^Jl;oqODNX>s3rfQ6Po%y`U%c@=_?Z?DUnwF{zMVZPz9p1vOVm + + + Tilting quadrotor + 1.0 + tilting_quadrotor.sdf + + Generic tilting quadrotor + + + diff --git a/models/tilting_quadrotor/tilting_quadrotor.sdf.jinja b/models/tilting_quadrotor/tilting_quadrotor.sdf.jinja new file mode 100644 index 0000000000..cf7caefa87 --- /dev/null +++ b/models/tilting_quadrotor/tilting_quadrotor.sdf.jinja @@ -0,0 +1,876 @@ + + + + + + 0 0 0 0 0 0 + + + 0 0 0 0 0 0 + 2.0 + + 0.008 + 0.00 + 0.00 + 0.008 + 0.0 + 0.008 + + + + 0 0 0 0 0 0 + + + 0.5e-3 0.5e-3 0.5e-3 + model://tilting_quadrotor/meshes/body.stl + + + + + + 0.001 + 0 + + + + + + + + + 0 0 0 0 0 0 + + + 0.5e-3 0.5e-3 0.5e-3 + model://tilting_quadrotor/meshes/body.stl + + + + + + + 1 + + 0 + + + 0 0 0.025 0 0 0 + + 0 0 0 0 0 0 + 0.015 + + 1e-05 + 0 + 0 + 1e-05 + 0 + 1e-05 + + + + + /imu_link + base_link + + 1 0 0 + + 0 + 0 + 0 + 0 + + + 0 + 0 + + 1 + + + + + + 0 0 0 0 0 0 + + 0.0 0.0 0.0 0 0 0 + 0.20 + + 0.0001 + 0 + 0 + 0.0001 + 0 + 0.0005 + + + + + + 0.5e-3 0.5e-3 0.5e-3 + model://tilting_quadrotor/meshes/arm.stl + + + + + + + + + + + + + + + 0.5e-3 0.5e-3 0.5e-3 + model://tilting_quadrotor/meshes/arm.stl + + + + + + + 1 + + 0 + + + + 0.07 0.075 0.025 0 0 0.785 + tilt_arm_2 + base_link + + 0.25 0.25 0 + + -2 + 2 + + + 1.0 + 0 + 0 + + 1 + + + + + 0 0 0 0 0 1.5 + + 0.0 0.0 0.0 0 0 0 + 0.20 + + 0.0001 + 0 + 0 + 0.0001 + 0 + 0.0001 + + + + + + 0.5e-3 0.5e-3 0.5e-3 + model://tilting_quadrotor/meshes/arm.stl + + + + + + + + + + + + + + + 0.5e-3 0.5e-3 0.5e-3 + model://tilting_quadrotor/meshes/arm.stl + + + + + + + 1 + + 0 + + + + 0.07 0.075 0.025 0 0 0.785 + tilt_arm_3 + base_link + + -0.235 0.265 0 + + -2 + 2 + + + 1.0 + 0 + 0 + + 1 + + + + + 0 0 0 0 0 3.1415 + + 0.0 0.0 0.0 0 0 0 + 0.20 + + 0.0001 + 0 + 0 + 0.0001 + 0 + 0.0001 + + + + + + 0.5e-3 0.5e-3 0.5e-3 + model://tilting_quadrotor/meshes/arm.stl + + + + + + + + + + + + + + + 0.5e-3 0.5e-3 0.5e-3 + model://tilting_quadrotor/meshes/arm.stl + + + + + + + 1 + + 0 + + + + 0.07 0.075 0.025 0 0 0.785 + tilt_arm_4 + base_link + + -0.25 -0.25 0 + + -2 + 2 + + + 1.0 + 0 + 0 + + 1 + + + + + 0 0 0 0 0 4.64 + + 0.0 0.0 0.0 0 0 0 + 0.20 + + 0.0001 + 0 + 0 + 0.0001 + 0 + 0.0001 + + + + + + 0.5e-3 0.5e-3 0.5e-3 + model://tilting_quadrotor/meshes/arm.stl + + + + + + + + + + + + + + + 0.5e-3 0.5e-3 0.5e-3 + model://tilting_quadrotor/meshes/arm.stl + + + + + + + 1 + + 0 + + + + 0.07 0.075 0.025 0 0 0.785 + tilt_arm_1 + base_link + + 0.235 -0.265 0 + + -2 + 2 + + + 1.0 + 0 + 0 + + 1 + + + + + + 0.16 -0.18 0.055 0 0 0 + + 0 0 0 0 0 0 + 0.005 + + 4.85e-07 + 0 + 0 + 0.0001857 + 0 + 0.000274004 + + + + 0 0 0 0 0 0 + + + 0.005 + 0.128 + + + + + + + + + + + + + 0 0 0 0 0 0 + + + 1 1 1 + model://iris/meshes/iris_prop_ccw.dae + + + + + + + 1 + + + + rotor_1 + tilt_arm_1 + + 0 0 1 + + -1e+16 + 1e+16 + + + 0 + 0 + + 1 + + + + + 0.1635 0.175 0.05525 0 0 0 + + 0 0 0 0 0 0 + 0.005 + + 4.85e-07 + 0 + 0 + 0.0001857 + 0 + 0.000274004 + + + + 0 0 0 0 0 0 + + + 0.005 + 0.128 + + + + + + + + + + + + + 0 0 0 0 0 0 + + + 1 1 1 + model://iris/meshes/iris_prop_cw.dae + + + + + + + 1 + + + + rotor_2 + tilt_arm_2 + + 0 0 1 + + -1e+16 + 1e+16 + + + 0 + 0 + + 1 + + + + + -0.16 0.17535 0.05525 0 0 0 + + 0 0 0 0 0 0 + 0.005 + + 4.85e-07 + 0 + 0 + 0.0001857 + 0 + 0.000274004 + + + + 0 0 0 0 0 0 + + + 0.005 + 0.128 + + + + + + + + + + + + + 0 0 0 0 0 0 + + + 1 1 1 + model://iris/meshes/iris_prop_ccw.dae + + + + + + + 1 + + + + rotor_3 + tilt_arm_3 + + 0 0 1 + + -1e+16 + 1e+16 + + + 0 + 0 + + 1 + + + + + -0.164 -0.175 0.05525 0 0 0 0 0 0 + + 0 0 0 0 0 0 + 0.005 + + 4.85e-07 + 0 + 0 + 0.0001857 + 0 + 0.000274004 + + + + 0 0 0 0 0 0 + + + 0.005 + 0.128 + + + + + + + + + + + + + 0 0 0 0 0 0 + + + 1 1 1 + model://iris/meshes/iris_prop_cw.dae + + + + + + + 1 + + + + rotor_4 + tilt_arm_4 + + 0 0 1 + + -1e+16 + 1e+16 + + + 0 + 0 + + 1 + + + + + + + base_link + 10 + + + + rotor_1_joint + rotor_1 + ccw + 0.0125 + 0.025 + 1100 + 9.84e-06 + 0.09 + /gazebo/command/motor_speed + 0 + 0.000175 + 1e-06 + /motor_speed/0 + 10 + + + + rotor_2_joint + rotor_2 + cw + 0.0125 + 0.025 + 1100 + 9.84e-06 + 0.09 + /gazebo/command/motor_speed + 1 + 0.000175 + 1e-06 + /motor_speed/1 + 10 + + + + rotor_3_joint + rotor_3 + ccw + 0.0125 + 0.025 + 1100 + 9.84e-06 + 0.09 + /gazebo/command/motor_speed + 2 + 0.000175 + 1e-06 + /motor_speed/2 + 10 + + + + rotor_4_joint + rotor_4 + cw + 0.0125 + 0.025 + 1100 + 9.84e-06 + 0.09 + /gazebo/command/motor_speed + 3 + 0.000175 + 1e-06 + /motor_speed/3 + 10 + + + model://gps + 0.05 0 0.04 0 0 0 + gps0 + + + gps0::link + base_link + + + + + + + 100 + 0.0004 + 6.4e-06 + 600 + /mag + + + + 50 + /baro + 0 + + + + /imu + /mag + /baro + INADDR_ANY + {{ mavlink_tcp_port }} + {{ mavlink_udp_port }} + {{ serial_enabled }} + {{ serial_device }} + {{ serial_baudrate }} + INADDR_ANY + 14550 + INADDR_ANY + 14540 + {{ hil_mode }} + 0 + 0 + 1 + 1 + 1 + /gazebo/command/motor_speed + + + 0 + 0 + 1000 + 0 + 100 + velocity + + + 1 + 0 + 1000 + 0 + 100 + velocity + + + 2 + 0 + 1000 + 0 + 100 + velocity + + + 3 + 0 + 1000 + 0 + 100 + velocity + + + + 8 + 0.0 + 1.57 + 0 + 0 + position + tilt_arm_1_joint + +

20

+ 0.0 + 0.5 + 0.0 + 0.0 + 2 + -2 +
+
+ + 9 + 0.0 + 1.57 + 0 + 0 + position + tilt_arm_2_joint + +

20

+ 0.0 + 0.5 + 0 + 0 + 2 + -2 +
+
+ + 10 + 0.0 + 1.57 + 0 + 0 + position + tilt_arm_3_joint + +

20

+ 0.0 + 0.5 + 0 + 0 + 2 + -2 +
+
+ + 11 + 0.0 + 1.57 + 0 + 0 + position + tilt_arm_4_joint + +

20

+ 0.0 + 0.5 + 0 + 0 + 2 + -2 +
+
+
+
+ 0 + + + /imu_link + /imu + 0.00018665 + 3.8785e-05 + 1000.0 + 0.0087 + 0.00186 + 0.006 + 300.0 + 0.196 + +
+
diff --git a/worlds/empty.world b/worlds/empty.world index e196ed972e..ad4cf6c311 100644 --- a/worlds/empty.world +++ b/worlds/empty.world @@ -3,7 +3,7 @@ 0.95 0.95 0.95 1 - 0.3 0.3 0.3 1 + 0.98 0.98 0.98 1 true @@ -14,9 +14,9 @@ model://ground_plane - +
0 0 -9.8066 @@ -38,5 +38,15 @@ 250 6.0e-6 2.3e-5 -4.2e-5 + + + + true + true + -2 -2 1.5 + true + + +