From 8e54924af5fb3427ffa9c3930dd11518d45233ef Mon Sep 17 00:00:00 2001 From: Yishin Li Date: Sat, 16 Feb 2013 12:37:08 +0800 Subject: [PATCH 001/256] Cleanup code --- nc_files/rigid_tap.ngc | 4 ++-- src/emc/task/emccanon.cc | 9 ++++++--- 2 files changed, 8 insertions(+), 5 deletions(-) diff --git a/nc_files/rigid_tap.ngc b/nc_files/rigid_tap.ngc index f748b93a5..66cb3f8ea 100644 --- a/nc_files/rigid_tap.ngc +++ b/nc_files/rigid_tap.ngc @@ -1,4 +1,4 @@ g0z0 -s60m3 ; 1rpm -g33.1 z5 k1 ; 1 thread per second +s60m3 ; 1rps +g33.1 z5 k1 ; 1 thread per second, k - distance per revolution m2 diff --git a/src/emc/task/emccanon.cc b/src/emc/task/emccanon.cc index 19249ad6a..7ec1cc3cc 100644 --- a/src/emc/task/emccanon.cc +++ b/src/emc/task/emccanon.cc @@ -1099,7 +1099,6 @@ void RIGID_TAP(int line_number, double x, double y, double z) from_prog(x,y,z,unused,unused,unused,unused,unused,unused); rotate_and_offset_pos(x,y,z,unused,unused,unused,unused,unused,unused); - // printf ("debug: RIGID_TAP: x(%f) y(%f) z(%f)\n", x, y, z); vel = getStraightVelocity(x, y, z, canon.endPoint.a, canon.endPoint.b, canon.endPoint.c, @@ -1122,7 +1121,9 @@ void RIGID_TAP(int line_number, double x, double y, double z) canon.endPoint.u, canon.endPoint.v, canon.endPoint.w)); flush_segments(); - // printf ("debug: RIGID_TAP: vel(%f) acc(%f) jerk(%f) \n", vel, acc, rigidTapMsg.ini_maxjerk); + DP("x(%f) y(%f) z(%f)\n", x, y, z); + DP("vel(%f) acc(%f) jerk(%f)\n", vel, acc, rigidTapMsg.ini_maxjerk); + DP("spindleSpeed(%f) spindle_dir(%d)\n", canon.spindleSpeed, canon.spindle_dir); if(vel && acc) { interp_list.set_line_number(line_number); @@ -1246,6 +1247,7 @@ void START_SPEED_FEED_SYNCH(double feed_per_revolution, bool velocity_mode) spindlesyncMsg.velocity_mode = velocity_mode; interp_list.append(spindlesyncMsg); canon.synched = 1; + DP("feed_per_revolution(%f), velocity_mode(%d)\n", spindlesyncMsg.feed_per_revolution, velocity_mode); } void STOP_SPEED_FEED_SYNCH() @@ -2162,7 +2164,8 @@ void SET_SPINDLE_SPEED(double r) canon.css_numerator = 0; } interp_list.append(emc_spindle_speed_msg); - + DP("emc_spindle_speed_msg.speed(%f) canon.spindleSpeed(%f) canon.spindle_dir(%d)\n", + emc_spindle_speed_msg.speed, canon.spindleSpeed, canon.spindle_dir); } void STOP_SPINDLE_TURNING() From 9ce8306d74b63ad0beafa9a5bbda7104fea92eb8 Mon Sep 17 00:00:00 2001 From: Yishin Li Date: Sat, 16 Feb 2013 12:37:45 +0800 Subject: [PATCH 002/256] FIX configs/araisrobo/xyzabc.ini --- configs/araisrobo/stepper.bin | Bin 7508 -> 7708 bytes configs/araisrobo/xyzabc.hal | 10 +--------- configs/araisrobo/xyzabc.ini | 1 + 3 files changed, 2 insertions(+), 9 deletions(-) diff --git a/configs/araisrobo/stepper.bin b/configs/araisrobo/stepper.bin index 8c05b4914bb4d73fee49136e56607cb79fc9f5a8..b461c9d7127f12e3e2271dc31dd7381960af72da 100644 GIT binary patch delta 3448 zcmai1eQaCR6+h4K#vhIAJi3HFClPjWN?e+SG?Rv*Oauy}8kL%TFm-DMW-ePKOyZ$x zineaH+UKrX!wS4gLEHKET<(IQbMSMwj%nx>J6CJSASXq(te8qsboC_)vBkm=j+ zyc9|i(*C$U_v74i&-tCNXL*0&fvNQ#<)W#3zP09#Xj_$N^4(3l%(SO1Ty7yEJ4wRM zkq|`Rwa1ux%jTHpF3%l7bJp|Z{SmE@ByVAilzGuUq$fvdRCv?#YMii7*r$0Bd0)re zO5G8a;+|_#w9gg|U)oHnZTH#55fXY1r^a1{rLHJ_#c@6w)hJp>f6`aLKHlqwl}@j7r~}#KeMEY)NUcP4N{eW%RnWg}>YqGF+T=NE9?g-mdNHC2QhL~+k&GCs zs6-l3W9d~qJi;9K#sKcm-oWMgb!SC90X4t|H&ib44=Jlq=+%>vk%t%AlTe z6~%cF@3W$UJk$L6O=Yuc>#f?0?5%6{PF~--CoX)!!Yho*O`$Z!Ybe^y)W}e7)jbjI za|*W{*GZYo0!G;pmaM&HkTCYTR%r|`v~Igqu(E;Is^b)yg1?XXv7U7;E#I~XxIb_o z-5ZcglRCryA70CjAAIQ>Sup&Y8E$GX-aWOAwGPbPP@?_jd3-s)jv$C1k1xM)jwnA) zLE~*-+W62nl7Bu>%fB3$lf8ZZ{5lb|o=5oR$d7<)ki9)5dlN$T?h4A@q$Yba&9Zl3 zqb^9iD%U+$hZPt2AwdmYd=YdfQ|vFAd%Q1Yr-9BA`SXH;Qb3r1Fwy6Cm0N%TRpmF< z%#OcKt3ApYJMMA!pC&3_BCVXFeq)-NaaXrf36bAR?T`f-deFX@0PWErt67R&I)G57 zeYygEKX?Szsy&mS?6g-`3ii+>AlIhV1hT@p4uQ>9>WSR6Usv=hd90c41JjLPPymmY zFOXJgAX-TE2xN_lhuTX&0m=^%Jwn^5uz^HjgR>$PjS3Hu|5OZFmijEqx=|F&fB6#1 zkg5Ak{GRr2&3?wLS4ZjWUVfaC1snBdvWJZGMDHx#Td$5K6s{oEvACx^O&;S9PCZNt z*)uvB?+MGENO-0j`V>C1Y-e@Z6qn+{N>Ps#U*ECttWE_(95$YH;Wdx?!{)Mot9c>tz{UXk#2BQUn+Aw*Kq0I_ z_O*BvffDmM&O2uFn(t+cFr$R%YO5ltQu}@JeQ&IiHK8d6hSs+0SRjS#aS^f1G*QGT7NQ0 zOZfy_rN9N9uyJpLo6Zslqyam%z6i*hmec_r4z zbW0`H&vZv6mSnoS63a0CrIo9G%6r7BPGR1|`=*r}bN7+!e{x*_+2bdg92lkG{3NIc z^mm|s&^IejZ6tw7iJ6gqrP9i(LgT3@-6;HSB{I^!wEe0sD#EQ+cQQK0V4zmQx`5g& zyMI6Td9)zwP1zl;nMN>{?L}OD)7}^L+o?GEms|gIWF)_schyY$Mn07eEbr#M1wuRy z(DAZ`q`HjEK1Uk(U$M{k2!_lJf)x42ji#zTRwRC7J`}lX!O`=f&JPMzQjBNNQA62# z-$$F+&Y>tnk!uh#0J_XVu-9Z1U`mAqN{4EvGH_Vzv{W}wNwp&=)h>Q?55vL+oK86o z)-@QS{vY!P*?fJ>`NZfP^sQJEj#F6&A-D(&pMnA_Tt;k^2^hPZ*XEA3QBP^b99*ks zGmOpGkai>GA$k~jtrm_Vrc!ageSX-@Z9ApW#1c7>z`XH)T)gKpW5R70m^fwB2_#5_ zO@fCt#33h46rr)N{0#N8Nx0WKA8H>m_5*?g&Q;WmW!{(BP4HnK+=laLY&wQ)* zu78Ak`@4)^x!S!iL;7Lkw}Bd*b#}OFgf4%DJ7krH809E3y`Z2h>hB@c5-~tXBVE#|r zrD-?aeLF-LaX4|n{a7nPEFz?4Mzz~LoBGX!woREe_iNkM&e|t+;tFb<7nV7vZB=I9 z@ZWYsy-nH^QO^zWPvh=C&GF`g4N|Im=FP5_R?i;W+};vV=FNeY&IW0m5cB4-maSOV zTC(QmKsYOv7n>I!iBicxFue_m+KFhs2HqE=~i)eo1`q?V7+achzTFGJE?R5YgG1?A|aZ z8?k6a9-_ieoWPgaSKSBO%X5h650jJ+;qnX~yo9)YO;~3~Nab8C`bo)yBAyldQic{r zGGx5~5WTyvvL|KtLpAA3ON@CLL_H41rev@^D1#kv2Z=s)!M>Sj)V{Jx>e7Pq85 zTDl0uF8b<>Oi}gjVDFZnLnpBipKmdO!z6w2pm7jA?*!Z`!r$Jh-cz?{hKWBhfV7AC zEsJ#NeXw3Ie06Tle9t}#Px&co{E;o7HB!B|ery1SqX=?t0T>VWRdYPNIoq=ocLV*u z1%nd>UsXrQZ~YY7p`<}84=j1Rm;|)gFHBN^J2SWL!WCKrDI?_x%-^C$!0*We3)>jx z81dK>&~(VRBE@5M`x53y(a9Sks}>9e0DEU$dP9*q1P84lVCXm*b9?LNEpx`XKuy9} ziAIBP@W6v!oIX`L2yoK)fQ*s*xx@csWLJ33T=uLt|J=H^S)!vE=g8noY&9-DZfb3v m;UR7%@aozUG+b@6@p|C|ywcy+scd;;xa}8;Qa7))C;tbzsg2A4 delta 3120 zcmZ`*ZERE58Gi4*C$W<_%}p@rb!@_=4#5-}OvJRbOsd;ZDeL;f)tJUM#@rdUNQ+9k z!WM04w%{hMidiyl)K=9^YBdSm;7sxam7K|1y%JcYb_h*JB|p$~1Kt{`uH+xA&9`kkrC&(?1`;4ctm{u;`e1G3*YvXO|K7%?YF zj1hg)NsGC5#7xVb@}_;}qI~Fy_NW!3S}RS`5(|uKu}PX_wW%c~L|7-R(^7}lsNugI z-xT8=Aunfvl?lU@GGmJW@x_T0F)fK*W9wRRr%oFxmCq(s(yf92L@cZ`s#ya{;Vwcb zivKaJeQsV-`V*4{A}uySZA5fIZI5P75o^Pt3*(_|Mj5srIOmgWdoo$ass0dqWsH z)9dMjjAqyLFpd#T$4SZut3-BL$;ubT041Hcu5gc* ztdhi@2X_mSjN~)8c%5iMFqLoL&z$w$FUy|@`TjMQdf;`R2#b9AdKwq9aiU626;=X) zhWm9S&&C9llu9L2RsL1=|3`xHmq4r__J&p0oN=9!XRfo+>8m6eWmjrAOUCdZ@!>Hg zbx$AucEi6lJRIp5R+)!~dvqQS@8RM89;^j;_&|t=nKlRP{a-goaH0;01@Vz90x z*uq~o?q^%$dO-e)kU{>>X1?|}iD_cS0=bPMc{qbRS(tIwvi`*oE&n=9#uOfDP|c)=E#A1bYt1rhQ^q@$HDeGuBRaV%mG3x5G}-uJ zWsQ3d4RBRM7){bdirIFY!pqk*GG2r+JQ@veG2gFkaqpu(vbK=^%}JiTrR=M%%PsRFljha!)2nx^RQ&?UR+2B~7F8Ul856wRz1r zSy`K51^7$d>f`V;d^$2V7QbwECcSH?-@%{xkX zU1D|CCc1?ZW{e;U&Jp9T;2d}D$jo)TkKL*AtD6${wR2+!`J3-2<7lo!3HqK~d zy-bp0BPd;BgxUXlbyKBsMO-8Z+3D*bRHh;x0kZGqgAtL!-T7ct%unTmF)>H;!9g(} zvXccW26gd&z)lph5W+$@W+&6t4P?~$d*IVkO_lsslCb|OW*PGkW;f>7F*D4s30-8@ zTNgefT8knB4l$axEJl)|&6w*FXV0pLZ#qqj!Ib&@%4!flqmh_NsBVt_)+BiXECL$%n=HySiWen|E(7nT6V~ zn(sAfQq){(`W}Aws9kNLtS}2IBy*-h%JPrGs~;K@(1YK~I7>?|q$*J(k_K%Q?>9nOQ*G{*R?Pj)y^Sl*d5sWSWL#m3=5+I3 zY2~8Rd|GL~I+qz<1(ht0rTc0W0P?_tH^YOZ&RG;m%? z#880i%A#0XA`cpL;te5&dMoiRUl}%P=UrP$DALK9DSU`LR=w1hE0Jtmt1Hjra_8eg zve34z^K5bXCxaw%YZxX%7)$mU*t~0ZnY(&RylZ=js{?m1R(XSejyD9ed}Bkv!y7tK zgop|MBW`Y51@jNJt@k>C*X-A}!7pRl(~r2(LUjddF5anW#)y!6+;9}bxjVd5*G#=$ zGd;fV%I<*K@B4;tG{2jK8=jfH4Mw-!0b!O2g$MZ=E19(ThZL zM#$YYwvI a motion.align-pos-cmd net usb-cmd wou.usb.cmd <= motion.usb.cmd net usb-cmd-param0 wou.usb.param-00 <= motion.usb.param-00 net usb-cmd-param1 wou.usb.param-01 <= motion.usb.param-01 @@ -112,13 +111,6 @@ setp wou.stepgen.3.position-scale [JOINT_3]INPUT_SCALE setp wou.stepgen.4.position-scale [JOINT_4]INPUT_SCALE setp wou.stepgen.5.position-scale [JOINT_5]INPUT_SCALE -# export pos-scale -net j0_pos_scale wou.stepgen.0.position-scale-pin -net j1_pos_scale wou.stepgen.1.position-scale-pin -net j2_pos_scale wou.stepgen.2.position-scale-pin -net j3_pos_scale wou.stepgen.3.position-scale-pin -net j4_pos_scale wou.stepgen.4.position-scale-pin -net j5_pos_scale wou.stepgen.5.position-scale-pin # set wou module pulse_per_rev - get values from ini file setp wou.stepgen.0.pulse_per_rev [JOINT_0]PULSE_PER_REV @@ -159,7 +151,6 @@ net j4-probed-pos wou.stepgen.4.probed-pos => joint.4.probed-pos net j5-probed-pos wou.stepgen.5.probed-pos => joint.5.probed-pos net rt-abort => wou.rt.abort -net cl-abort => wou.cl.abort net vel-sync wou.motion.vel-sync net usb-busy wou.usb-busy => motion.usb-busy @@ -231,6 +222,7 @@ net teleop_mode wou.motion.teleop-mode <= motion.teleop-mode net coord_mode wou.motion.coord-mode <= motion.coord-mode net homing wou.motion.homing <= motion.homing net probe_result wou.motion.probe-result => motion.probe-input +net machine_is_moving <= wou.motion.machine-is-moving # mapping wou.gpio to motion.synch_di[] net din_00 wou.gpio.in.00 => motion.digital-in-00 diff --git a/configs/araisrobo/xyzabc.ini b/configs/araisrobo/xyzabc.ini index 19d07edd4..5ca63fab5 100644 --- a/configs/araisrobo/xyzabc.ini +++ b/configs/araisrobo/xyzabc.ini @@ -70,6 +70,7 @@ TRAJ_PERIOD = 655360 # list of hal config files to run through halcmd # files are executed in the order in which they appear HALFILE = xyzabc.hal +HALFILE = ../sim/sim_spindle_encoder.hal # Single file that is executed after the GUI has started. Only supported by # AXIS at this time (only AXIS creates a HAL component of its own) From 0ca6e6719b2321242630d238db74a2a91300a668 Mon Sep 17 00:00:00 2001 From: Yishin Li Date: Sun, 17 Feb 2013 10:13:05 +0800 Subject: [PATCH 003/256] Add WOU_PROTOCOL description to ar-usb/ --- src/hal/drivers/ar-usb/WOU_PROTOCOL | 159 ++++++++++++++++++++++++++++ 1 file changed, 159 insertions(+) create mode 100644 src/hal/drivers/ar-usb/WOU_PROTOCOL diff --git a/src/hal/drivers/ar-usb/WOU_PROTOCOL b/src/hal/drivers/ar-usb/WOU_PROTOCOL new file mode 100644 index 000000000..2095c2390 --- /dev/null +++ b/src/hal/drivers/ar-usb/WOU_PROTOCOL @@ -0,0 +1,159 @@ +[WOU] WISHBONE Over USB Application Layer Protocol + + Refer to 802.3 MAC Frame (http://en.wikipedia.org/wiki/Ethernet) + + take its Preamble and Start-of-Frame-Delimiter from 802.3 MAC Frame + + take its 16-bit CRC + + The WOU messages is organized as the following sequence: + +---> [WOU_FRAME][WOU_FRAME][...] --->+ + HOST <==> <==> FPGA Tranceiver + +<--- [WOU_FRAME][WOU_FRAME][...] <---+ + + drop a WOU_FRAME if it's CRC is incorrect + + adopt GO-BACK-N ARQ for WOU_FRAME + + for JOINT command: + - HOST send DIFFERENTIATE_JOINT_POSITION_COMMAND to FPGA.RISC + - FPGA.RISC do close-loop control based on received position commands + + for GPIO.OUTPUT: + - HOST send GPIO.OUTPUT command to FPGA.RISC + - FPGA.RISC update corresponding GPIO REGISTER + + for GPIO.INPUT: + - FPGA.RISC drop GPIO REGISTER to mailbox + - HOST parse GPIO REGISTER from fetchmail + + for the other FPGA.RISC STATUS: + - FPGA.RISC drop STATUS to mailbox + - HOST parse STATUS from fetchmail + - STATUS includes joint-encoder-position, joint-velocity, analog-channel ... etc. + +WOU_FRAME Format +=================== + PLOAD_SIZE_TX: + + (host-to-target): 0x03 ~ 0xFF bytes for {WOUF_COMMAND, TID, PLOAD_SIZE_RX, WOU_PAYLOAD} + + (target-to-host): 0x02 ~ 0xFF bytes for Responsed payload (not include the size of CRC-16) + WOUF_COMMAND: + + 00, TYP_WOUF : typical WOU_FRAME packet; need at least TID. + + 01, RST_TID : reset Expected TID of receiver to 0 + + 02, MAILBOX : MAIL from OR32; need at least MAIL_TAG. + + 03, REALTIME : real-time WOUF command. + TID: + + Transaction ID for GO-BACK-N protocol + PLOAD_SIZE_RX: + + 0x02 ~ 0xFF bytes for Responsing WOU_FRAME + + initiated by WOU Read commands from this frame. + + there would be no PAYLOAD in response WOU_FRAME; + in this case, the PLOAD_SIZE_RX should be 2 + {WOUF_COMMAND, TID/MAIL_TAG}. + WOU_PAYLOAD is composed of multiple WOU packets. + + WOU_PAYLOAD{[WOU][WOU][WOU]...} + CRC-16: + + covers the PLOAD_SIZE_TX, PLOAD_SIZE_RX, and WOU_PAYLOAD. + + it's little endian + +WOU Frame (TX) +=================== + 0 1 2 3 + 0 1 2 3 4 5 6 7 8 9 0 1 2 3 4 5 6 7 8 9 0 1 2 3 4 5 6 7 8 9 0 1 + +-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+ -------- + |Preamble (2 octets of 10101010)|SOFD (10101011)| PLOAD_SIZE_TX | HEADER + +-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+ -------- + | WOUF_COMMAND | TID | PLOAD_SIZE_RX | | + +-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+ | + | WOU_PAYLOAD | + | Byte[6] to Byte[6+PLOAD_SIZE_TX] | PAYLOAD + | | + | +-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+ + | | CRC-16 | + +-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+ -------- + +WOU Frame (RX) (for TYP_WOUF) +============================= + 0 1 2 3 + 0 1 2 3 4 5 6 7 8 9 0 1 2 3 4 5 6 7 8 9 0 1 2 3 4 5 6 7 8 9 0 1 + +-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+ -------- + |Preamble (2 octets of 10101010)|SOFD (10101011)| PLOAD_SIZE_TX | HEADER + +-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+ -------- + | WOUF_COMMAND | TID | | + +-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+ | + | WOU_PAYLOAD | + | Byte[6] to Byte[6+PLOAD_SIZE_TX] | PAYLOAD + | | + | +-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+ + | | CRC-16 | + +-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+ -------- + +WOU Frame (RX) (for MAILBOX messages) +===================================== + 0 1 2 3 + 0 1 2 3 4 5 6 7 8 9 0 1 2 3 4 5 6 7 8 9 0 1 2 3 4 5 6 7 8 9 0 1 + +-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+ -------- + |Preamble (2 octets of 10101010)|SOFD (10101011)| PLOAD_SIZE_TX | HEADER + +-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+ -------- + | WOUF_COMMAND | MAIL_TAG | | + +-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+ -------- + | BP_TICK | | + +-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+ | + | MAIL_PAYLOAD | + | Byte[10] to Byte[10+PLOAD_SIZE_TX] | PAYLOAD + | | + | +-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+ + | | CRC-16 | + +-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+ -------- + +WOU Frame (TX - REALTIME) +========================= + 0 1 2 3 + 0 1 2 3 4 5 6 7 8 9 0 1 2 3 4 5 6 7 8 9 0 1 2 3 4 5 6 7 8 9 0 1 + +-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+ -------- + |Preamble (2 octets of 10101010)|SOFD (10101011)| PLOAD_SIZE_TX | HEADER + +-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+ -------- + | WOUF_COMMAND | PLOAD_SIZE_RX | | + +-+-+-+-+-+-+-+-+- - - - - - - - | + | WOU_PAYLOAD | + | Byte[5] to Byte[5+PLOAD_SIZE_TX] | PAYLOAD + | | + | +-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+ + | | CRC-16 | + +-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+ -------- + +WOU Frame (RX - REALTIME) +========================= + 0 1 2 3 + 0 1 2 3 4 5 6 7 8 9 0 1 2 3 4 5 6 7 8 9 0 1 2 3 4 5 6 7 8 9 0 1 + +-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+ -------- + |Preamble (2 octets of 10101010)|SOFD (10101011)| PLOAD_SIZE_TX | HEADER + +-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+ -------- + | WOUF_COMMAND | | + +-+-+-+-+-+-+-+-+ | + | WOU_PAYLOAD | + | Byte[5] to Byte[5+PLOAD_SIZE_TX] | PAYLOAD + | | + | +-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+ + | | CRC-16 | + +-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+ -------- + +WOU packet Format +=================== + (WOU_PAYLOAD is composed of multiple WOU packets) + 0 1 2 3 + 0 1 2 3 4 5 6 7 8 9 0 1 2 3 4 5 6 7 8 9 0 1 2 3 4 5 6 7 8 9 0 1 + +-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+ -------- + |F| DATA_SIZE | WB_ADDR | | HEADER + +-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+ | -------- + | | DATA + | DATA | + | Byte[4] to Byte[4+DATA_SIZE] | + | | + | +-+-+-+-+-+-+-+-+-+-+-+-+-+ + | | + +-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+-+ + FUNCTION(F): + 0: READ from wishbone + 1: WRITE to wishbone + DATA_SIZE[6:0]: + support up to 128bytes of burst access + 1(7'h01) ~ 128(7'h00) bytes + WB_ADDR[15:0]: WishBone Address; little endian + WB Addressing Mode: Automatic Increment mode + the WB_ADDR increments by one for each DATA byte + +HOST: + + send [WOU_FRAME] messages, then recv [WOU_FRAME] messages if any + + TODO: HOST.Tx thread: send [WOU_FRAME] messages + + TODO: HOST.Rx thread: recv [WOU_FRAME] messages From 8f302fa845b3becd5cfa43444933530c0f9d7dae Mon Sep 17 00:00:00 2001 From: Yishin Li Date: Mon, 18 Feb 2013 09:11:30 +0800 Subject: [PATCH 004/256] Add blender.comp: blend requested motion with joint command --- src/hal/components/blender.comp | 128 ++++++++++++++++++++++++++++++++ 1 file changed, 128 insertions(+) create mode 100644 src/hal/components/blender.comp diff --git a/src/hal/components/blender.comp b/src/hal/components/blender.comp new file mode 100644 index 000000000..f555014b2 --- /dev/null +++ b/src/hal/components/blender.comp @@ -0,0 +1,128 @@ +component blender "Blend requested motion with joint command"; + +description +""" + +TODO + +"""; + +author "Yishin Li"; + +license "GPLv2 or greater"; + +// Input Pins +pin in float motor_pos_cmd_i "Motor Position Command In"; +pin io bit enable "Enable the blender, if not enabled motor-pos-cmd is passed through"; +pin in u32 nu_of_cmd "Number of distance commands to blend for"; +pin in float vel_req_0 "Request velocity for dist-0"; +pin in float pos_cmd_0 "Position command 0"; +pin in float vel_req_1 "Request velocity for dist-1"; +pin in float pos_cmd_1 "Postion command 1"; + +// Output Pins +pin out float motor_pos_cmd_o "Motor Position Command Out"; +pin out bit blending_o "Set to 1 while blending"; + +// Parameters +param rw float max_vel "Max velocity"; +param rw float max_acc "Max acceleration"; +param rw float max_jerk "Max jerk"; + +function _; + +;; + +#include "rtapi_math.h" + +FUNCTION(_) +{ + double max_dv, tiny_dp, pos_err, vel_req, pos_cmd, vel_limit; + static unsigned int pos_cmd_id; + static double curr_pos, curr_vel; + + max_dv = max_acc; + tiny_dp = max_jerk; + if (!enable) + { + pos_cmd_id = 0; + curr_pos = 0; + curr_vel = 0; + motor_pos_cmd_o = motor_pos_cmd_i; + blending_o = 0; + } else if (pos_cmd_id < nu_of_cmd) + { + /* calculate desired velocity */ + + if (pos_cmd_id == 0) + { + if (vel_req_0 > max_vel) + { + vel_limit = max_vel; + } else + { + vel_limit = vel_req_0; + } + pos_cmd = pos_cmd_0; + } else + { + if (vel_req_1 > max_vel) + { + vel_limit = max_vel; + } else + { + vel_limit = vel_req_1; + } + pos_cmd = pos_cmd_1; + } + + /* planner enabled, request a velocity that tends to drive + pos_err to zero, but allows for stopping without position + overshoot */ + pos_err = pos_cmd - curr_pos; + + /* positive and negative errors require some sign flipping to + avoid sqrt(negative) */ + if (pos_err > tiny_dp) { + vel_req = -max_dv + + sqrt(2.0 * max_dv * pos_err + max_dv * max_dv); + } else if (pos_err < -tiny_dp) { + vel_req = max_dv - + sqrt(-2.0 * max_dv * pos_err + max_dv * max_dv); + } else { + /* within 'tiny_dp' of desired pos, no need to move */ + vel_req = pos_err; + enable = 0; + } + + /* limit velocity request */ + if (vel_req > vel_limit) { + vel_req = vel_limit; + } else if (vel_req < -vel_limit) { + vel_req = -vel_limit; + } + + /* ramp velocity toward request at accel limit */ + if (vel_req > (curr_vel + max_dv)) { + curr_vel += max_dv; + } else if (vel_req < (curr_vel - max_dv)) { + curr_vel -= max_dv; + } else { + curr_vel = vel_req; + } + + /* integrate velocity to get new position */ + curr_pos += curr_vel; + + motor_pos_cmd_o = motor_pos_cmd_i + curr_vel; + blending_o = 1; + + if (!enable) { + pos_cmd_id += 1; + if (pos_cmd_id < nu_of_cmd) { + enable = 1; + } + } + } +} + From baf0136dafb660d663cc63ca50a33bb0a5e3fd7d Mon Sep 17 00:00:00 2001 From: WH Zheng Date: Fri, 22 Feb 2013 15:53:58 +0800 Subject: [PATCH 005/256] add blender_offset --- src/emc/motion/control.c | 9 ++--- src/emc/motion/mot_priv.h | 1 + src/emc/motion/motion.c | 2 ++ src/emc/motion/motion.h | 3 +- src/hal/components/blender.comp | 64 +++++++++++++++++---------------- 5 files changed, 43 insertions(+), 36 deletions(-) diff --git a/src/emc/motion/control.c b/src/emc/motion/control.c index 3f9afb44c..4285e823d 100644 --- a/src/emc/motion/control.c +++ b/src/emc/motion/control.c @@ -471,6 +471,7 @@ static void process_inputs(void) joint->pos_fb = joint->motor_pos_fb - (joint->backlash_filt + joint->motor_offset); joint->risc_pos_cmd = *(joint_data->risc_pos_cmd); + joint->blender_offset = *(joint_data->blender_offset); /* calculate following error */ joint->ferror = joint->pos_cmd - joint->pos_fb; @@ -730,7 +731,7 @@ static void process_probe_inputs(void) for (joint_num = 0; joint_num < emcmotConfig->numJoints; joint_num++) { joint = &joints[joint_num]; - joint_pos[joint_num] = joint->probed_pos - (joint->backlash_filt + joint->motor_offset); + joint_pos[joint_num] = joint->probed_pos - (joint->backlash_filt + joint->motor_offset + joint->blender_offset); } kinematicsForward(joint_pos, &emcmotStatus->probedPos, &fflags, &iflags); } else @@ -825,7 +826,7 @@ static void handle_special_cmd(void) /* point to joint struct */ joint = &joints[joint_num]; /* copy risc_pos_cmd feedback */ - joint->pos_cmd = joint->risc_pos_cmd - joint->backlash_filt - joint->motor_offset; + joint->pos_cmd = joint->risc_pos_cmd - joint->backlash_filt - joint->motor_offset - joint->blender_offset; joint->coarse_pos = joint->pos_cmd; joint->free_tp.curr_pos = joint->pos_cmd; /* to reset cubic parameters */ @@ -2095,13 +2096,13 @@ static void output_to_hal(void) joint = &joints[joint_num]; /* apply backlash and motor offset to output */ joint->motor_pos_cmd = - joint->pos_cmd + joint->backlash_filt + joint->motor_offset; + joint->pos_cmd + joint->backlash_filt + joint->motor_offset + joint->blender_offset; /* point to HAL data */ joint_data = &(emcmot_hal_data->joint[joint_num]); /* write to HAL pins */ *(joint_data->motor_offset) = joint->motor_offset; *(joint_data->motor_pos_cmd) = joint->motor_pos_cmd; - *(joint_data->joint_pos_cmd) = joint->pos_cmd; + *(joint_data->joint_pos_cmd) = joint->pos_cmd - joint->blender_offset; *(joint_data->joint_pos_fb) = joint->pos_fb; *(joint_data->amp_enable) = GET_JOINT_ENABLE_FLAG(joint); *(joint_data->index_enable) = joint->index_enable; diff --git a/src/emc/motion/mot_priv.h b/src/emc/motion/mot_priv.h index 5ea353621..86c5b29b4 100644 --- a/src/emc/motion/mot_priv.h +++ b/src/emc/motion/mot_priv.h @@ -83,6 +83,7 @@ typedef struct { hal_s32_t *risc_probe_pin; /* OUT */ hal_s32_t *risc_probe_type; /* OUT */ hal_s32_t *home_sw_id; /* IN */ + hal_float_t *blender_offset; } joint_hal_t; diff --git a/src/emc/motion/motion.c b/src/emc/motion/motion.c index d8db91e39..8051f3453 100644 --- a/src/emc/motion/motion.c +++ b/src/emc/motion/motion.c @@ -551,6 +551,7 @@ static int export_joint(int num, joint_hal_t * addr) if ((retval = hal_pin_float_newf(HAL_OUT, &(addr->motor_pos_cmd), mot_comp_id, "joint.%d.motor-pos-cmd", num)) != 0) return retval; if ((retval = hal_pin_float_newf(HAL_IN, &(addr->motor_pos_fb), mot_comp_id, "joint.%d.motor-pos-fb", num)) != 0) return retval; if ((retval = hal_pin_float_newf(HAL_OUT, &(addr->motor_offset), mot_comp_id, "joint.%d.motor-offset", num)) != 0) return retval; + if ((retval = hal_pin_float_newf(HAL_IN, &(addr->blender_offset), mot_comp_id, "joint.%d.blender-offset", num)) != 0) return retval; if ((retval = hal_pin_bit_newf(HAL_IN, &(addr->pos_lim_sw), mot_comp_id, "joint.%d.pos-lim-sw-in", num)) != 0) return retval; if ((retval = hal_pin_bit_newf(HAL_IN, &(addr->neg_lim_sw), mot_comp_id, "joint.%d.neg-lim-sw-in", num)) != 0) return retval; if ((retval = hal_pin_bit_newf(HAL_IN, &(addr->home_sw), mot_comp_id, "joint.%d.home-sw-in", num)) != 0) return retval; @@ -762,6 +763,7 @@ static int init_comm_buffers(void) joint->backlash_corr = 0.0; joint->backlash_filt = 0.0; joint->backlash_vel = 0.0; + joint->blender_offset = 0.0; joint->motor_pos_cmd = 0.0; joint->motor_pos_fb = 0.0; joint->pos_fb = 0.0; diff --git a/src/emc/motion/motion.h b/src/emc/motion/motion.h index 2af900783..38d2b10b4 100644 --- a/src/emc/motion/motion.h +++ b/src/emc/motion/motion.h @@ -552,7 +552,8 @@ typedef struct { home_state_t home_state; /* state machine for homing */ double index_pos; /* motor index position in absolute motor pulse counts */ double motor_offset; /* diff between internal and motor pos, used - to set position to zero during homing */ + to set position to zero during homing */ + double blender_offset; /* offset created by realtime component, blender.comp */ int old_jog_counts; /* prior value, used for deltas */ double probed_pos; diff --git a/src/hal/components/blender.comp b/src/hal/components/blender.comp index f555014b2..9834650f1 100644 --- a/src/hal/components/blender.comp +++ b/src/hal/components/blender.comp @@ -12,16 +12,16 @@ author "Yishin Li"; license "GPLv2 or greater"; // Input Pins -pin in float motor_pos_cmd_i "Motor Position Command In"; -pin io bit enable "Enable the blender, if not enabled motor-pos-cmd is passed through"; +pin in bit enable "Enable the blender if not enabled motor-pos-cmd is passed through"; pin in u32 nu_of_cmd "Number of distance commands to blend for"; pin in float vel_req_0 "Request velocity for dist-0"; pin in float pos_cmd_0 "Position command 0"; pin in float vel_req_1 "Request velocity for dist-1"; -pin in float pos_cmd_1 "Postion command 1"; +pin in float pos_cmd_1 "Position command 1"; +pin in u32 pos_cmd_id "0:up and down, 1:only down"; // Output Pins -pin out float motor_pos_cmd_o "Motor Position Command Out"; +pin out float offset_o "Motor Position Command Out"; pin out bit blending_o "Set to 1 while blending"; // Parameters @@ -32,29 +32,32 @@ param rw float max_jerk "Max jerk"; function _; ;; +#include #include "rtapi_math.h" FUNCTION(_) { double max_dv, tiny_dp, pos_err, vel_req, pos_cmd, vel_limit; - static unsigned int pos_cmd_id; - static double curr_pos, curr_vel; - - max_dv = max_acc; - tiny_dp = max_jerk; - if (!enable) + static unsigned int _cmd_id; + static double curr_pos, curr_vel, p; + static double offset = 0; + p = 0.000655; + max_dv = max_acc * p; + tiny_dp = max_dv * p * 0.001; + if (!enable) { - pos_cmd_id = 0; + _cmd_id = pos_cmd_id; + //pos_cmd_id = 0; curr_pos = 0; curr_vel = 0; - motor_pos_cmd_o = motor_pos_cmd_i; blending_o = 0; - } else if (pos_cmd_id < nu_of_cmd) + } else if (enable && _cmd_id < nu_of_cmd) { + blending_o = 1; /* calculate desired velocity */ - if (pos_cmd_id == 0) + if (_cmd_id == 0) { if (vel_req_0 > max_vel) { @@ -63,7 +66,7 @@ FUNCTION(_) { vel_limit = vel_req_0; } - pos_cmd = pos_cmd_0; + pos_cmd = pos_cmd_0; // h2-dist } else { if (vel_req_1 > max_vel) @@ -73,36 +76,35 @@ FUNCTION(_) { vel_limit = vel_req_1; } - pos_cmd = pos_cmd_1; + pos_cmd = pos_cmd_1; // h3-dist } /* planner enabled, request a velocity that tends to drive pos_err to zero, but allows for stopping without position overshoot */ pos_err = pos_cmd - curr_pos; - /* positive and negative errors require some sign flipping to avoid sqrt(negative) */ if (pos_err > tiny_dp) { vel_req = -max_dv + - sqrt(2.0 * max_dv * pos_err + max_dv * max_dv); + sqrt(2.0 * max_acc * pos_err + max_dv * max_dv); } else if (pos_err < -tiny_dp) { vel_req = max_dv - - sqrt(-2.0 * max_dv * pos_err + max_dv * max_dv); + sqrt(-2.0 * max_acc * pos_err + max_dv * max_dv); } else { /* within 'tiny_dp' of desired pos, no need to move */ vel_req = pos_err; - enable = 0; + blending_o = 0; } - /* limit velocity request */ if (vel_req > vel_limit) { vel_req = vel_limit; } else if (vel_req < -vel_limit) { vel_req = -vel_limit; } - + /* ramp velocity toward request at accel limit */ + if (vel_req > (curr_vel + max_dv)) { curr_vel += max_dv; } else if (vel_req < (curr_vel - max_dv)) { @@ -110,19 +112,19 @@ FUNCTION(_) } else { curr_vel = vel_req; } - + /* integrate velocity to get new position */ - curr_pos += curr_vel; - - motor_pos_cmd_o = motor_pos_cmd_i + curr_vel; - blending_o = 1; + curr_pos += curr_vel*p; + offset += (curr_vel*p); + - if (!enable) { - pos_cmd_id += 1; - if (pos_cmd_id < nu_of_cmd) { - enable = 1; + if (!blending_o) { + _cmd_id += 1; + if (_cmd_id < nu_of_cmd) { + blending_o = 1; } } } + offset_o = offset; } From accd701d7d334c672ae986dcad62b04821b2ca69 Mon Sep 17 00:00:00 2001 From: WH Zheng Date: Mon, 25 Feb 2013 10:37:40 +0800 Subject: [PATCH 006/256] cleanup code --- src/emc/motion/control.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/emc/motion/control.c b/src/emc/motion/control.c index 4285e823d..496212d12 100644 --- a/src/emc/motion/control.c +++ b/src/emc/motion/control.c @@ -2102,7 +2102,7 @@ static void output_to_hal(void) /* write to HAL pins */ *(joint_data->motor_offset) = joint->motor_offset; *(joint_data->motor_pos_cmd) = joint->motor_pos_cmd; - *(joint_data->joint_pos_cmd) = joint->pos_cmd - joint->blender_offset; + *(joint_data->joint_pos_cmd) = joint->pos_cmd; *(joint_data->joint_pos_fb) = joint->pos_fb; *(joint_data->amp_enable) = GET_JOINT_ENABLE_FLAG(joint); *(joint_data->index_enable) = joint->index_enable; From 5f0068be9e8330bd7aa598b009da87f1d5569c7d Mon Sep 17 00:00:00 2001 From: WH Zheng Date: Mon, 25 Feb 2013 17:35:32 +0800 Subject: [PATCH 007/256] BUGFIX for h3_dist error *the second dist will set curr_pos = 0 --- src/hal/components/blender.comp | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/src/hal/components/blender.comp b/src/hal/components/blender.comp index 9834650f1..13a4f99f3 100644 --- a/src/hal/components/blender.comp +++ b/src/hal/components/blender.comp @@ -48,7 +48,6 @@ FUNCTION(_) if (!enable) { _cmd_id = pos_cmd_id; - //pos_cmd_id = 0; curr_pos = 0; curr_vel = 0; blending_o = 0; @@ -94,6 +93,7 @@ FUNCTION(_) } else { /* within 'tiny_dp' of desired pos, no need to move */ vel_req = pos_err; + curr_pos = 0; blending_o = 0; } /* limit velocity request */ @@ -117,7 +117,6 @@ FUNCTION(_) curr_pos += curr_vel*p; offset += (curr_vel*p); - if (!blending_o) { _cmd_id += 1; if (_cmd_id < nu_of_cmd) { From 649e85723474e5f8ffbb4b46af2f4d46eb59657c Mon Sep 17 00:00:00 2001 From: Yishin Li Date: Wed, 27 Feb 2013 16:11:41 +0800 Subject: [PATCH 008/256] Update INI and HAL configs for miller machine --- configs/araisrobo/miller/miller.hal | 151 +++++++++++++++++----------- configs/araisrobo/miller/miller.ini | 64 +++++++++--- 2 files changed, 142 insertions(+), 73 deletions(-) diff --git a/configs/araisrobo/miller/miller.hal b/configs/araisrobo/miller/miller.hal index 9e4e04e10..23b6fc4fa 100644 --- a/configs/araisrobo/miller/miller.hal +++ b/configs/araisrobo/miller/miller.hal @@ -5,10 +5,9 @@ loadrt ddt count=3 loadrt hypot count=2 # load RT modules - loadrt [KINS]KINEMATICS loadrt [EMCMOT]EMCMOT servo_period_nsec=[EMCMOT]SERVO_PERIOD traj_period_nsec=[EMCMOT]TRAJ_PERIOD num_joints=[KINS]JOINTS num_dio=64 -loadrt [WOU](WISHBONE) ctrl_type=[WOU](CTRL_TYPE) pulse_type=[WOU]PULSE_TYPE enc_type=[WOU]ENC_TYPE bits=[WOU](FPGA) bins=[WOU](RISC) servo_period_ns=[EMCMOT]SERVO_PERIOD alarm_en=[WOU]ALARM_EN max_vel_str=[JOINT_0]MAX_VELOCITY,[JOINT_1]MAX_VELOCITY,[JOINT_2]MAX_VELOCITY max_accel_str=[JOINT_0]MAX_ACCELERATION,[JOINT_1]MAX_ACCELERATION,[JOINT_2]MAX_ACCELERATION max_jerk_str=[JOINT_0]MAX_JERK,[JOINT_1]MAX_JERK,[JOINT_2]MAX_JERK pos_scale_str=[JOINT_0]INPUT_SCALE,[JOINT_1]INPUT_SCALE,[JOINT_2]INPUT_SCALE alr_output=[WOU](ALR_OUTPUT) +loadrt [WOU](WISHBONE) ctrl_type=[WOU](CTRL_TYPE) pulse_type=[WOU]PULSE_TYPE enc_type=[WOU]ENC_TYPE bits=[WOU](FPGA) bins=[WOU](RISC) servo_period_ns=[EMCMOT]SERVO_PERIOD alarm_en=[WOU]ALARM_EN max_vel_str=[JOINT_0]MAX_VELOCITY,[JOINT_1]MAX_VELOCITY,[JOINT_2]MAX_VELOCITY,[JOINT_3]MAX_VELOCITY max_accel_str=[JOINT_0]MAX_ACCELERATION,[JOINT_1]MAX_ACCELERATION,[JOINT_2]MAX_ACCELERATION,[JOINT_3]MAX_ACCELERATION max_jerk_str=[JOINT_0]MAX_JERK,[JOINT_1]MAX_JERK,[JOINT_2]MAX_JERK,[JOINT_3]MAX_JERK pos_scale_str=[JOINT_0]INPUT_SCALE,[JOINT_1]INPUT_SCALE,[JOINT_2]INPUT_SCALE,[JOINT_3]INPUT_SCALE alr_output=[WOU](ALR_OUTPUT) # add motion controller functions to servo thread addf motion-command-handler servo-thread @@ -43,130 +42,115 @@ net usb-cmd wou.usb.cmd <= motion.usb.cmd net usb-cmd-param0 wou.usb.param-00 <= motion.usb.param-00 net usb-cmd-param1 wou.usb.param-01 <= motion.usb.param-01 net usb-cmd-param2 wou.usb.param-02 <= motion.usb.param-02 +net usb-cmd-param3 wou.usb.param-03 <= motion.usb.param-03 + net usb-stauts wou.motion.status => motion.wou.status net motionState motion.motion-state => wou.motion-state -# TODO: remove align-pos-cmd -net align-cmd wou.align-pos-cmd <=> motion.align-pos-cmd +net Xpos joint.0.motor-pos-cmd => wou.stepgen.0.position-cmd +net Ypos joint.1.motor-pos-cmd => wou.stepgen.1.position-cmd +net Zpos joint.2.motor-pos-cmd => wou.stepgen.2.position-cmd +net Spos joint.3.motor-pos-cmd => wou.stepgen.3.position-cmd -net Xpos joint.0.motor-pos-cmd => wou.stepgen.0.position-cmd # joint.0.motor-pos-fb -net Ypos joint.1.motor-pos-cmd => wou.stepgen.1.position-cmd # joint.1.motor-pos-fb -net Zpos joint.2.motor-pos-cmd => wou.stepgen.2.position-cmd # joint.2.motor-pos-fb # loop position commands back to motion module feedback # for OPEN_LOOP net Xpos-fb wou.stepgen.0.position-fb => joint.0.motor-pos-fb net Ypos-fb wou.stepgen.1.position-fb => joint.1.motor-pos-fb net Zpos-fb wou.stepgen.2.position-fb => joint.2.motor-pos-fb - -net Xvel-fb wou.stepgen.0.vel-fb -net Yvel-fb wou.stepgen.1.vel-fb -net Zvel-fb wou.stepgen.2.vel-fb +net Spos-fb wou.stepgen.3.position-fb => joint.3.motor-pos-fb # motor_index positions net J0_index-pos wou.stepgen.0.index-pos => joint.0.index-pos net J1_index-pos wou.stepgen.1.index-pos => joint.1.index-pos net J2_index-pos wou.stepgen.2.index-pos => joint.2.index-pos +net J3_index-pos wou.stepgen.3.index-pos => joint.3.index-pos # estop loopback # net estop-loop iocontrol.0.user-enable-out iocontrol.0.emc-enable-in -net estop-loop iocontrol.0.emc-enable-in <= wou.gpio.in.00 +net din_00 => iocontrol.0.emc-enable-in # create signals for tool loading loopback net tool-prep-loop iocontrol.0.tool-prepare iocontrol.0.tool-prepared net tool-change-loop iocontrol.0.tool-change iocontrol.0.tool-changed -# connect sync in signal -# net sync_in_trigger motion.sync-in-trigger => wou.sync.in.trigger -# net sync_in_index motion.sync-in-index => wou.sync.in.index -# net sync_in_wait_type motion.sync-in-wait-type => wou.sync.in.wait_type -# net sync_in_timeout motion.sync-in-timeout => wou.sync.in.timeout - - +# digital sync I/O signals +net sync_in_trigger motion.sync-in-trigger => wou.sync.in.trigger +net sync_in_index motion.sync-in-index => wou.sync.in.index +net sync_in_wait_type motion.sync-in-wait-type => wou.sync.in.wait_type +net sync_in_timeout motion.sync-in-timeout => wou.sync.in.timeout # amp control -net xena joint.0.amp-enable-out => wou.stepgen.0.enable -net yena joint.1.amp-enable-out => wou.stepgen.1.enable -net zena joint.2.amp-enable-out => wou.stepgen.2.enable - +net din_00 => motion.enable +net j0ena joint.0.amp-enable-out => wou.stepgen.0.enable +net j1ena joint.1.amp-enable-out => wou.stepgen.1.enable +net j2ena joint.2.amp-enable-out => wou.stepgen.2.enable +net j3ena joint.3.amp-enable-out => wou.stepgen.3.enable setp wou.stepgen.0.steplen [JOINT_0]STEPLEN setp wou.stepgen.1.steplen [JOINT_1]STEPLEN setp wou.stepgen.2.steplen [JOINT_2]STEPLEN +setp wou.stepgen.3.steplen [JOINT_3]STEPLEN +# TODO: connect wou.rt.abort to GPIO setp wou.rt.abort 0 # connect signals from FPGA. # pulse_pos: the actual pulse sent to servo drive. -net pulse_cmd_j0 <= wou.stepgen.0.pulse_pos -net pulse_cmd_j1 <= wou.stepgen.1.pulse_pos -net pulse_cmd_j2 <= wou.stepgen.2.pulse_pos -# enc_pos: the encoder position read from FPGA. +net pulse_pos_j0 <= wou.stepgen.0.pulse_pos +net pulse_pos_j1 <= wou.stepgen.1.pulse_pos +net pulse_pos_j2 <= wou.stepgen.2.pulse_pos +net pulse_pos_j3 <= wou.stepgen.3.pulse_pos +# enc_pos: the encoder position read from FPGA. net enc_pos_j0 <= wou.stepgen.0.enc_pos net enc_pos_j1 <= wou.stepgen.1.enc_pos net enc_pos_j2 <= wou.stepgen.2.enc_pos +net enc_pos_j3 <= wou.stepgen.3.enc_pos # pass vel status and req_status to FPGA -# obsolete: net current_vel motion.current-vel => wou.current-vel -# obsolete: net requested_vel motion.requested-vel => wou.requested-vel - - -net sync_in_trigger => wou.sync.in.trigger -net sync_in_index => wou.sync.in.index -net sync_in_wait_type => wou.sync.in.wait_type -net sync_in_timeout => wou.sync.in.timeout - -# to CL: net alarm <= wou.gpio.in.00 -# to CL: net alarm => joint.0.amp-fault-in -# to CL: net alarm => joint.1.amp-fault-in -# to CL: net alarm => joint.2.amp-fault-in -# to CL: net alarm => joint.3.amp-fault-in -# net servo_ready <= wou.gpio.in.01 - - # set wou module scaling - get values from ini file setp wou.stepgen.0.position-scale [JOINT_0]INPUT_SCALE setp wou.stepgen.1.position-scale [JOINT_1]INPUT_SCALE setp wou.stepgen.2.position-scale [JOINT_2]INPUT_SCALE +setp wou.stepgen.3.position-scale [JOINT_3]INPUT_SCALE # set wou module pulse_per_rev - get values from ini file setp wou.stepgen.0.pulse_per_rev [JOINT_0]PULSE_PER_REV setp wou.stepgen.1.pulse_per_rev [JOINT_1]PULSE_PER_REV setp wou.stepgen.2.pulse_per_rev [JOINT_2]PULSE_PER_REV +setp wou.stepgen.3.pulse_per_rev [JOINT_3]PULSE_PER_REV # set wou module velocity limits - get values from ini file setp wou.stepgen.0.maxvel [JOINT_0]MAX_VELOCITY setp wou.stepgen.1.maxvel [JOINT_1]MAX_VELOCITY setp wou.stepgen.2.maxvel [JOINT_2]MAX_VELOCITY +setp wou.stepgen.3.maxvel [JOINT_3]MAX_VELOCITY # set wou module accel limits - get values from ini file setp wou.stepgen.0.maxaccel [JOINT_0]MAX_ACCELERATION setp wou.stepgen.1.maxaccel [JOINT_1]MAX_ACCELERATION setp wou.stepgen.2.maxaccel [JOINT_2]MAX_ACCELERATION +setp wou.stepgen.3.maxaccel [JOINT_3]MAX_ACCELERATION +net j0_ferror_flag wou.stepgen.0.ferror-flag => joint.0.usb-ferror-flag +net j1_ferror_flag wou.stepgen.1.ferror-flag => joint.1.usb-ferror-flag +net j2_ferror_flag wou.stepgen.2.ferror-flag => joint.2.usb-ferror-flag +net j3_ferror_flag wou.stepgen.3.ferror-flag => joint.3.usb-ferror-flag +net j0-probed-pos wou.stepgen.0.probed-pos => joint.0.probed-pos +net j1-probed-pos wou.stepgen.1.probed-pos => joint.1.probed-pos +net j2-probed-pos wou.stepgen.2.probed-pos => joint.2.probed-pos +net j3-probed-pos wou.stepgen.3.probed-pos => joint.3.probed-pos - -net X_ferror_flag wou.stepgen.0.ferror-flag => joint.0.usb-ferror-flag -net Y_ferror_flag wou.stepgen.1.ferror-flag => joint.1.usb-ferror-flag -net Z_ferror_flag wou.stepgen.2.ferror-flag => joint.2.usb-ferror-flag - -net x-probed-pos wou.stepgen.0.probed-pos => joint.0.probed-pos -net y-probed-pos wou.stepgen.1.probed-pos => joint.1.probed-pos -net z-probed-pos wou.stepgen.2.probed-pos => joint.2.probed-pos net vel-sync wou.motion.vel-sync - -# for sync command for risc jogging -# when program is not running or is not jogging (application should disable risc jogging as -# well), make wou to sync pos-cmd and prev-pos-cmd -# net ignore-host-cmd wou.ignore-host-cmd net usb-busy wou.usb-busy => motion.usb-busy # loop position commands back to motion module feedback net J0-risc-pos-cmd wou.stepgen.0.risc-pos-cmd => joint.0.risc-pos-cmd net J1-risc-pos-cmd wou.stepgen.1.risc-pos-cmd => joint.1.risc-pos-cmd net J2-risc-pos-cmd wou.stepgen.2.risc-pos-cmd => joint.2.risc-pos-cmd +net J3-risc-pos-cmd wou.stepgen.3.risc-pos-cmd => joint.3.risc-pos-cmd # for usb-homing: # original homing switchs: @@ -184,29 +168,34 @@ setp joint.1.home-sw-id 6 # use LSP as homing switch for AXIS-Z: setp joint.2.home-sw-id 9 # home switch status from FPGA -net home_j0 joint.0.home-sw-in <= wou.gpio.in.04 -net home_j1 joint.1.home-sw-in <= wou.gpio.in.06 -net home_j2 joint.2.home-sw-in <= wou.gpio.in.09 +net din_04 joint.0.home-sw-in +net din_06 joint.1.home-sw-in +net din_09 joint.2.home-sw-in net j0-homing joint.0.homing => wou.stepgen.0.homing net j1-homing joint.1.homing => wou.stepgen.1.homing net j2-homing joint.2.homing => wou.stepgen.2.homing +net j3-homing joint.3.homing => wou.stepgen.3.homing net j0-risc-probe-vel joint.0.risc-probe-vel => wou.stepgen.0.risc-probe-vel net j1-risc-probe-vel joint.1.risc-probe-vel => wou.stepgen.1.risc-probe-vel net j2-risc-probe-vel joint.2.risc-probe-vel => wou.stepgen.2.risc-probe-vel +net j3-risc-probe-vel joint.3.risc-probe-vel => wou.stepgen.3.risc-probe-vel net j0-risc-probe-pin joint.0.risc-probe-pin => wou.stepgen.0.risc-probe-pin net j1-risc-probe-pin joint.1.risc-probe-pin => wou.stepgen.1.risc-probe-pin net j2-risc-probe-pin joint.2.risc-probe-pin => wou.stepgen.2.risc-probe-pin +net j3-risc-probe-pin joint.3.risc-probe-pin => wou.stepgen.3.risc-probe-pin net j0-risc-probe-type joint.0.risc-probe-type => wou.stepgen.0.risc-probe-type net j1-risc-probe-type joint.1.risc-probe-type => wou.stepgen.1.risc-probe-type net j2-risc-probe-type joint.2.risc-probe-type => wou.stepgen.2.risc-probe-type +net j3-risc-probe-type joint.3.risc-probe-type => wou.stepgen.3.risc-probe-type net j0-risc-probe-dist joint.0.risc-probe-dist => wou.stepgen.0.risc-probe-dist net j1-risc-probe-dist joint.1.risc-probe-dist => wou.stepgen.1.risc-probe-dist net j2-risc-probe-dist joint.2.risc-probe-dist => wou.stepgen.2.risc-probe-dist +net j3-risc-probe-dist joint.3.risc-probe-dist => wou.stepgen.3.risc-probe-dist # RISC_CMD REQ and ACK net update-pos-req wou.motion.update-pos-req => motion.update-pos-req @@ -220,3 +209,45 @@ net coord_mode wou.motion.coord-mode <= motion.coord-mode net homing wou.motion.homing <= motion.homing net probe_result wou.motion.probe-result => motion.probe-input net machine_is_moving <= wou.motion.machine-is-moving + +# mapping wou.gpio to motion.synch_di[] +net din_00 wou.gpio.in.00 => motion.digital-in-00 +net din_01 wou.gpio.in.01 => motion.digital-in-01 +net din_02 wou.gpio.in.02 => motion.digital-in-02 +net din_03 wou.gpio.in.03 => motion.digital-in-03 +net din_04 wou.gpio.in.04 => motion.digital-in-04 +net din_05 wou.gpio.in.05 => motion.digital-in-05 +net din_06 wou.gpio.in.06 => motion.digital-in-06 +net din_07 wou.gpio.in.07 => motion.digital-in-07 +net din_08 wou.gpio.in.08 => motion.digital-in-08 +net din_09 wou.gpio.in.09 => motion.digital-in-09 +net din_10 wou.gpio.in.10 => motion.digital-in-10 +net din_11 wou.gpio.in.11 => motion.digital-in-11 +net din_12 wou.gpio.in.12 => motion.digital-in-12 +net din_13 wou.gpio.in.13 => motion.digital-in-13 +net din_14 wou.gpio.in.14 => motion.digital-in-14 +net din_15 wou.gpio.in.15 => motion.digital-in-15 +net din_16 wou.gpio.in.16 => motion.digital-in-16 +net din_17 wou.gpio.in.17 => motion.digital-in-17 +net din_18 wou.gpio.in.18 => motion.digital-in-18 +net din_19 wou.gpio.in.19 => motion.digital-in-19 +net din_20 wou.gpio.in.20 => motion.digital-in-20 +net din_21 wou.gpio.in.21 => motion.digital-in-21 +net din_22 wou.gpio.in.22 => motion.digital-in-22 +net din_23 wou.gpio.in.23 => motion.digital-in-23 +net din_24 wou.gpio.in.24 => motion.digital-in-24 +net din_25 wou.gpio.in.25 => motion.digital-in-25 +net din_26 wou.gpio.in.26 => motion.digital-in-26 +net din_27 wou.gpio.in.27 => motion.digital-in-27 +net din_28 wou.gpio.in.28 => motion.digital-in-28 +net din_29 wou.gpio.in.29 => motion.digital-in-29 +net din_30 wou.gpio.in.30 => motion.digital-in-30 +net din_31 wou.gpio.in.31 => motion.digital-in-31 + +net j0_index_en joint.0.index-enable => wou.stepgen.0.index-enable +net j1_index_en joint.1.index-enable => wou.stepgen.1.index-enable +net j2_index_en joint.2.index-enable => wou.stepgen.2.index-enable +net j3_index_en joint.3.index-enable => wou.stepgen.3.index-enable + +# emcrsh +# loadusr linuxcncrsh -ini xyz.ini diff --git a/configs/araisrobo/miller/miller.ini b/configs/araisrobo/miller/miller.ini index d7b5bfc51..2119502f7 100644 --- a/configs/araisrobo/miller/miller.ini +++ b/configs/araisrobo/miller/miller.ini @@ -109,9 +109,9 @@ HALUI = halui # Trajectory planner section -------------------------------------------------- [TRAJ] -AXES = 3 -COORDINATES = X Y Z -HOME = 0 0 0 +AXES = 4 +COORDINATES = X Y Z S +HOME = 0 0 0 0 LINEAR_UNITS = mm ANGULAR_UNITS = degree @@ -124,9 +124,6 @@ ANGULAR_UNITS = degree #orig: MAX_ANGULAR_VELOCITY = 100 #orig: MAX_ANGULAR_ACCEL = 800 -# DEFAULT_LINEAR_VELOCITY = 75 -# DEFAULT_LINEAR_ACCEL = 350 -# DEFAULT_LINEAR_JERK = 950 DEFAULT_LINEAR_VELOCITY = 5 DEFAULT_LINEAR_ACCEL = 47 DEFAULT_LINEAR_JERK = 230 @@ -135,7 +132,7 @@ MAX_LINEAR_ACCEL = 47.5 MAX_LINEAR_JERK = 233 [KINS] -JOINTS = 3 +JOINTS = 4 KINEMATICS = trivkins # Axes sections --------------------------------------------------------------- @@ -157,6 +154,12 @@ MAX_VELOCITY = 9.5 MAX_ACCELERATION = 48 MAX_JERK = 234 +[AXIS_S] +HOME = 0.000 +MAX_VELOCITY = 9.5 +MAX_ACCELERATION = 48 +MAX_JERK = 234 + # Joints sections # First joint @@ -253,6 +256,38 @@ STEPLEN = 200 DIRDELAY = 0 +[JOINT_3] +TYPE = ANGULAR +HOME = 0 +MAX_VELOCITY = 10 +MAX_ACCELERATION = 49 +MAX_JERK = 245 +BACKLASH = 0.000 +INPUT_SCALE = 25000 +OUTPUT_SCALE = 1.000 +PULSE_PER_REV = 25000 +MIN_LIMIT = -87 +MAX_LIMIT = 10 +FERROR = 190 +MIN_FERROR = 190 +HOME_OFFSET = 11.541 +# HOME_OFFSET = -21.5 +# HOME_SEARCH_VEL = 0.0 +# HOME_LATCH_VEL = 0.0 +# HOME_FINAL_VEL = 0.0 +HOME_SEARCH_VEL = -9.0 +HOME_LATCH_VEL = -1.0 +HOME_FINAL_VEL = 9.0 +HOME_USE_INDEX = NO +HOME_IGNORE_LIMITS = YES +HOME_SEQUENCE = 0 +#TODO: HOME_IS_SHARED = 1 +# minimum steplen, 200ns, 5MHz +# minimum delay for dir change +STEPLEN = 200 +DIRDELAY = 0 + + # section for main IO controller parameters ----------------------------------- [EMCIO] # Name of IO controller program, e.g., io @@ -268,18 +303,21 @@ TOOL_CHANGE_POSITION = 0 0 50.8 [WOU] FPGA = "usb.bit" RISC = "miller.bin" -CTRL_TYPE = "p,p,p" +CTRL_TYPE = "p,p,p,p" # PULSE_TYPE(a): ab-phase # PULSE_TYPE(s): step-dir -PULSE_TYPE = "s,s,s" +PULSE_TYPE = "s,s,s,s" # ENC_TYPE(l): LOOP-BACK PULSE_CMD to ENCODER (fake ENCODER counts) # ENC_TYPE(r): REAL ENCODER counts -ENC_TYPE = "l,l,l" +ENC_TYPE = "l,l,l,l" # PROBE_CONFIG[31:0]: -# [7:0] indicates digital pin -# [15:8] indicates analog channel -# [23:16] inciates probe mode (0:d 1:a 2:a or d 3: a and d) +# [ 7: 0] digital pin +# [15: 8] analog channel +# [20:16] probe type +# probe_type: DIGITAL_ONLY(0), ANALOG_ONLY(1), +# DIGITAL_OR_ANALOG(2), DIGITAL_AND_ANALOG(3) +# PROBE_CONFIG = DIGITAL_ONLY(0), analog-ch(0), din-ch(0x1) PROBE_CONFIG = 0x00000001 WISHBONE = wou From e7ec4486ad91b09724192e10949885d048ddea41 Mon Sep 17 00:00:00 2001 From: Yishin Li Date: Wed, 27 Feb 2013 18:11:42 +0800 Subject: [PATCH 009/256] Support AXIS_S for .INI file --- src/emc/ini/iniaxis.cc | 5 ++++- src/emc/ini/initraj.cc | 4 ++++ src/emc/motion/emcmotcfg.h | 4 ++-- src/emc/motion/motion.c | 10 +++++----- src/emc/nml_intf/emcpos.h | 4 +++- src/emc/usr_intf/axis/scripts/axis.py | 24 ++++++++++++------------ 6 files changed, 30 insertions(+), 21 deletions(-) diff --git a/src/emc/ini/iniaxis.cc b/src/emc/ini/iniaxis.cc index d5bac9b61..da41a3bc7 100644 --- a/src/emc/ini/iniaxis.cc +++ b/src/emc/ini/iniaxis.cc @@ -65,7 +65,6 @@ static int loadAxis(int axis, EmcIniFile *axisIniFile) double maxVelocity; double maxAcceleration; double maxJerk; - // int res; // compose string to match, axis = 0 -> AXIS_X etc. switch (axis) { @@ -78,6 +77,10 @@ static int loadAxis(int axis, EmcIniFile *axisIniFile) case 6: sprintf(axisString, "AXIS_U");break; case 7: sprintf(axisString, "AXIS_V");break; case 8: sprintf(axisString, "AXIS_W");break; + case 9: sprintf(axisString, "AXIS_S");break; + default: + rcs_print_error("Unknown axis id: %d\n", axis); + assert(0); // unknown axis id } axisIniFile->EnableExceptions(EmcIniFile::ERR_CONVERSION); diff --git a/src/emc/ini/initraj.cc b/src/emc/ini/initraj.cc index a5a16ad1e..463632fd8 100644 --- a/src/emc/ini/initraj.cc +++ b/src/emc/ini/initraj.cc @@ -130,6 +130,10 @@ static int loadTraj(EmcIniFile *trajInifile) axismask |= 256; axes += 1; } + if(strchr(coord, 's') || strchr(coord, 'S')) { + axismask |= 512; + axes += 1; + } } else { axismask = 1 | 2 | 4; // default: XYZ machine axes = 3; diff --git a/src/emc/motion/emcmotcfg.h b/src/emc/motion/emcmotcfg.h index b0df3cc50..214b15c4d 100644 --- a/src/emc/motion/emcmotcfg.h +++ b/src/emc/motion/emcmotcfg.h @@ -20,9 +20,9 @@ /* number of joints supported Note: this is not a global variable but a compile-time parameter since it sets array sizes, etc. */ -#define EMCMOT_MAX_JOINTS 9 +#define EMCMOT_MAX_JOINTS 10 /* number of axes defined by the interp */ //FIXME: shouldn't be here.. -#define EMCMOT_MAX_AXIS 9 +#define EMCMOT_MAX_AXIS 10 #define EMCMOT_MAX_DIO 64 #define EMCMOT_MAX_AIO 64 diff --git a/src/emc/motion/motion.c b/src/emc/motion/motion.c index d8db91e39..8eabf8683 100644 --- a/src/emc/motion/motion.c +++ b/src/emc/motion/motion.c @@ -517,11 +517,11 @@ static int init_hal_io(void) /* export axis pins and parameters */ for (n = 0; n < EMCMOT_MAX_AXIS; n++) { - if ((retval = hal_pin_float_newf(HAL_OUT, &(emcmot_hal_data->axis[n].pos_cmd), mot_comp_id, "axis.%c.pos-cmd", "xyzabcuvw"[n])) != 0) goto error; - if ((retval = hal_pin_float_newf(HAL_OUT, &(emcmot_hal_data->axis[n].vel_cmd), mot_comp_id, "axis.%c.vel-cmd", "xyzabcuvw"[n])) != 0) goto error; - if ((retval = hal_pin_float_newf(HAL_OUT, &(emcmot_hal_data->axis[n].teleop_pos_cmd), mot_comp_id, "axis.%c.teleop-pos-cmd", "xyzabcuvw"[n])) != 0) goto error; - if ((retval = hal_pin_float_newf(HAL_OUT, &(emcmot_hal_data->axis[n].teleop_vel_lim), mot_comp_id, "axis.%c.teleop-vel-lim", "xyzabcuvw"[n])) != 0) goto error; - if ((retval = hal_pin_bit_newf(HAL_OUT, &(emcmot_hal_data->axis[n].teleop_tp_enable), mot_comp_id, "axis.%c.teleop-tp-enable", "xyzabcuvw"[n])) != 0) goto error; + if ((retval = hal_pin_float_newf(HAL_OUT, &(emcmot_hal_data->axis[n].pos_cmd), mot_comp_id, "axis.%c.pos-cmd", "xyzabcuvws"[n])) != 0) goto error; + if ((retval = hal_pin_float_newf(HAL_OUT, &(emcmot_hal_data->axis[n].vel_cmd), mot_comp_id, "axis.%c.vel-cmd", "xyzabcuvws"[n])) != 0) goto error; + if ((retval = hal_pin_float_newf(HAL_OUT, &(emcmot_hal_data->axis[n].teleop_pos_cmd), mot_comp_id, "axis.%c.teleop-pos-cmd", "xyzabcuvws"[n])) != 0) goto error; + if ((retval = hal_pin_float_newf(HAL_OUT, &(emcmot_hal_data->axis[n].teleop_vel_lim), mot_comp_id, "axis.%c.teleop-vel-lim", "xyzabcuvws"[n])) != 0) goto error; + if ((retval = hal_pin_bit_newf(HAL_OUT, &(emcmot_hal_data->axis[n].teleop_tp_enable), mot_comp_id, "axis.%c.teleop-tp-enable", "xyzabcuvws"[n])) != 0) goto error; } /* Done! */ rtapi_print_msg(RTAPI_MSG_INFO, diff --git a/src/emc/nml_intf/emcpos.h b/src/emc/nml_intf/emcpos.h index 4e2b80995..0fd8aab59 100644 --- a/src/emc/nml_intf/emcpos.h +++ b/src/emc/nml_intf/emcpos.h @@ -20,6 +20,7 @@ typedef struct EmcPose { PmCartesian tran; double a, b, c; double u, v, w; + double s; /* s: spindle position */ } EmcPose; #define ZERO_EMC_POSE(pos) do { \ @@ -31,6 +32,7 @@ pos.b = 0.0; \ pos.c = 0.0; \ pos.u = 0.0; \ pos.v = 0.0; \ -pos.w = 0.0; } while(0) +pos.w = 0.0; \ +pos.s = 0.0; } while(0) #endif diff --git a/src/emc/usr_intf/axis/scripts/axis.py b/src/emc/usr_intf/axis/scripts/axis.py index ff083d07a..31035ee0b 100755 --- a/src/emc/usr_intf/axis/scripts/axis.py +++ b/src/emc/usr_intf/axis/scripts/axis.py @@ -1234,7 +1234,7 @@ def activate_axis(i, force=0): axis = getattr(widgets, "joint_%d" % i) else: if not s.axis_mask & (1< Date: Wed, 27 Feb 2013 18:12:31 +0800 Subject: [PATCH 010/256] WIP: synchronized rigid tapping --- src/emc/kinematics/tc.h | 2 +- src/emc/kinematics/tp.c | 248 +++++++++++++++++++++------------------- 2 files changed, 133 insertions(+), 117 deletions(-) diff --git a/src/emc/kinematics/tc.h b/src/emc/kinematics/tc.h index 55517d806..a6fc5c344 100644 --- a/src/emc/kinematics/tc.h +++ b/src/emc/kinematics/tc.h @@ -42,7 +42,7 @@ typedef struct { } PmCircle9; typedef enum { - TAPPING, REVERSING, RETRACTION, FINAL_REVERSAL, FINAL_PLACEMENT + TAPPING, REVERSING } RIGIDTAP_STATE; typedef unsigned long long iomask_t; // 64 bits on both x86 and x86_64 diff --git a/src/emc/kinematics/tp.c b/src/emc/kinematics/tp.c index 505a92fa2..05c1d7bb7 100644 --- a/src/emc/kinematics/tp.c +++ b/src/emc/kinematics/tp.c @@ -314,18 +314,20 @@ int tpAddRigidTap(TP_STRUCT *tp, EmcPose end, double vel, tc.cycle_time = tp->cycleTime; tc.coords.rigidtap.reversal_target = line_xyz.tmag; - // allow 10 turns of the spindle to stop - we don't want to just go on forever - tc.target = line_xyz.tmag + 10. * tp->uu_per_rev; - +// // allow 10 turns of the spindle to stop - we don't want to just go on forever +// tc.target = line_xyz.tmag + 10. * tp->uu_per_rev; + // tc.target: set as revolutions of spindle + tc.target = line_xyz.tmag / tp->uu_per_rev; DP("tpAddRigidTap(): jerk(%f) req_vel(%f) req_acc(%f) ini_maxvel(%f)\n", jerk, vel, acc, ini_maxvel); - DP("tpAddRigidTap(): reversal_target(%f) target(%f) uu_per_rev(%f)\n", + DP("tpAddRigidTap(): reversal_target(%f) target(%f) uu_per_rev(%f)\n", tc.coords.rigidtap.reversal_target, tc.target, tp->uu_per_rev); tc.progress = 0.0; tc.accel_state = ACCEL_S3; tc.distance_to_go = tc.target; + // TODO: should be vel/acc/jerk of spindle tc.reqvel = vel; tc.maxvel = ini_maxvel * tp->cycleTime; tc.maxaccel = acc * tp->cycleTime * tp->cycleTime; @@ -356,7 +358,6 @@ int tpAddRigidTap(TP_STRUCT *tp, EmcPose end, double vel, return -1; } tc.synchronized = tp->synchronized; - tc.uu_per_rev = tp->uu_per_rev; tc.css_progress_cmd = 0; tc.velocity_mode = tp->velocity_mode; @@ -371,11 +372,21 @@ int tpAddRigidTap(TP_STRUCT *tp, EmcPose end, double vel, tc.syncdio.sync_input_triggered = 0; } + // TAPPING if (tcqPut(&tp->queue, tc) == -1) { rtapi_print_msg(RTAPI_MSG_ERR, "tcqPut failed.\n"); return -1; } + // REVERSING + pmLineInit(&line_xyz, end_xyz, start_xyz); // reverse the line direction + tc.coords.rigidtap.xyz = line_xyz; + tc.motion_type = TC_RIGIDTAP; + if (tcqPut(&tp->queue, tc) == -1) { + rtapi_print_msg(RTAPI_MSG_ERR, "tcqPut failed.\n"); + return -1; + } + // do not change tp->goalPos here, // since this move will end just where it started @@ -1330,7 +1341,7 @@ int tpRunCycle(TP_STRUCT * tp, long period) static double spindleoffset; static int waiting_for_index = MOTION_INVALID_ID; static int waiting_for_atspeed = MOTION_INVALID_ID; - static double revs; +// static double revs; EmcPose target; emcmotStatus->tcqlen = tcqLen(&tp->queue); @@ -1515,69 +1526,69 @@ int tpRunCycle(TP_STRUCT * tp, long period) emcmotStatus->spindleSync = 1; waiting_for_index = MOTION_INVALID_ID; tc->sync_accel=1; - revs=0; +// revs=0; } } - if (tc->motion_type == TC_RIGIDTAP) { - static double old_spindlepos; - double new_spindlepos = emcmotStatus->spindleRevs; - if (emcmotStatus->spindle.direction < 0) new_spindlepos = -new_spindlepos; - - switch (tc->coords.rigidtap.state) { - case TAPPING: - if (tc->progress >= tc->coords.rigidtap.reversal_target) { - // command reversal - emcmotStatus->spindle.speed *= -1; - tc->coords.rigidtap.state = REVERSING; - } - break; - case REVERSING: - if (new_spindlepos < old_spindlepos) { - PmPose start, end; - PmLine *aux = &tc->coords.rigidtap.aux_xyz; - // we've stopped, so set a new target at the original position - tc->coords.rigidtap.spindlerevs_at_reversal = new_spindlepos + spindleoffset; - - pmLinePoint(&tc->coords.rigidtap.xyz, tc->progress, &start); - end = tc->coords.rigidtap.xyz.start; - pmLineInit(aux, start, end); - tc->coords.rigidtap.reversal_target = aux->tmag; - tc->target = aux->tmag + 10. * tc->uu_per_rev; - tc->progress = 0.0; - tc->css_progress_cmd = 0; - - tc->coords.rigidtap.state = RETRACTION; - } - break; - case RETRACTION: - if (tc->progress >= tc->coords.rigidtap.reversal_target) { - emcmotStatus->spindle.speed *= -1; - tc->coords.rigidtap.state = FINAL_REVERSAL; - } - break; - case FINAL_REVERSAL: - if (new_spindlepos > old_spindlepos) { - PmPose start, end; - PmLine *aux = &tc->coords.rigidtap.aux_xyz; - pmLinePoint(aux, tc->progress, &start); - end = tc->coords.rigidtap.xyz.start; - pmLineInit(aux, start, end); - tc->target = aux->tmag; - tc->progress = 0.0; - tc->synchronized = 0; - tc->reqvel = tc->maxvel; - tc->css_progress_cmd = 0; - - tc->coords.rigidtap.state = FINAL_PLACEMENT; - } - break; - case FINAL_PLACEMENT: - // this is a regular move now, it'll stop at target above. - break; - } - old_spindlepos = new_spindlepos; - } +// if (tc->motion_type == TC_RIGIDTAP) { +// static double old_spindlepos; +// double new_spindlepos = emcmotStatus->spindleRevs; +// if (emcmotStatus->spindle.direction < 0) new_spindlepos = -new_spindlepos; +// +// switch (tc->coords.rigidtap.state) { +// case TAPPING: +// if (tc->progress >= tc->coords.rigidtap.reversal_target) { +// // command reversal +// emcmotStatus->spindle.speed *= -1; +// tc->coords.rigidtap.state = REVERSING; +// } +// break; +// case REVERSING: +// if (new_spindlepos < old_spindlepos) { +// PmPose start, end; +// PmLine *aux = &tc->coords.rigidtap.aux_xyz; +// // we've stopped, so set a new target at the original position +// tc->coords.rigidtap.spindlerevs_at_reversal = new_spindlepos + spindleoffset; +// +// pmLinePoint(&tc->coords.rigidtap.xyz, tc->progress, &start); +// end = tc->coords.rigidtap.xyz.start; +// pmLineInit(aux, start, end); +// tc->coords.rigidtap.reversal_target = aux->tmag; +// tc->target = aux->tmag + 10. * tc->uu_per_rev; +// tc->progress = 0.0; +// tc->css_progress_cmd = 0; +// +// tc->coords.rigidtap.state = RETRACTION; +// } +// break; +// case RETRACTION: +// if (tc->progress >= tc->coords.rigidtap.reversal_target) { +// emcmotStatus->spindle.speed *= -1; +// tc->coords.rigidtap.state = FINAL_REVERSAL; +// } +// break; +// case FINAL_REVERSAL: +// if (new_spindlepos > old_spindlepos) { +// PmPose start, end; +// PmLine *aux = &tc->coords.rigidtap.aux_xyz; +// pmLinePoint(aux, tc->progress, &start); +// end = tc->coords.rigidtap.xyz.start; +// pmLineInit(aux, start, end); +// tc->target = aux->tmag; +// tc->progress = 0.0; +// tc->synchronized = 0; +// tc->reqvel = tc->maxvel; +// tc->css_progress_cmd = 0; +// +// tc->coords.rigidtap.state = FINAL_PLACEMENT; +// } +// break; +// case FINAL_PLACEMENT: +// // this is a regular move now, it'll stop at target above. +// break; +// } +// old_spindlepos = new_spindlepos; +// } if(!tc->synchronized) emcmotStatus->spindleSync = 0; @@ -1595,56 +1606,61 @@ int tpRunCycle(TP_STRUCT * tp, long period) } - if(tc->synchronized) { - // for CSS and TC_RIGIDTAP - double css_progress_cmd; - double pos_error; - double new_spindlepos = emcmotStatus->spindleRevs; - - tc->feed_override = 1.0; - - if (emcmotStatus->spindle.direction < 0) new_spindlepos = -new_spindlepos; - revs = new_spindlepos; - - if(tc->motion_type == TC_RIGIDTAP && - (tc->coords.rigidtap.state == RETRACTION || - tc->coords.rigidtap.state == FINAL_REVERSAL)) - revs = tc->coords.rigidtap.spindlerevs_at_reversal - new_spindlepos; - else - revs = new_spindlepos; - - // feed-forward reqvel calculation for CSS motion - css_progress_cmd = (revs - spindleoffset) * tc->uu_per_rev; - - pos_error = tc->css_progress_cmd - tc->progress; - if (pos_error > tc->jerk) { - pos_error = tc->jerk; - } else if (pos_error < -tc->jerk) { - pos_error = -tc->jerk; - } - - tc->reqvel = (css_progress_cmd - tc->css_progress_cmd + pos_error) / tc->cycle_time; - tc->css_progress_cmd = css_progress_cmd; - - if (nexttc) { - if (nexttc->synchronized) { - // nexttc->reqvel = tc->reqvel; - // nexttc->feed_override = 1.0; - // if (nexttc->reqvel < 0.0) - // nexttc->reqvel = 0.0; - - // disable velocity blending for CSS motion - nexttc->reqvel = 0; - nexttc->feed_override = 0; - } else { - nexttc->feed_override = emcmotStatus->net_feed_scale; - } - } - } else { - tc->feed_override = emcmotStatus->net_feed_scale; - if(nexttc) { - nexttc->feed_override = emcmotStatus->net_feed_scale; - } +// if(tc->synchronized) { +// // for CSS and TC_RIGIDTAP +// double css_progress_cmd; +// double pos_error; +// double new_spindlepos = emcmotStatus->spindleRevs; +// +// tc->feed_override = 1.0; +// +// if (emcmotStatus->spindle.direction < 0) new_spindlepos = -new_spindlepos; +// revs = new_spindlepos; +// +// if(tc->motion_type == TC_RIGIDTAP && +// (tc->coords.rigidtap.state == RETRACTION || +// tc->coords.rigidtap.state == FINAL_REVERSAL)) +// revs = tc->coords.rigidtap.spindlerevs_at_reversal - new_spindlepos; +// else +// revs = new_spindlepos; +// +// // feed-forward reqvel calculation for CSS motion +// css_progress_cmd = (revs - spindleoffset) * tc->uu_per_rev; +// +// pos_error = tc->css_progress_cmd - tc->progress; +// if (pos_error > tc->jerk) { +// pos_error = tc->jerk; +// } else if (pos_error < -tc->jerk) { +// pos_error = -tc->jerk; +// } +// +// tc->reqvel = (css_progress_cmd - tc->css_progress_cmd + pos_error) / tc->cycle_time; +// tc->css_progress_cmd = css_progress_cmd; +// +// if (nexttc) { +// if (nexttc->synchronized) { +// // nexttc->reqvel = tc->reqvel; +// // nexttc->feed_override = 1.0; +// // if (nexttc->reqvel < 0.0) +// // nexttc->reqvel = 0.0; +// +// // disable velocity blending for CSS motion +// nexttc->reqvel = 0; +// nexttc->feed_override = 0; +// } else { +// nexttc->feed_override = emcmotStatus->net_feed_scale; +// } +// } +// } else { +// tc->feed_override = emcmotStatus->net_feed_scale; +// if(nexttc) { +// nexttc->feed_override = emcmotStatus->net_feed_scale; +// } +// } + + tc->feed_override = emcmotStatus->net_feed_scale; + if(nexttc) { + nexttc->feed_override = emcmotStatus->net_feed_scale; } /* handle pausing */ From 6ee552f0a3b682d5da88343b4da4a6a91f743bc5 Mon Sep 17 00:00:00 2001 From: Yishin Li Date: Wed, 27 Feb 2013 18:56:19 +0800 Subject: [PATCH 011/256] WIP: add kinematics/miller_kins.c for sync-spindle-motion --- configs/araisrobo/miller/miller.ini | 2 +- src/Makefile | 4 ++ src/emc/kinematics/miller_kins.c | 81 +++++++++++++++++++++++++++++ 3 files changed, 86 insertions(+), 1 deletion(-) create mode 100644 src/emc/kinematics/miller_kins.c diff --git a/configs/araisrobo/miller/miller.ini b/configs/araisrobo/miller/miller.ini index 2119502f7..d4990d413 100644 --- a/configs/araisrobo/miller/miller.ini +++ b/configs/araisrobo/miller/miller.ini @@ -133,7 +133,7 @@ MAX_LINEAR_JERK = 233 [KINS] JOINTS = 4 -KINEMATICS = trivkins +KINEMATICS = miller_kins # Axes sections --------------------------------------------------------------- [AXIS_X] diff --git a/src/Makefile b/src/Makefile index 4a7820b70..7d518a773 100644 --- a/src/Makefile +++ b/src/Makefile @@ -895,6 +895,9 @@ align_gantry_kins-objs := emc/kinematics/align_gantry_kins.o obj-m += yyzzkins.o yyzzkins-objs := emc/kinematics/yyzzkins.o +obj-m += miller_kins.o +miller_kins-objs := emc/kinematics/miller_kins.o + obj-$(CONFIG_MOTMOD) += motmod.o motmod-objs := emc/kinematics/cubic.o motmod-objs += emc/kinematics/tc.o @@ -1024,6 +1027,7 @@ endif ../rtlib/alignmentkins$(MODULE_EXT): $(addprefix objects/rt,$(alignmentkins-objs)) ../rtlib/align_gantry_kins$(MODULE_EXT): $(addprefix objects/rt,$(align_gantry_kins-objs)) ../rtlib/yyzzkins$(MODULE_EXT): $(addprefix objects/rt,$(yyzzkins-objs)) +../rtlib/miller_kins$(MODULE_EXT): $(addprefix objects/rt,$(miller_kins-objs)) ifeq ($(TRIVIAL_BUILD),no) RTDEPS := $(sort $(patsubst objects/%.o,depends/%.d,$(RTOBJS))) diff --git a/src/emc/kinematics/miller_kins.c b/src/emc/kinematics/miller_kins.c new file mode 100644 index 000000000..cc0f8e578 --- /dev/null +++ b/src/emc/kinematics/miller_kins.c @@ -0,0 +1,81 @@ +/******************************************************************** +* Description: miller_kins.c +* Synchronized spindle position kinematics for rigid tapping. +* Based on Trivial kinematics for 3 axis Cartesian machine. +* +* Derived from a work by Fred Proctor & Will Shackleford +* +* Author: +* License: GPL Version 2 +* System: Linux +* +* Copyright (c) 2004 All rights reserved. +* +* Last change: +********************************************************************/ + +#include "kinematics.h" /* these decls */ + +int kinematicsForward(const double *joints, + EmcPose * pos, + const KINEMATICS_FORWARD_FLAGS * fflags, + KINEMATICS_INVERSE_FLAGS * iflags) +{ + pos->tran.x = joints[0]; + pos->tran.y = joints[1]; + pos->tran.z = joints[2]; + pos->s = joints[3]; + + return 0; +} + +int kinematicsInverse(const EmcPose * pos, + double *joints, + const KINEMATICS_INVERSE_FLAGS * iflags, + KINEMATICS_FORWARD_FLAGS * fflags) +{ + joints[0] = pos->tran.x; + joints[1] = pos->tran.y; + joints[2] = pos->tran.z; + joints[3] = pos->s; + + return 0; +} + +/* implemented for these kinematics as giving joints preference */ +int kinematicsHome(EmcPose * world, + double *joint, + KINEMATICS_FORWARD_FLAGS * fflags, + KINEMATICS_INVERSE_FLAGS * iflags) +{ + *fflags = 0; + *iflags = 0; + + return kinematicsForward(joint, world, fflags, iflags); +} + +KINEMATICS_TYPE kinematicsType() +{ + return KINEMATICS_IDENTITY; +} + +#include "rtapi.h" /* RTAPI realtime OS API */ +#include "rtapi_app.h" /* RTAPI realtime module decls */ +#include "hal.h" + +EXPORT_SYMBOL(kinematicsType); +EXPORT_SYMBOL(kinematicsForward); +EXPORT_SYMBOL(kinematicsInverse); +MODULE_LICENSE("GPL"); + +int comp_id; +int rtapi_app_main(void) { + comp_id = hal_init("miller_kins"); + if(comp_id > 0) { + hal_ready(comp_id); + return 0; + } + return comp_id; +} + +void rtapi_app_exit(void) { hal_exit(comp_id); } From d55809a91daffe7986598b2fb50faa61a501cfe4 Mon Sep 17 00:00:00 2001 From: WH Zheng Date: Fri, 1 Mar 2013 18:54:12 +0800 Subject: [PATCH 012/256] BUGFIX for STRAIGHT_PROBE after RISC-JOGGING * After RISC-JOGGING, set emcmotStatus.update_current_pos_flag == 1 at control.c * In taskintf.cc, it will force to update current position for interp_convert.cc --- src/emc/motion/control.c | 4 ++++ src/emc/task/taskintf.cc | 27 ++++++++++----------------- 2 files changed, 14 insertions(+), 17 deletions(-) diff --git a/src/emc/motion/control.c b/src/emc/motion/control.c index 496212d12..cda95c1f7 100644 --- a/src/emc/motion/control.c +++ b/src/emc/motion/control.c @@ -814,6 +814,7 @@ static void handle_special_cmd(void) *emcmot_hal_data->update_pos_ack = 0; } + emcmotStatus->update_current_pos_flag = 0; // prevent emcTaskPlanSynch() at emcTask.cc if (*emcmot_hal_data->update_pos_ack != 0) { int joint_num; @@ -841,10 +842,12 @@ static void handle_special_cmd(void) positions[joint_num] = 0.0; joint_num++; } + /* update carte_pos_cmd for RISC-JOGGING */ kinematicsForward(positions, &emcmotStatus->carte_pos_cmd, &fflags, &iflags); /* preset traj planner to current position */ tpSetPos(&emcmotDebug->coord_tp, emcmotStatus->carte_pos_cmd); // for EMCMOT_MOTION_COORD mode + emcmotStatus->update_current_pos_flag = 1; // force emcTaskPlanSynch() at emcTask.cc } } @@ -1977,6 +1980,7 @@ static void output_to_hal(void) emcmotStatus->sync_risc_pos); *(emcmot_hal_data->align_pos_cmd) = 1; emcmotDebug->coord_tp.currentPos = emcmotStatus->carte_pos_fb; + assert(0); } else { *(emcmot_hal_data->align_pos_cmd) = 0; } diff --git a/src/emc/task/taskintf.cc b/src/emc/task/taskintf.cc index ffd6d9b4b..e82226921 100644 --- a/src/emc/task/taskintf.cc +++ b/src/emc/task/taskintf.cc @@ -51,9 +51,10 @@ // MOTION INTERFACE - -/*! \todo FIXME - this decl was originally much later in the file, moved -here temporarily for debugging */ +/** + * emcmotStatus: + * copied by usrmotReadEmcmotStatus() from emcMotionUpdate() + **/ static emcmot_status_t emcmotStatus; /* @@ -559,22 +560,14 @@ int emcAxisUpdate(EMC_AXIS_STAT stat[], int numAxes) return 0; } -static int issue_sync_count = 0; -#define SYNC_FREQ 50 void checkPlanSyncReq(void) { - // TODO: check sync req flag from emcmotStatus and issue -// emcTaskPlanSynch? - if (emcmotStatus.update_current_pos_flag == 1 || issue_sync_count > 0) { - issue_sync_count ++; - if (issue_sync_count > SYNC_FREQ) { - issue_sync_count = 0; - emcmotStatus.update_current_pos_flag = 0; - EMC_TASK_PLAN_SYNCH taskPlanSynchCmd; - emcTaskQueueCommand(&taskPlanSynchCmd); - } - } - return; + if (emcmotStatus.update_current_pos_flag == 1) { + // force to update current position for interp_convert.cc + emcTaskPlanSynch(); + } + return; } + /* This function checks to see if any joint or the traj has been inited already. At startup, if none have been inited, usrmotIniLoad and usrmotInit must be called first. At From e3c01974005fd763b13804d8817b61de31c85c95 Mon Sep 17 00:00:00 2001 From: WH Zheng Date: Tue, 5 Mar 2013 14:01:42 +0800 Subject: [PATCH 013/256] move GANTRY_POLARITY from taiwan-plasma-machine.h to taiwan-plasma.ini --- src/emc/kinematics/align_gantry_kins.c | 7 ++++--- src/hal/components/blender.comp | 11 +++++------ src/hal/drivers/ar-usb/sync_cmd.h | 1 + src/hal/drivers/ar-usb/wou_stepgen.c | 11 +++++++++++ 4 files changed, 21 insertions(+), 9 deletions(-) diff --git a/src/emc/kinematics/align_gantry_kins.c b/src/emc/kinematics/align_gantry_kins.c index 62393f9e5..5d9c808a2 100644 --- a/src/emc/kinematics/align_gantry_kins.c +++ b/src/emc/kinematics/align_gantry_kins.c @@ -152,7 +152,8 @@ int kinematicsInverse(const EmcPose * pos, // (pos->tran.y - y_cent - Y_OFFSET) * cos(rad) + Y_OFFSET + y_cent; joints[0] = pos->tran.x; joints[1] = pos->tran.y; - joints[2] = (pos->tran.y - YY_OFFSET) * GANTRY_POLARITY; // YY +// joints[2] = (pos->tran.y - YY_OFFSET) * GANTRY_POLARITY; // YY + joints[2] = pos->tran.y; // YY joints[3] = pos->tran.z; joints[4] = pos->a; joints[5] = pos->b; @@ -161,8 +162,8 @@ int kinematicsInverse(const EmcPose * pos, // joints[7] = pos->v; // joints[8] = pos->w; // fprintf(stderr,"kI j0(%f) j1(%f)\n",joints[0], joints[1]); - DP("kINV: x(%f), y(%f), j0(%f), j1(%f), j2(%f), yy_offset(%f), POLARITY(%f) \n", - pos->tran.x, pos->tran.y, joints[0], joints[1], joints[2], YY_OFFSET, GANTRY_POLARITY); + DP("kINV: x(%f), y(%f), j0(%f), j1(%f), j2(%f), yy_offset(%f)\n", + pos->tran.x, pos->tran.y, joints[0], joints[1], joints[2], YY_OFFSET); return 0; } diff --git a/src/hal/components/blender.comp b/src/hal/components/blender.comp index 13a4f99f3..b7c31f8c7 100644 --- a/src/hal/components/blender.comp +++ b/src/hal/components/blender.comp @@ -40,11 +40,10 @@ FUNCTION(_) { double max_dv, tiny_dp, pos_err, vel_req, pos_cmd, vel_limit; static unsigned int _cmd_id; - static double curr_pos, curr_vel, p; + static double curr_pos, curr_vel; static double offset = 0; - p = 0.000655; - max_dv = max_acc * p; - tiny_dp = max_dv * p * 0.001; + max_dv = max_acc * fperiod; + tiny_dp = max_dv * fperiod * 0.001; if (!enable) { _cmd_id = pos_cmd_id; @@ -114,8 +113,8 @@ FUNCTION(_) } /* integrate velocity to get new position */ - curr_pos += curr_vel*p; - offset += (curr_vel*p); + curr_pos += curr_vel * fperiod; + offset += (curr_vel * fperiod); if (!blending_o) { _cmd_id += 1; diff --git a/src/hal/drivers/ar-usb/sync_cmd.h b/src/hal/drivers/ar-usb/sync_cmd.h index 88ffc4776..b9b516224 100644 --- a/src/hal/drivers/ar-usb/sync_cmd.h +++ b/src/hal/drivers/ar-usb/sync_cmd.h @@ -176,6 +176,7 @@ typedef enum { enum machine_parameter_addr { AHC_JNT, AHC_POLARITY, + GANTRY_POLARITY, TEST_PATTERN_TYPE, TEST_PATTERN, ANALOG_REF_LEVEL, // wait analog signal: M110 diff --git a/src/hal/drivers/ar-usb/wou_stepgen.c b/src/hal/drivers/ar-usb/wou_stepgen.c index 7dacade21..46ee6bfb3 100644 --- a/src/hal/drivers/ar-usb/wou_stepgen.c +++ b/src/hal/drivers/ar-usb/wou_stepgen.c @@ -223,6 +223,9 @@ const char *alr_output= "0"; RTAPI_MP_STRING(alr_output, "Digital Output when E-Stop presents"); +int gantry_polarity = 0; +RTAPI_MP_INT(gantry_polarity, "gantry polarity"); + static int test_pattern_type = 0; // use dbg_pat_str to update dbg_pat_type static const char *board = "7i43u"; @@ -937,6 +940,12 @@ int rtapi_app_main(void) return -1; } + if (abs(gantry_polarity) == 1) { + // set risc positive + write_machine_param(GANTRY_POLARITY, gantry_polarity); + } + while(wou_flush(&w_param) == -1); + // "pulse type (AB-PHASE(a) or STEP-DIR(s)) for up to 8 channels") data[0] = 0; for (n = 0; n < MAX_CHAN && (pulse_type[n][0] != ' ') ; n++) { @@ -1042,6 +1051,8 @@ int rtapi_app_main(void) assert(0); } while(wou_flush(&w_param) == -1); + + // config debug pattern if (strcmp(pattern_type_str, "NO_TEST") == 0) { write_machine_param(TEST_PATTERN_TYPE, NO_TEST); From 14a89d3ed7efa2418ff8b55a643a0811d4d8e256 Mon Sep 17 00:00:00 2001 From: Yishin Li Date: Tue, 5 Mar 2013 16:44:54 +0800 Subject: [PATCH 014/256] WIP: update miller configs for synchronous spindle setting --- configs/araisrobo/miller/halcmd.sh | 70 +++++++++++++----- configs/araisrobo/miller/miller.bin | Bin 8072 -> 7992 bytes configs/araisrobo/miller/miller.hal | 21 ++++-- configs/araisrobo/miller/miller.ini | 63 ++++++++-------- configs/araisrobo/miller/miller_vcp.hal | 2 +- src/emc/kinematics/tp.c | 5 ++ src/emc/motion/command.c | 1 + src/emc/usr_intf/axis/extensions/emcmodule.cc | 2 - 8 files changed, 108 insertions(+), 56 deletions(-) diff --git a/configs/araisrobo/miller/halcmd.sh b/configs/araisrobo/miller/halcmd.sh index 882637a57..eabf07366 100755 --- a/configs/araisrobo/miller/halcmd.sh +++ b/configs/araisrobo/miller/halcmd.sh @@ -1,23 +1,59 @@ #!/bin/bash -# echo "homing: " `halcmd getp wou.motion.homing` -# -# for a in 0 1 2 3; do -# echo "joint.$a.risc-probe-vel: " `halcmd getp joint.$a.risc-probe-vel` -# echo "joint.$a.risc-probe-pin: " `halcmd getp joint.$a.risc-probe-pin` -# echo "joint.$a.risc-probe-type: " `halcmd getp joint.$a.risc-probe-type` -# echo "joint.$a.home-sw-id: " `halcmd getp joint.$a.home-sw-id` -# echo "joint.$a.homing: " `halcmd getp joint.$a.homing` -# done -# +# tclsh ${HOME}/proj/emc2-dev/tcl/bin/halshow.tcl + +echo "bp-tick: " `halcmd getp wou.bp-tick` +# for a in 0 1 2 3 4 5; do for a in 0; do -echo "pulse_pos[$a]: " `halcmd getp wou.stepgen.$a.pulse_pos` -echo "enc_pos[$a]: " `halcmd getp wou.stepgen.$a.enc_pos` -echo "rawcount32[$a]: " `halcmd getp wou.stepgen.$a.rawcount32` -echo "cmd-fbs[$a]: " `halcmd getp wou.stepgen.$a.cmd-fbs` +echo "pulse_pos[$a]: " `halcmd getp wou.stepgen.$a.pulse_pos` +echo "enc_pos[$a]: " `halcmd getp wou.stepgen.$a.enc_pos` +echo "ferror[$a]: " `halcmd getp wou.stepgen.$a.ferror-flag` +echo "cmd_fbs[$a]: " `halcmd getp wou.stepgen.$a.cmd-fbs` +echo "joint.$a.pos-cmd: " `halcmd getp joint.$a.pos-cmd` +echo "joint.$a.pos-fb: " `halcmd getp joint.$a.pos-fb` +echo "joint.$a.motor-pos-cmd: " `halcmd getp joint.$a.motor-pos-cmd` +echo "joint.$a.motor-pos-fb: " `halcmd getp joint.$a.motor-pos-fb` +echo "joint.$a.probed-pos: " `halcmd getp joint.$a.probed-pos` done -for a in 0 1 2 3 4 5 6 7; do -echo "debug-$a: " `halcmd getp wou.debug.value-$a` -done +echo "wou.sync.analog_ref_level: " `halcmd getp wou.sync.analog_ref_level` +echo "wou.sync.in.timeout: " `halcmd getp wou.sync.in.timeout` +echo "wou.sync.in.wait_type: " `halcmd getp wou.sync.in.wait_type` +echo "wou.sync.in.index: " `halcmd getp wou.sync.in.index` +echo "wou.sync.in.trigger: " `halcmd getp wou.sync.in.trigger` + +# for a in 0 1 2 3 4 5 6 7; do +# echo "debug-$a: " `halcmd getp wou.debug.value-$a` +# done + +echo "debug-0, j[3]req_vel ......" `halcmd getp wou.debug.value-0` +echo "debug-1, j[3]jog_vel ......" `halcmd getp wou.debug.value-1` +echo "debug-2, risc_cmd ......" `halcmd getp wou.debug.value-2` +echo "debug-3, rcmd_seq_num ......" `halcmd getp wou.debug.value-3` +echo "debug-4, probe_cmd ......" `halcmd getp wou.debug.value-4` +echo "debug-5, probe_status ......" `halcmd getp wou.debug.value-5` +echo "debug-6, machine_status......" `halcmd getp wou.debug.value-6` +echo "debug-7, usb_status ... " `halcmd getp wou.debug.value-7` +# echo "debug-5, j[1].vel_err ......" `halcmd getp wou.debug.value-5` +# echo "debug-6, j[2].req_vel " `halcmd getp wou.debug.value-6` +# echo "debug-7, j[2].cur_vel ......" `halcmd getp wou.debug.value-7` +# echo "debug-8, j[2].cur_acc " `halcmd getp wou.debug.value-8` +# echo "debug-9, j[2].acc_req ......" `halcmd getp wou.debug.value-9` +# echo "debug-10, j[2].vel_err " `halcmd getp wou.debug.value-10` +# echo "debug-11, j[1].max_vel ......" `halcmd getp wou.debug.value-11` +# echo "debug-12, j[1].max_acc " `halcmd getp wou.debug.value-12` +# echo "debug-13, j[1].max_jerk ......" `halcmd getp wou.debug.value-13` +# echo "debug-14, j[2].max_vel " `halcmd getp wou.debug.value-14` +# echo "debug-15, j[2].max_acc ......" `halcmd getp wou.debug.value-15` +# echo "debug-16, j[2].max_jerk " `halcmd getp wou.debug.value-16` +# echo "debug-17, j[1].ferror " `halcmd getp wou.debug.value-17` +# echo "debug-18, j[1].max_ferror " `halcmd getp wou.debug.value-18` +# echo "debug-19, j[2].ferror " `halcmd getp wou.debug.value-19` +# echo "debug-20, j[2].max_ferror " `halcmd getp wou.debug.value-20` +# echo "debug-21, AHC_STATE " `halcmd getp wou.debug.value-21` +# echo "debug-22, ctrl_state " `halcmd getp wou.debug.value-22` +# echo "debug-23, start_i " `halcmd getp wou.debug.value-23` +# echo "debug-24, test_run_i " `halcmd getp wou.debug.value-24` +# echo "debug-25, motion_blending_o " `halcmd getp wou.debug.value-25` + diff --git a/configs/araisrobo/miller/miller.bin b/configs/araisrobo/miller/miller.bin index cbd755bd0a1bf97b4f27ebf429aecb6c0de7fca3..6c577b76bbe3f8ebaebb3517665cdaffd443e216 100644 GIT binary patch delta 3037 zcmai0ZERat8Gi4*C;q4%_cn2wn=j(vusCU!da#mIrAtavHBu+d(?A3^sRp-ArDmzu zR8WZsoAtPgw6rxj{*hI77f90DO{8@!NbY2$%bJ!-jUY^C;2#mXp$V;6K#>NhNZl^) zxlUI=2rOM+pL5=i=REJ1N4xXSU9XmJkiTd=4E0QW7sMbh|=hQG6s#vV>~<~gZf z%ustUqnl#mAix% z#_;N4Vabw-pnFNku&%N_Qjnc4Yl#JUMQ4at9DbHpbbpOk40Q2|ll^FKl5Y(@}7 zo^mEFGl)z`BvdG#=lGrnH(jy^>4rU&h&oe=q%+CYgNq53s3J8m)D8@D8CN?OxY~V( ztB04kI>5R5y&_jnE~EW9l-Cv0yesSyD0@!m;rrX!=oSDxxG$WsIPtO(&CTZRt+8o< z0;UZH-;s*|S6w?h#|)xUvb_E@Z@>$UPy8pK`7=^G&^w(8KHh z!_tfQSoQ>-$1+^$<#ZoFFZ2P+y3}{6V~>O^A~y)5LzE5u5zs3~K+4?%Ewhb;GOsBi zW;p%QFe6(Seot(P)yx?)UGhR%kCa~kIcu0;+}2Rdrm~>R-!R9OE)4x;+zpUy1cID= zSzS4yL7I{=7Il4J8fELQx>lzZwIQHZ3Y0LA?2zD%d=ancx0~kgxFxTKLy zT0fsFL%AVmDu;BXv0iw`kCTRurEXwa-?zf`Gu}~?Vtt;2Qivrz2V1Xa(Pz=q^3${q z50b`LDNOPU~U7vEY?WIBl;8b(e!P0Y3pt& z$@tdpn9qnrMJ6GV02G>`3A5ugW=BXMLL{|CPyH|*K{{SH*HL>z>~l~3Y3^x0gXb08 z(>|hwGa&XclzqYu?z>B&BNSVWBr?@nqn%B=1Z_|{!p7BIPsiyGEMI@-9&LTAX!0IWbOt-Kx zb`|8p0cb=lt=RFU^o(hgI!v2j%|WMujQtWMV=ACL?n;HHa6O8NI{*ar0yq&k?uk+$ z1xyiqixiE0*2d^r%vFm0wb?ps5{|V=Bxc4J%%8w;jN-V#H7D&{i(eM)D~vgUC5`!F z51=%7x!vdf4`A@WfK{5?&1DPO7p&S|6HYM#%S``Vy(3RSrc-2*=@t98EgDxfFeqN= z7MY{dL}lK}&ZHsd}XI}hpkucEZd;>P~PXQmKIr; zcfT~rM!a>>G@I}?N?Df2@9V7SZISqR)gdg2=c{HL76kv8Pp@qv`Vct=<6^%k^APiH zk2zPlq>}VLsAoNHE%Y7*BD!#PK@@`qxm$?kEGZf@K6#VwuczbCF9x=8&Tlhl9M1JZ zDnVgcpVTBg1AWpb|2$!_zn6Kd{nGoatGY2}Uz<&$%{XLGmn)}>TzO?#>|t1K*$>cO zI4Q4T2f}rA_O9?B$I2(m$O#yUFsxniiEwWbSK*2ej1-t>18gnqLJq zGeuP6k6k43Dvr1FI7RM+Vf9>(AmFKtfh`Q%pK%pqh3yN8m5jFoAUY23XiD;O{9PU- zbO>T}W(xEDY0Ft{ehK7+$C3Yl9O$6kCCqqznm|D}}^QOKT0CT)8* zL{amOeJSo9EaJ2LxHofGy~mk7DVGAeX1J zcAfFsL%W9y&scNz01i7y-?QtP2vIYNP0dW=Jbo2RD~n)6xH&pmAHbo~Cx4VsZ;Dp1@*9nE1f!9t=oxX$yZrYd(UOs58)m}c+*!mo zh<|GQK=5XYC>`EjlVlrmb;HBW>T__Z50koOf!>5sp>1L4Y1mOSEC!-rB!}#khF|M) SddjZ9OB<#nNn?S=@IL`8c;;OI delta 3042 zcmai0du&tJ8UL>Di68i4oEN!?lf{`c#SJtu+PVbMmQ(~0iD+W$9+^PGox@|oOFWcq zk%s20avUPnP;UoKU1ig-BydeqHBvjtOx|P-8bu=7tm%kF6Phj%3M-+?RtFuWjGu5`&HSQ|_%>1qWEf%#kG&rhj0l)|YF*G0q z;B{j{td43nVQZ5{*@A6@UE z$WTW#Q!q_E2Edh=c>MVE;1fpezDyE`s-X-GD$85_P;Hw3I_Cv{I{H~p8tDY=gQ&Zp zhV4Redzkf*i(l6o3ILa`x2GDA<1@7@u*p**=)(>+2$v!R|lY0f> z2~p6<-yb`>yelklx-SBJq7?oj_UP!h#7d8YR>sw@J>_uiJ1R&s2ncVj=fZiN0-=Le zP+kF)!hU7MjkImYBEyMX-j$9Fq9aOI9mzz@RZOH@i#*ihOn8YRN&{2v#57m%PzZRaoAA(p z!b4#%55;PD=%|X}7r1v%NjA-ELND6;hLFScM|x}n03O^G#@MR2i(PY6#WAKlmJBA| znVkg49RiyXISTZoBbvu1!Q`mMp&%GX2IO^zT^0}0MBN#YAmkz-3mN=Xa=Ep*E}s7sG#TLtN5-;jWYVnd%NS>0Iu{q@M$0K1lQkggE(X|IK46q$wF^1MZ)0 zqX`PIJZoj?k-*A`sx~w!p-G|-3CzfD3^Cv^%^Tbkrr6v*_GP6P>wi@Fj-;@nQdhY` zF>X2zgu8vS+#Q%>Yf1pm8aICWLezL$CF>x5FLK}ln0@Q(9~Mgg1JzyiK& zCFVE0qrS*`J$s}iOM3P^x1vvjcgfTCNxA?MJ%oe9)Aazmr%x0r_cTAmWFEzJm6bfc z_$-&V%ps%-m$!QH0XCtPGdrV7E{y!cJ2@li>^D{c+SktFXGhbz;SVl|^ zqNO#pAj%_zF~EMYr++X@^w(x-YM%Xa({}W`xM}BW%|;|93dhTF=;d3%k3}$oMYB(M zgq}1kc^Zf53B==da|NYW1)X~uW8Bj^g6CD-vvpJrXF$*~cYQ(+(iM>Coe#K29j9kpMfyE+Wx3VL>Tbbbw)yBj?|5zzi~egiF&ZoTO* z+8#D;`yqJ>n*n3PXkQYt$%|mi?}lcKr2~hzl%6(?@~~)6A(~D)g_p@>P`-IM1oabW z>s`NQ918(G1w=H(X$MH68S+7pP)9%%JiZJ4agxV^z!#Sgcs!lxNzkS!j?Gr^?N z3rN3bTkD$RPGckn8I&tew-n+_IhPMC3HqIxIg74eFWbfB;xs#87~whF9UL;a_vzP! zkFn3?(-E?S;DM0{!<`F$k$bD4x$J+I?+W2`^4rKf25<|p!(R)xYeLX==dd3(ndU=L zotU>zxf}vf$^Xj`^50wM{|9?m*H-%zV^AfRk3k=5`0dT;fGryXz~1oJ^gvK_%b8o;q`V8_$F!*b* z?{WorbIah(M6fnK>L!W%0Ap_KoCOV*$9e=XtXN3M z@D`h^-}1uK9}R9*GfjHfu_nH7P}srkI3dTxzT1f%MG)_Y+}^f^cifSUlsl{<*qGKG zB}NfLPepr?=-o*Sl!B5`Yqd%Ni$p zO2%E(^CsSy70qRx!!CrUt%T8(*f$%ywk^^tt|FH^OFR$)%#;nmwPPh5%$`L5qWEPK z0D|brqV4$BdYrqqx~8@Df^u@H4|o7)!WE!G+VWwwaZCO1`t049MfA$|VtX__=_tMb Om8MBaI?9&55dIGWod{w8 diff --git a/configs/araisrobo/miller/miller.hal b/configs/araisrobo/miller/miller.hal index 23b6fc4fa..fbb4f3578 100644 --- a/configs/araisrobo/miller/miller.hal +++ b/configs/araisrobo/miller/miller.hal @@ -1,8 +1,8 @@ # core HAL config file for simulation - 4 joint # load 3 differentiators for accel signals loadrt ddt count=3 -# load additional blocks loadrt hypot count=2 +loadrt spindle # load RT modules loadrt [KINS]KINEMATICS @@ -20,6 +20,17 @@ addf ddt.1 servo-thread addf ddt.2 servo-thread addf hypot.0 servo-thread addf hypot.1 servo-thread +addf spindle.0 servo-thread + +# spindle +setp spindle.0.max-vel [JOINT_3]MAX_VELOCITY +setp spindle.0.max-acc [JOINT_3]MAX_ACCELERATION +setp spindle.0.max-jerk [JOINT_3]MAX_JERK +# TODO: velocity-mode +setp spindle.0.velocity-mode 1 +net spindle-on spindle.0.on <= motion.spindle-on +net spindle-speed-cmd-rps spindle.0.velocity-cmd <= motion.spindle-speed-cmd-rps + # send the position commands thru differentiators to # generate velocity and accel signals net Xvel-fb => ddt.0.in hypot.0.in0 @@ -31,7 +42,6 @@ net Yacc <= ddt.1.out net Zvel => ddt.2.in hypot.1.in0 net Zacc <= ddt.2.out - # Cartesian 2- and 3-axis velocities net XYvel hypot.0.out => hypot.1.in1 net XYZvel <= hypot.1.out @@ -50,20 +60,20 @@ net motionState motion.motion-state => wou.motion-state net Xpos joint.0.motor-pos-cmd => wou.stepgen.0.position-cmd net Ypos joint.1.motor-pos-cmd => wou.stepgen.1.position-cmd net Zpos joint.2.motor-pos-cmd => wou.stepgen.2.position-cmd -net Spos joint.3.motor-pos-cmd => wou.stepgen.3.position-cmd +net Spos spindle.0.curr-pos => wou.stepgen.3.position-cmd # loop position commands back to motion module feedback # for OPEN_LOOP net Xpos-fb wou.stepgen.0.position-fb => joint.0.motor-pos-fb net Ypos-fb wou.stepgen.1.position-fb => joint.1.motor-pos-fb net Zpos-fb wou.stepgen.2.position-fb => joint.2.motor-pos-fb -net Spos-fb wou.stepgen.3.position-fb => joint.3.motor-pos-fb +net Spos-fb wou.stepgen.3.position-fb => motion.spindle-revs # motor_index positions net J0_index-pos wou.stepgen.0.index-pos => joint.0.index-pos net J1_index-pos wou.stepgen.1.index-pos => joint.1.index-pos net J2_index-pos wou.stepgen.2.index-pos => joint.2.index-pos -net J3_index-pos wou.stepgen.3.index-pos => joint.3.index-pos +# net J3_index-pos wou.stepgen.3.index-pos => joint.3.index-pos # estop loopback # net estop-loop iocontrol.0.user-enable-out iocontrol.0.emc-enable-in @@ -151,6 +161,7 @@ net J0-risc-pos-cmd wou.stepgen.0.risc-pos-cmd => joint.0.risc-pos-cmd net J1-risc-pos-cmd wou.stepgen.1.risc-pos-cmd => joint.1.risc-pos-cmd net J2-risc-pos-cmd wou.stepgen.2.risc-pos-cmd => joint.2.risc-pos-cmd net J3-risc-pos-cmd wou.stepgen.3.risc-pos-cmd => joint.3.risc-pos-cmd +# TODO: forward risc-pos-cmd to spindle.0 # for usb-homing: # original homing switchs: diff --git a/configs/araisrobo/miller/miller.ini b/configs/araisrobo/miller/miller.ini index d4990d413..5f2183e84 100644 --- a/configs/araisrobo/miller/miller.ini +++ b/configs/araisrobo/miller/miller.ini @@ -132,8 +132,9 @@ MAX_LINEAR_ACCEL = 47.5 MAX_LINEAR_JERK = 233 [KINS] -JOINTS = 4 -KINEMATICS = miller_kins +JOINTS = 4 +# KINEMATICS = miller_kins +KINEMATICS = trivkins # Axes sections --------------------------------------------------------------- [AXIS_X] @@ -154,11 +155,11 @@ MAX_VELOCITY = 9.5 MAX_ACCELERATION = 48 MAX_JERK = 234 -[AXIS_S] -HOME = 0.000 -MAX_VELOCITY = 9.5 -MAX_ACCELERATION = 48 -MAX_JERK = 234 +# [AXIS_S] +# HOME = 0.000 +# MAX_VELOCITY = 9.5 +# MAX_ACCELERATION = 48 +# MAX_JERK = 234 # Joints sections @@ -178,12 +179,12 @@ MAX_LIMIT = 131 FERROR = 3 MIN_FERROR = 2 HOME_OFFSET = -11.327 -# HOME_SEARCH_VEL = 0.0 -# HOME_LATCH_VEL = 0.0 -# HOME_FINAL_VEL = 0.0 -HOME_SEARCH_VEL = 9.0 -HOME_LATCH_VEL = 1.0 -HOME_FINAL_VEL = 9.0 +HOME_SEARCH_VEL = 0.0 +HOME_LATCH_VEL = 0.0 +HOME_FINAL_VEL = 0.0 +# HOME_SEARCH_VEL = 9.0 +# HOME_LATCH_VEL = 1.0 +# HOME_FINAL_VEL = 9.0 HOME_USE_INDEX = NO HOME_IGNORE_LIMITS = YES HOME_SEQUENCE = 1 @@ -209,12 +210,12 @@ MAX_LIMIT = 157 FERROR = 190 MIN_FERROR = 190 HOME_OFFSET = -11.368 -# HOME_SEARCH_VEL = 0.0 -# HOME_LATCH_VEL = 0.0 -# HOME_FINAL_VEL = 0.0 -HOME_SEARCH_VEL = 9.0 -HOME_LATCH_VEL = 1.0 -HOME_FINAL_VEL = 9.0 +HOME_SEARCH_VEL = 0.0 +HOME_LATCH_VEL = 0.0 +HOME_FINAL_VEL = 0.0 +# HOME_SEARCH_VEL = 9.0 +# HOME_LATCH_VEL = 1.0 +# HOME_FINAL_VEL = 9.0 HOME_USE_INDEX = NO HOME_IGNORE_LIMITS = YES HOME_SEQUENCE = 1 @@ -240,12 +241,12 @@ FERROR = 190 MIN_FERROR = 190 HOME_OFFSET = 11.541 # HOME_OFFSET = -21.5 -# HOME_SEARCH_VEL = 0.0 -# HOME_LATCH_VEL = 0.0 -# HOME_FINAL_VEL = 0.0 -HOME_SEARCH_VEL = -9.0 -HOME_LATCH_VEL = -1.0 -HOME_FINAL_VEL = 9.0 +HOME_SEARCH_VEL = 0.0 +HOME_LATCH_VEL = 0.0 +HOME_FINAL_VEL = 0.0 +# HOME_SEARCH_VEL = -9.0 +# HOME_LATCH_VEL = -1.0 +# HOME_FINAL_VEL = 9.0 HOME_USE_INDEX = NO HOME_IGNORE_LIMITS = YES HOME_SEQUENCE = 0 @@ -272,12 +273,12 @@ FERROR = 190 MIN_FERROR = 190 HOME_OFFSET = 11.541 # HOME_OFFSET = -21.5 -# HOME_SEARCH_VEL = 0.0 -# HOME_LATCH_VEL = 0.0 -# HOME_FINAL_VEL = 0.0 -HOME_SEARCH_VEL = -9.0 -HOME_LATCH_VEL = -1.0 -HOME_FINAL_VEL = 9.0 +HOME_SEARCH_VEL = 0.0 +HOME_LATCH_VEL = 0.0 +HOME_FINAL_VEL = 0.0 +# HOME_SEARCH_VEL = -9.0 +# HOME_LATCH_VEL = -1.0 +# HOME_FINAL_VEL = 9.0 HOME_USE_INDEX = NO HOME_IGNORE_LIMITS = YES HOME_SEQUENCE = 0 diff --git a/configs/araisrobo/miller/miller_vcp.hal b/configs/araisrobo/miller/miller_vcp.hal index ca34918df..df444fc69 100644 --- a/configs/araisrobo/miller/miller_vcp.hal +++ b/configs/araisrobo/miller/miller_vcp.hal @@ -18,7 +18,7 @@ net estop-inactive estop-not.out => gladevcp.settings net machine_is_on => gladevcp.commands # show the current spindle speed in the top hoizontal bar -net spindle-speed motion.spindle-speed-out => gladevcp.spindle-rpm-hbar +net spindle-speed-rpm spindle.0.speed-rpm => gladevcp.spindle-rpm-hbar # net laser_distance => gladevcp.laser-dist-meter # net laser_distance => gladevcp.laser-dist-label diff --git a/src/emc/kinematics/tp.c b/src/emc/kinematics/tp.c index 05c1d7bb7..348acff4b 100644 --- a/src/emc/kinematics/tp.c +++ b/src/emc/kinematics/tp.c @@ -1344,6 +1344,11 @@ int tpRunCycle(TP_STRUCT * tp, long period) // static double revs; EmcPose target; + if (tp->synchronized == 0) { + // prepare spindle speed command + + } + emcmotStatus->tcqlen = tcqLen(&tp->queue); emcmotStatus->requested_vel = 0.0; tc = tcqItem(&tp->queue, 0, period); diff --git a/src/emc/motion/command.c b/src/emc/motion/command.c index ecc7c6647..40484387e 100644 --- a/src/emc/motion/command.c +++ b/src/emc/motion/command.c @@ -1643,6 +1643,7 @@ void emcmotCommandHandler(void *arg, long period) emcmotCommand->timeout, emcmotCommand->wait_type); } break; + case EMCMOT_SPINDLE_ON: rtapi_print_msg(RTAPI_MSG_DBG, "SPINDLE_ON"); diff --git a/src/emc/usr_intf/axis/extensions/emcmodule.cc b/src/emc/usr_intf/axis/extensions/emcmodule.cc index cb49173e7..08e62f644 100644 --- a/src/emc/usr_intf/axis/extensions/emcmodule.cc +++ b/src/emc/usr_intf/axis/extensions/emcmodule.cc @@ -1193,8 +1193,6 @@ static PyObject *teleop(pyCommandChannel *s, PyObject *o) { en.serial_number = next_serial(s); s->c->write(en); emcWaitCommandReceived(s->serial, s->s); - - printf ("emcmodule.cc: teleop.en(%d)\n", en.enable); Py_INCREF(Py_None); return Py_None; From bceceb4b12d825c886a0c4ef6fea9616ca94b6b3 Mon Sep 17 00:00:00 2001 From: Yishin Li Date: Tue, 5 Mar 2013 17:25:17 +0800 Subject: [PATCH 015/256] BUGFIX to HAL Comp Generator -- comp.g * initialize __comp_inst at export() so that the other funcitons could use exported HAL signals --- src/hal/utils/comp.g | 1 + 1 file changed, 1 insertion(+) diff --git a/src/hal/utils/comp.g b/src/hal/utils/comp.g index 82cb9c1d3..540549eb6 100644 --- a/src/hal/utils/comp.g +++ b/src/hal/utils/comp.g @@ -445,6 +445,7 @@ static int comp_id; print >>f, " r = hal_export_funct(buf, (void(*)(void *inst, long))%s, inst, %s, 0, comp_id);" % ( to_c(name), int(fp)) print >>f, " if(r != 0) return r;" + print >>f, " __comp_inst = inst;" print >>f, " if(__comp_last_inst) __comp_last_inst->_next = inst;" print >>f, " __comp_last_inst = inst;" print >>f, " if(!__comp_first_inst) __comp_first_inst = inst;" From cbdbfe6ce852ec2c1988a9c4d26d9b81cfe6de27 Mon Sep 17 00:00:00 2001 From: Yishin Li Date: Tue, 5 Mar 2013 17:25:53 +0800 Subject: [PATCH 016/256] Add HAL component -- spindle.comp --- src/hal/components/spindle.comp | 176 ++++++++++++++++++++++++++++++++ 1 file changed, 176 insertions(+) create mode 100644 src/hal/components/spindle.comp diff --git a/src/hal/components/spindle.comp b/src/hal/components/spindle.comp new file mode 100644 index 000000000..1e1388db3 --- /dev/null +++ b/src/hal/components/spindle.comp @@ -0,0 +1,176 @@ +/** + * Reference: Comp HAL Component Generator + * http://linuxcnc.org/docs/html/hal/comp.html + **/ + +component spindle "Spindle with pulse command interface"; + +pin in float velocity-cmd = 0 "Commanded speed (rps)"; +pin in float position-cmd = 0 "Commanded position"; +pin in bit velocity-mode = 0 "Velocity(1) or position(0) mode"; +pin in bit on = 0 "Spindle on"; + +pin out bit at-speed "Set when spindle is at speed for velocity-mode"; +pin out bit in-position "Set when spindle is in position for position-mode"; +pin out float curr-pos "Feedback position, in revolutions"; +pin out float curr-vel "Current velocity (rps)"; +pin out float curr-acc "Current acceleration (rev/s^2)"; +pin out float speed-rpm "Current speed in RPM"; +param rw float max-vel "Max velocity"; +param rw float max-acc "Max acceleration"; +param rw float max-jerk "Max jerk"; + +param rw float scale = 1.0 +"""factor applied to \\fBvelocity-cmd\\fP. + +The result of '\\fBvelocity-cmd\\fP * \\fBscale\\fP' be in revolutions per second. +For example, if \\fBvelocity-cmd\\fP is in revolutions/minute, \\fBscale\\fP should be set to 1/60 or 0.016666667. +"""; + +license "GPL"; + +function _; + +;; + +#include +#include +#include +#include + +typedef enum { + S_IDLE, + S_VEL_MODE, + S_VEL_DECEL, + S_POS_MODE, +} spindle_state_t; + + +/** + * vel_ctrl: Velocity Control + * Algorithm is taking from simple_tp.c + **/ +void vel_ctrl (double vel_cmd, double period) +{ + double max_da, tiny_dv, vel_err, acc_req; + // static double curr_vel, curr_acc; // global signal + + max_da = max_jerk * period; + tiny_dv = max_da * period * 0.001; + + /* limit velocity cmd */ + if (vel_cmd > max_vel) { + vel_cmd = max_vel; + } else if (vel_cmd < -max_vel) { + vel_cmd = -max_vel; + } + + /* calculate desired acceleration */ + + /* request a acceleration that tends to drive + vel_err to zero, but allows for stopping without velocity + overshoot */ + vel_err = vel_cmd - curr_vel; + /* positive and negative errors require some sign flipping to + avoid sqrt(negative) */ + if (vel_err > tiny_dv) { + acc_req = -max_da + + sqrt(2.0 * max_jerk * vel_err + max_da * max_da); + } else if (vel_err < -tiny_dv) { + acc_req = max_da - + sqrt(-2.0 * max_jerk * vel_err + max_da * max_da); + } else { + /* within 'tiny_dv' of desired vel, no need to accel */ + acc_req = 0; + curr_vel = vel_cmd; + if (curr_vel != 0) { + at_speed = 1; + } + } + + /* limit acceleration request */ + if (acc_req > max_acc) { + acc_req = max_acc; + } else if (acc_req < -max_acc) { + acc_req = -max_acc; + } + + /* ramp acceleration toward request at jerk limit */ + if (acc_req > (curr_acc + max_da)) { + curr_acc += max_da; + } else if (acc_req < (curr_acc - max_da)) { + curr_acc -= max_da; + } else { + curr_acc = acc_req; + } + + /* integrate acceleration to get new velocity */ + curr_vel += curr_acc * period; +} + + +FUNCTION(_) { + // double old_position = position_fb; + // double new_position = position_fb + velocity_cmd * fperiod * scale; + + // if(index_enable && (floor(old_position) != floor(new_position))) { + // index_enable = false; + // if(velocity_cmd < 0) + // new_position = new_position - ceil(new_position); + // else + // new_position = new_position - floor(new_position); + // } + // position_fb = new_position; + static spindle_state_t cur_state = S_IDLE; + + if ((!on) && (curr_vel == 0)) + { + cur_state = S_IDLE; + } + + at_speed = 0; + in_position = 0; + switch (cur_state) + { + case S_IDLE: + if (on) { + if (velocity_mode) { + cur_state = S_VEL_MODE; + } else { + cur_state = S_POS_MODE; + } + } + break; + + case S_VEL_MODE: + /* will set at-speed as 1 inside vel_ctrl() */ + vel_ctrl (velocity_cmd, fperiod); + curr_pos += curr_vel * fperiod; + if ((!on) || (!velocity_mode)) { + cur_state = S_VEL_DECEL; + } + break; + + case S_VEL_DECEL: + // decel to vel == 0 + vel_ctrl (0, fperiod); + if (curr_vel == 0) { + cur_state = S_IDLE; + } else if (on && velocity_mode) { + cur_state = S_VEL_MODE; + } + break; + + case S_POS_MODE: + // TODO + break; + + default: + assert(0); + break; + } + + speed_rpm = curr_vel * 60.0; +} + + From ad6860fb282cd5c29aa68bb2bd8b381431d73d78 Mon Sep 17 00:00:00 2001 From: Yishin Li Date: Tue, 5 Mar 2013 18:07:06 +0800 Subject: [PATCH 017/256] Add testing nc_files for araisrobo/miller machine --- nc_files/araisrobo/miller/test_00.ngc | 36 +++++++++++++++++++++++++++ nc_files/araisrobo/miller/test_01.ngc | 12 +++++++++ 2 files changed, 48 insertions(+) create mode 100644 nc_files/araisrobo/miller/test_00.ngc create mode 100644 nc_files/araisrobo/miller/test_01.ngc diff --git a/nc_files/araisrobo/miller/test_00.ngc b/nc_files/araisrobo/miller/test_00.ngc new file mode 100644 index 000000000..62fa14007 --- /dev/null +++ b/nc_files/araisrobo/miller/test_00.ngc @@ -0,0 +1,36 @@ +G21 +G90 +G64 P0.3 +G40 +F500 +G0 X0 Y0 Z0 +G91 +G1 Z-7 +G0 Z7 +G0 X8.4 Y18.5 +G1 Z-7 +G1 X-2 + Y2 + X4 + Y-4 + X-4 + Y2 + X2 +G0 Z7 +G0 X30 +G1 Z-7 +G1 X-2 + Y2 + X4 + Y-4 + X-4 + Y2 + X2 +G0 Z7 +G0 X8.4 Y32 +G1 Z-7 +G0 Z7 +G90 +G1 X0 Y0 +M2 +% diff --git a/nc_files/araisrobo/miller/test_01.ngc b/nc_files/araisrobo/miller/test_01.ngc new file mode 100644 index 000000000..79ac45110 --- /dev/null +++ b/nc_files/araisrobo/miller/test_01.ngc @@ -0,0 +1,12 @@ +G21 G64 P0.1 G40 +F12.5 +G91 +G1 Z -0.25 +#=5 +G1 X[#] + Y[#] + X[-#] + Y[-#] +G1 Z 50 +M2 +% From ccbdb3fc6e7fc18d7a3cd4eb00920c656213f6b5 Mon Sep 17 00:00:00 2001 From: Yishin Li Date: Wed, 6 Mar 2013 16:45:00 +0800 Subject: [PATCH 018/256] Testing file for rigid-tapping -- nc_files/araisrobo/rigid_tap.ngc --- nc_files/araisrobo/miller/rigid_tap.ngc | 5 +++++ 1 file changed, 5 insertions(+) create mode 100644 nc_files/araisrobo/miller/rigid_tap.ngc diff --git a/nc_files/araisrobo/miller/rigid_tap.ngc b/nc_files/araisrobo/miller/rigid_tap.ngc new file mode 100644 index 000000000..18e279fc5 --- /dev/null +++ b/nc_files/araisrobo/miller/rigid_tap.ngc @@ -0,0 +1,5 @@ +G21 G91 +g0z0 +s60m3 ; 1rps +g33.1 z5 k1 ; 1 thread per second, k - distance per revolution +m2 From 7820277e666d1f4026ec71bb61a127f598d208a0 Mon Sep 17 00:00:00 2001 From: WH Zheng Date: Wed, 6 Mar 2013 18:27:49 +0800 Subject: [PATCH 019/256] WIP: connect emcmotStatus->spindleSync to spindle-velocity-mode --- configs/araisrobo/miller/miller.hal | 2 +- configs/araisrobo/miller/miller.ini | 14 ++++--- nc_files/araisrobo/miller/test_00.ngc | 3 ++ nc_files/araisrobo/miller/test_01.ngc | 4 +- src/emc/kinematics/tp.c | 58 ++++++++++++++------------- src/emc/motion/control.c | 1 + src/emc/motion/mot_priv.h | 3 ++ src/emc/motion/motion.c | 1 + src/hal/components/spindle.comp | 6 +++ 9 files changed, 58 insertions(+), 34 deletions(-) diff --git a/configs/araisrobo/miller/miller.hal b/configs/araisrobo/miller/miller.hal index fbb4f3578..04af88368 100644 --- a/configs/araisrobo/miller/miller.hal +++ b/configs/araisrobo/miller/miller.hal @@ -27,7 +27,7 @@ setp spindle.0.max-vel [JOINT_3]MAX_VELOCITY setp spindle.0.max-acc [JOINT_3]MAX_ACCELERATION setp spindle.0.max-jerk [JOINT_3]MAX_JERK # TODO: velocity-mode -setp spindle.0.velocity-mode 1 +net spindle-velocity-mode spindle.0.velocity-mode <= motion.spindle-velocity-mode net spindle-on spindle.0.on <= motion.spindle-on net spindle-speed-cmd-rps spindle.0.velocity-cmd <= motion.spindle-speed-cmd-rps diff --git a/configs/araisrobo/miller/miller.ini b/configs/araisrobo/miller/miller.ini index 5f2183e84..6a7ef3b16 100644 --- a/configs/araisrobo/miller/miller.ini +++ b/configs/araisrobo/miller/miller.ini @@ -38,7 +38,7 @@ MAX_FEED_OVERRIDE = 1.2 MAX_SPINDLE_OVERRIDE = 1.0 # Prefix to be used PROGRAM_PREFIX = ../../../nc_files -OPEN_FILE = ../../../nc_files/araisrobo/test.ngc +OPEN_FILE = ../../../nc_files/araisrobo/miller/rigid_tap.ngc # Introductory graphic INTRO_GRAPHIC = emc2.gif @@ -235,8 +235,10 @@ BACKLASH = 0.000 INPUT_SCALE = 25000 OUTPUT_SCALE = 1.000 PULSE_PER_REV = 25000 -MIN_LIMIT = -87 -MAX_LIMIT = 10 +# MIN_LIMIT = -87 +# MAX_LIMIT = 10 +MIN_LIMIT = -50000 +MAX_LIMIT = 50000 FERROR = 190 MIN_FERROR = 190 HOME_OFFSET = 11.541 @@ -267,8 +269,10 @@ BACKLASH = 0.000 INPUT_SCALE = 25000 OUTPUT_SCALE = 1.000 PULSE_PER_REV = 25000 -MIN_LIMIT = -87 -MAX_LIMIT = 10 +# MIN_LIMIT = -87 +# MAX_LIMIT = 10 +MIN_LIMIT = -50000 +MAX_LIMIT = 50000 FERROR = 190 MIN_FERROR = 190 HOME_OFFSET = 11.541 diff --git a/nc_files/araisrobo/miller/test_00.ngc b/nc_files/araisrobo/miller/test_00.ngc index 62fa14007..a7d51b91c 100644 --- a/nc_files/araisrobo/miller/test_00.ngc +++ b/nc_files/araisrobo/miller/test_00.ngc @@ -4,6 +4,8 @@ G64 P0.3 G40 F500 G0 X0 Y0 Z0 +M3 S200 +(G33 Z-1 K0.0625) G91 G1 Z-7 G0 Z7 @@ -32,5 +34,6 @@ G1 Z-7 G0 Z7 G90 G1 X0 Y0 +M5 M2 % diff --git a/nc_files/araisrobo/miller/test_01.ngc b/nc_files/araisrobo/miller/test_01.ngc index 79ac45110..c63151e4b 100644 --- a/nc_files/araisrobo/miller/test_01.ngc +++ b/nc_files/araisrobo/miller/test_01.ngc @@ -1,12 +1,14 @@ G21 G64 P0.1 G40 F12.5 G91 +M3S200 G1 Z -0.25 #=5 G1 X[#] Y[#] X[-#] Y[-#] -G1 Z 50 +G1 Z 0.25 +M5 M2 % diff --git a/src/emc/kinematics/tp.c b/src/emc/kinematics/tp.c index 348acff4b..4de69d4c1 100644 --- a/src/emc/kinematics/tp.c +++ b/src/emc/kinematics/tp.c @@ -29,7 +29,7 @@ #define SMLBLND // to evaluate seamless blending // to disable DP(): #define TRACE 0 -#define TRACE 0 +#define TRACE 1 #include #include "dptrace.h" #if (TRACE!=0) @@ -363,6 +363,7 @@ int tpAddRigidTap(TP_STRUCT *tp, EmcPose end, double vel, tc.velocity_mode = tp->velocity_mode; tc.enables = enables; tc.indexrotary = -1; + tc.motion_type = TC_RIGIDTAP; if ((syncdio.anychanged != 0) || (syncdio.sync_input_triggered != 0)) { tc.syncdio = syncdio; //enqueue the list of DIOs that need toggling @@ -377,11 +378,9 @@ int tpAddRigidTap(TP_STRUCT *tp, EmcPose end, double vel, rtapi_print_msg(RTAPI_MSG_ERR, "tcqPut failed.\n"); return -1; } - // REVERSING pmLineInit(&line_xyz, end_xyz, start_xyz); // reverse the line direction tc.coords.rigidtap.xyz = line_xyz; - tc.motion_type = TC_RIGIDTAP; if (tcqPut(&tp->queue, tc) == -1) { rtapi_print_msg(RTAPI_MSG_ERR, "tcqPut failed.\n"); return -1; @@ -1509,32 +1508,35 @@ int tpRunCycle(TP_STRUCT * tp, long period) // honor accel constraint in case we happen to make an acute angle // with the next segment. - if(tc->synchronized) { - if(!tc->velocity_mode && !emcmotStatus->spindleSync) { - // if we aren't already synced, wait - waiting_for_index = tc->id; - // ask for an index reset - emcmotStatus->spindle_index_enable = 1; - spindleoffset = 0.0; - // don't move: wait - return 0; - } - } +//USB-RIGID-TAP: +// if(tc->synchronized) { +// if(!tc->velocity_mode && !emcmotStatus->spindleSync) { +// // if we aren't already synced, wait +// waiting_for_index = tc->id; +// // ask for an index reset +// emcmotStatus->spindle_index_enable = 1; +// spindleoffset = 0.0; +// // don't move: wait +// return 0; +// } +// } } - if (MOTION_ID_VALID(waiting_for_index)) { - if(emcmotStatus->spindle_index_enable) { - /* haven't passed index yet */ - return 0; - } else { - /* passed index, start the move */ - emcmotStatus->spindleSync = 1; - waiting_for_index = MOTION_INVALID_ID; - tc->sync_accel=1; -// revs=0; - } - } +//USB-RIGID-TAP: +// if (MOTION_ID_VALID(waiting_for_index)) { +// if(emcmotStatus->spindle_index_enable) { +// /* haven't passed index yet */ +// return 0; +// } else { +// /* passed index, start the move */ +// emcmotStatus->spindleSync = 1; +// waiting_for_index = MOTION_INVALID_ID; +// tc->sync_accel=1; +//// revs=0; +// } +// } +//USB-RIGID-TAP: // if (tc->motion_type == TC_RIGIDTAP) { // static double old_spindlepos; // double new_spindlepos = emcmotStatus->spindleRevs; @@ -1596,7 +1598,9 @@ int tpRunCycle(TP_STRUCT * tp, long period) // } - if(!tc->synchronized) emcmotStatus->spindleSync = 0; +//USB-RIGID-TAP: +// if(!tc->synchronized) emcmotStatus->spindleSync = 0; + emcmotStatus->spindleSync = tc->synchronized; if(nexttc && nexttc->active == 0) { diff --git a/src/emc/motion/control.c b/src/emc/motion/control.c index cda95c1f7..7b9a492e0 100644 --- a/src/emc/motion/control.c +++ b/src/emc/motion/control.c @@ -2021,6 +2021,7 @@ static void output_to_hal(void) } *(emcmot_hal_data->spindle_speed_cmd_rps) = emcmotStatus->spindle.speed / 60.; *(emcmot_hal_data->spindle_on) = ((emcmotStatus->spindle.speed * emcmotStatus->net_spindle_scale) != 0) ? 1 : 0; + *(emcmot_hal_data->spindle_velocity_mode) = (emcmotStatus->spindleSync); *(emcmot_hal_data->spindle_forward) = (*emcmot_hal_data->spindle_speed_out > 0) ? 1 : 0; *(emcmot_hal_data->spindle_reverse) = (*emcmot_hal_data->spindle_speed_out < 0) ? 1 : 0; *(emcmot_hal_data->spindle_brake) = (emcmotStatus->spindle.brake != 0) ? 1 : 0; diff --git a/src/emc/motion/mot_priv.h b/src/emc/motion/mot_priv.h index 86c5b29b4..31b464140 100644 --- a/src/emc/motion/mot_priv.h +++ b/src/emc/motion/mot_priv.h @@ -160,6 +160,9 @@ typedef struct { // simplest way of spindle control (output start/stop) hal_bit_t *spindle_on; /* spindle spin output */ + // spindle_velocity_mode: velocity(1) or position(0) mode + hal_bit_t *spindle_velocity_mode; /* spindle velocity_mode output */ + // same thing for 2 directions hal_bit_t *spindle_forward; /* spindle spin-forward output */ hal_bit_t *spindle_reverse; /* spindle spin-reverse output */ diff --git a/src/emc/motion/motion.c b/src/emc/motion/motion.c index c8ea2ccc3..a3672c13d 100644 --- a/src/emc/motion/motion.c +++ b/src/emc/motion/motion.c @@ -329,6 +329,7 @@ static int init_hal_io(void) if ((retval = hal_pin_bit_newf(HAL_IO, &(emcmot_hal_data->spindle_index_enable), mot_comp_id, "motion.spindle-index-enable")) != 0) goto error; if ((retval = hal_pin_bit_newf(HAL_OUT, &(emcmot_hal_data->spindle_on), mot_comp_id, "motion.spindle-on")) != 0) goto error; + if ((retval = hal_pin_bit_newf(HAL_OUT, &(emcmot_hal_data->spindle_velocity_mode), mot_comp_id, "motion.spindle-velocity-mode")) != 0) goto error; if ((retval = hal_pin_bit_newf(HAL_OUT, &(emcmot_hal_data->spindle_forward), mot_comp_id, "motion.spindle-forward")) != 0) goto error; if ((retval = hal_pin_bit_newf(HAL_OUT, &(emcmot_hal_data->spindle_reverse), mot_comp_id, "motion.spindle-reverse")) != 0) goto error; if ((retval = hal_pin_bit_newf(HAL_OUT, &(emcmot_hal_data->spindle_brake), mot_comp_id, "motion.spindle-brake")) != 0) goto error; diff --git a/src/hal/components/spindle.comp b/src/hal/components/spindle.comp index 1e1388db3..5d6235ff6 100644 --- a/src/hal/components/spindle.comp +++ b/src/hal/components/spindle.comp @@ -121,6 +121,7 @@ FUNCTION(_) { // new_position = new_position - floor(new_position); // } // position_fb = new_position; + double tmp; static spindle_state_t cur_state = S_IDLE; if ((!on) && (curr_vel == 0)) @@ -163,6 +164,11 @@ FUNCTION(_) { case S_POS_MODE: // TODO + in_position = 1; + tmp = curr_vel; + curr_vel = (position_cmd - curr_pos) / fperiod; + curr_acc = curr_vel - tmp; + curr_pos = position_cmd; break; default: From 9136523ac10562dab7c9cc0ac8585538beb21729 Mon Sep 17 00:00:00 2001 From: WH Zheng Date: Thu, 7 Mar 2013 18:35:58 +0800 Subject: [PATCH 020/256] Release candidate for usb-rigid-tapping * RIGID_TAP of emccanon.cc: prepare spindle velocity, accel, and jerk * tpAddRigidTap of tp.c: prepare tc for TAPPING and REVERSING * tcGetPosReal of tc.c: calculate xyz position based on spindle progress * control.c, motion.c: prepare HAL signals to interconnect with spindle.comp * spindle.comp: spindle component that takes velocity and position commands * configs/araisrobo/miller: 3 axes milling machine for usb-rigid-tapping --- configs/araisrobo/miller/miller.hal | 7 +++-- configs/araisrobo/miller/miller.ini | 20 ++++++------ configs/araisrobo/miller/param.ods | Bin 29541 -> 29432 bytes src/emc/kinematics/tc.c | 25 +++++++++++---- src/emc/kinematics/tc.h | 3 ++ src/emc/kinematics/tp.c | 33 ++++++++++++++++++-- src/emc/motion/control.c | 7 +++-- src/emc/motion/mot_priv.h | 4 +++ src/emc/motion/motion.c | 4 +++ src/emc/motion/motion.h | 6 +++- src/emc/task/emccanon.cc | 46 ++++++++++++++++++---------- src/hal/components/spindle.comp | 14 +++++++-- 12 files changed, 127 insertions(+), 42 deletions(-) diff --git a/configs/araisrobo/miller/miller.hal b/configs/araisrobo/miller/miller.hal index 04af88368..a5b66383a 100644 --- a/configs/araisrobo/miller/miller.hal +++ b/configs/araisrobo/miller/miller.hal @@ -26,10 +26,13 @@ addf spindle.0 servo-thread setp spindle.0.max-vel [JOINT_3]MAX_VELOCITY setp spindle.0.max-acc [JOINT_3]MAX_ACCELERATION setp spindle.0.max-jerk [JOINT_3]MAX_JERK -# TODO: velocity-mode net spindle-velocity-mode spindle.0.velocity-mode <= motion.spindle-velocity-mode net spindle-on spindle.0.on <= motion.spindle-on net spindle-speed-cmd-rps spindle.0.velocity-cmd <= motion.spindle-speed-cmd-rps +net spindle-position-cmd spindle.0.position-cmd <= motion.spindle-position-cmd +net spindle-curr-pos-cmd spindle.0.curr-pos => motion.spindle-curr-pos-cmd +net spindle-in-position spindle.0.in-position => motion.spindle-in-position +net spindle-at-speed spindle.0.at-speed => motion.spindle-at-speed # send the position commands thru differentiators to # generate velocity and accel signals @@ -60,7 +63,7 @@ net motionState motion.motion-state => wou.motion-state net Xpos joint.0.motor-pos-cmd => wou.stepgen.0.position-cmd net Ypos joint.1.motor-pos-cmd => wou.stepgen.1.position-cmd net Zpos joint.2.motor-pos-cmd => wou.stepgen.2.position-cmd -net Spos spindle.0.curr-pos => wou.stepgen.3.position-cmd +net spindle-curr-pos-cmd => wou.stepgen.3.position-cmd # loop position commands back to motion module feedback # for OPEN_LOOP diff --git a/configs/araisrobo/miller/miller.ini b/configs/araisrobo/miller/miller.ini index 6a7ef3b16..52629e2ba 100644 --- a/configs/araisrobo/miller/miller.ini +++ b/configs/araisrobo/miller/miller.ini @@ -155,11 +155,11 @@ MAX_VELOCITY = 9.5 MAX_ACCELERATION = 48 MAX_JERK = 234 -# [AXIS_S] -# HOME = 0.000 -# MAX_VELOCITY = 9.5 -# MAX_ACCELERATION = 48 -# MAX_JERK = 234 +[AXIS_S] +HOME = 0.000 +MAX_VELOCITY = 33.33 +MAX_ACCELERATION = 116.67 +MAX_JERK = 583.33 # Joints sections @@ -262,13 +262,13 @@ DIRDELAY = 0 [JOINT_3] TYPE = ANGULAR HOME = 0 -MAX_VELOCITY = 10 -MAX_ACCELERATION = 49 -MAX_JERK = 245 +MAX_VELOCITY = 33.33 +MAX_ACCELERATION = 116.67 +MAX_JERK = 583.33 BACKLASH = 0.000 -INPUT_SCALE = 25000 +INPUT_SCALE = 15000 OUTPUT_SCALE = 1.000 -PULSE_PER_REV = 25000 +PULSE_PER_REV = 10000 # MIN_LIMIT = -87 # MAX_LIMIT = 10 MIN_LIMIT = -50000 diff --git a/configs/araisrobo/miller/param.ods b/configs/araisrobo/miller/param.ods index 9972f7f046bdb9c7b8c677d35dd6aae7f53840e4..ec6ec30df9e6382a7148dfef32e0b9bce7753dba 100644 GIT binary patch delta 27026 zcmb5UV~{36*Z$dd_cW(%+dXaDwryK?+qR8q+qP}nw!3$p=Y9XX`(eLqMO0KqMP^p! zsmRRh{LVQ#27WyPhL@KD1w#b_f&v0^R4|K&SAhTb5Zrvzj-&}2BX zY+-BWMCWc}eWhiiw9kq9?F$HAsBuf0*KwJk;3}TjsIFfXRO!AfvI){&C`v3s{e1dU zT&uRGS~uHu5rz+zamW$+aDRB%nB|iL{;CgyDVCH)y+o|S;Wt>wOLX95!fuZ1tH`?o z_~9&ca~ln0&Gl3O3THo*hvEpvA3X|Mncs6FH7pVZ7V8w{2l9|{XT=h%*Hrc5?r26# z(M>lHzMe@AM>MEX3_p0K__h~bYgJrw>8i)jk$IwM6FQI)DQ>`zEJ*rBO`;J`)__`2 zeljBcs>Gp5_BO_nDXY1xeSd#yDE4~<93etukTi3s>&hx~sTGZ`qxQX)E+tjE$gQx4 z5u*zQ3NYm5*JGhR$RiLDCAE91zM&ne^rGL&CIxy&dozv&EX(rY0#>oQLFe2P%G#sQ ztJ*2Q4S@QEguU4VzuRdr%)Bh>M2FEc?Fty9I=(Y9v>7l#Bzd62RxC37s?Rt8K=VZO zl<&@CCJUFJwI4E0fdnkX!;}|FF+r35nKXgu&c{lJ8`6idLwQ_D`H+%ey{=*Ltwp@r zZhb-ZwEZ|t{+;!+D~);@=BXC%>OaW0@N#*S+Id=jQBISEXrOv$9Y*JxeVQJf^`zIf zl-|MXd4jV9iKei}(_!=a1P1j0A614G6nV&9b6nP?#{~-kVn0S{sArAG#DL$;vZ2CoNIv9`9l;X0EP6%ixK&p!LhHLT+C5+lfyd#21Mz{Yxr7 z2LVq$4yxLtn`tN>2(vKN(?H@ri=qcQhB`Yg{t%U=BY8$x4#n_R$WpKa&45w>{-C zoA!>g8_^&c0ggPZJ@5){SLCFme}}h+S~Cmu@5A|>HgIj!-oxV%ICwYd zSuip;Jz-;L{x2|VMh)0rg2DT*Ys@@)s{#`7ys+g7J9K;Z`#OIpeWzkxHco(=GJc0Y zGvrF@fx(H@DKe~=(LwAdcDb*WA9nM@{i4-CD@*@Rx7Y#$nd|-e1i&?qxMEAu&c?_z zA>{LVFXsmGHFu6bT4uAgKBLQGpLi9}Naow|X0vJ=AHM)=z`)&x zrHv_CXr*1|X}4+(Z>Kzg$!1n{k+O~bS9JpCPe#l_Yh%{f7C&xN3qZ3(Bt6m_AK3{6 z<5swy((dDOGMJl3YCfV}%evx%%cgP5qRwQ(N({?DMp*`kLTPjJyc88aciu-Tpao-zKS5;_gdZd!$fR zRH)qc)CpfQE0K%*B`YoM;W1>Ne)L?gdph=uV{I)2jOh@U#_Tr=al;`mE#SUm1bl-) z6l4D_PUsmNN?sJfJ1`1En@NU`C?||x^yU>F$J^CXZKvls^71w8Nef}#+vps8M&70AB8rzo~+Pua!;xhu1y7g(~MZ@I$Q z2a?p6p1c$!l%`TvRRK5<5Ck(2(EpqjP*70+IV%$VVekQN8^g)p-8~=`S;wQ2!28j5 zl9zbt#+IZhl})HC5;5hViHO0p(6>N&q$i0RB^q31nXa+f%XQe~S7is*R^&1Zs@NkR zR>G2>i#@f>KoanJ{L_A*h>dx_5`f@L@g_IDPTJhIb>I4QoBFj?WTcoM7o0#wW*EzL zStK)bd3gXY!^0KUrq_^W-&bfxURu=Uk)(y{HRbJ7zu~ta0GPMUwzTbXax+UZK6COk zQ<{s(<(9PTLn4JG=h-d4=N2PnHLh_dx>fspwkT!nd|`Y}NMR8nO`U z*R1tV2P8H@WZHf!H9HM2-gzP#G(%deY9q-QhAvAcpQCtI*3(Kjf6Md zg=@&PSc~vgW1_GHoTQSWlxQ+bcW5zgybc4<8&g(?nvK+`w@W~IuSjS!i|1#HfMSw> zOu;A^y;PLk^iJ!l3Xcdg?U7x;)s(1lY0pY*05R=qN;2@i;fnqNy{feG7X0i{>qPgi zH9o8rUhZoG{tS{EUmVYrVsrH*Uh25k+S0vdG?%)5z&5Et&K3Kc>9Y9e=TXV0+p7Qw zAIgp@RF&qU-_*T~nbhTYM~c}RYR*>T8uV1G1D==?2iq7Ll}!~IzXj?*mK^6$ zS*PegDm+yfS;fFc^fi~t)y`9taGU_!D9Uo>4EkTna#F4*SfRcIRIxz#TAzAxU2bBOK1O?zC! zXtU{(UF9<_+roDBtooPA3(LxpYiz%3(#r2qo+Dr`@kSAUZ;jPud#h0kP!R#_)02|s za6aPsZ=*oSLm=srC5lITB@Fxz+N?zpM|;Qima^i;jmLUP2P)c>Rb>g3 z5`mUUDC1Oh!n(jtNuXF&q3Qscqa_VRwAhAxghgTSlIFPJmxjzm5TuPcAb+h@NiK(j z5IbPfqgK*&owrzAKm7c;D5zeLI@<~@k8rV7qer~MyZu1RX@Vd&2U`EVn?JSp^IG)*^e&{&+Iu}h@dBv1(Nu#s#_bE| z+cZ>Yv{=_N6jj$`olUjM)GoVg1iMFZAE_)dM@6=S^N2qlwV30JkqV-CR1`{f=(8&CI)v#-DmJS(Q*+awd1xf-p&H ztT)x_CE?N!N#ZLQkq30W)@hbG=PaV4Aoz2l6I&s5vryn1jW?|$Sfy#26-9Kx1~6z>VbgTFk}fky*^|VcBsfl)(i9dXrvcF2Pfjr6%6@ODQ8%yA zPMQPo%oW*($A9tqv3uQVag~((1U13CYH>lF@?Iz_ophC}Qsu|<&eBO@?rxu5^v7O+ zvDIEjk^66`4AFp=mHpk2m&y-7NVNP*H6p^U@pOz}?gxB+0xl6>uUKD-8`Z8e=iGF| zoF#V4Yju+*+6Cx5kW{qeVc+XDn6sBJc$l2u2A%<{Gv#_g>{{E%baH4)9-eCc&@H7w zQO{_zeNyL=ghm*GA63+WoVv-o5?C9vZLulge0$0_Lz7Z^^bh-XAbQ2j7QP;7{l&Gj z;BoA&66(f*zwE&zZ&j`9nv1aONEj==3lwV9i{@g7^9Zo5&)@Bk3+=t(eRu^rY+E6J zB<~|1E>A7Q&1_qpgwJR*im0zR>y@pIL2ahRABUpI=-Q5#{?+hDB=MMI{@i5#6ocHZ z0wv?>HX?AY0r$`pSSdL4+?eLMZq+EPOU;kkudMdLHgEGF2GKcd z2KGoW5jy($G#n``e3>U@4D8UB7EtqmRW*3d)hPvvwrBva-jP}O?hqD|6&O?6B`dmf zM$D8k&(R?jvjRC9wQi+5djxvC1&;IEsq)z|G%g?{N@wYBdwEVIIN5P#c>E9q-{;wg zrTm3%T?L^2j$!5;UD!YxRGN)wPsg5NJfgCi2# zo)h4^a_NjU!a#`}c;IMV$cAM&iD&qWa2-!DF8*3zfpzh3Txhu{7Nj(@pQTr>=ty0a zx_>R2dA+?I0hj?3ZDhxj5iz3MK^t&y)*W?#l*U751Ny@tOLNP$L)Y(1Ba87a;Rk2Nfg)6s`_L=9h4)j z(Wt+!IE*<$Km)qsB!>}g8ayqO@0KYJbpaYR))MqcUEyl?(6h~KcW}M_ zpF9pCyhe-}xIq>URRSy+mZzh^26i!Hi1sJ<7;)=h(-9bO4kcQmx$0J}STrh<;B^2- z79j|g%R84(8#s2#v1{t*3x@wm4?3*sAsF?ZN2AV1A6lXF)obfyMi~{Um6*yEb4_dJ z99Pc<_CkkDyW(i}hNd3%;qiKlg3z^f#Lad!unL!RDVnBZLxlc1TZ9Yj9^b7& zm1^5?iZU!RUuvi``VQgfI%GJUz&-$HZe?43=SpYuyNEnGgJe{$C@WW(gD>6DcTCpz z>g#i>==X)AZ4=l^K|e>n5zN)&l@EC4@O7Nxo&>EAkbv*NZr=hZr&$kGGAD!Disf#% z31}U)7eR|saI9?h0^xRT}!| zhOOIs^?ko3`sYjQV4y} zRD3X*09xyuv=Xb``_Z|_U--O0SUN{6HiuHyZ(qFUiA>AAiB zDbq5Q{NgmGrPd1=7*p`|460=?vX7DUC##uGRE%ybWxp4Q#D-#FO@ zOAYSYRom{nN3`(z{BT^@VK6p$Bu|PT|Dk?9aJ9Yf%8PXMsk%8GZw)YWDA1*8k3p~I z5)tCGzaW>%Q_5!!1)>pxp&zXU)VO>JJVZiPnf>@YZvC+IbmCS6BH3H|UJxZWPBcCdMRH|O)4&Uhf{9}qs@KeDA!`=z-nwc zO>Gkx{4mx_9UiB2ugy{YI$-8~bEtMhKtb)AQztW|XL%MR zSJ+&IjW&LW24w=@yMR2p)Ce-AGfPOg{0cABA4}{l&>-?GCEt-vku9@qqHxTp7V&|s zPuiKP6Fp2vAefN`@-Q7apMCvW9F;=zz7b=iTDapHL$Y;bleVZ;gFJY;sQD*Xw^sMl z-zHFp3jtx{sA(Qp*q4aOluQqH!8#>_lQp4g$5@YcEmWE+4dLTOR;vyet@R_V)9x~? zm{PRwWd%8{dmEb?7EXi`4B`kUUj>DS)2!e)ZDG5kiF=42rto3irSOk?6#O^?KKwUp zuwM)4WRM`BGSE3vq=|}_gv7=Y{gZ}#CDYmVjR0#3g8>9L0r&^ZmrI+m>ym11*|7bv2*pIzkmrpdOCbxDyT;R;IAUvxA>OBiEl8o4>NdB?Y3xKnJDUv$t%J4i|AW(Z~uaYM0+<}lmP4z4z6#95aWx8 z*9YqDOo#$eP~6nB!*kGMRJg3-g^Ny6<+(YlE`Bf>i&U2@7J(j#{Z~TLVM0AkI7Mba z3x&fL#s0XQpOm`o4evG?&`libfSVU z$oHaA{f1;3%XbzynjK7OxCoLTM)4>}YvW}nO-hd#t$mVivB{Q$xU z8}YMkpbRgW;AeLIumBu|B#$1JQrZXXL8D9E1+z_ji~*Fe5bJu0a1`N1LjZ@H_no+% zd>ci;IEp{Azt|YO3*8oZcc+w{Jvfnlm}O_2UU$;&kIyoiv5$=hb&t2d#r8+Z+nid} z1;Az-F#9=h^DF23KySxqa}Mu#sQ!zIn644U&PM+0d~vZmBS9zb4V*oO%=nKUvMg;F zEV2Sk@k^&t4`dDka8e{z9>9AM2(1K$LUI$4YS8oAB@Z?AuWy8OuRr4ZL#Ogd#pLIB zo7*Wv?4WmUHsRg0SBHnCk2jwm`~DI8AF<6==n73!t9}ui0#=FYvUBl%Dg68KIZ`WWCBbM`oam(ViEJyor_c}17l$7TF=|6rR2t7og8P{t zKClO6AJcUT)AinS6rkRwf=r3oweQCB>H|($f0=Fd37^*PaJr9%*5#3D`Aq!Pw!aq` zJt#_w=brX0xkdnPpe+Fk>SH4)a!uX;Mquni6!Y)zJgPWC(NiUG1pF<|O~CwS&j=3n zz~0CWp6{FO!FLtF=Vc=BD^x5N?@vzes!_hjgXh6_VW3$H0w9+MI9$6pyoghN2|`Z7 zIG-eeM$JgUX!5;fxD|ucH_;&d?Tv1;f!{%vk)ClDAM&UER?hWdkum|7&OgJ+FXQ=? zrxR&6^zci$nIIq5iG*->oURq)K^SAMj;H4pB8B5tR!WKlwh|1piaOmM6NL=Tmgj4b z6*H9YBV{lB7_gNKOx#aEl5VlRW~co_2NcOPH%vOF->j0+f2wF!m`KUEUo?7GhHA*Z ziOq_uT(fF0gQH==at=%aENFaZXC}Rsp(~pBtt5m4-*#w zeJ4DQ2to*v0L76ZT>r}BEJ))9T?hL@BcFvp2=OBb0)WJOB^ac1j_LFoQ9J#eiu6%t zLl|BSFHsU`I!HInjWo=UQFqD4I%kW;b73xC$}tq>UV>4_PAi&~%%LEfru!i}8TLU2 z>4fQwG1nHg#^CQR7Y%PVH)_RpdTXyM+0jKbb}d759-r_qi8zRlDU@J@#~qIq)EBtH zB+fLF3z*8gTa=!iq@g!qBRtE#>F0q}E|~~aqO*}gx!33SOk|3c)eHSYaoNVJyYpqI zjl>Qq>qg}?j>CSy#yr-m@f&H}deX0O%1>xD^Mf`epkx;foRlER7UN+;uK+Hjyika! z2`nBnN9s8ya{xOj$|S9XLELiK>GT`_mI~E11b`*ZKj3$FxKYxuV*(u>3{D#0bB}Ip z20s=@({JvH_emHDM5d58W-fV7l7SkB;_!GnyqCCxcgc4>?*|oeA0e5v^g1@**pQ^I@Bw+6!6HYQk6?2 z6lNH&W0F~zv46`m^usL}>6oAFwmB3d;~50|q~Q&Q8h~T{*|zd|9y|PsqtHiNd4EI? zeaQ(@#R&l)p+>mr9Q_|bTrgV(>kgd)xv+=W17bSP{8B zi3XU`;`2cca_0JvZP(6g&rT(c4uX=QxamQdHe2}MS}$p^#y|rl!z);bv_4?iZ`dt& z&^ahp98Z@L?CG&{5hUiYr^~_NtVw42Mm>tp6GdIZ-?|!ID`_lDa&w*hZ&Ru)zg6nu zy)>Ka@18m_n-19nx9^5*K^9I?vUz<<>F6Blx& zJ=w#jtgd&gbpGwz_pYtYcJlycXgTN1rvH(|Q}le?o~{q44SIOI?*!64X{V3!x4xW# zgNnT_t@%m+mC*Ggu;SMLvG3+*yGLlk7AeME_HEQ9G*}MZ2GB^mmSI}xJj_L7W z$=hq}^<bg9X!uNDpYO+2q6rr;dRbQqUe zj^pz_N0%4hSOEDq2Ay0l`JE$Ky67KPXS*P&LnB7$uuLP`P@flO&LIOjnYZUXn&w6= zDBbzJlQnRF#Lb;#(enHnrnN@q7L8WHTi z8aX2%Z3v#$e>Uliaf#fHIMH9slQz$9LpiOR|8|FYzF;8Pd?lYhiP5FD^v;@twJ|DmY?U)z%MN^ zKEQJ8U2^TcPl?CRiPT9d-8|2T#{JFyn@ZWyQqv!{=4B_T6G|Fq?(GQ^eY4#uuuWsS zwsgM_4jbf3|9?kzN-8_Q$Dp<9bOeR}8FxOQp0yDDIV+OqM1N-L_j6|?&yD^JiUGO@ zUFPousN?@gzKEmo zkDnT<{UI)nM}bahgSTcvo3tb{bMF~{Qr-i>I`Y!zzQDu7FU=KvmTn*S+Mn*3(__Hw zo5TMA>yUB%q{*)R=>(iY48PiFuvB8s(1Z&YgVw`CA_~$s;RyX(=$thFZ-OK+?)+=n zbXID?AWW=*V(n^sUj1;iFxkyR5@$;4)+}u*(FyC;+uJu!CgObOYqHj zeiFn+)rbk>cskOdH%@^t;go)W82X^;xi3V1!d?gY30);k%{L-)`&e6KXrn|XtZigy zOBV=4wYIRs(O3bAFR+Z%?DF!m1v`B09aI-YyUoe?ulxaiOu_A7{zK}?tX}IV_{;-k zRWEiJgd6@d!Zmz^Ef=O9Z_2)pb(eW;89GJtdxL^}EdRmyvZtn_s?U1>c!|eN=0Dco zRQ=QB@gwl?tB241J@%hqa1h%~L!Wq_h-#gc?L#SG+K8&0B)K ziGWUAn4CV6M+k76fSjkj2y|2mYECuZl;edfzDhb?=lO{NkDQktJ?@#DuE+6$knKy$ zxKo;7jIEy!EMzZ%QHKc#q(m2xexuay&pCkvuN*A*VpVFQnVO}2HN}nuxBVaFbC9VP zHQ#hlk)Tkirm_X`UbL}$ll}wwpWs?WOgID-HV}|uBJlqP*ZwyVLokS~%>R=E2pyD2xHHTv2m|CTFAzpf4Wm-Xs;%A3Y9XfE*6)m<7vF=#UeIR+3eJ! zW)r?$kKyJ{!De0}1s$w_qZ#{QJ<;Fo%* zO$uB=ZY4iy(Ij~nXJ@oU7?)=#Kq<8f=$4fu)#q8&R>o1)LQAA>e;Vq~gST77M}<;g z)GU4=jnHC@bw#(l=pQiGCfm7JHuD?$P$x>Iq26P;(5g;5%;C)0W~jfGYC(AJoRs<) zKzS;a&$;!UCmru4N0c>nAd_1cdb#cvSjpB;QyX`ZdjU`7hZQ>+Zco+yfUI4#2FXhv zkcuF_3q0;JQeZ>UeOuIw)w0Kpt9%SaI96j!=w9bJn7pTtg-khKRV%^e*~(tYvNxNy zOT@SLJndDn3!!T&M?F&6d3b-FDlSB;dS0qEIYiJg8(_4=@FlhGrp7ibih`4CWptd! zelv`hugr-Fu+RwNIok1EKud(G-=*bXM9bN{CYv~m>yVzJk!mA}Ni5Nh1HVDmZ6u&# z`R{1Jms!|hrH-^vLN_7s5}hV+UNU;?YH62*8D8}ijHA-<!_62hXX59Q@rFWWwl_?EGGb*naIa?nZd{W~R$PipJpkt>FS^{(lt`$d| zU$dkvFJ)CzR~(BIT}C6Y=36#yNdy@F2NxRj^VxuyXy?@H0;X`VNNd6B){mwgzmkB6 zQT&b(E16PWD5d$(Z7Je;wkppLgK0}rtjpRT=4p{Iq_=t*oWb#YlzIb~E?)U^pzBC! zbET3!f^_LXtWCHLFiL=x_JwFDnsYtoISrrrZy4$`YXs9qS3U`c;|wO}#bOe0A}LGC zJ-l5X6$fLu4+0)5OTaTT__JkI{M2DDS5pR>bySM#^1h`v3$)Tg&BQHw)mH^*SNWO> zk);5M00O8+o|rr7|C%JPD11i)<$b<+aAG#v(6m)~9H58uR0=zMC_YWT4q>ySZ1YSE zEwh@E1gGO4w>(!SZZ&(?RV}8&7Tabd`+fFsqSyy*)y0_V85^u%Pw9yaf{4^Oo9-S-QY_|hnTguqJ)pJ%0U65%m~J3w#K3LhdocDkY3ih7u9_L>b1~WEQ= ze%EDTc5|0PRkcmquB(eEPb~;hCc}_X72)6H`r0hxhnifwD+@Y2G}7j1F3N}sH z2XQM(V?Dt^NW7I`VeTqQ!o_{fhB@TFeZVDvfaOSGm}g!~A*2?FQ4xy0cBnhpu(-Skf-m*}iSs6w zj63>`R#a?aXGH8A5s99{j#5GG-^Klcta}$3%%Nto`h`1}V(!@wcY-yc#)jr(K65ny zWgEL|4z(6x-*c_icgGxv8jnKf;mOur%p!L_*EE7ICUyWf@T`{x*vtStE5Yf-y{10V zA{(69CRSu-=@xV&(f`KG7L1YTo)aqeHw~>kS>I`ax|g(4#%i3qehuU1#uAtlIf_KX5S? zdm*}RsrY7-8wQwd-@yUYP^(}5G7fQKg^PyMW^aV#-tHTV%h43@9Xfx_nJ4^{jPk6s zEKC}wH|fBB{Grf8ajT~NA(4!Dy@QWZ!;gDy$%Y8E~E`(lXlT= zIm8dJ*8j%v+_f}x+TZtj)aBVmI(7r{E$_R9T3yn22m7NISoqTgnt;4DE`5)X{%nD7 z)Tm$DO;NUAy|Ev;++yV16LfcC4oof-GO0!9`eEqnR>dz+@B^mvb82DchUzt#dE&*9 zL+#>rW%!uec`yd(fg=B_g`F`0t5viZy;1NZWA{SC5l7AEdwqH%=Sca{-k#t8Z5D@G z2pn_9ei(BlQb;g@_-z)u!9qu5&k7+y*e}k!3@L&l-J;Q#+-FHFTj*nG=bj% z`~0v^b^Zg8j_t8jBt&2xIREC9#!$0|>rzo$o}k{rVY078_+c2DVZqZE`J(=s5Qil-%a(SyDmdbQ9~o}89t|$ zA`r9lbjsJ;oeX0{0n)DGG}D9WW5BI9fI-MFkl3jq3JV03ub=3hHlNn}uNPEyY>;9r z)!T&;h~pLraIqf)chFDez&#|NeaoN%;ZotNTN4X~p_Gmj@t1|DOTLij2#mmZfU9bp z9<+&@YZaF!QS_Gr+r{9SL~0jBy!vO{T-xQNDzxPEi$T`{^)CjedJ6@OwmHszeBC9b zgnpl{S~uOTpL@aBxR0ai6$R~_xV*v5JPI#XX>v2rf$;x!|E!t^WO#N(^7(vN1Z_dr zoQvVGe$!^6)NG5FAT;)7I}b1#8!HhpDQt-}Gr>|!?1wcGIzC6Y#1_wujgjMT(`Enj zAQtr1W^Gk-2ZA#LQX;fYX$U8|uH_FRE)3!?K6O;=eK%)RW%fsXM4K6=zWCUCp}#h6 zAP)TwQ(>~mo-B~~1>Y2iA6PutgDr1MQA#2|m-d0Aq)N@LNYqeFMiKBTJMotC-I5_x zi&_odgscqVestW&i3*d!D~(-H<|l7jCPjBmjpFQ2qy2cI}VA4=WjyrE1@#Tslx z;!0N}6Fct7pV(izqb=@REX}y8ztv;*N#0u?#;9)403!0niRyD;?Ii`qv&bgtxGM{H z{3rC%5=x^XPAbqM0SYjg7o@dY@^)|+XE>3KwUUL>RQO_U)aD#`<`kBUSQniAUJ%GE zIo1bLU%}e>=v-JLbiEySv;V%$@miXp{p)z&RYaFIj=pEDNf8zCRk5N2(%c7 z-R9$LqXbth^i}#n&ob@9$@bVH8+56Z#{{k+^Zp*l{1Y6Ab_K|>%nO@74x^poP5fPg zGCN>84`RAlNgx{@XDtaO!>`qGR)W?P=$=S)_I5N$Z{&L+Jjx4B)x68Z{sp&d4nDO+ za26*XPgo$Hht{VtlEs5mpN%Z21y&s%59{GrIUcxhxAT)EJh}~vriF1D4$c!Ah-R#Y zBEO8z$uALFbO9h_5P*_Y0x>;0FjGo8;UE!gRuVJ^O@PI0H`r9z;3Gq-U#T5O4dRNz zNhRMjZFM=_C3Oilu#DL|En$D2OcZ;0~DF?1I|7S zP3!$oKPV9`klh8y)PBxIEf9s!z!Utx%c8d82}_d{P$Of_dA|8qj?Y(Na9g#j&^V~% zmxI`QRTidOyMee`CD1C|KULq-sB+)mn2H*co!%McB9jnm`E1n(t(2H$v&ss3dw)RE z(_Ld;eEv0^Gq-az*^0?DHE#D@pQF`BrwzyY&uh^IDLY(}RdhG)V11IQ0eh-CM_#vp zK->-nTvK&we#{1yzeHZ&IGSq1*9rTc2cumDMb6oCG;{|ljKS{6Dz`!C*VC{FfVimDM}V9Hf_9=` zlMmUZ@BU9!!BqIO(FoW6q5t-+F&3E!D6;QhRUUSjgIjIyu9~Ain&k916~7A7)dEJN z3&8^E(6rlA9IN;PC(Y6D&Gw&}{0jl7*s(^4S- ze5^~v1)_Wkwgskim`YiUD9d^@B4PDsbrle;t< zYss$oFiFoP{aBfVQaY$LLq!0$6_`;a8Ge-xqQ~9^3E)PUyS$(}w@(SBKKf8}2w(F> z{~T7$q4QnJ3b*bGJI$PXEZA_27S!#wZ9@;vX~FxGfyGa~=(TYF;OElm8ANjL9+yuM ziHi0^J_%Cll{ov@iK$dch8IxM5_fWvjELtYlPe|8Dw$?I1)k-W(?|fQnSrcreYTFp zOFqAa9aUu=X1&W{66#JsD%(~gh#}Pf?Kp;>TNRxH5IAc%B+TP=PtOS84&8?ECQqLX zevka};5G+3l=*|zY}^ALbvZ=gaU^tNqYe>ARh>hZ-eU&YI``mvW+-*+yZBN+U;uQ9 zQJR-MjO?8(2iUQ&sgDZRe7DpN=4cypbuHcs1u5<-s~t8C(+1BMX#P;G#Q=%Gw07$; zLP>xqKTFJI5#^H0vi6!s1VDlG_$ma@z3L^q3jo*C+h+`Kr+K`$FRlmfB?Q$lMt1(N z-Q$GD`si6n_?Dv$uH#@KvC}@A6x*K?Do$c)g{k3cK&xYQLGpm#!BG8dK zwx|GXWJ$Xl2a04N<({?-wm}CMqL9nWM7Iz-oC!6QM$Q@;vTB-zUV${FviJ98eI&k} zY1sdcE0(%4d?o|)`iY&vy&Xfy;%PSesD*o(_qqfvNsWzMDb$C8ld40zqX2n+VoA;wNxH%vf zjAQN0(1wYVhP10ckP^@?e_OFLk^YZbV4)F)eV>+lWVJt8aWES$^`z2uRp&*U>7$xe zv*1I^5&7*2+v&g)ayXyk5(@ypye55;NIO$S~Gh4E*b-}sd>R) z&?AHltE$>YRIk7S6SBeRx$I~*U59ld-y5=(eY~=Da@@)*sP<1hGHHuuXMbl}Op0G_ zhpSnaA!!o&-2C{1yTqt9qv-@1Kj|s#wYgG5<`%zCG8@is`9y(>LyRQsq^J#Q-3=@lpPyM z0tHyV((o`vQ+J%5!n^@K@^qJlPlPW! z>ocv(MOd#`N?Qd+|9nQjghX_pKl9_t_j*J?4gnkN4T(KJN8N1ks) zMReYKl-;}Zp&`xdQ%jL7>-f*bswX}vI4;vk(x4;CGp4@|9A)`+Kr%OKd1VfG5F1Z= zXVXtN`ChmlWdY_1+P8TEq-4tdYZ#YkIhzAap(v{D=Da!ItS46Aq_*)P!c2bU)h(kv zC!~w@1NHcGt-)`@Z((jIYF255PF0LT9LphKLhYaB!6B*Fd71Ols=@nwLf=Ky{9pKu z&bCm+E1x`@J;$zVV#wVlA&+#_Ai4Pfz3Nfd*6LMgDER3oAztEsK=GeVAKv)H$k^OH zw1Sby7zfDp18N2v8E9g4MV_A&sT4nDB1loQwn0^=YPQVM0*GL*mPzG5{)2d2GYnYr<#o`vF)(MD8mdI1%hbR(^-xOc#-&7Ly4 zhyVj@xG(|3{rP?Wso9DlzSQ3@CraX%zMbeNUAyRI51Q2O9*eI7M#&v)mXej7sPJz& zWB-N)NgvGdy$d{>H6fU=G>Na$#xuSjlkc~Hod?7;Q~Q8A@3ly~3OikO0^VA5v)spe5jv-S4)~`tJ5~<_&|!Aj|aOk0LVxpUbs38pL#f~YAgwd#8IS7bMu}5wN3G0x&NN$h#B9g#6akO&g z@3U)Hq`-vSi#ib`WexqP(fTw^L0@q-M_sM5P(*T|r={?F-U%DuD=BAza>zBC5z4yXRy zW_xN3`qt+}2>3v;JxdIvst);ie&LC6*~D~cI=0IdIhoR97U^Ihs5C7aEpl z!hC@pPPf^%c^_ad(rj)*t9;AQn5E&eJIAPNymt(Wik|`rUyg^7*_qG^|7+#aMnp`Nq+?dA&ipsaWdU0L`3f;^T^Ok!Kh_T>q4GK%cDIy}C;Eqn_Ml1b zVKM!P04vhp^*Q?<>_B(=3)ff<@O_Yct#3!A__VGnOrGzy6t}tkK6>{OP7< zrDO0FJs6MhjED}mmHkg27I;Aac|)`dnhj{mQtsW|mjTh+?Av7fZ-D#ve4CBQNEbZLzpAM)>PS0h?^$ef~E_cS!?2 z0F(e3{A&)Jh+S*~kwO^Vv+r~4k%%<`rU+ZS+$eqGy66?S9;53tI+!taaEuSna1B>3 z^_7VccuwQn;5WW1V`=^cT*1XcI9iu@G}vl;xEX%vw8_u=H|NEoYn;|TiL{bJ%I5Q{ z{*)O4o!x|sW7@(jCBhAk%|)Li>3=vm!5YP!T6}Py&Nr+-zdG-fNrM zEt$TZAU_WwJA~KwwpHt23o_P(stqEYl(x$Ow%CCke`%W?vr$q9ef0_N}@4mL-iTNFXQi<;| z;9v6c1>gH*6~fA}3?4V4NA*^=aTce6A=8zoB9l5n1I0o7kFToVn`Bj0VO4l&yhS8u8Wf;<1IcD8jpUVB){4FFW{Czs}$X+h^9O z=6?Og&EX3ZY}IKla3j>Fs3a;>IWtV`+P60~jJE4c(WAAF2McRDi?=1O%NfxghUxQ# zs5Rb$xwszI0rM>mh4j(M*K+b?2)6IA6{!(yrKydGvW&OX18-a1!)nk4ELXK%MRzGX z+Suh4g!KWV39QbT^Vi!`vY3&Q!K{Z+8Tx9#l_1)#RGo@IwQzh0_x3pXnEpYD$B5H0 zZiGQyc;WUPm#+L?QwieEwDAw3Mh4NHS`mulPm}f zi1}wyD0Je|n9lmGJ!A=hiAoVeFJ}`^7LvfgC>3k=L=C?G@BRYPr)N(d?IR~K>i(#a zV!F4S_a8bmOk3;#^BNM)wA0xL-5`4b36!1&vM7<~vMWmVbG^p)k0pwGJtdv<0)t-G zfo}#!`~J~>@Std7#i%k`S5k%V(n!@_LTwB@;81%5cQBm(;5{TjZAIU0Shq{l@Jh#u zSsPiU!Xf)nHSd@EekA(MQla5%D>}&$|iM0|Gq85wWkgd{K z)T#qZLs{_OCXRWXiw7%#uDz;oB-(K9>^ygApnL0ptKU$Bx5ev~|be zlJYyqPI4AU{_NO5W=B7oxQ=n}#AKj9z}H53(6f$-DgTB7U&Z>oQ>$QhI*$IypQ|C@ z!U`se5y+nh76gU}gaix{jXC!Lpp)6G^L+oSM!?_yrzsDy$1)?#I5#Kcl_mALnV-rYlBd!DiOdyyB z!u-ua6Tr591Bx z#L_1_i0Sbc+V&0FzkifS#NFY_9Y_kiu0rQTUTSQ9qPNoW9`@QQWOxB!E0P8oEN0I)eGnJ?3fV|4U z|EsjGjH+YV*2P_dJHaJDa0qU}-4^cd?$UU0TWEqi1a}E;L4&)61PksCk7VzA&e`X_ z_v`f-J*v8D)||bnNB64w<~OTg@@^yy-=ixKZKD@`t^@`Ir3@Wb_nUA(VGYWQk#2Lt zpndQ88*Tp$Z$PhBllFHk-*u>hlv&GulgccAAt zwgHw0ubk30l6bC#!+t`@Cl0PyV@ew=+jYXI>(1qRM`p2>w|O!@Xda2(w*b)o8axut zc0F&sM;0rwBiZxi@La5J%;PNhwY-0D_C-}s9Yg5bvMqUNSmT0R@MY@ahKjgDy!!b5 zMC6rX!$6bBeI&_vp&SnMCn1u?vkp#g{I)!JR7my1$O&jgT38fHW)2|yVx&gCl|vQE z_Rg2Op(Kn&F3dey_|NnS_~-noymJ&S^^JFMxwHP@i{FVnY4zHpR#h0Qj175a&}>U; zd`UdB^KFhXTg}~ug%Ou{9G5VLfJbrbMh>2!se#R?yrlfIY><+xQ`LHZxeDxJzXaPw zy|%L7C*=eUL1y)ix6KrygtpY(cOwUmrFq=VZ-5;)V{x6HYujwiJG_z`{Fvd-1P$f` z#)h)r>pYCHB%l#+#nEYU(z@NR`MAifaz0*#pQ0A8sWGwX5#m>1a9B8?LQW}4`OMzr z{HWQZNExIO*`P((XZC=ok6gsWfb*r)GG62 zdyiS-C%r5q*u3pct*_JdHn7Dte2Jo{>%GGq4>x93C~|SF!?GH=jO$M2yQ0ijCZePikEm}p=CSz z&Rfs=u-j3(XFg4Q4frPY@t#O(ki%)RjvCY%zThHmewa(Sgek9>mOyKAJ6vRpb_f~w z*@+{>R=nBZx?)3Kw*tDlEDQ=`zuY7gRv0J<{BgD})*P&d*qG4xQO$pucJp=p5%=Ie z67D^8dIBw~7$r2`Upm+dia{r2m2ku5QanR`%4!y>qQ8ndn%_P^w_!3;E}6PjO+>a3 zVtNq{7YcMavi23e!o)u;!*SI8{oQbS`HZkm2*JI$_x|mf*WQIGy5UIi#$JzRnZ+(`VNzp3? zhwNVeXtoV$y8K}WsJtnq0X@1bTrJE#d);-ADJ6eg9UP4hZ&S83E@qR;ZW=AHP;t|? z9$V5}iTHJf zLXWKFGk~D@)FPl`v)mUYF4EYpX&NgIe?mB+7-1~#XrTGW#L4VBVr?rO1U=h(Y{Yts zS89dZcHx+1D(8zaz5Ra}D#G*d#5XvidZ9Cs(1Q}iZM;7tlRNIw#fZLJRY(Z|ac}h> zCc6QRPt>WfZ(LUV_aP=MKqvl&NYt#@TA(P4%A7Zx@I@viGGkH@20DSDSFZ~UvKe#w z#M!x*^o5bj+DM5iZg?XEdw$S8n=}s9Dp%T)v^) z!wp*IR{u2jUTS|=tzcHca@uvdUMdwctgKo(6~t6?W7ZL%EM%pn2rg$H9v}Tmmy}iKTZ^*u{x}Ta zsIuE4(p$Ur)5mKUjU}D2d2&2ZDosv(D)u9d3;RZx|E}A0+cIJMS=4j%rb|MMi;!yT;w0}u3d0w~4$3zhdi>ua53wZYxV z?3YMrN-Q%VF^^?^f1`y${kpXQcx6#&=Tj4T>aO`?9Zy4)u6dr!|Icl|B3j{=mZ~ z(VtWLcz&XKo{7GwHTDip!&-r*?2?p1y5poxhMpxR6xw(DajxGSz#!Xaz{dHWe)Lhm z?!z=h1m<8IM@=Hn=dCn1p0_t|tOk5HgJ;kM+VJdIpTZpINmRCfiZ`_3t@70P2R?-loVUR6w{z8!?aI2OE6}MF}Uh=J2UpeweL$^TR~P zc2%N)_GenG@Y5YxB?5K|7?>GA##r+kYR*1um@#j->s#by+qLF&*~v`Ji0Rw~Ae zTjAnH-}faJVy%6H+El}4lpi%yicKKH>?5Mmh~LiL$^{6O8jzXfgE5OHhvgmEkZEs2 z7((%99FKl>FltZ1x-5K#YMuhWAhg+$f$9Q5W zR*^Js%xXfa6X5>5I6Mqw`+M!B3#pAv`W#vkG)x+cmapgWlaS;FzEU@+p0v^YMZPYU zV2#x~R`1f?f#PTM%2TReP8l^`&L=$G@& zK&Vm1GPlkTe?#4m3PC1)8>@5F4#Lj%$omdj#-kHt9x!$Xsckz|ssw&XZ=6mdXlHMg z@++NA2bL*AmPi-M&qaDjB#ga1m{*MJVb&V8F3KO<@hz2zX%egD*dhByElr?N7B2Nt zR1HKTh8Rsy)ClXa9x1a^(AYhcN3NT+7K1S3C!QEim^D5`x5Iz1ubHf9&E-J3m%@kU z0>TC8O-moyh7a9QaDyetUr~f8UV>f438(XofwFDVxd+k@ZIp&Ty_xB%HNAz9N}yh8 z29^amnO|P#_j4Vk-Lf`?m3*D-z|dLySyQpuy^GMrCM>Eob;rO@Xi5SN`JsB;8qynJ z4tSxB93I1_V*Mb|yMr$nbWwqswS$gZoEB6aS8E~1On{;28Y03f(J=mkb!!%#4R`A{ z2rTygME$fFM^>;OJYC4)exNUU%l>0Z^q2Ru@Yx8*nP2TkF|7}v58)*O?iMMGF_$? zwY$c%*=usxTd7F;uNS|r)&RdP;j>W8 zbUwZqVPQK8JVG)&C6KFl8Tm~z=fj@#L8VZJMV&J>GB=c)EZI7&g11`8dcd) z(hn&}TZ@Go1~=lQMIMeRANK4K@Rrtv53zc_24l8}qh>Z4Y1t@94K=g}MpD4RtHHGB zQJPyjx2fbl+B|Ip82mKyhPUuaI|_5meH_Epz$j|3YM>IDMKT8L&`{R}MF%b*#+ROk9E}YiSEG>R-NPTE zn)L;1`c)r3`yN?}r-@Ls5UYS8=Tvf8eCg1qDVx9cx^jn%tO484_O=#`mIZLi&xCNg z?52xRI@WCUYIFb!0m}1BpFq9ziAfK4_D_P|6U4`~lQCMa0Ty4Vsvp)bPW7{Ib*M&d z(S4;l;X=nDdN!4a9%I4Qcs~dHJi@F=G7u+npLw59r)YV^$8VI}Td-Q~`XTyebN02* zE7#Q1j)Y~l%Jn8BT&{*zi`Q^FJCwKYzFlqw3;HFBjRFzqW~qGn%b*jMN(q5-613o1 zN5rcFff>v6M22|k#DgVRr3z@&X;w7%z}z(YO|T;gIc`n;bWa)a1Wuv=eqsR)n2M|nKVtt+Q@=PnSqB^vFb&+!?>Pj`uB zJB}#4Ojk|dFLB&xYriqaLoK4UIi$GyEzhxAOVXy-rl7QSD*5Ix!^%C2G7!>mEi#~4 z(9GQc12(s_J-C!Pde-(P?#70>kM!n^hxpcL%r-9?c^>|Q#V}m^+MOn`W)}YQiqR6& zr~|_6tW-l)knVwFj283$+{#t2O0D6dii=L|I+Vm!w5`tFTKR2j!LUuS?Dp{@r2WMg zgVqJ@fXiyAod?e`+f3yHi;s{wzNee>&HpWsO@q> zjik9!t(Df9TZE9Ru>lC_11ZJq7p6A7T4Rh6qo~vf_D27<3SK#H*quZpmQDu7XIw+m z}(j8o}~Jw+UW7KXV~2%g_V1ZQvss>?b`TWn$9n3 z!wbB?Qn&Gr+sd@Pk-sEeB~1%e=*JtRoY~bXiG*i`;-b~sqHU4B3!!Z z((ECU0m64L$m-ZD-0GX^VX9^=c?sS5`{q=%!UyNe%dH8{zQ{KFC}!>T*z_f3fg2HX z*xAqp=&}`LiEdZulC&+5*Vkk{NnFOr;K|WJ%4ymg#kYBmt+NyZ=(oma%6k`AvG~Fc0EuIv@s8FI7AJEK_ai>Xq8*J za5_iCC+0Z({G6-)#ijfMI%-Pg9+z9*qYjjrO!NmSvyk*q&}_U(Z2<#oYbCnwV|IV@ zbH_XBFku9brU;0Z=E|Ft^=e}^gLM21n|p=twX(HElqsf8x~w2!e7-BM{t*V!6jeCp1MT^cqh7WaD<)4v_rU#T=$|lV!uNJU~MUomH+7Zd@D7tLd3rY3kj(8}it``fu zRmsdPZg)25!Ym}!weuAj9j>k^MkhjU@+hgwtu)VTs$SI3J(UCLEO6 zV=#h9no11tOBt54<2Sx!2tTq-vx!-C)mAK@3u6Hk8*E&n_oC3QjPW+trWm3tlA8^O z`HQ~s`i^$Ut~TwXdo)~amS0>#l`Y}q!e=QU;m=J6zXaHbDlmEdPk@adRqNtQRL<)t z_k&%d0|!(Yxl;ux4m*SXg3O}>S0^b&V|tgtl!JKjcq9`T#72{_4DA)awkJ;w=oUb& z4NClCCG%HMu>Or}_k1%+fg;&|p^nv-gQO3Pqfc`)JqGUY&U&q)RVNfo5L?5Y_*NIO z`nR5S3orVtn_+wu%nzjW`F9D;or08&P`WSER=>x2aJoBzzQVBvA0BzwicSf029v%n zKo=e!zltaX0#$%|lPb{$6G>=<#-<|Nr_B>JvHIyuPRRWo7H`Z?X?$Gf!~#&IEauMP z%dBnC2iCTmS{r`TE_j@d#gtW;0#ct;S7WX>a4^rqCPol{Gc0;%ugBau~Okn zBObc#t3}qf8>x%a!H=3w%j6-3>9W2rvcBF%QT~lQ#!3H$Ja*@i*u)YIKFy&EE;|b1 ziU!GhaB*VPD%*3KU|`Q0Rj`=%`j3(>Tz+WNP9+09`s_{ZBk{XI=D%|R3U8&lAq5NH z_Gnn3wQ2AC6?XD&!eSEZ=GUmvzku$r&*}#H+tD&o>54&cNt7#-d>IR(J2hhFP5LeU z^qMPa7>(}7pFv9gmy;9yNKy(8^AD$^k+lX_I24Gi4rj+$inkRpVXxY#rR8 z8u|U9D>WNDC4C7fmhxPe`pDTQRS}JMs%v_1A5okz2=MRjBT*Xl#M$_&jiY#H9XhbO%BN`3402V_ ze){|}vY_=7gDTTQ$>dH=MMT4q%+pEgcEG6!coV61`!09%64)_+3a=JQ1u7KY+jvVb zH*aLgGPY-itY>9#kdO7J;7UP=yK+g|S_xJQ=3|=FTJLO6MY9K@cXFV<(Xe@N>|t&+ zOp5xZjdx$qy_ckJxdnT{)p6pBpyS2-6@)aV6%i5Cm>XHpQ+FT$kNefDv8|ucrX$tS ze%d=xui`)4m;k*&du0voDouF zuS$t_4L<(O^$jEwip#&&%WO8eyil%!(^8ibVcH4Cm;ssG$J{so9x4UpM`kOXs{FdF zH+kdUXk@=TD5l2OOqKP6`zQ7si0BO7vtjoSfGkzAdO}aoS$XK_pU|zscGT1f9xNjP zi{N*04cF3%482M8in2=9cT42%BTN(`>05)uunN>3qtIFcNc0r6 zx@Q-*zOq(X7oD@6V?sgpx$L&u2b7|KTUbRr6ZewmW0i#OjpPUrh=)TO{%}C` znsMQ;eVt(O2j6rXj=zFHlC7FBU;`3q{4M11B~8%jTo5x|kZ_UzCob$GhNm5z-_SMo z7P6B;5a~q5Gz-szbMusJlYB!hIP;l1eNMzn5o#;#9q~DWd3*C)=&+3fh!rX{J9Dop z*!oR__==tZ4Eljlu@hy0haD;U{Jn_7snSQB2~OQ5HSf!nT`LwsCi=U9#j6wq?-IKt zQwIeI^H-A$8v8F5w&-hQV*{UaNoc4)xCCqi6n)P7FT#* zDQXz>kLAJtv9kB;7b!6ZdvkEAAvN^x^SUO+zR;7>Eo^-QhnDK;K`bVhQz5^>g z=DWh&@sArrVNU@d_eU=^PukGFOp^^t;0Ox-?z}6*1ie+d&@07zye;zRWZ?a0mrdJ4 z2tl~KWCFX&x6OFR=~xyvIxx2H8Q8TWts3tzqd@)_c3u%?SbU@i6KHsGT+W@X;5m_v zF&wkH#TDCVA~{eb*QYUT{f}(6MS!cml&ykUI#NCP{-{Phk-W4e2|k4K6TV#vHMi># zIYt;9Oiqq^oN#ucl2f`~Bxh0uxUT9$app+}r4&)g4$OSgK0_6O zq#|&xOId+wOs9y=WSgMNEK))u5M%)>mLOua)@~(;=6sNjXRF0VcgH3XaGQ18SeUIG zmcg3BsVP@c8IH|WYARHq6e4T(N{KSNy!nQ$ko2+sm`FtHwSxgext#g;M7WT5#ugHY zdfHTCJ($zq4H4z&bSCN_`vJS3!+VD!u4BTjV8MsI<<}keSG@-Q&)L9}GNF=%>@KmX z5Kd$rDl3#1te(`X2FM_i4H+3fi|n5DAcGIV++CNlcXtS$3(r(ySgR$6bL(X5LOD7W z)BbhXq)2jv*rX65y7@kycd*V!V%Z+tH(wGKi;3m2QLl*w0+JBrG^Q5PZWcwHC~!GfzBG!Y9PEZ9oZAWbvHT53#+ zcW@XY&Fzkc2`|c!R;6)xy z#kh&H?{q37U=^{$No`kTmqt$Rs&b|_mt2I_sf5KtS}l*ooiYhe6#}S8Lo1F8G-BDGeU!Ci zU((@MBv`h}6Ya>;nv=~+szg8&5Zu~~wtyHKd5aXGX7+7`-%ifu++w6q2GBHc`V{R> zUMz4vf-J!T)di_<{j)MOZ?6x!TI}XDDh||5>rr|N@vY8;e=Ec3a9*N;*0L3}h1`}H zdnMKSP4-vXggB6%Mv{PN(wRTUUfg(9)a#WJvhqXI*Tbln_?inJ0cN3YTIU+$q+Fff zwsccj2dC-vF4|5D@;v|HNsp65aQ6+=CD+j+r(*eLO+X~{`{`?yY8oAJm80H(JZyu3 zsBJEHjW(9C5u-D5tei5)!mcO?pJ{A?$aI?^h~b6gQ)qxn_7l?~Q{bV6ty7HHW)!PW z?9}+3vP3eujSqg66E7t@<+(h}D#YY%i|+9|?TR1xEh;y=lk}9C5$=g^2=AVn2PS>j zjx|?xvsP=$EC$-bO?Bz*gkODqW|k?HhzdNwyj*uCHA0|DAG=%!C`_<1C$b2R-$4hi0dp$$#@%aouJ4YRvF^1lS^ZAKYckay|hvgVp zbnqx|Wh{Sq${*(MUdk#i|K5XAoy8ozlI%IZ2Z?vf4S``d`5T|}NP_p9rk|jd7#(M# zy)Gu6hq2Y#OVx*SnUoTKNn*5b3ZTjF)%SF&Qk;Cwhu?>EeHJop&|k7f4D+~p!8Tl* zS?K_?TpaIaR%Ue%<C9{-r0b4 zTYpr|uFUQh9muAm`6Yg1!uiyN@vh^&7}4(Y_g|jZcE5@u1rFJ#oksA;2cT4IkX3D? z<|~+I;IuoO1UhPG_iA>3U9c9F(7tM1-`WFChf<0MSD6&!__VV~o3yjC5SSIOv$RQi z)oAmOXM&%=<&;AVyC3D&?7z4;*Q)=L_V_#ljs=y{R=k{0=nrwpxWxU$m-%Q>7PJSm zOsa|(;M>NvOox4vmt?p}+yKX(_be-&8^NOQ@moMF)iEUH@fJ(~xNr@8q;f0`NS0m~ z==~DFAnA({NNIQ2w5y2;r)G@iu)7ZoK5SxGtBP8$^t>-jvO1Esr7RP(GZFZj6w>wf zx-}9mi;Rrmd!sW#c+ux#tO|l&ZRjwcfM#px-Ecq2AC9rNMe`v++@2E>%BPt{ZLD-1 z5U~e5V~t;87vNdOH8&-6fVRMLV4(a1Dwzq0zN<>*M}~2M_=l>ljS`vi(~e(|rfS#i z!M)@=2l~BlvBP9lZ>#LFhNTXokQ*!&o*c}!nu#d@wcCwBk$KB_a3h>ndvT>fF#l%) z+TOzBYLCWcGh<3C6ElfRaKh_`WCHlH&)#T07Pj$WU-^_~t?DOD-P7dr0eM5Qc_{4j z`Ob$$@(9;YaF*VBTJ4imit&o@_VUP16W2wa2L+U+FRJ=bSi9|vcpv*7)zO?dz@b1#>2PS&_MH(N^ zxsi%Trhk}wnFkW7hh7I1ar1XS1j>?1S{vxfFnYwF{tujngE&) z(mZ0yMG4`8Ov>O?O3)yqR?oW@CDeC$H`8<~GTwGyO&if$@qTVVpG;j#fzNCp+&YF# zeuf;1zI!slhYi&ph<;4hHdR^VL8t359XOmAF3P~BBCg1>4W=cA<4M=|8h0nsdhu*v z^Sz5jBI8>yR%M}pzt+htFLiBmqUmVrODl7bG-7;LX+mAXeP_!dGAS*DM#i9R-b>9e zv`)q9_jDwH2IbC@>774b)VuqWyzt}av`ke;Lc^-0F@9MYKm-qpccx12L-_$IRuqX> z={kx9X>ywQRX2O`vm+F`=45VJ{YT!(MC-1H$e7B?2sauxKaKG!J%_eGauLzoyd5C6i#OQ!}v&gk*h|Tgm%cs9(&*lec>q-L?seewF z^xLLTM<0<4T_rg?Xbi^<>p!6XUP|V4&Z`3RC7##X=fC!8sGG1;hx{|3rgLEb=k7jW zO9%Sbzjy5U&rKeF@7VM2qYzx}K=eoEKi8^xvGX5CAo!O9A=z&||GjF>zlD0J!Bmbk ze{MtGkqGL-0Gwb*3660@`fI5FQp9Qq9ycUKg@nR}_}6|!;EyjAR)*keBU~`C5dxUR z>EH4%fy;tMq;LKq|Bnd@@xQIV!AHR{VM^Cz{JM%;81CU@p@Gd&GxntYrjYs#KCwb<#<9 zPWP8D{d@p=a0rU1C<6|G0RjR80zzT^Jq}R`@n0p9>=y;e009ERP;2cC2CHT1Y+-3f zENhu?0fvvr!obR-%F4pa%E8ORoPY&R49?2Wlt2QGkst@|4bH~RnlJ{w5BxU@$p7m> z_}6web#bw@Gk0e6u(i3+(Q#kpM)BJ+h}&EG4m;S|;DF{8*;fgR!TfDEg>Xe(D2m>b z0!P&EV^p^db^w;8Wi2xn+eqhbA~)@Y9XDc(Nri|=j(9ILo{j>@qm_(pnHM#2DZKYy z*qa(nnFS0|?mr1zYmSw;?nzLG@Zm^8uE}WRJsfYIrD1Vsl)F)x(6&YOG3?@?Vk`Q? z6(q5bMzP$BzQu*mnbM0XjvwSv^M=VQP~#ok28obx0d2Ua%1$v7Yh~Jzer4gxuPRFP zHOyvJvMLMp>$}=K+PE(!R_uih=^+bCOnQu%^ngHg+%G?VF3GXAT1$;^Rjo|oZy%W) zrU~oLIPi}9KTFtPyx0}hkq78wkx@~lr8>ty;BG0mbv&5rgb9fiBDsXEk5{O|g4B#dRdP5(0`o{pLSxnZLb$q+CNgHv1~$AiWS9gIhiKAAQZcg0Bx$V2NDBYamT z1>ppb6ie`O*nl)1b%SvphH$DEF{ty7^sY z39c!lpN?<$GNo6e#FQ4|fot~X=z1;9gExR?RzD>__gfnzK2i}@{|3X1t8SAUiqB)6P=-iX5(3ZUqM_1`D+nxpJG66vG z!M{vJ$#r!8MKJaCos7kGcF)t;du=|wxdYwnw4B$+{MHd?U>TJD=KCO(YlsJTB6tLG z1ZE-*1hOsE-V%uvs5>&VLTHQa{BrC}>&N>AYA2#!M0iE+T;Y!OFiV**i>dW=>Y!BO z5~DoF1;1(Q+juq3xHN%-rPpx+V-#?T;t^|_-;Xa!O}=FEYjb-`#2?lFaNM2xkW$yc zwK#(V3aG>tD_sJ_XGEcMXtZZDfBTCT}l-g*xF)y7l7 z&6+}9aJu`dh2uxIxU?QA({wS_fuJxLZ%E?M-jBX|$$DxBNdMS$=k7 z-t2aqk)-RiMj-W62oOPUD}`{k~(&gDfM~YpLSCdwF)xCemc$~0Z+tiaR0C8aq6msct39FGbSze!lkxr8o8^7U@IYF9yZpN zw&O3l7hcRNpx1Hd9h_}uS@A851`UP3;j`8FDAJ$GSswdwjjXl*B?ex!8_08a_zFeuq;!yE&EX+-AQeLA&FuJi(DRpXI8xtD{ejL_xpC2V67! zwV@Q)K4S}rFsv5|Y{bANa{J$}zEAhsx7nCSI@7~+tJHM;?|ehfBRmq7SoeAA3|T;y zx9=S$C)-oL^Veg1SA9O_{6L<5iN<`{0M>mOP)ZX8dP%Gwnc=Mh9c9N{AqLe+&kE;6e_-xnbljE2D^=+ zN@E=taeoh;7`j~lcj6TsstwHC9w^Dq`lT6XM7FqrR%eaUvKpN8;COKMvYAj{#wk zNf(7>{?n6OA>`PY`+8GMcj zT95-zInXJQqMg4i3cy1WRd+*?TGgUlJMUotRY{kwVYi63aPETYlAKIsBzV$we1=<_ zax+LPLuL2sfeYm5=f)EpWY(4XVzBKQ**0k6S<y^03{Ds zeekSGDFY>sRDGbVB}ECI0vG4ZUn*442cCi<-kUrY2rd5uK9C^=vG(A(;RjT-LU4)9 zY`j<~BRd`m=we)%p#VEs+&*hTdNlIH4-i|@y8=1vyd)5b07au0lnF7;EQ*U2lnaO) zQg!M-IB*t5Y(N1V1-lHW7$+S{I*Wjq3Q63HYj8@t-LW@#w-8+TXe%VTyIN&~bx#p$ zd{ghYs201j3jO+qaAmWZA%^^_c#x;*+0S2mP@MSNgt+V24%@VMe?XrUFF${ot2kM7 zf4}ci*w!Lp-zKE&A-Z;Ajl><49f=H;0! zj*dQXX1iH3XIHAp*oZR)#E(K*>k$N>j%PPeDJ>fgTRXAB>K?i^)hRP9fVR~;+h4h% z!+UjF;pE;<kj%nSA!mFR!gYF|Q~S%rg|BVI(r zRl*SA9s&}jKAlZtr@@P9>xR`mZ;*uuEwiQhB{USBa4imv2q!KA4WHAwOW^OsGUr@2k1zzsM;D`;z&;%5=CCCyJG3{MJ_~|eKWr`dm;*N{fjpY2Gj*YxTdRg{!vN%EC`0UpGC!Ut^hC=)BO6`ZB+o!y zE?v`0?{vlKux5q{kFg6O9IlX3uk|y!k*Zczn2B5SzEO0i*R_EMVZfE(mH#QZFRO_- zWg=(+<+aE;5)&T}cQOz>b}g?^Tkv11vF~wNT;;g;vRpEZml0faQE^UhWC}mVT89)m z_Xdg{Ia`L{ImYBg`z--r(tjFCeIg{`s@+6sH45>tjaExL8l-fj{zlCER{m z;E4O3xrh&|4RM7#k zISjG4IJ~g|!{Y*JCFC16r^mCM%KaEWw!X*9ze7u5^BG1u)_wTRoC?kUDws;09w5$< z9IT1^F7taSQ<)yIHpJ(Z-=vyHR>U&26k8=G(MunFo=P5-40Iujpdob`k*CuxbO{Uw z_nc^GciA-bp$RzjVu%hSQ;myIbj4mxfGnN2Vu@B97-Z&8+HK6UO|RNESv7KEav~Lu z8eqX1f-RZ|h>3fNqqEBM-#|(b2PAn*xIB@hg>h)*|5z3cQud-N9=;Qf%8z>JmV&vN^Pt!E}J$~nA!-Ja6OQxcyW z)J=mw!%C{xlO_BU>ROPTue9>>JG_}`US~SJ=sP)acP+D#q9>l|Q*VejfK$VTgEG}& zvTCv<@FHBHLSLagGFEde_-O=~SmuYM{Dwk$&a>|nC>b}J@DqVpaJP3^hLCL9KF0Ng z@blyF7=;{*sKi?QGPny`$|TQf&5jP1f!M1tq-gr)__EE8{2a!=mKn1;-uogsX@b~lS@t;=s;bD-}4xs5aol+rNqVRg>A1OvT zY{>yDu>l?=vo0Olg0*={65P=Q1FsB=_I8@m6N*@z#MVAF@jdU5@k0rXL#H=N$5pdk5V zWxa#;Q6&h5MoI2RO7`9jk3UA0d);_l?XRZ)p%r)5P^L0PHix$?1P$cVB z$Q)E%b>xDg<-Gr%qP+vF2o56bX?ML{N}gq$n&d=KQhvq}Yp4CojRJY!Os-U&#KDpn z9OU&A=sRm*4X1X>-)qht6KU zy}on<+uy`*5SyM!0Z90Wjl)Qt@#b^kcC(PpPlV@!Q-@N!t_DURoEC7S1Qd~{CHgX3 zK7Stu%)i-66*es%{pD_ZBCl9YcSpkI>OwAW8l+M{%Gt>7XzIox-)8;MZ`K*QAfgeS zL)dWn?tDw>R1Me_SJ0_{5m@YBP(WVb?x-m)Aa~go?iLp%EFRf&`%aEGUvBvB$(HEl zBzrT@I;~$Ay1iwnptzzYx!fee@iuuAM>n$0!pO_!RC9lK{@gufZLjTUa=byCd%hey z%x^bz+?6gFm-Ha27tp=Kdb%q;KH}Q*i#8F2N7t%7MglqW?cSExbIKwg5tm)pR?CC! z9TH~NnmiEf%=l2}dSooTmJ+&1aUTgBVKO8;ePxWXx0W^o_{THAkBjq-7&czJWXY8;YR2X!o`(8Hmo2a zq+K>R&3^rJYH?$&(w%5Vi-@BLRDLe?@VJwytuH6f0WC&RUhWE7Km>JL z-k6*WgC|W4n)>m8hA2nY)z;EIl69*C$bUH6YRvY-THf7Vc`$@tY`*>+hsnuOito<{ zGGN%i*ZQ}awtLSD-kN{uEVn$A?-ditZo1&;3cB2u71a>FK}4%>@SV@|-Ee0)d0Z#X z#`k$d;>IYEt(da0NEB{3a#tfj5uxIGXO`U1xLJr?;{9GtDfU6&%EKm9J(`tvYqBL z0}F*MD^qEkvOvpbz%g1fsmgQEwlZcA~gCpT!!0@>(Ug_6a zXO%KHK{*)~(>+=&PsfZL#e~(inLUWw?3W4-HR^tlZLhk?z~!C#(<;P;woN9zTieM} zbSGd?O8$%L+`0ipJ%77nXms`UEMpC?wGe&`W0|VG9@*kuA=RW+mDN>_)^j**?|+|pv;Z+tA9 z+oG^ci+TSd7VSos{i1LZd*k7d2omWIE5C=_mxGW>JY?Lh@BIAFzdZcV|1P|y+urU( zTQi_3hhZoZ_~OnSHSH-G0U-1AGOg>kkhoS9^^L?%5PyhJS4MU280!($@G{ms?I{wY?%s@$4elPA*eRsWddg%rR5T%YQYqqU_TUZsr-fNQ>Mq4_P&= z<`MKDu1A_lY*vzZG`6B)lZsedu9Ff(5)~Llfiex_!iN-@vC5k~FKwcWo@t2iNYq2p z#rvpuk>}ObgaXiIx$$g$_xbyf$PakFC;EE*oI^55JCa$9h^(2O?C6wws64oatbHR@ zC0CMW><;C~+3@lgtS6=qCEpA4Pgr~>Y&-;`#^w-uDFq9UC;9chHrxrt?U8m`9*h4L z^ld3&HnW=fuKZ}L$XFZw4%|qN)#$w0cs^1ST7@wn^%j`x!@$KHQcZ!&c}Y>{bQ*u1 zEi7En;u?r0>aCQvrZQx?!eZ>GiNxDFc9~}Um7BCouMs= zjDgO24O?AZ1LnJ92g~X0%i z7FlOp3Z*jl)P3c35fbTpTUJ<)C#bbDo)sdVetOI#P}H~885j-D2m=-2dyaWhJGAi! z<(I}A)()6UvclsZS!J=X3CF~3oZVMnwD;qgi+tcW)x>Xa*_czwoG$nK2k)r2=C6kj zCS+tnLP4)}4=^&Bu?Zb6+$SOefp*{fbJ*cP$JrXex-s;GEZU{-o`WLUarEZqO5&rl z^97gR2KKS~SnuxiTA09Vx%)c0yLX75Q-Xjx9rHDBBVHAMBh= zd1t_*_@=!vGQ*JUDg#YCed8eoMugZiCTJ1*ve#=GS-hm+SF{xCM7tog$SCn8$y|r? zbjyt|2pZqaQd#NGCaH{{7_4bvyTu0#qhKkrg(y8PX!0r5!*`a9Nuzl;=6pMIc-mO5Gy9|IISpE@yH&OkR@AcTZzQ_Ifd;@> z<;Nr9&zah9ttp(2cqDgFv!#!yR8*ed1dK8a$;<6l5O71ro*%Vq3W@6>33^``*Hiq3 zTzvZz_sEK1eZ{s>MwQX@B;e4gZIF5N(?5V?=?TGc?uj3)dU4{s-|@UdW*(75mxr(9 zk^?HX)gWCnJ1sU$0$YBm%yRb0TY^`kvWu9)oi z$Lnp!B_YY!$f|6lebD<>@;puNpX3fbKO*HX*BY2Dw$>EhW`wx|`(cq~#BKn!RlIBj zBAFX*BYC=HL6J3{yGAq@1Vxr@#3RY`QliyaUtr-6jc<_KXnpy)-E?zjT{53S(~b|( zG%8+fgfSN}Q%NuLoMoLCDhCpbQiaD}8*`e9}T!q4;qfZH!Ys=pE zW@UfzM>jvi`JDm&hBunF>o-6fznXV^@O^(|r+zI#g9^@L9qtpw=qQ$?gR__I`~N`2 z1d*H{RiDV$di@m*)6GjX{!jkTgj0I@ZP%~2e^rFS-R+Xp8P1g(2ieBrxO$IZ!a`^Z zd0Y^id~xc@U6ScRli5FCiu=r;@R|iJ-nZ=4Q>p?-zQw!Zf~5dSaX&Cy3ThUeIAMQZ zb;qKbAy~YVBr=z6T5!S%^JOKfcN>1{WTYhPZ|okAi*2`Y`7f|@-hQ)Aye3F$X;x6O zXUYoLWGpMxI=3lC>!@IrQs**v@HNf0p~47DsTYyPI*{dzs>ly?r-p#PHu$dW2)X_f zR4(V!r7a}kxZ@D$>0FG0Rz>=vnDKQ{`1)?@yZApS@$cvH^Gf9&lb`4PaUb*0fLJk; z|Ir){c`{g4A7UXn!UHZ>1QrwZD*OL|lN6mY%x8SeS2D)Y_z5tRCo!;tOxQ3ID`XaX z_s8QiMK8}Wlcx#4bQlRcWas6Ew)_a)Rq%oQ$Y}d7iSsoD9p|C0kMV~U7hmr@6;b0Y z0jq{E-?!!F7~i)9s*PHE!4ErJaNbpUYTGS8n#YUc%2t}!$CKq|ytgcJV7C*s0zAG~@VpB zW!l6!WYJ%YQ+wd8N;!w7%!7!asu_s)dKSLIslD%JMCPgPrl!Uj4g+jzao zeP1_kyty)fx4xa8 zi#_)o4m-cT>d#oqO~C!6cb1|Jxn-MsvvE z^rQoQa#AL=?XCEyETgRDpdjG<;l4?Q3oa(g<#g*&mvk*4|t6f@)shRT3l zDiX=#aIlFWv8e|ChvkBP;f$eYsSJl57guaMIjKh;+O%9>f4K6H7{qEryD|>y1Imor$P8)9Oi|Zukb%nkiJoi4)dXe4#KfXrcTrv zI%f`ADMf9y=_QQgs{pi3FF%X{UIhy!qP0YFHoXAyG%NVVc;*u*Ib%+vVSIp8AzRW!C)%I$HOzv z4x2aWZ%@&~z~{+szut*#%@cJLK>ROcb^?+P*Usrw4H~RhgkL@sGeZoTzG6|Kk@~U# z+}Y37T8F)W#*wdqz$1POkm(Jb_$J#5V>GG&ivGwe_@joj{Bj9lft{n%s+Vd_Q#Q5) zV?s}@(JM^jVfSHEO^Ioq&T0YdR<*Hv%lQlWzY8ZPxr1~p zd}|jz5Rm`Mw||KQsul^m6g0pn2nZ+$4A{RHzTkdoARv5vQewiY9+?+e(3*2r*h2|T zLMu9)0VTxTC^&Yy)JPbZm=KWoxw@IT+={|tkeG_=2+$s_c_l3lz~q_GJUmQjC@V%B zP5tx(2ZL?GY#n^%{uBQ!xqW=s(FBX_7ta+BH*FGJZtgX-u7bM|HBi#QxrK8D_8b=^B6&baB18J{Efl*1AaegingHQzF1xjs7>@>+rk zz2BTaCPYe$E@P#`;yOPu;nhq&INbUr#Uh0K*5{@5bTUt+%)MOTr2fms#;zAU@~gp= zgpP%KV5&GR3nJEF-rC;bm(eRg)(3$~VJ+B9H;2FJNvR)r z>B5Yz_+%9qTrmfFReX^-3qt)3H(5}+vW}1robyodi19n}K9^cGrc1p|8i!<`-CdJFiC%=f;yzNCsqmH$KbMGh=c z9AYBykXa6d*_U!T<2Yq}_K!QR8Q7^l18G@ajNJOZS5ny?+G#oNRin!e3x8uWd-wNs zJy?~YO=L2*)gijc@k%>}7<8%hRxL3vCO|0303%P1$R#tAw`t$q^!DY#b8ONk8??-e z8>*wFVG1ZHlNFO|f@hLRNt?!RgHE{G>t;Pa9VEFi|HL0@Y_eR{L zHYUgb=^UK>8x^WeIPuwU!Tc!0e8`{BUlYaRc#Zf?96h0K$(7QNYvTBfO<^-j>W%Y` zqS9?22cy^Ls4QbJ+~6a;kpazbI$@o|j_vv;8=*SNdQAGPwuQOS-P8tGEe~f;EWr zq6`@NERQ|_d5D5)`YpIMN3&CQn$<9&4ci|d<#!N$7(U?%W`tJvq)tVIilQNFy_@}cobphWmgTc7@6 z15w{K_*4aDPEqqBN8%wD?QzV8pU=lnevqu5xhsmaS?=LE0zC8qZvOc~N)x^Lr9rO+ zQ>rJ0E3)m&wP&(QRVj@aP8+hu{!l?emLO7*OY75cm0EO}C#z%0XG|Z*Acz{-G#4QG z8;r&rI7#2CBP1d_t45CJ0kv;N!jI}(Rpa$w6bq)q=; zV+LakX5C9wjtFn%&gNCFEK#L$XbZLh7grov;TBdTgpd5)y2kDK;Q=(+ppC%@M)zP@GCEu0^6&vE6{MUurjir7HacG_qy41>9cQ-wh5T#5a0U-b61?R2%_{5dy zxH7&io%OufI+Cqm+Q+wGP2EOzZb!0+0n=HJ85?6phkz%-Ky=k~TMa|y%c(<}oQ9FR zF5FF_%G{vF{)x-uiztez{DW{;qwk$A-W z#h8$C`g2$AeKKtt3uw%L64B|+w*<@v2f->ZK|&)pKtnK#-ZLK zU|Kasu2vbus!^fAGAj}Kf^9-u`*qU4G zc3xQol_QivuW-)v?#m0K#mNa-p&(ccfm!{h_%vLcg+E-Uz_mZM2!hv>$PQV@I((88 z9~}K*^e_?$KlA4tVKQZ_*3|*-8Xc0me7YYjs*qMA1Emd1N>TF0T|=i49{;rsvjVyU z^S_+EdE&-r5quR&$Yb6k-nPjVT^dM2hd3!qIbn2r?yD&!JaC%A?sfv_r-KrtEY9np z1pJbPK6LC`pjlitR=Z+uM>y`!UV)br$_qICArhfTYUOK2sg%S!6R2|`0+s)|u!G40 zXDUjT)VDt$#Lri(_>HFM#B`|v=3;_T;La%a{j)q7bcMdHBL#|c7U7|PkVS*2K&EfI zP~VP<*t8A&@rJM{3xFBVqWb9@pk_sX$U>jK^eP7bI@jPa)!)#xY*c}C5 zt5FSIK+9HB-)ZFP!XzD2m`J)`PA5(cv}hYPR*F6iL+ChjJxN(UEphW+sEbL42Gc*8 z=6td1RT^tWGT-Tq!66pn(`B0^P`!~!^aDL9`D!cuvi@YVFn5S)vn)$%w@mDr#-WZD z-;NR=;J2bz`-XRWK^JT`kZ=yh^IP3yfwCuo-@g6ep^?sj#Y7pT%9&F``t0A*8j7SQ zC`pE+e-ngiG;?|x8sK&6WI8tsB5T6zkc2@qy2#C56s5~47Sx+`>~(cjnUOg`D5?kb zO+d6&;Nm82i_wI;t`~PmP%V1DIB(X`hHQ@j{h#>c3B4}z18+4SYD#VBx{{Czs+8iE z1oxLgy^_3F`uhR(bW^w?lK_FfMYC_2QHsLU83%g~ID-p2oBv~qu9N#&xUqQnbDl1s zl@D5gi}qc@#Zv1R9!3pZBoe=oo8OE;pmG`OwAk%lhIYwKVK2DE{GdYm&|=>F~3 zh12&`G7?5E2I_Tjg@&Zf+-?g2XzgPQJ20eNjIA&d+wcgSN3XcueUE{M$&Zs$YBPP6 z?$dlG2sZh``)A6P@q4BFMV|xkx$!$7iUEUZNJDXqNHWFa-Pdt;ia8}h3u!Gl{N@r4 z4tnBH2%cy{t{YSpE=~3iG(`Xg$gJQ6@rR1Q*>jtiSNADijTC`t_U|THX+(QCbKkxj zLu!bdQR)q7r0y~~cd)FZl@S>X9eR#XXFZ3os_0Q>Fm=2LXUr`PC#&3X2lW!*;csy5 ze2U|gTrK;TYHCeK%pF)pU+!!GI^l68JS4O)Q8^xt7lZ0u($OmI7n?IihIU5=nEHvV zF(Y%5ve;SRTD>K3BK_BDJ1T5r`a%$WAK&6nU>^kjy(QJhqODYXV(4qU!%Ozrw^1UP z#7(i4*KV~xux65|lpZwnh&aUn62_`6j!WM~#mx=D;IrL@s(qj`QU-YEfUY*ogD4~A z^m_SaQVf-EUE>nEV<*`4ZOsJJo2yzjGCcg)fZ_%IeE!;_fdxl@-un12^ z@=Z_$uRn}INrTOIHQD`Q4Z4qn;7{J6{+oe}?3%6-5&H^nPQcD{bP%dWAbaKPAC+AG zzZUPrUqX}qNUj%5KFISe|ACW=SD$4QYur`7yg%bEGh~*4&E$HM15 zeNYOl%5QNVv|KDy8cakhQC|ChNR}X2>9!x~EsV|exBxI45wnK1@1M9R&u^9Ulr($7 z*fE&F&ZguRCdJH~vL5nCP{%(7`-i+wnaAU)GD}4>sL(4X3iQ%VJshi4HhJp2N8Md# zQkqghV!7Ye#s51U7-~`|Xy;SjHMR`E@uyDsj`Fd#Qo<_ zb)mne5+%!C_e>Ia7>!{zDAVb1Qc^eo->1-qvt3Tqe#%rKkmYKb40a;Z^1(8f8molX zu*Eb`t8Pq&G0q_lnt8bX>$}@(K>V+gK1|(jtuNb<(OQ)qWd+wXd?bRh77;uZ=Yg`@ znD&;xoQ!?*CpE(W9#-cCncOe#LpxI5$G29jKHKrX-t{w=J_S+l)snCV)~EHrB-CMh zW;?r5@;lkd{1|Co*ZW@<@rYz)W1^JFOsbG?;EHyU_V-$JCsnv}jCucCatkHVz8Xc4 z!V2t*p@`17Ken%7x6)0r_RE!DbD{ZgRCxVTs-UdZ2HK2&xrmKC!M&d*bcuE)&O+(~ z(zgq+q{V?!g)eIXA%=E8pvz(~dSV+l2YR5%EmZX6>Hwb(ZW~b@$`*%?ia4&DplZ8! zcw&g-g}9oQ#%EN17#V%l2uadSgtsQV`LKa+^q8S|O2{2!bP7I(aY0DXK#Jpl+>vE< z;D}SJN#NsMF6iJ*^kBr3>gZX3;DRj>BTn5^vfbM^!hv_0$-$=|D0dnWg)aTOm9$Qi z&WCg}IPDF)`EQH-Zw;4zX#RgRydKe2L%Uh!Z?D>D^;oBxSBTa)5DpULQ$ULGGhBeyjOI$+u6&*xY8#wOFZy^;1x+5qO*@BRF#Em-SC}&SxW1C^zEe739b)cYjo=iC$K#=>y@ar z>9f1Yhl(cHoD?@7m=_6i+Lk~lQ6^wL0okcKzBlDO@SXLKtMjqTCyOKghz?-A_wLzt@X_GrM#hM;XTV_j@YCSfUWqH(i%?FsOk_jK7CX zl)xS&6WQUDoz+1W=45LZEMZ%!K}zPL3NnF}3+|MFO_F`I%{uUuM~I9z z44xeHvQ}bTjv8M6(TrJTdUhcYXkc8@NY-!w0LhP12)GRKs3z`0Osu2wYCovV8^NA# zX}{~;7wR=wfPGvBEiHbzKDZw2haEg+k02)wO$U`w!Zy&_4fNprKXgODM-lkJApH!l z=f~M72Wt$vI94F=(6b&?p5Me)VVgH`b{%IQjw1IbA+yH3WLmvkF$XCb7C_R*YPa>bCK za!dp)&OsALfu}@HcU%YVn>+rCj9vIX3}I3cfZ##d_+0EID~&|Zldhl|%!oI+j}HB> zhGAT|^#Z}9ym4a1$9k2lv&T`Ihmwk>MBB$T_5UrDxdOy=!WMUO=wpuCV{pBJ45VBBL?~CmpxA1>c3sogD-hkrm#Jc{vwV*CjwKa=9tGZ0wxMV=d3inwB3|A~oQ%bwfy ztk16k7L{&fbYkQEI&+AVTNYy69U=2JINFVmVBg^I{AG3+=r!gK67(1cry}{=oHwaz`nd%(A_l`3 z|1gOSKO+vVicqyKq>>zLUJ}{)?d^&ACl3;R_2~-&z*JIN6@OcY|F4GJ=)@H;kS3n2 zp_O~5CNt1wkS;>dGFb`9L?_Z=b1rpTY^B?G)UKX=YaKsjQh&T@Pc#&?L^xRb*c*{3 zH!l;72Q6$O-kYlq4zAWP1~l6umAZeLz9Qog!*g($NDwk=)p&N$3(4SF`ukD_9Rm+wQb;`zN*ng_4?ESlaqpE7Z`QW_$HK}THmqV)`OC7_B1f`-;< zyrSwGhno8Kb)#IB+B5y>A=Gebe0fyH#ERZftRU5{(q&R~xc#S10_}FoH?JJglzD4T zrkq{uZ7h`a5U(`4-hdOLLk$5;1xQhF&(7~#G!U+!&V~{~?V*iyR_%DptEjzJw-|pu z`DkDkgS$A>jfs*$?hy^a$kkrG@J|FzKsrm@Adt0^-uGslCsxL|?7rPOyg3{5)yL!O z;*^MZ_-UC2&#kJpc?!6X)#NP|RP zU${S4C;0Dp!oT=Xxi-D%_@IdBxTfcOMUYB-J*mPfI3PN5XskMxn_k5wf<`nAUm>=k zJB);bB-JT=0k0e-)r@?0ZW(n*OiEkLcQPalaG2+G?G4m}HzUc*bRmLHL#fS^^qenK z)t`t*6R6c+vDYL#_8lWJ0CK6umedPA!qz;K_?84c#aVNl?LL4SVdJWHDygjMZ|dw3=K3Qf#h$7o7XKOKvB<8iu7$>rv&=}l5Pmb zxb|wL|JhkTeOVMe;$*xU3)(0xobRjZr&Vfg--)+!^3}ovS0CFjz^N{Mn(l#^poEoY zd>&j(Bu~KOoar=^FPp(e6|CRxa;u3M_Ii&XudDHrV&e8-v2q5=2S`P(JO1=Ko!IV9 zF}4X=>YDlk6ch2{+1w%^3RorrOh5G?mw z$A%-I>6YHawbI&K-WZLVDMZtHwnwN&N=Eq|@N^HI7#cV~nWyY!Wvxt| z4s#Fz>C!nF_pH+@-WCqc+8L9wWgpDYFTOa{j8cN&-k9z zR?N5Prp@w4WhZcW!^}?{0#$f9%asRY zL!_L{2gq4dx{zkZf~_H@d+6Rd{c=P7A z=w2i>KAJm5br0)VH^|s|^cJbWLszE#x6a6P^dq4EtSgjQc%S|v>)Kc+l>J;h^wF8e zcOs}UJXM~7yuk1-hU$qmx%ht~NV z>eWFPByle+2`=kYHl~5o57CA}iGQEA0GJG^)392NBxf$&Z&9o86T8@31g5ZS9=KowTx z>N4~kzf9rubl!hM2z$zW0rXnsnJNu?#wXRJuR3)lI^WhLAlJ8Hz|OL2dSO9FY7K9U zPh>K+Xd#J;FnJkLfBk0}h<{wjGYoC{Ex1SQhVYqV=PkIcm zd|ffaF)4c6bmwV8bM@$bD4<`~&-k9P4n+mc@NCX=kx$ezWvs=>*znM&9 zWEh_ko`klp`!F94OwSl>qLcfSS_1)=`$%`YowZFCs{->6K{KTy)oIK9W$X$q{om5I zEB@~d@;c!{oEyGA?}8cdo%v>d8%^g%wJDOu^837h4-b+x=#wzGbO1`I{e=SjM_nvE z^=q~#?9E|CT;9Hwi9SdZ*>*UO*sRgem&k)~alfI9;>h3;k?U~!FH6Lh?#vik7?&v6 z`*w}`)v5nqN?dq7f!aj8eOeQHJZQi>L6Z1#zhKse@gUhCtIMR3P8Go-*N7b(xQK88 ziypJKL2P-NOz;a{%}@URWjP(x{rlWV9|=#l8kWJHBi-Fs`&84mi5{YSSY+6{H#;WX z@X&I(Z&eICO~{>TvUlX6bm&Q!plijk_m_r=2pN*fU53yf9ui4p;urV=;;W2R)fGsQg9 z=@(E+>dV)@N)iT_dKJw+-r4GPF$&${11EtG(sTMx_h((7_&}53M;|Wm`vdcA$00%6 zob$)YtW`+yG|uD?*FFzdx?y5I6_0KLbUg_v%mT&!^qAGVe+p-R>dkN{g(4V35zi>2 zmXvVH#7SgbbK@P=4(?)o_t^E(#H)51Lt#}nH_#M@S9?;o$qi(l`gI#JyJ!&oLs%_c z75RS8pjhz}WA#)&GoTEJ5Ix$|FtZ|GvYDm^FiI-IdnFbBV}nb)|6HTacPc)^oa+DE z+pbLi{7)M;9Fgz_d{9j8e>|VV^xR28ga}lQAgg*E3)wKqB<)~?OS;}G@A79~#mO+w zx`x=7QzabIaJE1(Gy6+Fd8s{>-ekI@4HnN{>xF(4b!+%Cuyvt%?NeE_f6kD!u8y-x zRqU}T*vSQNR$WpUmHVkTO(=G9=C7UU+=3H&f}29H`eY;a3(K}}XV38KoPtGzYQ#Tq zDhw9#?})Z^B#Bk&KIhFp`k?j_7aFv{eSVfQg@3toR!c5WH||po_+iGGcmMD?6_4-S zk^xdU-l47zKtp$~OWjq!W@4-dE;#K6(6zr;n_!jGtVOFE1;gAjwpMaU-6=#oSYdbO zCv&QMj!wcHhLEYgzVde5KL~;RPVJk3`hQ(`wroweIos16YEHoO3s75}R&ALq`|-=z ziMm&RwYjoGBn!4Bb0XZJ>b%D<)k_-?0os|ZA4on(?%+P=k>eIb)!b~&ZH>R(pU*xH zEbvMz=&PyoOC#}#^(mSMl5RYo(7b)IWJ3j;k~!tg)xh?$$*qnPP(T=L_`Rci=f{^x zK%9`cx~Y8$tbYg&-&#CUy+-31+uQHoO#V~v} zRg3x1AQ%HZ#Y41#2D*}@tkkzP9l{Bkt$MGsX8y0rz5=R_C2JQA7Ti7f!5tFZ-CYmv z?oQ+GP6(PH0RjPny9I(nkl^m_4nN7M$cna{@Q}GXF$l`XRuc8)8Rq z%o#BOK4WW|$e@w4$Q$K2r*Sa_c$h9ojYbx-`?Vv11 zCpI|l;yZs_vnAD(Ug5HtV&e1meOiWVC7p&W)v%Fxgls2Vtw|G%o9&zkp_KD`K=1;j z;eu4d2{ZSdXdM~e_QvUQt|m`~!PYk8x2n@p%+Q{5O0daXid5Oye~rsL0IJam=1fJlU-P_?ch|JIs8(sP2+ z37b9u!>mPqhh#At*K<+X*odBpoU#`XD(|g^1%#*}Mqc|}#tctR@bY#)VY5EA9Tb(< zsSu|_^#!ROG`L|-+Fre4qpAq5$D#CM28Oyr?8jP#3PVpV8Y=$*c}%+{HjBN@wa>-MeZ_WNL)Fo$Ds55W}Z z&tI44s1{^c&|Xl_$KR}p1ZrvvxM?e#UI#tkv)=16Q$k-y>r!a_!jvN$>h$ZjG-Y@1 z$O`x~v_nKK<-H<}Rqnv&>e7g~$3T}l(gz}k`RsWvykyKqal4ksBP%3e_lMfk#2nV@ zO)e_Ho|T{8Dc0Dpdz&`G)8(mZ1~;utZ$R?^CPC*tJ+GrmXM4rPrY3_OOOP3=oVB}4 zS@yvdTUd;Ngm2bVb)VEwq`tq@7G!p;f)#u4Ra=F6ziXQNKsWWSEF*gu4Ndu995BWt7Uh)4G}CDr7Cej%qrz?C5$6}m*Q#! zL+q)$y;O;%5W)SzLI}gbl9w9*Ya-hWgf~zS%=M3$OFblM@H$7ep!u`08PXFu~{W0x5pwubaM zd49ysin$plOCf=3Rn0p=Z)?Im?W@UR_U~%zhsLuC{*ipIQMkyL_NKajRxb15T-NCH z+Icv$#&qe4hP}c-XR=m=l}=i$Jjb?a!3~t*FQDvNA%2%y3ed7kIjG2#R0j{;ec~_F znJw{edQh8omsl>!MGIlRPU`K`1*7Q&b9D!jGZ!*-piDA(v#5E~?^gSk{PSIF*k|GOneXI@#%u~2m6hI~ zE5fwU56d#*3eDQfMx{*Ahn3C!Fhs!5x>uXySwoN}Q=|M@Z8lzWBkiemG_TVj2&xNE zHnVutsrvgDTh6aczM}`NexizwG0WdZiZx))l>+dq<`mKgnIpLbb0JpZK?DLMC@F1O z(|hL#MGa#omm?pok;?MV%IOi~>7Lg3F7NAoqe?gufJirNCK?Or_{&)H(0E1LrE7OR zSTONEN}lyMXwA@HAA-awyN%OlVgUD$J`TShPZVO+ZQNt8KR%2M3Bf^A2U$=iYsA5E-sl9iWp*I z*v)0Tgfwx`LLczL{IHAOmS~W5^%eu0lgpY=m-03%Ho%isdMF#L9 z)6+pUODYjat@V7sQ0^t2l8J(7e0U7z-o&BT9=G)*Y`Sc8NK|{aKdE>* zIJEaEW^hT5_Ip1>t#zkPQ}n~$F3b9-KZ5$NQ^}Ueob7T$w$W28qTh+Z9^6?E!Wde_`iF)0=o zVs_VX8+VKr>H{h6FzC-QlIi59S8DQkk*jXHvkoj2H}%{Zf1=~w-#$2(egGP}zE%Zq z7$ivU2@KPbJ&k#s)YCpW(=`Xu6-L~ia)}NZ=0ScwbJLj>u|b~e?X!6wKUs{Gx?IMZ z%~wczAH36^*M6i$dXE2nlT5ZbM-if25{q8rWe4&4VW>}CMuJhe$`=47=i49TbRk;5p<)` zIQ`zmD8%Q!t_QszZxcbbd;@2AM7F`GX_7-z#jcd@w3rB1^_nV^g_-U9nS|WLqbn3X zL~oCyHWl5ipt-#}s|ri5H|Twf8vUkR%uWDnb%+tY+&*2IfrK9S#T;N2X@>;|sUgpa z#!M54r}n^-TVlju!h7cnWm#&j2#B5H>uB}b2x*VfXc5L}gpH)0?}&P8${5C)U_GXLE4 z9+M?48`jO!JpSr5lm-X{oI<)tq+33RRbJ;ao2XgbyH^v)H(R;+3VlT)ajw0lgO}p- z-aiVJ;HsCqj#2bk78j}@D4qNG@(vm(U4Y@gJZmQNXoM9-@}lI>H1v{mk{{ehLFL-ink9& z&`ez+p>r%&>$0(#E3S9p?jw1=ZkWm~+hi{LpPpDEeJL6;+|F1jE+0T(!+Wnh)2g8e zY{f@~*rSuYG)~(mMrg_Zr>^H04v1k8$t(QV#2K##kr)pW$MlR~5o^*H&yCh;0^U)- zT{RZbRWTo1jV_Wk}&QAGEkM zkC=cJax`fO9=K~th{K82x9%kWrLXi*6{ITjt7`tyoc@Y0cGiJ*#`eQ6Yy1vvn-Wb5 zM`?&T)cC(jYOoM&mNi$IF#C}(i0LarC2LG}YW zqOF91vQT6Go|KT5=|@w1gr&Dd?GARvUyx0 zn2mYcjVzFUClY}0Xp!=@kI)%Y0Ty7ax2FF#A99qYzPe4m1#U0q>P&s#;bPArCOVyY zxV?l;y-cT#Z*ngjv5wqW5*L)FTgy3TC*tv=bm;8hM);^xASMf!;+rE`om9?CDPN|` zH}ue&0COZ~b4)jJSh{~4`jV$8Q|ZUNO%1zP_pCAfYPx1VULc+WKC8he0nIcYiQ&6Mi&xE=es@jYkRre7Vjjq zK0 z`4~D?T*Cwmt3bRPX|$*|W^7K)z&A7wWvDzetg}@_g_W5RZTAUeqo^1Et}{57 z?Z0jb@lvhF{n(Lj`uRbIFtj%%Il~^yiOC}o_QczuhtIMi;vg*E6_6@ zsigIWVGj*4D?Z*+oylwG&E<7-60bPY_L~vyw+1*%);8mOFI`fEIh_Kl0ouuqr#6fm zV5MIxcST=2Ps2y#xFlHY-6x~(cPcgR8_zIIBVWC+76A>g>d8%};;;_fB3W^5L&42S03W}Pd8uCDd+ z!cGxHQ_BE^{th*9#MU+TdpSH5Q|LuE|kpMtPNFhAN_e1)t#NZu0!WQFGoGL7^b?hq2B{rDBrP7|IEf<$iN#npIByU$|NyG z{JA%yXzCy2;7Ti`+wCvFO8cNA2LHk}b<=m4u%l3{cd*rTHA;}VmE~;40w#^diOWv+ zv>(+ce6tn&iE2zr@B-9p5qMg^r?hPfeu2bYQn-4bNIL#A+hUB9nnmE^t(ZbdgltQI zx)~1j%6Y2Ee`ANA+TWy3mB{ji>s`jDL^=f3Tc$9IR^3>6?oD z^q~9HkAUsuMQx~_8H&*3YlfP7!FXYIMr4ud7l$N8*$XSVV4X)h!rS@}LTX4|`EQ6a zNCj)Zp|aBE4@?PB$YMo@6^r&xvQFt`OgIy2GUXfP+o#RsoR(h5qP75q#4xRbP)@?j zQgVm+x02yMLB4-awg1N%`Tr>f{IAfW_ZJ_hA3r?BFPLXaR{{=pT@Xc+73Grd+$T26 zy*{-gup1!%hWY-mgp|C$mGUZ#jpP<7*!d?_U%HcaRTj4T>*eu|4|$H~1T?-sB(|8S z|6h>GY-YA!z;CEB;(EAM$&8yzq*G57tHWvp`IkxY@JOckXJ6<+PW-jgc`qmv#fLY% z$&y*?*t>%gK&UO}2ya`}=ZW~*>;9Wf)*;LzJz<{4ZR>l+z1o*|2n~fxb4G>JY`)*9 z1dOHI1?3C>2ySHfab??c{%E1DQ$Nw8@(;Gz2K2vxo5x54v8S;DHd8G-LN$8Hn5LON zDpAZW;lxuJy%iTOyXx;b)3?fdA`y3kI66t zu|*$Gf)|4QB)aJy<-jFcy^kS>`MAxv$6f4sF}>84%?fbfU~e2^0cnd)I>lN1&IiYk zGjVYEb~F*Z;oGHjaB%qGBGONWnNL(&yq6s3N3epW0;&4Dede3&MAw*g;Y$Z#My#C9 z{+O%ND0Y`J-RQRgdcGFnHdTlULmhs=OoWEwM5xd$dGhQnIV$7Gf`9nB-{(~3D+U)n zdc>)Md5k7=77~93hM5hc(Sh1$X8^ZkLQzY#kTlwiBIjVmzsr5hW-;1E;k%ai>U%BG zJCroZ8bLA?^l{y1J`;W$H$EQ=CK||-@BRqiiH}JBpr&BZKTy**XX3z!EtqqA)q>_| zyQ|-6csS9l7Sm|iwe%&-ytHebiGQn&RWafVJ5+8Pbh!!>T}eadiA%LKjt;fyv3NOR=i09LoRsl z=SK8535^$A9Z$^W(#bpviQSXW!iBC|Y28xxMzwkRRLQ?bA}Ps}g}m!A*GzN!vfXI2 z@HVr{^1X(0h6(r0B2tovO+sM^13sf8nXXu$|M5G(hY8Bw?rc|6W7X+u*)N@HYgDH& z8XC0uJiqGAA}K;t$)KYpcF1dfpU(=LTVrp}lcrQ2@vO~u+g}&7z-Ii&yWDvH2hi(5 zJyOk(NPrC-4-A)Ya-wX8S&O%*&oxyeaAtB*n+xQW{+s5Ih*A2|5u?qgzP3(ISX9y>uV9MCwwip^o{kQwPgMKh z3#2#yHg|%u!x+!$)uY}t;DM<825l2$+0W;r;roLO+4@Nk z4(4+aT1)P51%pqt41S|RJPsC4sy%nu6WbfB;r)a-9h1Hfh`flq3q`JRy1edEO3^p~x@p?t{p3+=IQd-w4`Ogmp2ZrG%uru@_D8ZvJwM8)%#NmMI0r_lGw>5$(@wBN zY@K5`FT@5ouch!=Fl~t4DFq{`YKzR&1=A6r3bTue40h-M$-Qo2MQ;;dupPCUm7OWl z*Zp)m;9{40CRM+a_-)vKJ1<`3u%mwWB>M|59|?cxO+>&ibiK6QRQI?E@U}CDbR2Rt z>7W4k<(U%xdKbCgQXOH_nxU>LmF-fmut?7H2_?E;w%tuPiIS?IjZ&|T{Wy;N#&rN_ zeK}*2@yNwW2M)HQeZ6yyL^jrItc%*h{qpF~v=&W5Z%AS^{<76?l_DP#e)xo~S z!iCy2jSjarN6*oHQ+s`#HwN}#2D?MHcBZ1?pVS5~kA4h&^czs8+0j;#$LMBU#vkZABzZDe+pE)xe|0pa<+4^GcB$B%5!q;-L0#tgIu_Bu)p(K(2aV>HSnC={+1%{MLHFYBvx@#GMDuX61H(*cta___V0Laxzs9sbW=-@_ z#~kNSCP>0(U((cl5RxwmWsdHd=5%Af`ie&Ed2&ZH{FqI~eutqqzv$CV$KMKQ=|zbJL3r zN+nElspnKpAvo$jd&eH>26VHpsB@Or(Xv+exFNV?95b_`Hx^?#xFOv+rzDE>n<@vm z0#P zQ1|V0lFSBoO%ue{$h<~8+C)hvl05JC#;YVz$50tImJkMF8DjFvD7u}8c~>8s4I*4t zr}k*-EnDkc8vu@kHn+U!UI@Wi7QDm(`>(H&jzhj2Goizm8}35Ey^<|wPJ~-*m|$aU zHPsLG&@yS6%5-ev3X9LEXGxSc98c<6!d|%Nf(UM9Et*b|&EExy) zHTCD(c-=zfQ3&$)C6y%i=EY%!X5ltk+UQ;p&p6CimEDlefiBdG@thlY`fSdDz769elo+x(?ZE_o52A zK@-{*1!>^ey4RyEG(Q((#-`WJa35i0mpe|?cK zGA+`zff8DT!?@TSL0zj?wTmEe*AUqiM4(h3JO$X{4g5G%_LLWH!W4MgohNO(zgjnF zyB!sL2E|By?RAbb6U2`CiL4Ac9>R3N*ab=Yt^@ni-H1SNJ8b(>+!7QwXm=lTC4c2- zik#=ix_Ltj*v@==U`w}yX_uu9D7pO>Vquis^923I?eqE#qXrLWW2l0G*2p85;bN>n zr5Zp-F%_;ui#1u1=Z(nXib6}J-Yf4aI8<)DiQMo?mv^9kEscU$n<1L#n;jX>@-ha0 zZclqWV^U$S{B9bwRG>T$@)3+1Y9gGk;a$f(mQ5m#^maccGJQu!p;eAAdzDJ3BwVC1 zzd4u|dfL(odS(GCIYl^qacq3LSD1Ky@JE{J!CD+I1@EK-bs1VRBw$O z7bmMowH28Zl_N(gl_NK$3Z(>)C8}>iW-kD-4tTP6N#Qt)eB2qR(i?YX<&fs@W@D7o zEB+cMGbcAUR^O(0c2itkf#vm3NHl*MV4Ji*Mu~T?3rgWQ*;t_9ou=Mz)Z*G~eeoh7 zR;7oDeT8kM?ck+neP_8}rH-h|2P-x04wed`6JYnAi}+MCI&G8rknbmMr!t$GaWTXM z7h?z?0NoO@QDGE{e*^us{-k$MQSM<^UxZ}E%RQtxgKWmgK}|BKfKI(Cq2ATGV?tC} zr8s1utYs?P{%K7Hz zbRT)-ncWOOe6GO!`kD(*4sNI3YBb-=99Qw3UJPSWTY3=ZJa3X^doN7k4%?hXU82pF zkxp7SmXNiOI<$%~F3RN=f;SAiCLCT=KlV8E#SGUXvMw~Ql#^3%oqtF10TrOrywiuT zE~bG30%N-BSc~KA;J8+aPj4Iht$=C+Kbpy`ew0j$F{PT5E-m>S-p3iXb?(2tw{^9# zU7CY^Y)omQUxSNy!(eh7H=%U*L1xGgTseNbl}v7R2(o5@BqUP?lXCdDSh84i!8 z-xw(%_V_+v)%er5gdf)9yNqP8G`D$n5ZX|_9eigqN(+ie$s;N??of8x;IPwv>-gY% z>j-{CO@@ny``$=f^+sFbNJ+OJU8ODEw%z1L3}H+HhNPsU`&J}WD@1_&Y!`;=F zl{e|B4Cp=zZ;8PlzO?)_y8b9fHgy2{)@Olq=;V>lfAo_4B9i5SS}_~rV^qZ=xEtf+ z^xb*1p*!;7c9tAi(g!w1d7~b@vift+w&tE6ub0D5Kklh9SqpT)ofSDZ4@c7;E9^KD zm2oUD5P;xx?EMwIa?>sQ1D^oB?5*4)`@LW1Pv$&!w{LnsISm%axIcdjrVq{v`_YrPbFE7P74ti-k)yaVp2!&67Ugc_VG$ zGW;x8?Z$A?WdXGe(7+Qk+`WUQ?=P%&{nI0Ek4a1mu-i0rXrOQK3vpIy#0Lu8W60?>0-(Jd>e2_kOi-7wfI zdkoc3?`v-?`0?;nHGxh%p^$|3kNiqC%n!Z=y#bXSE5Ij(^2oM51XGpk*5GwAi#>3+ zE(j~V=*nPG7KGWx%rsf>?p||$@f^hm2WEOS^+K&qQ?IA5C*fhO`$41A- z2I-Mf6JcgLm&_D`)@fFfU&_2mu9z|s2u9hJrmVhAo4REvd~`Duoq>Qk=Wf5dWsP*r zdL`wpuMM=0lWW^lZ)}9E-UEI!I1%x{{hcR>4f)|+`~3Xt5^DM>4WwekPAW>oL zwd|WEp>mboqm9z)_hDjMRq(qOt43HqZgG2|#Xju~I2bA!aMPUz~wXJOYyh)etOhB7mBTE`Wf*n3KIqzT|jaeY01U3dbg;w#wbEsH2@wXx5Hq4_$ zI~E{B)sqNH(k?^+N6S4=_51vVQWQb^0|u10i~)Dt=Xcy;!cs&gO~yhRuPA@F>LfAq_iNz)>gS{|6}7QuFzd&e%KW(8w)fI=eW zhee`7lhheo+MWuP#`N~AFejt+wcaM?hh$I&Kbk8u=PHCcR$nrvIs5Q(YEP< z7#Dt}A9PFJwtR0YT0R)hKHkbH(&P6oe7w^M^PO;;GH!AvcFx5*#4@EBm)_5$19`!u z(WO>Nyq`4-8-!l0q~SEE(o;I(dmltqV_H-=Yv`n54IFQjTG>b^s(m&HFH)o~&09`@ zh+bDyQvT#wQtA~*3cm0ZwPXt!J>(sO@!2WPwbh4Ark?;tgbIe~5tmUQ3#?0cXNfHA zAxnGVz&Jgfqfi0|`hg3Tdvcvx`p74W0@E?1DTBocE3;kkXJjt4u!%CwO7No0ZPqw3 zGn~lC<7D#bg&i!VxG$Yt02!C`v4IMpTYyyRp3(j#rJ;SYH3-p36@Sb|Jpu78Nzj$N z>xdb0wKe4ITTGVS6bWn|jDzuLB^2FX3eh1m%t%6}-UAE9$|?KVN7R~IT9hubA!2D^ z$zw^_@+sJfB;YrL829vpi8yMGmp_%uS;oO>=?4x4uK0e{ciFM36ts-}Y072Hz2uB| zOT6gUpUy1P2Ncu6kAEETu(`QiKOsUuWPATtV*xA%K)*A)&A!ups^lDC9gOTLb@d4^q$@0$ByuSzG@Av2BHvMgjHGUalS1(($KQWg6 YITrtn+fnh-UU%|17XBHcmMzZ diff --git a/src/emc/kinematics/tc.c b/src/emc/kinematics/tc.c index dd74de686..a3b526300 100644 --- a/src/emc/kinematics/tc.c +++ b/src/emc/kinematics/tc.c @@ -24,6 +24,10 @@ #include "emcpos.h" #include "tc.h" #include "nurbs.h" +#include "../motion/motion.h" +//#include "hal.h" +//#include "../motion/mot_priv.h" +//#include "motion_debug.h" #define TRACE 0 #include "dptrace.h" @@ -32,6 +36,10 @@ static FILE *dptrace = NULL; static uint32_t _dt = 0; #endif + +extern emcmot_status_t *emcmotStatus; + + int nurbs_findspan (int n, int p, double u, double *U) { // FIXME : this implementation has linear, rather than log complexity @@ -170,14 +178,19 @@ EmcPose tcGetPosReal(TC_STRUCT * tc, int of_endpoint) #endif if (tc->motion_type == TC_RIGIDTAP) { - if(tc->coords.rigidtap.state > REVERSING) { - pmLinePoint(&tc->coords.rigidtap.aux_xyz, progress, &xyz); - } else { - pmLinePoint(&tc->coords.rigidtap.xyz, progress, &xyz); - } +// if(tc->coords.rigidtap.state > REVERSING) { +// pmLinePoint(&tc->coords.rigidtap.aux_xyz, progress, &xyz); +// } else { +// pmLinePoint(&tc->coords.rigidtap.xyz, progress, &xyz); +// } + pmLinePoint(&tc->coords.rigidtap.xyz, tc->coords.rigidtap.xyz.tmag * (progress / tc->target) , &xyz); // no rotary move allowed while tapping abc.tran = tc->coords.rigidtap.abc; uvw.tran = tc->coords.rigidtap.uvw; + if (!of_endpoint) + { + emcmotStatus->spindle_position_cmd = tc->coords.rigidtap.spindle_start_pos + tc->coords.rigidtap.spindle_dir * progress; + } } else if (tc->motion_type == TC_LINEAR) { if (tc->coords.line.xyz.tmag > 0.) { @@ -342,7 +355,7 @@ EmcPose tcGetPosReal(TC_STRUCT * tc, int of_endpoint) } } -#if (TRACE != 0) +#if 0 if(l == 0 && _dt == 0) { last_l = 0; last_u = 0; diff --git a/src/emc/kinematics/tc.h b/src/emc/kinematics/tc.h index a6fc5c344..1caa9fb00 100644 --- a/src/emc/kinematics/tc.h +++ b/src/emc/kinematics/tc.h @@ -68,6 +68,9 @@ typedef struct { double reversal_target; double spindlerevs_at_reversal; RIGIDTAP_STATE state; + double spindle_start_pos; + int spindle_start_pos_latch; + double spindle_dir; } PmRigidTap; enum state_type { diff --git a/src/emc/kinematics/tp.c b/src/emc/kinematics/tp.c index 4de69d4c1..31c113f58 100644 --- a/src/emc/kinematics/tp.c +++ b/src/emc/kinematics/tp.c @@ -364,6 +364,8 @@ int tpAddRigidTap(TP_STRUCT *tp, EmcPose end, double vel, tc.enables = enables; tc.indexrotary = -1; tc.motion_type = TC_RIGIDTAP; + tc.coords.rigidtap.spindle_start_pos_latch = 0; + tc.coords.rigidtap.spindle_start_pos = 0; if ((syncdio.anychanged != 0) || (syncdio.sync_input_triggered != 0)) { tc.syncdio = syncdio; //enqueue the list of DIOs that need toggling @@ -374,6 +376,13 @@ int tpAddRigidTap(TP_STRUCT *tp, EmcPose end, double vel, } // TAPPING + if (vel > 0) // vel is requested spindle velocity + { + tc.coords.rigidtap.spindle_dir = 1.0; + } else + { + tc.coords.rigidtap.spindle_dir = -1.0; + } if (tcqPut(&tp->queue, tc) == -1) { rtapi_print_msg(RTAPI_MSG_ERR, "tcqPut failed.\n"); return -1; @@ -381,6 +390,13 @@ int tpAddRigidTap(TP_STRUCT *tp, EmcPose end, double vel, // REVERSING pmLineInit(&line_xyz, end_xyz, start_xyz); // reverse the line direction tc.coords.rigidtap.xyz = line_xyz; + if (vel > 0) + { + tc.coords.rigidtap.spindle_dir = -1.0; + } else + { + tc.coords.rigidtap.spindle_dir = 1.0; + } if (tcqPut(&tp->queue, tc) == -1) { rtapi_print_msg(RTAPI_MSG_ERR, "tcqPut failed.\n"); return -1; @@ -1467,7 +1483,7 @@ int tpRunCycle(TP_STRUCT * tp, long period) // check for at-speed before marking the tc active if (MOTION_ID_VALID(waiting_for_atspeed)) { - if(!emcmotStatus->spindle_is_atspeed) { + if(!emcmotStatus->spindle.at_speed) { /* spindle is still not at the right speed: wait */ return 0; } else { @@ -1482,7 +1498,7 @@ int tpRunCycle(TP_STRUCT * tp, long period) // atspeed check for the start of all spindle synchronized // moves. if((tc->atspeed || (tc->synchronized && !tc->velocity_mode && !emcmotStatus->spindleSync)) && - !emcmotStatus->spindle_is_atspeed) { + !emcmotStatus->spindle.at_speed) { waiting_for_atspeed = tc->id; return 0; } @@ -1601,7 +1617,18 @@ int tpRunCycle(TP_STRUCT * tp, long period) //USB-RIGID-TAP: // if(!tc->synchronized) emcmotStatus->spindleSync = 0; emcmotStatus->spindleSync = tc->synchronized; - + emcmotStatus->spindle_position_cmd = emcmotStatus->spindle.curr_pos_cmd; + if(emcmotStatus->spindleSync) { + if(!emcmotStatus->spindle.in_position) { + // don't move: wait + return 0; + } + if (!tc->coords.rigidtap.spindle_start_pos_latch) + { + tc->coords.rigidtap.spindle_start_pos_latch = 1; + tc->coords.rigidtap.spindle_start_pos = emcmotStatus->spindle.curr_pos_cmd; + } + } if(nexttc && nexttc->active == 0) { // this means this tc is being read for the first time. diff --git a/src/emc/motion/control.c b/src/emc/motion/control.c index 7b9a492e0..07a922bfc 100644 --- a/src/emc/motion/control.c +++ b/src/emc/motion/control.c @@ -413,7 +413,9 @@ static void process_inputs(void) /* read spindle angle (for threading, etc) */ emcmotStatus->spindleRevs = *emcmot_hal_data->spindle_revs; emcmotStatus->spindleSpeedIn = *emcmot_hal_data->spindle_speed_in; - emcmotStatus->spindle_is_atspeed = *emcmot_hal_data->spindle_is_atspeed; + emcmotStatus->spindle.at_speed = *emcmot_hal_data->spindle_is_atspeed; + emcmotStatus->spindle.in_position = *emcmot_hal_data->spindle_in_position; + emcmotStatus->spindle.curr_pos_cmd = *emcmot_hal_data->spindle_curr_pos_cmd; /* compute net feed and spindle scale factors */ if ( emcmotStatus->motion_state == EMCMOT_MOTION_COORD ) { /* use the enables that were queued with the current move */ @@ -2021,7 +2023,8 @@ static void output_to_hal(void) } *(emcmot_hal_data->spindle_speed_cmd_rps) = emcmotStatus->spindle.speed / 60.; *(emcmot_hal_data->spindle_on) = ((emcmotStatus->spindle.speed * emcmotStatus->net_spindle_scale) != 0) ? 1 : 0; - *(emcmot_hal_data->spindle_velocity_mode) = (emcmotStatus->spindleSync); + *(emcmot_hal_data->spindle_velocity_mode) = (!emcmotStatus->spindleSync); + *(emcmot_hal_data->spindle_position_cmd) = (emcmotStatus->spindle_position_cmd); *(emcmot_hal_data->spindle_forward) = (*emcmot_hal_data->spindle_speed_out > 0) ? 1 : 0; *(emcmot_hal_data->spindle_reverse) = (*emcmot_hal_data->spindle_speed_out < 0) ? 1 : 0; *(emcmot_hal_data->spindle_brake) = (emcmotStatus->spindle.brake != 0) ? 1 : 0; diff --git a/src/emc/motion/mot_priv.h b/src/emc/motion/mot_priv.h index 31b464140..524822e78 100644 --- a/src/emc/motion/mot_priv.h +++ b/src/emc/motion/mot_priv.h @@ -117,6 +117,8 @@ typedef struct { hal_bit_t *enable; /* RPI: motion inhibit input */ hal_bit_t *spindle_index_enable; hal_bit_t *spindle_is_atspeed; + hal_bit_t *spindle_in_position; + hal_float_t *spindle_curr_pos_cmd; hal_float_t *spindle_revs; hal_float_t *adaptive_feed; /* RPI: adaptive feedrate, 0.0 to 1.0 */ hal_bit_t *feed_hold; /* RPI: set TRUE to stop motion */ @@ -163,6 +165,8 @@ typedef struct { // spindle_velocity_mode: velocity(1) or position(0) mode hal_bit_t *spindle_velocity_mode; /* spindle velocity_mode output */ + hal_float_t *spindle_position_cmd; + // same thing for 2 directions hal_bit_t *spindle_forward; /* spindle spin-forward output */ hal_bit_t *spindle_reverse; /* spindle spin-reverse output */ diff --git a/src/emc/motion/motion.c b/src/emc/motion/motion.c index a3672c13d..22f7ff739 100644 --- a/src/emc/motion/motion.c +++ b/src/emc/motion/motion.c @@ -333,6 +333,7 @@ static int init_hal_io(void) if ((retval = hal_pin_bit_newf(HAL_OUT, &(emcmot_hal_data->spindle_forward), mot_comp_id, "motion.spindle-forward")) != 0) goto error; if ((retval = hal_pin_bit_newf(HAL_OUT, &(emcmot_hal_data->spindle_reverse), mot_comp_id, "motion.spindle-reverse")) != 0) goto error; if ((retval = hal_pin_bit_newf(HAL_OUT, &(emcmot_hal_data->spindle_brake), mot_comp_id, "motion.spindle-brake")) != 0) goto error; + if ((retval = hal_pin_float_newf(HAL_OUT, &(emcmot_hal_data->spindle_position_cmd), mot_comp_id, "motion.spindle-position-cmd")) != 0) goto error; if ((retval = hal_pin_float_newf(HAL_OUT, &(emcmot_hal_data->spindle_speed_out), mot_comp_id, "motion.spindle-speed-out")) != 0) goto error; if ((retval = hal_pin_float_newf(HAL_OUT, &(emcmot_hal_data->spindle_speed_out_rps), mot_comp_id, "motion.spindle-speed-out-rps")) != 0) goto error; if ((retval = hal_pin_float_newf(HAL_OUT, &(emcmot_hal_data->spindle_speed_cmd_rps), mot_comp_id, "motion.spindle-speed-cmd-rps")) != 0) goto error; @@ -359,8 +360,10 @@ static int init_hal_io(void) // before merge: *(emcmot_hal_data->feed_hold) = 0; if ((retval = hal_pin_float_newf(HAL_IN, &(emcmot_hal_data->spindle_revs), mot_comp_id, "motion.spindle-revs")) != 0) goto error; + if ((retval = hal_pin_float_newf(HAL_IN, &(emcmot_hal_data->spindle_curr_pos_cmd), mot_comp_id, "motion.spindle-curr-pos-cmd")) != 0) goto error; if ((retval = hal_pin_float_newf(HAL_IN, &(emcmot_hal_data->spindle_speed_in), mot_comp_id, "motion.spindle-speed-in")) != 0) goto error; if ((retval = hal_pin_bit_newf(HAL_IN, &(emcmot_hal_data->spindle_is_atspeed), mot_comp_id, "motion.spindle-at-speed")) != 0) goto error; + if ((retval = hal_pin_bit_newf(HAL_IN, &(emcmot_hal_data->spindle_in_position), mot_comp_id, "motion.spindle-in-position")) != 0) goto error; if ((retval = hal_pin_float_newf(HAL_IN, &(emcmot_hal_data->adaptive_feed), mot_comp_id, "motion.adaptive-feed")) != 0) goto error; if ((retval = hal_pin_bit_newf(HAL_IN, &(emcmot_hal_data->feed_hold), mot_comp_id, "motion.feed-hold")) != 0) goto error; if ((retval = hal_pin_bit_newf(HAL_IN, &(emcmot_hal_data->enable), mot_comp_id, "motion.enable")) != 0) goto error; @@ -449,6 +452,7 @@ static int init_hal_io(void) /* initialize machine wide pins and parameters */ *emcmot_hal_data->spindle_is_atspeed = 1; + *emcmot_hal_data->spindle_in_position = 0; *(emcmot_hal_data->adaptive_feed) = 1.0; *(emcmot_hal_data->feed_hold) = 0; diff --git a/src/emc/motion/motion.h b/src/emc/motion/motion.h index 38d2b10b4..012c34b0a 100644 --- a/src/emc/motion/motion.h +++ b/src/emc/motion/motion.h @@ -608,6 +608,9 @@ typedef struct { int locked; // spindle lock engaged after orient int orient_fault; // fault code from motion.spindle-orient-fault int orient_state; // orient_state_t + int in_position; + int at_speed; + double curr_pos_cmd; } spindle_status; typedef struct { @@ -696,6 +699,7 @@ typedef struct emcmot_status_t { int spindleSync; /* we are doing spindle-synced motion */ double spindleRevs; /* position of spindle in revolutions */ double spindleSpeedIn; /* velocity of spindle in revolutions per minute */ + double spindle_position_cmd; spindle_status spindle; /* data types for spindle status */ @@ -733,7 +737,7 @@ typedef struct emcmot_status_t { unsigned int tcqlen; EmcPose tool_offset; int atspeed_next_feed; /* at next feed move, wait for spindle to be at speed */ - int spindle_is_atspeed; /* hal input */ +// moved to spindle_status: int spindle_is_atspeed; /* hal input */ unsigned char tail; /* flag count for mutex detect */ } emcmot_status_t; diff --git a/src/emc/task/emccanon.cc b/src/emc/task/emccanon.cc index 7ec1cc3cc..043cc0079 100644 --- a/src/emc/task/emccanon.cc +++ b/src/emc/task/emccanon.cc @@ -1092,33 +1092,47 @@ void STRAIGHT_FEED(int line_number, void RIGID_TAP(int line_number, double x, double y, double z) { - double ini_maxvel, vel, acc; +// double ini_maxvel, vel, acc; + double vel, acc; EMC_TRAJ_RIGID_TAP rigidTapMsg; double unused=0; from_prog(x,y,z,unused,unused,unused,unused,unused,unused); rotate_and_offset_pos(x,y,z,unused,unused,unused,unused,unused,unused); - - vel = getStraightVelocity(x, y, z, - canon.endPoint.a, canon.endPoint.b, canon.endPoint.c, - canon.endPoint.u, canon.endPoint.v, canon.endPoint.w); - ini_maxvel = vel; - - acc = getStraightAcceleration(x, y, z, - canon.endPoint.a, canon.endPoint.b, canon.endPoint.c, - canon.endPoint.u, canon.endPoint.v, canon.endPoint.w); +//USB-RIGID-TAP: +// vel = getStraightVelocity(x, y, z, +// canon.endPoint.a, canon.endPoint.b, canon.endPoint.c, +// canon.endPoint.u, canon.endPoint.v, canon.endPoint.w); +// ini_maxvel = vel; +// +// acc = getStraightAcceleration(x, y, z, +// canon.endPoint.a, canon.endPoint.b, canon.endPoint.c, +// canon.endPoint.u, canon.endPoint.v, canon.endPoint.w); +// +// rigidTapMsg.pos = to_ext_pose(x,y,z, +// canon.endPoint.a, canon.endPoint.b, canon.endPoint.c, +// canon.endPoint.u, canon.endPoint.v, canon.endPoint.w); +// +// rigidTapMsg.vel = toExtVel(vel); +// rigidTapMsg.ini_maxvel = toExtVel(ini_maxvel); +// rigidTapMsg.acc = toExtAcc(acc); +// rigidTapMsg.ini_maxjerk = TO_EXT_LEN(getStraightJerk(x, y, z, +// canon.endPoint.a, canon.endPoint.b, canon.endPoint.c, +// canon.endPoint.u, canon.endPoint.v, canon.endPoint.w)); + vel = canon.spindle_dir * canon.spindleSpeed / 60; // unit: rps + acc = emcAxisGetMaxAcceleration(9); // AXIS_S: 9 rigidTapMsg.pos = to_ext_pose(x,y,z, canon.endPoint.a, canon.endPoint.b, canon.endPoint.c, canon.endPoint.u, canon.endPoint.v, canon.endPoint.w); - rigidTapMsg.vel = toExtVel(vel); - rigidTapMsg.ini_maxvel = toExtVel(ini_maxvel); - rigidTapMsg.acc = toExtAcc(acc); - rigidTapMsg.ini_maxjerk = TO_EXT_LEN(getStraightJerk(x, y, z, - canon.endPoint.a, canon.endPoint.b, canon.endPoint.c, - canon.endPoint.u, canon.endPoint.v, canon.endPoint.w)); + // spindle velocity unit: rps + rigidTapMsg.vel = (vel); + rigidTapMsg.ini_maxvel = emcAxisGetMaxVelocity(9); // AXIS_S: 9 + rigidTapMsg.acc = acc; + rigidTapMsg.ini_maxjerk = emcAxisGetMaxJerk(9); // AXIS_S: 9 + flush_segments(); DP("x(%f) y(%f) z(%f)\n", x, y, z); diff --git a/src/hal/components/spindle.comp b/src/hal/components/spindle.comp index 5d6235ff6..ccb00f074 100644 --- a/src/hal/components/spindle.comp +++ b/src/hal/components/spindle.comp @@ -129,14 +129,17 @@ FUNCTION(_) { cur_state = S_IDLE; } - at_speed = 0; - in_position = 0; + + //printf("cur_state(%d)\n", cur_state); switch (cur_state) { case S_IDLE: + at_speed = 1; + in_position = 0; if (on) { if (velocity_mode) { cur_state = S_VEL_MODE; + at_speed = 0; } else { cur_state = S_POS_MODE; } @@ -154,6 +157,8 @@ FUNCTION(_) { case S_VEL_DECEL: // decel to vel == 0 + at_speed = 0; + in_position = 0; vel_ctrl (0, fperiod); if (curr_vel == 0) { cur_state = S_IDLE; @@ -164,11 +169,16 @@ FUNCTION(_) { case S_POS_MODE: // TODO + at_speed = 1; in_position = 1; tmp = curr_vel; curr_vel = (position_cmd - curr_pos) / fperiod; curr_acc = curr_vel - tmp; curr_pos = position_cmd; + if ((!on) || (velocity_mode)) + { + cur_state = S_VEL_DECEL; + } break; default: From c0cad300288e4ea72bd725c3f2f4161c8cf35c3a Mon Sep 17 00:00:00 2001 From: Yishin Li Date: Sat, 9 Mar 2013 12:30:18 +0800 Subject: [PATCH 021/256] Update miller settings at configs/araisrobo/miller --- configs/araisrobo/miller/miller.bin | Bin 7992 -> 7952 bytes configs/araisrobo/miller/miller.hal | 4 +-- configs/araisrobo/miller/miller.ini | 40 ++++++++++++------------ configs/araisrobo/miller/miller_vcp.hal | 4 +-- nc_files/araisrobo/miller/rigid_tap.ngc | 2 +- 5 files changed, 25 insertions(+), 25 deletions(-) diff --git a/configs/araisrobo/miller/miller.bin b/configs/araisrobo/miller/miller.bin index 6c577b76bbe3f8ebaebb3517665cdaffd443e216..2f046adb10a804d928f8a1ec8c4e6dfe1e19d034 100644 GIT binary patch delta 529 zcmZ8eKS&!<82`PymungwE~(PXh1e?!$)VKP(y1g(hYHd~x;VHTgl-uf95Ni_#3hLM zI-c>sOG%p!LKZ=XgCaV0EKc%<2##HJ6a5~g^w03V?|r}D_x*m~;~mzvYX^@t<_JrB z_s}dPz~I8Y5>2g;zn%mjJ#guRb6{OYDjU}#(n<{COk1rYPZOWNyE2S`U<-ufZow8tXp`IbjL4L72Dov=5Gv%IeI!nt0C@cGKZ(OzAlyRa#LdGEkZ zDF1M!?Nk2fMuRrY!8c6&Qga~EscCxQTxz!H#~(EGdK|qInDGhH@g?duXwIa*wbbTI z+C{JSJIX=r;!w?Z{;l=5s{R`j72^pxEE@%iP2&~CzR_S9jz4&jVUeh3S1E?sXSOS4 zqnr+6@Xjfi+%N0DeZ(j`UqsMG5C>q#Gk^&^RljCM1n|GWu$3ET*w&4v(iv?O) z*N$B*ra<>gAa%_uP7VtIvIruJAq4O+YZ+?~b;~L0|7R(T>}gzM;fM5L3s(vP3ediSwTPGmvdn=0@o=ovx@%4%d3UW284>KHYvx0 zIS&Y5=4Csvc9M9imUUlo>i!4v+>1@CI2u^n&<3~Gq zq0Yn%3$@6dE>+rhEOa^oodY=S1IYGQ#4f1LA>H-d`h`${FKjo=1akwAe6jJb&#xH& z@0gbMbcvMsVE%^Q@P@I;JtRkOMZK5pOSD65S6SE_*yl%BU#t8Io%i!++yGhCmq{C< u@fIw5?(^T%^_%=zs{5WV(kaKz{gL8-Y47$}Z-jmB$ joint.3.risc-pos-cmd # use LSN as homing switch for AXIS-X, AXIS-Y: setp joint.0.home-sw-id 4 -setp joint.1.home-sw-id 6 +setp joint.1.home-sw-id 7 # use LSP as homing switch for AXIS-Z: setp joint.2.home-sw-id 9 # home switch status from FPGA net din_04 joint.0.home-sw-in -net din_06 joint.1.home-sw-in +net din_07 joint.1.home-sw-in net din_09 joint.2.home-sw-in net j0-homing joint.0.homing => wou.stepgen.0.homing diff --git a/configs/araisrobo/miller/miller.ini b/configs/araisrobo/miller/miller.ini index 52629e2ba..7cb8a86a7 100644 --- a/configs/araisrobo/miller/miller.ini +++ b/configs/araisrobo/miller/miller.ini @@ -179,12 +179,12 @@ MAX_LIMIT = 131 FERROR = 3 MIN_FERROR = 2 HOME_OFFSET = -11.327 -HOME_SEARCH_VEL = 0.0 -HOME_LATCH_VEL = 0.0 -HOME_FINAL_VEL = 0.0 -# HOME_SEARCH_VEL = 9.0 -# HOME_LATCH_VEL = 1.0 -# HOME_FINAL_VEL = 9.0 +# HOME_SEARCH_VEL = 0.0 +# HOME_LATCH_VEL = 0.0 +# HOME_FINAL_VEL = 0.0 +HOME_SEARCH_VEL = 9.0 +HOME_LATCH_VEL = 1.0 +HOME_FINAL_VEL = 9.0 HOME_USE_INDEX = NO HOME_IGNORE_LIMITS = YES HOME_SEQUENCE = 1 @@ -210,12 +210,12 @@ MAX_LIMIT = 157 FERROR = 190 MIN_FERROR = 190 HOME_OFFSET = -11.368 -HOME_SEARCH_VEL = 0.0 -HOME_LATCH_VEL = 0.0 -HOME_FINAL_VEL = 0.0 -# HOME_SEARCH_VEL = 9.0 -# HOME_LATCH_VEL = 1.0 -# HOME_FINAL_VEL = 9.0 +# HOME_SEARCH_VEL = 0.0 +# HOME_LATCH_VEL = 0.0 +# HOME_FINAL_VEL = 0.0 +HOME_SEARCH_VEL = 9.0 +HOME_LATCH_VEL = 1.0 +HOME_FINAL_VEL = 9.0 HOME_USE_INDEX = NO HOME_IGNORE_LIMITS = YES HOME_SEQUENCE = 1 @@ -243,12 +243,12 @@ FERROR = 190 MIN_FERROR = 190 HOME_OFFSET = 11.541 # HOME_OFFSET = -21.5 -HOME_SEARCH_VEL = 0.0 -HOME_LATCH_VEL = 0.0 -HOME_FINAL_VEL = 0.0 -# HOME_SEARCH_VEL = -9.0 -# HOME_LATCH_VEL = -1.0 -# HOME_FINAL_VEL = 9.0 +# HOME_SEARCH_VEL = 0.0 +# HOME_LATCH_VEL = 0.0 +# HOME_FINAL_VEL = 0.0 +HOME_SEARCH_VEL = -9.0 +HOME_LATCH_VEL = -1.0 +HOME_FINAL_VEL = 9.0 HOME_USE_INDEX = NO HOME_IGNORE_LIMITS = YES HOME_SEQUENCE = 0 @@ -311,10 +311,10 @@ RISC = "miller.bin" CTRL_TYPE = "p,p,p,p" # PULSE_TYPE(a): ab-phase # PULSE_TYPE(s): step-dir -PULSE_TYPE = "s,s,s,s" +PULSE_TYPE = "s,s,s,a" # ENC_TYPE(l): LOOP-BACK PULSE_CMD to ENCODER (fake ENCODER counts) # ENC_TYPE(r): REAL ENCODER counts -ENC_TYPE = "l,l,l,l" +ENC_TYPE = "l,l,l,r" # PROBE_CONFIG[31:0]: # [ 7: 0] digital pin diff --git a/configs/araisrobo/miller/miller_vcp.hal b/configs/araisrobo/miller/miller_vcp.hal index df444fc69..dfe18abad 100644 --- a/configs/araisrobo/miller/miller_vcp.hal +++ b/configs/araisrobo/miller/miller_vcp.hal @@ -37,8 +37,8 @@ net dout3 gladevcp.do3 => gladevcp.led3 wou.gpio.out.03 net dout4 gladevcp.do4 => gladevcp.led4 wou.gpio.out.04 net dout5 gladevcp.do5 => gladevcp.led5 wou.gpio.out.05 net dout6 gladevcp.do6 => gladevcp.led6 wou.gpio.out.06 -net machine_is_on => gladevcp.led7 wou.gpio.out.07 -# net dout7 gladevcp.do7 => gladevcp.led7 wou.gpio.out.07 +# net machine_is_on => gladevcp.led7 wou.gpio.out.07 +#TODO: dout7 is for tool chang: net dout7 gladevcp.do7 => gladevcp.led7 wou.gpio.out.07 # the MDI Toggle action is called with the values of some of the HAL pins # as parameters like so: diff --git a/nc_files/araisrobo/miller/rigid_tap.ngc b/nc_files/araisrobo/miller/rigid_tap.ngc index 18e279fc5..6596982d8 100644 --- a/nc_files/araisrobo/miller/rigid_tap.ngc +++ b/nc_files/araisrobo/miller/rigid_tap.ngc @@ -1,5 +1,5 @@ G21 G91 g0z0 s60m3 ; 1rps -g33.1 z5 k1 ; 1 thread per second, k - distance per revolution +g33.1 z-5 k1 ; 1 thread per second, k - distance per revolution m2 From 7b53657716835ecd697129d7945e3d41c60f5ba4 Mon Sep 17 00:00:00 2001 From: Yishin Li Date: Sun, 10 Mar 2013 07:51:59 +0800 Subject: [PATCH 022/256] Update HAL for configs/araisrobo/miller --- configs/araisrobo/miller/miller_vcp.hal | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/configs/araisrobo/miller/miller_vcp.hal b/configs/araisrobo/miller/miller_vcp.hal index dfe18abad..1e5f36bee 100644 --- a/configs/araisrobo/miller/miller_vcp.hal +++ b/configs/araisrobo/miller/miller_vcp.hal @@ -38,7 +38,8 @@ net dout4 gladevcp.do4 => gladevcp.led4 wou.gpio.out.04 net dout5 gladevcp.do5 => gladevcp.led5 wou.gpio.out.05 net dout6 gladevcp.do6 => gladevcp.led6 wou.gpio.out.06 # net machine_is_on => gladevcp.led7 wou.gpio.out.07 -#TODO: dout7 is for tool chang: net dout7 gladevcp.do7 => gladevcp.led7 wou.gpio.out.07 +#dout7 is for tool chang +net dout7 gladevcp.do7 => gladevcp.led7 wou.gpio.out.07 # the MDI Toggle action is called with the values of some of the HAL pins # as parameters like so: From 1b1d6cb9fc66bab0ab90845422bdc12051e3dbe4 Mon Sep 17 00:00:00 2001 From: Yishin Li Date: Sun, 10 Mar 2013 07:54:20 +0800 Subject: [PATCH 023/256] tp.c: force updating motion.spindle-velocity-mode while tp is IDLE --- src/emc/kinematics/tp.c | 12 ++++-------- 1 file changed, 4 insertions(+), 8 deletions(-) diff --git a/src/emc/kinematics/tp.c b/src/emc/kinematics/tp.c index 31c113f58..2193dba5b 100644 --- a/src/emc/kinematics/tp.c +++ b/src/emc/kinematics/tp.c @@ -1356,14 +1356,8 @@ int tpRunCycle(TP_STRUCT * tp, long period) static double spindleoffset; static int waiting_for_index = MOTION_INVALID_ID; static int waiting_for_atspeed = MOTION_INVALID_ID; -// static double revs; EmcPose target; - if (tp->synchronized == 0) { - // prepare spindle speed command - - } - emcmotStatus->tcqlen = tcqLen(&tp->queue); emcmotStatus->requested_vel = 0.0; tc = tcqItem(&tp->queue, 0, period); @@ -1381,6 +1375,8 @@ int tpRunCycle(TP_STRUCT * tp, long period) tpResume(tp); // when not executing a move, use the current enable flags emcmotStatus->enables_queued = emcmotStatus->enables_new; + // spindleSync maps to motion.spindle-velocity-mode + emcmotStatus->spindleSync = tp->synchronized; return 0; } @@ -1912,9 +1908,9 @@ int tpSetSpindleSync(TP_STRUCT * tp, double sync, int mode) { tp->synchronized = 1; tp->uu_per_rev = sync; tp->velocity_mode = mode; - } else + } else { tp->synchronized = 0; - + } return 0; } From 694690edebc881c975d8d021e4a3360cedc36a6d Mon Sep 17 00:00:00 2001 From: davidzheng Date: Mon, 11 Mar 2013 13:13:50 +0800 Subject: [PATCH 024/256] Add testing config, .test.ini, for araisrobo/miller --- configs/araisrobo/miller/.test.ini | 332 +++++++++++++++++++++++++++++ 1 file changed, 332 insertions(+) create mode 100644 configs/araisrobo/miller/.test.ini diff --git a/configs/araisrobo/miller/.test.ini b/configs/araisrobo/miller/.test.ini new file mode 100644 index 000000000..14a1507c4 --- /dev/null +++ b/configs/araisrobo/miller/.test.ini @@ -0,0 +1,332 @@ +# General section ------------------------------------------------------------- +[EMC] + +# Version of this INI file +VERSION = $Revision$ + +# Name of machine, for use with display, etc. +# HP: high precision (0.5um per pulse) +# HS: high speed (MAX_VELOCITY: 15mm/sec) +MACHINE = MILLER + +# Debug level, 0 means no messages. See src/emc/nml_int/emcglb.h for others +DEBUG = 0 + +# Sections for display options ------------------------------------------------ +[DISPLAY] + +# add GladeVCP panel where PyVCP used to live: +GLADEVCP = -u miller_vcp.py miller_vcp.ui + +# Name of display program, e.g., xemc +DISPLAY = axis +# DISPLAY = keystick + +# Cycle time, in seconds, that display will sleep between polls +CYCLE_TIME = 0.030 + +HELP_FILE = doc/help.txt + +# Initial display setting for position, RELATIVE or MACHINE +POSITION_OFFSET = RELATIVE + +# Initial display setting for position, COMMANDED or ACTUAL +POSITION_FEEDBACK = ACTUAL + +# Highest value that will be allowed for feed override, 1.0 = 100% +MAX_FEED_OVERRIDE = 1.2 +MAX_SPINDLE_OVERRIDE = 1.0 +# Prefix to be used +PROGRAM_PREFIX = ../../../nc_files +OPEN_FILE = ../../../nc_files/araisrobo/miller/rigid_tap.ngc + +# Introductory graphic +INTRO_GRAPHIC = emc2.gif +INTRO_TIME = 2 + +EDITOR = gedit + +INCREMENTS = 1 mm, .1mm, .01mm + +[FILTER] +PROGRAM_EXTENSION = .png,.gif,.jpg Grayscale Depth Image +PROGRAM_EXTENSION = .py Python Script + +png = image-to-gcode +gif = image-to-gcode +jpg = image-to-gcode +py = python + +# Task controller section ----------------------------------------------------- +[TASK] + +# Name of task controller program, e.g., milltask +TASK = milltask + +# Cycle time, in seconds, that task controller will sleep between polls +CYCLE_TIME = 0.001 + +# Part program interpreter section -------------------------------------------- +[RS274NGC] + +# File containing interpreter variables +PARAMETER_FILE = miller.var +# Motion control section ------------------------------------------------------ +[EMCMOT] + +EMCMOT = motmod + +# Timeout for comm to emcmot, in seconds +COMM_TIMEOUT = 1.0 + +# Interval between tries to emcmot, in seconds +COMM_WAIT = 0.010 + +#- Servo task period, in nanoseconds - will be rounded to an int multiple of BASE_PERIOD +# 40ns * 16384ticks = 655360ns +SERVO_PERIOD = 655360 + +#- Trajectory Planner task period, in nanoseconds - will be rounded to an integer multiple of SERVO_PERIOD +TRAJ_PERIOD = 655360 + + +# Hardware Abstraction Layer section -------------------------------------------------- +[HAL] + +# The run script first uses halcmd to execute any HALFILE +# files, and then to execute any individual HALCMD commands. +# + +# list of hal config files to run through halcmd +# files are executed in the order in which they appear +# HALFILE = ../sim/sim_spindle_encoder.hal +HALFILE = miller.hal +HALFILE = axis_manualtoolchange.hal +POSTGUI_HALFILE = miller_vcp.hal + +HALUI = halui + +# Trajectory planner section -------------------------------------------------- +[TRAJ] + +AXES = 4 +COORDINATES = X Y Z S +HOME = 0 0 0 0 +LINEAR_UNITS = mm +ANGULAR_UNITS = degree + +#orig: DEFAULT_LINEAR_VELOCITY = 10 +#orig: DEFAULT_LINEAR_ACCEL = 50 +#orig: DEFAULT_ANGULAR_VELOCITY = 75 +#orig: DEFAULT_ANGULAR_ACCEL = 300 +#orig: MAX_LINEAR_VELOCITY = 39 +#orig: MAX_LINEAR_ACCEL = 50 +#orig: MAX_ANGULAR_VELOCITY = 100 +#orig: MAX_ANGULAR_ACCEL = 800 + +DEFAULT_LINEAR_VELOCITY = 5 +DEFAULT_LINEAR_ACCEL = 47 +DEFAULT_LINEAR_JERK = 230 +MAX_LINEAR_VELOCITY = 9.5 +MAX_LINEAR_ACCEL = 47.5 +MAX_LINEAR_JERK = 233 + +[KINS] +JOINTS = 4 +# KINEMATICS = miller_kins +KINEMATICS = trivkins + +# Axes sections --------------------------------------------------------------- +[AXIS_X] +HOME = 0.000 +MAX_VELOCITY = 9.5 +MAX_ACCELERATION = 48 +MAX_JERK = 234 + +[AXIS_Y] +HOME = 0.000 +MAX_VELOCITY = 9.5 +MAX_ACCELERATION = 48 +MAX_JERK = 234 + +[AXIS_Z] +HOME = 0.000 +MAX_VELOCITY = 9.5 +MAX_ACCELERATION = 48 +MAX_JERK = 234 + +[AXIS_S] +HOME = 0.000 +MAX_VELOCITY = 33.33 +MAX_ACCELERATION = 116.67 +MAX_JERK = 583.33 + +# Joints sections + +# First joint +[JOINT_0] +TYPE = LINEAR +HOME = 0.000 +MAX_VELOCITY = 10 +MAX_ACCELERATION = 49 +MAX_JERK = 245 +BACKLASH = 0.000 +INPUT_SCALE = -51200 +OUTPUT_SCALE = 1.000 +PULSE_PER_REV = 51200 +MIN_LIMIT = -10 +MAX_LIMIT = 131 +FERROR = 3 +MIN_FERROR = 2 +HOME_OFFSET = -11.327 +HOME_SEARCH_VEL = 0.0 +HOME_LATCH_VEL = 0.0 +HOME_FINAL_VEL = 0.0 +# HOME_SEARCH_VEL = 9.0 +# HOME_LATCH_VEL = 1.0 +# HOME_FINAL_VEL = 9.0 +HOME_USE_INDEX = NO +HOME_IGNORE_LIMITS = YES +HOME_SEQUENCE = 1 +#TODO: HOME_IS_SHARED = 1 +# minimum steplen, 200ns, 5MHz +# minimum delay for dir change +STEPLEN = 200 +DIRDELAY = 0 + +# Second axis +[JOINT_1] +TYPE = LINEAR +HOME = 0.000 +MAX_VELOCITY = 10 +MAX_ACCELERATION = 49 +MAX_JERK = 245 +BACKLASH = 0.000 +INPUT_SCALE = -51200 +OUTPUT_SCALE = 1.000 +PULSE_PER_REV = 51200 +MIN_LIMIT = -10 +MAX_LIMIT = 157 +FERROR = 190 +MIN_FERROR = 190 +HOME_OFFSET = -11.368 +HOME_SEARCH_VEL = 0.0 +HOME_LATCH_VEL = 0.0 +HOME_FINAL_VEL = 0.0 +# HOME_SEARCH_VEL = 9.0 +# HOME_LATCH_VEL = 1.0 +# HOME_FINAL_VEL = 9.0 +HOME_USE_INDEX = NO +HOME_IGNORE_LIMITS = YES +HOME_SEQUENCE = 1 +#TODO: HOME_IS_SHARED = 1 +# minimum steplen, 200ns, 5MHz +# minimum delay for dir change +STEPLEN = 200 +DIRDELAY = 0 + +[JOINT_2] +TYPE = LINEAR +HOME = 0 +MAX_VELOCITY = 10 +MAX_ACCELERATION = 49 +MAX_JERK = 245 +BACKLASH = 0.000 +INPUT_SCALE = 25000 +OUTPUT_SCALE = 1.000 +PULSE_PER_REV = 25000 +# MIN_LIMIT = -87 +# MAX_LIMIT = 10 +MIN_LIMIT = -50000 +MAX_LIMIT = 50000 +FERROR = 190 +MIN_FERROR = 190 +HOME_OFFSET = 11.541 +# HOME_OFFSET = -21.5 +HOME_SEARCH_VEL = 0.0 +HOME_LATCH_VEL = 0.0 +HOME_FINAL_VEL = 0.0 +# HOME_SEARCH_VEL = -9.0 +# HOME_LATCH_VEL = -1.0 +# HOME_FINAL_VEL = 9.0 +HOME_USE_INDEX = NO +HOME_IGNORE_LIMITS = YES +HOME_SEQUENCE = 0 +#TODO: HOME_IS_SHARED = 1 +# minimum steplen, 200ns, 5MHz +# minimum delay for dir change +STEPLEN = 200 +DIRDELAY = 0 + + +[JOINT_3] +TYPE = ANGULAR +HOME = 0 +MAX_VELOCITY = 33.33 +MAX_ACCELERATION = 116.67 +MAX_JERK = 583.33 +BACKLASH = 0.000 +INPUT_SCALE = 15000 +OUTPUT_SCALE = 1.000 +PULSE_PER_REV = 10000 +# MIN_LIMIT = -87 +# MAX_LIMIT = 10 +MIN_LIMIT = -50000 +MAX_LIMIT = 50000 +FERROR = 190 +MIN_FERROR = 190 +HOME_OFFSET = 11.541 +# HOME_OFFSET = -21.5 +HOME_SEARCH_VEL = 0.0 +HOME_LATCH_VEL = 0.0 +HOME_FINAL_VEL = 0.0 +# HOME_SEARCH_VEL = -9.0 +# HOME_LATCH_VEL = -1.0 +# HOME_FINAL_VEL = 9.0 +HOME_USE_INDEX = NO +HOME_IGNORE_LIMITS = YES +HOME_SEQUENCE = 0 +#TODO: HOME_IS_SHARED = 1 +# minimum steplen, 200ns, 5MHz +# minimum delay for dir change +STEPLEN = 200 +DIRDELAY = 0 + + +# section for main IO controller parameters ----------------------------------- +[EMCIO] +# Name of IO controller program, e.g., io +EMCIO = io + +# cycle time, in seconds +CYCLE_TIME = 0.100 + +# tool table file +TOOL_TABLE = simpockets.tbl +TOOL_CHANGE_POSITION = 0 0 50.8 + +[WOU] +FPGA = "usb.bit" +RISC = "miller.bin" +CTRL_TYPE = "p,p,p,p" +# PULSE_TYPE(a): ab-phase +# PULSE_TYPE(s): step-dir +PULSE_TYPE = "s,s,s,a" +# ENC_TYPE(l): LOOP-BACK PULSE_CMD to ENCODER (fake ENCODER counts) +# ENC_TYPE(r): REAL ENCODER counts +ENC_TYPE = "l,l,r,r" + +# PROBE_CONFIG[31:0]: +# [ 7: 0] digital pin +# [15: 8] analog channel +# [20:16] probe type +# probe_type: DIGITAL_ONLY(0), ANALOG_ONLY(1), +# DIGITAL_OR_ANALOG(2), DIGITAL_AND_ANALOG(3) +# PROBE_CONFIG = DIGITAL_ONLY(0), analog-ch(0), din-ch(0x1) +PROBE_CONFIG = 0x00000001 + +WISHBONE = wou + +# ALR_OUTPUT: the DOUT port value when ALARM is triggered +ALR_OUTPUT = 0x00000000 +ALARM_EN = 0 From c85f83b517c722d536e95b53b891f7b428a4c98b Mon Sep 17 00:00:00 2001 From: Yishin Li Date: Tue, 12 Mar 2013 18:33:12 +0800 Subject: [PATCH 025/256] Add ENC_POL setting to ar-usb/wou_stepgen.c * support ENCODER POLARITY setting on INI/HAL file * refer to araisrobo/miller/{.test.ini,miller.hal} --- configs/araisrobo/miller/.test.ini | 40 +++++++++++++++++++++++----- configs/araisrobo/miller/miller.hal | 2 +- src/hal/drivers/ar-usb/wou_stepgen.c | 24 +++++++++++++++++ 3 files changed, 59 insertions(+), 7 deletions(-) diff --git a/configs/araisrobo/miller/.test.ini b/configs/araisrobo/miller/.test.ini index 14a1507c4..898344171 100644 --- a/configs/araisrobo/miller/.test.ini +++ b/configs/araisrobo/miller/.test.ini @@ -173,7 +173,7 @@ MAX_JERK = 245 BACKLASH = 0.000 INPUT_SCALE = -51200 OUTPUT_SCALE = 1.000 -PULSE_PER_REV = 51200 +PULSE_PER_REV = 102400 MIN_LIMIT = -10 MAX_LIMIT = 131 FERROR = 3 @@ -204,7 +204,7 @@ MAX_JERK = 245 BACKLASH = 0.000 INPUT_SCALE = -51200 OUTPUT_SCALE = 1.000 -PULSE_PER_REV = 51200 +PULSE_PER_REV = 102400 MIN_LIMIT = -10 MAX_LIMIT = 157 FERROR = 190 @@ -232,9 +232,9 @@ MAX_VELOCITY = 10 MAX_ACCELERATION = 49 MAX_JERK = 245 BACKLASH = 0.000 -INPUT_SCALE = 25000 +INPUT_SCALE = 25600 OUTPUT_SCALE = 1.000 -PULSE_PER_REV = 25000 +PULSE_PER_REV = 51200 # MIN_LIMIT = -87 # MAX_LIMIT = 10 MIN_LIMIT = -50000 @@ -242,13 +242,15 @@ MAX_LIMIT = 50000 FERROR = 190 MIN_FERROR = 190 HOME_OFFSET = 11.541 -# HOME_OFFSET = -21.5 + HOME_SEARCH_VEL = 0.0 HOME_LATCH_VEL = 0.0 -HOME_FINAL_VEL = 0.0 +HOME_FINAL_VEL = 0.0 + # HOME_SEARCH_VEL = -9.0 # HOME_LATCH_VEL = -1.0 # HOME_FINAL_VEL = 9.0 + HOME_USE_INDEX = NO HOME_IGNORE_LIMITS = YES HOME_SEQUENCE = 0 @@ -306,6 +308,29 @@ TOOL_TABLE = simpockets.tbl TOOL_CHANGE_POSITION = 0 0 50.8 [WOU] +########################################################## +# Parameters: # +# (unit for all gains: 1/65536) # +# P : p gain # +# I : i gain # +# D : d gain # +# FF0, FF1, FF2: feedforward gains # +# M_ER: max error # +# M_EI: max error_i # +# M_ED: max error_d # +# MCD : max cmd derivative # +# MCDD: max 2nd order command derivative # +# MO : max output (redundant, replaced by MAX_VELOCITY) # +# + for motion control MO is replaced. # +# + for normal pid loop MO takes effect # +########################################################## +# J0/X, J1/Y, J2/Z, J3/SPINDLE +# P I D FF0 FF1 FF2 DB BI M_ER M_EI M_ED MCD MCDD MO +J0_PID = " 0, 0, 0, 0, 65536, 0, 0, 0, 0, 0, 0, 0, 0, 0" +J1_PID = " 0, 0, 0, 0, 65536, 0, 0, 0, 0, 0, 0, 0, 0, 0" +J2_PID = " 500, 0, 2500, 0, 65500, 0, 4, 0, 0, 0, 0, 0, 0, 0" +J3_PID = " 500, 0, 2500, 0, 65500, 0, 0, 0, 0, 0, 0, 0, 0, 0" + FPGA = "usb.bit" RISC = "miller.bin" CTRL_TYPE = "p,p,p,p" @@ -315,6 +340,9 @@ PULSE_TYPE = "s,s,s,a" # ENC_TYPE(l): LOOP-BACK PULSE_CMD to ENCODER (fake ENCODER counts) # ENC_TYPE(r): REAL ENCODER counts ENC_TYPE = "l,l,r,r" +# ENC_POL(p): POSITIVE POLARITY for ENCODER SIGNAL +# ENC_POL(n): NEGATIVE POLARITY for ENCODER SIGNAL +ENC_POL = "p,p,n,p" # PROBE_CONFIG[31:0]: # [ 7: 0] digital pin diff --git a/configs/araisrobo/miller/miller.hal b/configs/araisrobo/miller/miller.hal index 637ba8478..0fd43d9e2 100644 --- a/configs/araisrobo/miller/miller.hal +++ b/configs/araisrobo/miller/miller.hal @@ -7,7 +7,7 @@ loadrt spindle # load RT modules loadrt [KINS]KINEMATICS loadrt [EMCMOT]EMCMOT servo_period_nsec=[EMCMOT]SERVO_PERIOD traj_period_nsec=[EMCMOT]TRAJ_PERIOD num_joints=[KINS]JOINTS num_dio=64 -loadrt [WOU](WISHBONE) ctrl_type=[WOU](CTRL_TYPE) pulse_type=[WOU]PULSE_TYPE enc_type=[WOU]ENC_TYPE bits=[WOU](FPGA) bins=[WOU](RISC) servo_period_ns=[EMCMOT]SERVO_PERIOD alarm_en=[WOU]ALARM_EN max_vel_str=[JOINT_0]MAX_VELOCITY,[JOINT_1]MAX_VELOCITY,[JOINT_2]MAX_VELOCITY,[JOINT_3]MAX_VELOCITY max_accel_str=[JOINT_0]MAX_ACCELERATION,[JOINT_1]MAX_ACCELERATION,[JOINT_2]MAX_ACCELERATION,[JOINT_3]MAX_ACCELERATION max_jerk_str=[JOINT_0]MAX_JERK,[JOINT_1]MAX_JERK,[JOINT_2]MAX_JERK,[JOINT_3]MAX_JERK pos_scale_str=[JOINT_0]INPUT_SCALE,[JOINT_1]INPUT_SCALE,[JOINT_2]INPUT_SCALE,[JOINT_3]INPUT_SCALE alr_output=[WOU](ALR_OUTPUT) +loadrt [WOU](WISHBONE) ctrl_type=[WOU](CTRL_TYPE) pulse_type=[WOU]PULSE_TYPE enc_type=[WOU]ENC_TYPE enc_pol=[WOU]ENC_POL bits=[WOU](FPGA) bins=[WOU](RISC) servo_period_ns=[EMCMOT]SERVO_PERIOD alarm_en=[WOU]ALARM_EN max_vel_str=[JOINT_0]MAX_VELOCITY,[JOINT_1]MAX_VELOCITY,[JOINT_2]MAX_VELOCITY,[JOINT_3]MAX_VELOCITY max_accel_str=[JOINT_0]MAX_ACCELERATION,[JOINT_1]MAX_ACCELERATION,[JOINT_2]MAX_ACCELERATION,[JOINT_3]MAX_ACCELERATION max_jerk_str=[JOINT_0]MAX_JERK,[JOINT_1]MAX_JERK,[JOINT_2]MAX_JERK,[JOINT_3]MAX_JERK pos_scale_str=[JOINT_0]INPUT_SCALE,[JOINT_1]INPUT_SCALE,[JOINT_2]INPUT_SCALE,[JOINT_3]INPUT_SCALE ferror_str=[JOINT_0]FERROR,[JOINT_1]FERROR,[JOINT_2]FERROR,[JOINT_3]FERROR j0_pid_str=[WOU](J0_PID) j1_pid_str=[WOU](J1_PID) j2_pid_str=[WOU](J2_PID) j3_pid_str=[WOU](J3_PID) alr_output=[WOU](ALR_OUTPUT) # add motion controller functions to servo thread addf motion-command-handler servo-thread diff --git a/src/hal/drivers/ar-usb/wou_stepgen.c b/src/hal/drivers/ar-usb/wou_stepgen.c index 46ee6bfb3..136287724 100644 --- a/src/hal/drivers/ar-usb/wou_stepgen.c +++ b/src/hal/drivers/ar-usb/wou_stepgen.c @@ -90,6 +90,11 @@ const char *enc_type[MAX_CHAN] = RTAPI_MP_ARRAY_STRING(enc_type, MAX_CHAN, "encoder type (REAL(r) or LOOP-BACK(l)) for up to 8 channels"); +// enc_pol: encoder polarity, default to POSITIVE(p) +const char *enc_pol[MAX_CHAN] = +{ "p", "p", "p", "p", "p", "p", "p", "p" }; +RTAPI_MP_ARRAY_STRING(enc_pol, MAX_CHAN, + "encoder polarity (POSITIVE(p) or NEGATIVE(n)) for up to 8 channels"); const char *bits = "\0"; RTAPI_MP_STRING(bits, "FPGA bitfile"); @@ -1000,6 +1005,25 @@ int rtapi_app_main(void) return -1; } + // "encoder polarity (POSITIVE(p) or NEGATIVE(n)) for up to 8 channels" + data[0] = 0; + for (n = 0; n < MAX_CHAN; n++) { + if ((enc_pol[n][0] == 'p') || (enc_pol[n][0] == 'P')) { + // ENC_POL(0): POSITIVE ENCODER POLARITY (default) + } else if ((enc_pol[n][0] == 'n') || (enc_pol[n][0] == 'N')) { + // ENC_POL(1): NEGATIVE ENCODER POLARITY + data[0] |= (1 << n); + } else { + rtapi_print_msg(RTAPI_MSG_ERR, + "STEPGEN: ERROR: bad enc_pol '%s' for joint %i (must be 'p' or 'n')\n", + enc_pol[n], n); + return -1; + } + } + wou_cmd (&w_param, WB_WR_CMD, + (uint16_t) (SSIF_BASE | SSIF_ENC_POL), + (uint8_t) 1, data); + // configure alarm output (for E-Stop) write_machine_param(ALR_OUTPUT, (uint32_t) strtoul(alr_output, NULL, 16)); fprintf(stderr, "ALR_OUTPUT(%08X)",(uint32_t) strtoul(alr_output, NULL, 16)); From 8a11bf884036155f672b0daf5dd0a05ddb2c9fcf Mon Sep 17 00:00:00 2001 From: Yishin Li Date: Tue, 12 Mar 2013 22:31:16 +0800 Subject: [PATCH 026/256] wou_stepgen.c: could pass ENCODER-SCALE to FPGA * Add ENC_SCALE to motion_parameter[] for FPGA * Remove MAX_JERK_RECIP from motion_parameter[] from FPGA * Update configs/araisrobo/miller/.test.ini to test ENC_SCALE implementation --- configs/araisrobo/miller/.test.ini | 4 ++ configs/araisrobo/miller/miller.bin | Bin 7952 -> 8028 bytes configs/araisrobo/miller/miller.hal | 2 +- configs/araisrobo/miller/usb.bit | Bin 212486 -> 212486 bytes src/hal/drivers/ar-usb/sync_cmd.h | 6 +-- src/hal/drivers/ar-usb/wou_sim.c | 8 ---- src/hal/drivers/ar-usb/wou_stepgen.c | 64 +++++++-------------------- 7 files changed, 24 insertions(+), 60 deletions(-) diff --git a/configs/araisrobo/miller/.test.ini b/configs/araisrobo/miller/.test.ini index 898344171..802f4df21 100644 --- a/configs/araisrobo/miller/.test.ini +++ b/configs/araisrobo/miller/.test.ini @@ -173,6 +173,7 @@ MAX_JERK = 245 BACKLASH = 0.000 INPUT_SCALE = -51200 OUTPUT_SCALE = 1.000 +ENC_SCALE = 1.0 PULSE_PER_REV = 102400 MIN_LIMIT = -10 MAX_LIMIT = 131 @@ -204,6 +205,7 @@ MAX_JERK = 245 BACKLASH = 0.000 INPUT_SCALE = -51200 OUTPUT_SCALE = 1.000 +ENC_SCALE = 1.0 PULSE_PER_REV = 102400 MIN_LIMIT = -10 MAX_LIMIT = 157 @@ -234,6 +236,7 @@ MAX_JERK = 245 BACKLASH = 0.000 INPUT_SCALE = 25600 OUTPUT_SCALE = 1.000 +ENC_SCALE = 3.1250 PULSE_PER_REV = 51200 # MIN_LIMIT = -87 # MAX_LIMIT = 10 @@ -270,6 +273,7 @@ MAX_JERK = 583.33 BACKLASH = 0.000 INPUT_SCALE = 15000 OUTPUT_SCALE = 1.000 +ENC_SCALE = 1.0 PULSE_PER_REV = 10000 # MIN_LIMIT = -87 # MAX_LIMIT = 10 diff --git a/configs/araisrobo/miller/miller.bin b/configs/araisrobo/miller/miller.bin index 2f046adb10a804d928f8a1ec8c4e6dfe1e19d034..943ba6fa345ca53f6f84ab536aef7698a2362273 100644 GIT binary patch delta 1052 zcmaJ|bU!7J-RR;Z8B21OguK8UT(7?!>`4aKTAS>G6uR(!vgiSIY67MgyhXdlQZ% z(|~mi(25M2qu^34${egQHvq^deH6pAA}7BWEU(@9PT5we_L<0W$Uc8lg*&=QO!)vw<@W+*xt}A&hgHRk8Ve4 zG;==BRF?cgC5v}fBH=JygJ1=_q zOhV@~r!;P*fEn*eo;wZL^*Xoxdn2~L-LUPhbtrd6R&ovIP0tCn zgHG3LeXh(onJsQ7tHF8>=b0zM9;QR=VKJmky?}2j3nS?esk0IO{&Rc&@$xptI`ZY3 z4i}ph+N$HnW}UAZ5;0)mXi?cLF$Sfu2SHj&IB61-vK6NaI~;NPLtZNbo_Go7+zF|R ziz;j;{R+W|fm2?qm|hjUXjsFrG8R~&d7cs*WOXeq`KlXJr=U1jh~}i1JXLA)HhXbF zbRt;8{63}B*&e<29|ZUx0;1Ljo7b7pcK@?jS>A#=Z=WfqQ&LhbH01N`<-*oooTt% z@_3!X3`bXvRcPyr!1#y6C#Oe=M*WM`06Y`iv%ooU)pMowFFLN$z~H=8&NQQjQXalZ zcxe}~ZvuLeLH88g2w{$c)r|H4a!HKNFulkL4}!3;W2);}rE^VkR}~6f120!>t+TS?%zJG#${acVw%UE=(HbA#x%jVO$uK7dc+Pm zKh%u}$`lRlbBzYpluBPS8jN($FDp%PD(5hzTT7`4m-ej`Ym=C~rc6!OI9gRCco0XC zu1CZf3p;o5Ni!C!bi4?@Sb)NKD$eV_jQQyK-XRozSKz~T(LF| z`wEavf)zFa8qlm;Bd~j6r>)X&FKMVk(`_kK;vt~s;T_pEWnMn&N@;4dEMUdwxBvFl zL((tDs9<^}*$@8ipDuis6SqQwx6&t}C#1FeU@uRDbKKvwS|a-;qLxa-&anTKPjY^7 z7W`*xCWLmRNby%o489iG4-VhC{Kdd|H6N;sF}5S$7~1J$u47i68F0N%I#OLgK`r-T zpG-_WfKoVw7}cGiL1XD$$y<_;@VsO^XlKDwFTlKeadlaCVJrEAI_xfR%8Sz=3W~|z z@`A5yDwdHXu-tUW*vu(=G@mqC|$lru2d4aFOzDJNg>Mxk37`VBDYVL*wP4#bIy zeoep#{UZ$j6Gjs^Qx>)ba{A`0D~W~LH6t%~9@pu4FWkS1P2@W^+-FMNg7dS^`~xXF BF|q&v diff --git a/configs/araisrobo/miller/miller.hal b/configs/araisrobo/miller/miller.hal index 0fd43d9e2..88373da4b 100644 --- a/configs/araisrobo/miller/miller.hal +++ b/configs/araisrobo/miller/miller.hal @@ -7,7 +7,7 @@ loadrt spindle # load RT modules loadrt [KINS]KINEMATICS loadrt [EMCMOT]EMCMOT servo_period_nsec=[EMCMOT]SERVO_PERIOD traj_period_nsec=[EMCMOT]TRAJ_PERIOD num_joints=[KINS]JOINTS num_dio=64 -loadrt [WOU](WISHBONE) ctrl_type=[WOU](CTRL_TYPE) pulse_type=[WOU]PULSE_TYPE enc_type=[WOU]ENC_TYPE enc_pol=[WOU]ENC_POL bits=[WOU](FPGA) bins=[WOU](RISC) servo_period_ns=[EMCMOT]SERVO_PERIOD alarm_en=[WOU]ALARM_EN max_vel_str=[JOINT_0]MAX_VELOCITY,[JOINT_1]MAX_VELOCITY,[JOINT_2]MAX_VELOCITY,[JOINT_3]MAX_VELOCITY max_accel_str=[JOINT_0]MAX_ACCELERATION,[JOINT_1]MAX_ACCELERATION,[JOINT_2]MAX_ACCELERATION,[JOINT_3]MAX_ACCELERATION max_jerk_str=[JOINT_0]MAX_JERK,[JOINT_1]MAX_JERK,[JOINT_2]MAX_JERK,[JOINT_3]MAX_JERK pos_scale_str=[JOINT_0]INPUT_SCALE,[JOINT_1]INPUT_SCALE,[JOINT_2]INPUT_SCALE,[JOINT_3]INPUT_SCALE ferror_str=[JOINT_0]FERROR,[JOINT_1]FERROR,[JOINT_2]FERROR,[JOINT_3]FERROR j0_pid_str=[WOU](J0_PID) j1_pid_str=[WOU](J1_PID) j2_pid_str=[WOU](J2_PID) j3_pid_str=[WOU](J3_PID) alr_output=[WOU](ALR_OUTPUT) +loadrt [WOU](WISHBONE) ctrl_type=[WOU](CTRL_TYPE) pulse_type=[WOU]PULSE_TYPE enc_type=[WOU]ENC_TYPE enc_pol=[WOU]ENC_POL bits=[WOU](FPGA) bins=[WOU](RISC) servo_period_ns=[EMCMOT]SERVO_PERIOD alarm_en=[WOU]ALARM_EN max_vel_str=[JOINT_0]MAX_VELOCITY,[JOINT_1]MAX_VELOCITY,[JOINT_2]MAX_VELOCITY,[JOINT_3]MAX_VELOCITY max_accel_str=[JOINT_0]MAX_ACCELERATION,[JOINT_1]MAX_ACCELERATION,[JOINT_2]MAX_ACCELERATION,[JOINT_3]MAX_ACCELERATION max_jerk_str=[JOINT_0]MAX_JERK,[JOINT_1]MAX_JERK,[JOINT_2]MAX_JERK,[JOINT_3]MAX_JERK pos_scale_str=[JOINT_0]INPUT_SCALE,[JOINT_1]INPUT_SCALE,[JOINT_2]INPUT_SCALE,[JOINT_3]INPUT_SCALE enc_scale_str=[JOINT_0]ENC_SCALE,[JOINT_1]ENC_SCALE,[JOINT_2]ENC_SCALE,[JOINT_3]ENC_SCALE ferror_str=[JOINT_0]FERROR,[JOINT_1]FERROR,[JOINT_2]FERROR,[JOINT_3]FERROR j0_pid_str=[WOU](J0_PID) j1_pid_str=[WOU](J1_PID) j2_pid_str=[WOU](J2_PID) j3_pid_str=[WOU](J3_PID) alr_output=[WOU](ALR_OUTPUT) # add motion controller functions to servo thread addf motion-command-handler servo-thread diff --git a/configs/araisrobo/miller/usb.bit b/configs/araisrobo/miller/usb.bit index 30ecc3804c42dd37c8281ee3a17eb5aee5c01935..906adaa08df227663fdae09d6604cb7747415b12 100644 GIT binary patch literal 212486 zcmeFa4VYBLnJ@m<>C-)@+cV9XVIa+lH0-EnhLN;5u+>e24U5{6F&DkWH0UO1 zNYWDHvMx!gn-&{H(-?Ho3vNSVmdqt)5>1|2 z&-=tR*IsnRr~YEYvh+fGNk&8sHp?kDZ8OdUefYS|9LAE)7i@AApC;t|Ht{pV z%qBrudQOS_C!lCehqU-lpv!*}6}11?CjUvE#Mx@-gt23t&Hb(6Dzya4HhEo_uBpBy z3_jaUZoG1TYi1JyW#sb*r8}!UmCxDwsPONq#~(`$P3=>UzFwiT@4}?%G9U6ejXID_qyD z?*85-%HJ=AtPlTsx(R(~LOm!Zq@s3@$Z)I|5AQX={@<~l{bD% z{JW?8zc)tvEvo;v_}`NJj}ZNPt*ZQwpum5cEPt<-c$?P$-%`IVyZ?BGIIBoG5w7#= z;R*I1&3U)-{-etO4HffF#MPg*=QqgyrYNuYO|kDDS1-RVQ7``w&99!%@9Wk#NOkx3 zP5;N1{}0hi{IP5C?~}i~3jg6*{ay=J{fOBzQC_`l-ydH7ziY~=6S>v(sk^^tA*Z{S zR4FAD3@Kcnq%>)k6cHiF;F1)#XlhcDEG@^0CnL*-Zc|wxktl&%mPUpQGK?}wPKKsQ z!!!bv*=ocMq)rEfp@)bG$#r3f0#eEXag@m@Ep?&kqMNh~6hdB76iV8*dx}!XGV(4O zq7*A6WeI8UXQX9Dq-BaScq%d?{3LBEQCw+4#G#FDQ8zfiA0={&AVO*~NrFKFa3sRS zrH**zJ5A!W*Y&v)@YNr_Vped(Qk}yfoho{T$V4Dc6wcD>ux=RCqBu$dm!X>mnHL(S z5(0l=0BvHDX~6LlU6nvKAuq&q(oqOE$;dYw++{ z)EoCqyV+2UsCS_pKhPgP3RGmM<8VM}?hjC)k^Bsbhm=nDnYI!M=;TMa_0sCDN_(dN zts#xH_pc?&sjMt3i{`eJ*GSoxHDf+d-S_0|8-y=p8n*o_JGA@iT<-2BJ8!nE1bTr{%W@)4WiK^iaMuvJKXSK(a%-e|jwO|!sdCGzY}=JX zKEhTJZs^RDy#)^XuB)c<2~A14eGqBUqhu`&SL`=QS8=t1&yZK8fut)|ySrW`=*GCA z-{B_SQN{w-B2-_xC2QQ3a{Xu!Mq0PakR)m`^=M1DJ~AY_GA@#a8m$_7sH?1@s<0i` zX)-6G6h|Yg)*K`d!ll(KBN3jcEj&yUYAh*&{6rE2gyL{@o4C7PrGa#Pr*Go4_Yd{) z-!WlbPN|`;`d#&?GeT~Rdvm#`gA>)NRadc3`&=PbJX3bUub(aT4l=)yrQRGVf${N^ zgCiruG%~W^^^cEM<@os6esG7!dj{#`Nk^*q$K?3fsh=V|IEw36pBf!{?7@-YQTp|V z9(!k8!KL5)3eWT+iagBVteB{WH(ebgqzA+o_NMB#i=#e8Y&OJHw3;CR*{|x14Pn;Nu z9yl;&k3?T{4jdR7J#gUU*G7lNPxOqA_kFE8G}<%toYOOkzoDU?cW#_^QR8EX=^NdP z@tU8-;i}#`!FOGR>+xsu{V}9V7Gq2YoZw;%scjAHH$YS|7%T{@- z@SD7PIcK=8P7~o~ve79gbpNd`iaDF~%xMn%EGEzf;3FaJ?CZUMl=f)C?^duf-_8y3UrX^Xl%| z@n?p|#vF{1lY?rUyy?fdIeD@yPY#alAMY8avHc^%Cr|Dt+y`G?q3&wjyzu(?&>+Ul zFaGJ}72{*zW?!!k_59%TN5)?$zj9g6(2?<;(G%mZzwr7CqeCO<*I#(-!Lj|n`c&U| z-}ong{>h(z=23P3>wi)A)8SA4{FU=xIsdWG_l>`iA3ym6jMJ|@_sV6jefzapK}3GtV=B{prU(|N38!jU77loHG(Va^&0P zF%!BRId*K!K6b3H@6=C!{jxJYa&jd7LU|;8=+K#MQTID|e@xU#!3uGm*onrF;Cib^ z8#GqIZQ0ge$)eG%Sbq!L0AKR?N)~eVXrKjdVE$2Or{dcU?vn|S_N*H}#d?;qoT!Ov z`E$IZR_S6+JuKaFQM7>zJ1=00kk_b|Zk~MBK>EN1w_UPZmDB#O&+bz0VJg;RIgl1$&7_$apEH+ITFE&coN0)j zl*H2gYUFB^b{y$$1}=u&0MZUfNsfo)W}+%Q2agl&bp|#oF>-G4p!bk?0y%qd!Ayc^ zm}n3=Ai2{&nf}KUl8$}X^IqqPwDY(eeCD8&rsEz@bojdm(VYbHRD|=C7min@fVqiF4>nL=oxW!WL8~SwvWqUI?jtJrrBZp4N5V@ zLjkvoKm;L@s$P)OH7s!0+cj$ttfJPL5?A?@C}OGlaH5b(UMCA2rqWh$Ay1W^8{eeq zo|<+@4QfilmBLn~o|%CgdHR+&kqh$4Uu;l+70Et%x7*z7wu$^#?jzc`-X)<83~tFI=;&4I+)3Yvpj>v<7Rt_`SFQ7TrvDb` z@tkQV!C(8g+i5t|OfhQHG(l}wUPjkGZVXY2#;G4Ol=gYDlpK8xrOhC^e16(37jbNd%uV7tg}-84)jWk^#AD-CM`#N@{0s5!PGq zZ$w!24O=}j!y`ufd*LBU;2AJYzuJ0Yr@#r92WK(EDtcEo{O~Zk!>o*sBNN@}iRhLO zs6y;gZ_jfQniClV;;^f>^5I)&7p zCX3!=WCSHWj~gVpA;=J+yr5=u((T9`DP>YfvbaUDeT?2mxq>ozBGFQ%?+S)PXIxIh zuxSp)?!eNpMzkPDsNyjq6eUj)>0@}@RYobOrZri*-CQN&Xf}>EPsPMhlIS-&7uMxS z$pFaYWb-94yC_X!B9kL4qtWA#*U%P3JCVO+GDFmX3GHzbOy|(g(zJ^Zo5HZexTD!5 zf<V{nG%}E*Qpso!iY;fiMLUnIWEsyQgd$<|0+>3<(ts%Ya}%tAI9{0 zP9@ibnUH&|O^@p>^whR+ZZg8x@GTGa--Dy|%sUI5vgl|;k1Ng8#aCx!#GicdNo(fHI(D})_D0aDEkI!n9 zmJ`2`vrYX4N?J`G==m2P z^;<`wAGaEtAU7~;Dax22tL|}UBno+`=#fN4J?J*v$8I%cgfuoBPwB_2M4!CXPZ>`1 z*+zptP>?i781|pGaywucR3*9m`~qY9U=)r1c@6vFk1+PBqOss%6-F;XcQxV6#D4oYiajO@*WDJ zL#jt^h`oruGt-RF8N|r_lVBBVC_w80hy}M@eWqirA5?ETxuZ=59BN(PYfn5nFL52L>rc+HM2P$qJ>EUI5nCQY!n4 zD+s+KgMOGsu@&8vLReJf95vEcP|}FfvZ!AaC=imm6q!^cRFb9iR=L8GdQwVG8Y&=w zxxzs&kf{CJh%5a#lqSj<6$%hHc4MNvloWm#(r+|Pf35{Wzz^5it;T&6^yc-9!YYgw z!}NR4U4>cEY}{^!%&x|O-y2NC@6to7P5<=<`GVxl0Y?n_H2Q=$VEW^j?R9&#mmVcw zMXyZzM2Ux6(T)K7MA)#pbC`5iO|9zT;BwNxoZvC@3QSlzza89V?)F-F!wl@FE1;Kg z-$Ql~>3YLy?rpV$dau{Yb{X>@*zNb4fiER|_hu7*RO$d3p|6nPHM7P7)B(t2qv_j+ znrU9u8PpgB*;oYtnqmrF*MZS)kI~HyA00N@SBZ;q{uvv&S-Sq?T|gY$IzzT~NjnR_ zKh*S|V=II`ea^fWg9}Z~p32Ow#3NZY=>zN8sttXe(>4Fc$;>Ac!E7$KDStszqW!+a z1+m1O% zfI96K%6EmRy~Cb8+xl;PO`UYnH#f$(?4CtSvm1HGMyo5g%F5q+jc>J?uO@5#`)xbXm`_;KjW(pSHznp;{3frB>BGizw)5x+ zYAV5Y=uJX@QzUSqJGm}G20udtQ5e)%&^Tf=)tOx4TD$ZrP`GGgz{NBnJB2O~CDpF^%|`SNZl32o=HuhwS*J$TqT);Opt|} zj-~YEJ&H+`Rvctrkhp6((%fQn-BU#vnOSBW9*)Z;1@#65t`);KZ@j zL`3aUcSTB6=e3YPog~6F8P}t3^M>XPb#;9Nbk$W?^mMtT{OaoJQgO=t$Vb#QZ>Ywb zH>AQf`P#jfLdjgwqtbMBUD0zzPc79|pj!Sa2bG7ql%$G3apGj)YrqRn4mys)Fi!>^ z`@C|;fiRx>*)Rbw8M$$M*r^VUk1M?K(4iOSp8DC5QQ(qe3J)1SGE4`C4h)?PJontm zz^Nc`#=r|l#`DLH9XRl3Bm1igHyIiQiejJ4_Vv9`KA9aG`CNYd*ia9U$I+9jGro-` z&*_*l@7xW0zQH>7JUDB^^bXcB-SyAu*fVcV$8=nK6mP=aGcN*v#O0|puB?iO-<4Cm zv%+q^^N?m9@^{_S=^L3laoKoMHQclAD*l^s=-+4JiD&X%OmZTRGx=xA6Vgvy=pVJb zPRGBkNuW#S&5NOXvX~&{*7@(|cXLA8X66I#`c@3_ox;EsUA*zNSxakf4SPhJpiEpY zov91-P=rmD+s~D&uF1R>W?aQi=*wO2o3}I5)R}c&J*?b!;wk?45b*gP;E$tasZe@_ z& z92%cA2`GNgkq?TSBT$)GMc4sHJB<|??+ z!U|pSW72RZHBFwK-#dlzpmR8Ax)@@>#Soiu8p^t&MKcSG5pSV!qSXWR#B)29Tx=jY zs4&gWkDZ-g5=R@ITDaq;x9BfidHw`BZif=WlZp&j$9Vx~e5_3uA)j z(Wkd5ERweuww1u|^9ni%zzzz4?Y zarxE+#u$Bdt18dnYh1B2ZvDz{@LWCp7u{~oj&QwV~o~In; zf@&)>Rq?0z3h?4Y(%}rb^f#nu4k`r$h^>+XWCii6XhZ4Z7%EOw4W=VRDxpgXeS0@b z8r;E9(2HK~uh=NR#F35(P8I{WByfU9?YYVf&zehJGbtj`CY)K!BiyZzo42K7r^lFt zs3K&ex&Y~(5;}@R#sWA#oEB^x5X6=k5C|nz5%^akO`@I2qj?29i06iCUqrg8Rrw&D z;s%qFxPZ!VVDb`Cdedmz2af*+~Cx}V9!67zw>@sZwdlJ4$8uh~=YGcDB zQ2_xZRPCGCKKE$l@j-WxPdzT|yxPc9CAHh~9tkOxR!kK^NqK|9Yzxu8NtB5QRD2SN zA9hly>4(AmUVxI%U-6Or{lTkApJM*F3M}E(&);G7--5cPwHto;gh=iE!Ff4gi*oHG zE%!J!c-@?R-K%47TJne`5?HEivo&l*vgeoWq=6&-Wg?@RhB+KMyp4Lj1&Vtd^Jj=* zYgK<|-y@Ct^f+MDB40R|5^YESv;#LZzk{SC&P7Rz zd`#e;!{f*>C*gwt$9WTuCR$8%#ZaZYhde@mzGP6;GkmjX zh$CmS!f1sS^(<{3URt5|XA1Ih5;CmLi-0OjKc^g^1!- zf<_$R4OPi<7&hh`@dix#LVBm#R;%NeB0)Kf3xQhU&-E}34Ps!lWmPljBn985Y`@Um zAf`y|{*hHtSO*0sek*CZrAaHLPBGEQtd=Hrl=M*HT0AB_myRHJBbF-gXqEvg(X0dH zDNVDCTvjR#3nH!#K{#fk`)QmC8fF{3=GaRlX{q#X^G~j*uEHXMWL%rljq{_%?AjA_ z)j_%mGEtQ63CR2pzaTqF_ffA8MW8y75bj=TU*dFWxyf{a_ihZSDN7B=VY{j0qS6)!I;D&BPOW*;hjzF^5rY?Q3w&v$;pBwU1U1dJBS-T zwzV^L3(@;3M&|V`bS?lYyC2WYbL*CJ1UaBj<&$?bwl!|kl1pxtl=T>S2ie~uo09Lp zgW}zuxc$Qo>qb*9Kp zacOfAFGMIA<9ez?=Xk57H}9I8_H%8A))81nbGJr$kyv0`pt}VvnC4=+NKnk6Qby{+ zB9=;0dr>aKXw!LA2B?z3c!BYvSY~&p0WU}^5uw$~Ib=;O9W7~dmNQw@*?5S2(W5{uhAY-XyVdct{kSKJA zrps1cChUMrmMXevm3~`az9Vf#WXb5@MoU&k;#65BD|m2Hq7tV`1#Da`0P)}?8dWIJ zoZXde(X)*jrZ=VXx8pVs}HH>(2W^$##HpJd+*jl^C|HNdWmf?tI^KhxWe9j zVXqPPP6_XO)OX=}i-P$_1AR7y0+$#U7=3K#T_(|2c2_Juh4%QHDvj3Fe|7ijDUJM* zslKl^exjw~T|O<)nV+_x*Q>|xz0bb;Lwo3h^Fs?w-Z9r&cy5;+vb9~)%<06huC(si zWS!UOwHhx7U1!l170nC4#cy!0Y6~-vpFu$*w5!9Q1Xk{FV>oEry$fu+DfkaxUDuSTD3J}iS4;i zSF@R!x8gH)OJ)5{9n{KK?(dj>QNoTV_;se1<-1d6%&O#uSFe}$c0Ca;U$lEQKS2*Y zw62vB){m`_f8Eq@r~TKfLem#Db@}FW;8n*}7j?j`WA#;o3Hbb<*rt#Yr?^F4bbZ<#}#m9A_8z0>Bgdoi+Y zSa4!{f#s8!#Nf8jF)+TdlVKb_MJ`KV8qg3(#nER72`%@vF3AMLv}oIS1L$sfR0ckk zLKD2GOUxDRwnVUuX~Q3dhm~{+P@~bNSLi&68n77hKq&$aRyi%rgj}r` zb*7mqj6DWP)~@DXfO=jmCe4JWh&948FyIUeDJ^Mb@Ole5C@HlRnE0rD7RG{!;Q(#$ z<#L@QYEc^yI1)&=mJ`9cM9uZM&UPqC?xljtkGjCs;citolqn3UJPIR(Vo6mXWU$x5 zC2>JbuGu;!OLrVbbOTd}Km%is=ht;DiPt)eBPXuGY6ZI`DhE|X7={BUpC(9}QEHET zhBdpO7}KykV%9EMMItIJ@S#KrIWp6*jFu{dfh=t?jdTq~ZiQ43kBgZS&j8wcv2kG1 zQ1z%$#nssjVTX?LxT@E?kz4IEA}89A(AtETeNbAe$KXB+R~82dB5avZ9_Gr4xRihl z9^FLhf>b?@gM*!lU%(}cvlJYTy^UJmRXqNw9P1hYt}Mv-L{X6R35reRQOm2AjKfiv zo3vIQynNzfs!`R3NKx&sd`j3Qjuk<9;IgdpxCDLQMnm%e5?*l+sOO5IdCFCsfq_~` z`R>2}o_hvBH3{Xb$@N^JV(!1cmRhA$vMN-QQ9dPcn(Da@%~SkZ{K>JG;>sFq{D`uc z?4j`!Ko19pV0$?}e(K>L$diFze+Z_FKpqhug5=oP3%`Ej*Ka7hu#xnT!W^CPLxZlo zc=6E5F>?|y#d+0V(Adkb!447_%KkXc|6maeWP+4XWvlct2kVZ(RP~5u>j-sfEuStUWL_F zk5~M9oa-W;idSjtac8=HNwC zF^&s<*M(p4-8ke^=c)Mj&RRa@+q0JM!8QG&+O-F+8&-V9n{dyRQ9O0M6| z*%1G{^2^*m4l2$m{ogYGQu>$Dp#ujF{Y&Y_Fc#)!3A**~_<+guA@@KVjS2etv*1je|s7N)smDLJem z%8pXQx~#B7ZJtvLUvLbYM#Q&oCWToxPu5gAyd@@JOHO!s{R6s1gk^qLv z=r#-GSXh)?J5Dm5bTQSagw$`Pt!jtPBbVQ{9V-pDU#($_k^Zf^;=|5SVSBvuXyKp= z^UGcA5SV1qo!}!oYHsJ&0-_eGG)g@>m=*`c!Dp(Qhv{O6p4;qoijFh<#p*N18=w>O3_4zF z5On+;=L5)Cl8!{iuw&@M4iq)^rs=!1nLL9tX#hr-&SdgHV1S*2UWI5cd9babfK(x& zZf_$EHk0TI`0&PH4BJ?Wz_3cgBex_*0612XNTP{FRy|;Zg`2mdwvPgh=Fz#7NI)WP z!9YbCWhIW?o~Wn9SxO#Wd(KYGAy+iB*=Cn;ai+L-6QOYNPj zmv(9rFa5K@j-y*Bk@adB{~av8YEoPK^U{fDGpzkP)R|!0ts6Z!tD`p!5A5v3uY$eD z=b($n(i{o|;yYor(eFb%C*4_q788?wRlFg`6C@@v4ARZyzmM829>fNYdc6bKvxihu zpn@$h#JqL3o$``2QcH7RnT@UdWs}Hrhiu`K?#`o@m|lYOzl*kIU&9U;1>bo-B^Q?@ z`>TuZ7LE@#X@86JMle7j0Ttg)nWK9@OHVeCF?cb_E!cZDlDLFQlrZ|wBdMGD=PinB zoxXK3#}s8eBGyFfGzzbalqofESJr;MfLWTf6$jH+3Z`r}Ct7cqZFxRbuJd_;z%qFt zIx7=$8syE-5=~9^)5be=S{nH~`s#5CrZSA;K~G8yqCM7Bd~_H+11&-9Zb_RZY!!)w z6UNgu#r2;!cfK7ud;y7MEJ&vC2NQYJmK?%`F zhZ*{=ZULxGin}!t-7D!KJmL0c7KLNcPCP;bsT>%T5D=B9cP{EtG#qPIlEHi!ot?Kx zAH9(ST5b7cQF7p-1!4l0Vi*S)UnUY&G*Sm~bVkYwbb-NUJZ~Oj_LXQ8zFBvah8Vv^ zn@1-{U(#l^^Ob9nA;IeI5~1?GP%J#vi~=WY+M zP7kb_zmEA8O*L!@(mYm90Qb8_4+Byo!8Us+*&xUh3)^f!8XtxEGVnIf)_o26X-?42 zOKR_43WHC=d4Dg?&Jt&Rj17NpN>~oSr^-!+a~NvfKU@1rLC`g^#HL@|D#)R!wzZVv zQbMZ<@|4ST#$=>%LXK|VVr6AQCM1@OLO0puy@px z*J^OD!59;OqjD+e-#`f+4d%H8)0-D_rXv&CtV|Hmg*i=Py2sb3hOn8O(KH-IDx{-r za?L(;D)yyGP5otRxvHU@LzMfz2M-)u~dC$o0eh6rOAS zS5{7LA#2T&i$g4kXE!Bd4BUb7Equn0=VvJQcLqIOzS{WEVi9sMb(CPQIj@JP7&7}F ztVj=KZ&!M_1l93uDXKNi)j7#z%8uArFIXYMcgohwlNDLISGI}mtJEsv*U~%hi6&F6 zcxeHvMQ#aOtkya>QKea0RvC~~p*=#j8Q(5qFcWJF^UF!sWiyY8xzGPzYOd@m zwAfc_MO|8@E(7yviMphb<}z*+wXG?(6AK`H$v6C_vVk$_I&Z!%0tMOjy;#c2nZ<=i_Y6S#tolDtWaP0-_@E+^acJD%4U$L96oZoTYu5eo` z-eOgP)ZLb_7v?%Yv~vYD&apfF7uxh_-ppNScZDjg`RN9%9qHb1XVvEBwO?K|?S3y+ z7xKFT59Gz}t8Ti{_|U%iJqs^M=yv1&{DI(w{;oxrE}O1D+*4Wozyp+D9kdTD+V|zg z{eLyr*VXgYRYZ&K?Ok?%IF#$W{u0u5g&zq`o1@3?-xM>=PgLzjZ_E8XW+)iQZAwpT zyxz1{RT8wy_IiWu*D2?*e0`zx$Vda%SR)na1gi! zxl+5AGasR=OMQXfSQPa2@&m-1BL$P@0uUnd(e1#x%_O#s9r$X4rf$KMYf!aWCk+#Z z)R|9bu;TMc@|k_=cLCrcW2mkZ-cNP5QAaN{1wSZ*QX?*Q=nP1`k1_o7iz z7Ah*4mx{Ny!qPye9jJ9C(^!`6(Jg>EkQdegCg=kADH9YZcY3?Yz)5#$FcH0zwr%$s zjd&H{!)om_&Vv>LmXVkdn~0Y9-Q?G%UB%Jj0CF`ZSkTrQ&1h1CHTDWsgp$V-#N^6_ zfGm<}HfCoX0w9@n)05VS6-8ph(gLPXF}0bs=BwXhZhl-fEJ&vYX{lUv;;N-;Wg*VZ z8TZd%^_0m@R_DmZQ-+MT0xP#tQ9UC#?vo-DCF{C{d=#k{+-T00m>Y_zj1{+* zPWfEiQ)!7Vx3(4wwv@P?O|IQl&BjVuVJVxdy2aI`Nj1x?nzdEUK1;>c?6M|JQXG}0 z#yM@9RkPEoTWl%mTCR1U%C~0O)zjnJIs&`V@tL*42=|v^uXXIm_?SIr|N7-YdJUFV zuQ{Wmuv#4bysUn0(W#eRobeaqqob!r%JRU0(Vo^~QVYl^2Hzs3M)* zUX>%GKRE2raMi^pk@ts3M&+-1#-39<(bt?qhsKYLkDlEeDm;14{JUN|_ohAS`l-M6 z4YV7c1HZadT-|@BI}7{>;+6XcTod10H!7S_VSoxtR2X3m5454#>8sAGyHhcG+%z0E zjQU1A^WR_>>Asb*Nu^P8>O1m@3pktoW`9v_@g@NVs^f_7m)}?#i?Naz) z{d%y5Au4Q8@s#WOFM2DMcxF7>Wa7JQ1xHO>&G0GxCZnI%{mQNTRUG5EP0*SAI#0QE ze%)2P$#EQ!+Jy4HD=D1u(c-Z_g(Ds~r2bxtEB}!b>hHu6^-BWEyjK100IUgJQ`;Ix z{mwv7kHX(;2);rF6+T!)_)p`6HO^bPDn$)Td`v!Cd@26RoWklyhO1S%?dO%j@e||k zrTyg}{L||%U&{f1UP)nqdfXxChayC)8r?>hng|Wq&RWD3#m?2vwy_L zTxz~`KRlQauDG2{WpbLZR=EL~7Tkt|gWjw!b9*9QIGz?d?W@~8DvZwn#^_>#d;$Xm z#^_>y9N3|YK}KHPTtanuQj-VY-Rwk%iz;7W zixU{9BVE<_L?uq^`4*o+xvh$UZ^6-giqw+rl3PimzRrTBR$cyPynmv;M<@7L?%z(Z zF@zoClBY>a9vv7wzS(os!I#bW?iu~_3FjqPJ#JpSWYEEu=9#0!w1c|yv~Ui37#+Hm z8~~L7AHV1fu01FzI`b)K$soyNizhoUaXh$qu~&Mq7kcUV+F`7Sa`NW1^HiGTOEVp3 zACk%sJmGlw4l_U@M zV5O$$(&44ieFJGC$PjQv6p625s>Hq4fRb}`k7oegQ|$^6hJyM4>PC8l4(4H8Z>O>_ zN+bjh);vU-!*~fVwvn;K*Qydag*;x4+zgJdMYsf?VH;#{>|;5{iHVq3VC!pWeqbw7 z5LI~upa9g4zzs3%^^kc+k`yH&(I+JFs?RKqX7MC?X6(&2i(Z9VVVX zHbIyu!KsnzTG)|drbXR^PP#(`N0C%nKygKm%F3(rss}!y0*Z9QE8#;eLCD}83E-kp zP~RS^?>IYQSM=3sC5baVu^To^UASpfYbfFj{J1-%E44r~6~w$+Z<}+jhvJZ> zs=@?NY1AO2_U<5q33WG=Lg_$@q;=-5ktTtuL#J zWMBopW98G5J5j9<`|>g1WnVh~JbYZ)LfOTh8<%GqjsPHz*0prop7B=vSn{$)JMpg#aqFc82Z)C~Q zD325ZPYf4YRr-h%?N@aLQJaCO+^U!qYm}Fo_c)%@RYHGvd6rNk`BDW{V`6WI6{x@3)<6J0wiQnkjo{RFJ)f^nNaA zZHUS84idv5%dC`u?}m!fT1i$kPUl)te4kBJh_Gn$B#NPYs_=>71pVqGOZjXs#)6~H zltf}(3(P&M6m%M?OGU2vBKo;hl@~-mLi-S13o!y2hjCNtlLsHbd*wzp%J%0bp-&LS za~?I_!EGS1cL!yLiE_*VKy(hRLu1Cd$3=csyakMKQRMG-_hP;fALH?S@?QZ~+5!fm zu;rt$J^2;b?|RBV`|%{ee7D{`+S*UbPTfdWP5eZLdF}mJfjIf{p4q_tG++DTEkqyj zZrnHpzZI}X#+{}Tu*}U<^WVhOG~ji_f2D2s<~zLBd6w1{tvOJ)MtEj#62rsUmlAm$ zEftZPTjLzY436e(okzN3N8y~RZFGTTs1y!qimyW%`$!iL$59{~$;Td4tuQwftu zKsAhHIRxAm((x+NVm{Egl_6a&JLC>UDdKPRW4uxo~v6;tSO?K7Hjbby0^uIY?sj(26VZ2 zCy!| z=)8IBQut@5A)=PTDPHZ%$+4lsD?!*Fvn|8Q6 zH)Ca%8d224vle~!KFqe$jK0RU&nEEQxHa_=e7C)OMddTQpzEc(=~2t*w02>be{e=3 zAEd7C8IRcfA2x7od=2Xpa?=Jr?ni_hv^~O1mg!YFpd9UIR{JoY~v~ZK*ePmDY-bH@%K+lD+Ir*&B zcynvOT$H)+o@wi{*2AW;rrJ7smJ_AN{$djjh}xac!~Z+%5Ku2L(3#*z!P zhbr2J*6&;S4x@XrZMVE(YuYCB0?)2RR!1V<5e=kP-@S6vy7(ih!|TG2wnneqp9nWM zH{bbvyD$5O77q1v%wHeOcCGN;xr;g$+15YfMC)h*3N;Nvqo zf?YERK&##cliEK-c>93%@*V>W$RC>H8t;{bn{K7lmf$!ZE)eGbhHm4Fh`Y zl!#%s;IY-Tf$p0`Z*d7{MF3XrWI{=t95ZEw+;GCGrl`sA+5q|xfVCsi0Pu48z>Nr! z*x4EFzFy+ntrqGu-6*DE$}r3=LAQuzujbA~h%*|I%_sp{gv+Vma z)eeQGZNlatShB*&II$Q>XrK@~Z&~Gy*%-e&0L&4#oW|T{X8O7zz~~kk1J2p!+m2_h zW6w>p9ny*bKa+&vCwzcIk)4h7irg)d>%)AmsA^ay!wyH0W)vx^JUWIoX{NGLXQ-6&31W?5Nx1_NplFG65Duu3l; z>efct$h_Z(34I0KWEb&fH;ZSFNl00Ra-nKK%7sC+yL@C&IjAcH+6Q`R$n>qGbE4Qp z1?n-nTC%ZQc8?WrGSMB>Zd4VdNN3)H>%nA!gBbaQu73dj7FFLckV$_L8y>X{LA(w( z<4UX4X=SwymTDluoR^>rwnVjSPRgSISY?q5Z;Ty*xH_ zQhE068+o=aqud^RN&42-sD&oav0>u}?5{14_TLCBvKFqpis$DxxxeQKzryWY9B;z! z#>XIo%f<4*pUiFD4=hpf-n@{9!WUK8jc?mnD-W^^aVpO`K3Ky9-)gg1=hbD@BvHQ< z{#Z}1+{ySrp&nP4Khv$t)@0t^Dhh{Fm!BhU0{c@Kr1C3%-QJPKv37&6Ty-f@I9|<% zI1Zmm1J{*{AuY$dgb7#0)%l9YV4GMk2b1QTxS~o^539VCpFnk<@}Eu3dIs$Zy>R_D zV*Ip3J@3<;ny=QE#`Y`wM1@0+jqL{(`Dk%meRB=_MA$xRuMWRDtn3Vr^&RVDO(zEr z42_SdFRn+1UpV|2dhahVk`5et48IXsmFo9R4;*^52%AUzwCc$4FLPu2UncxkBtY_C z=6;zwhIov%BV+r!1{Bg+`_8&1^UC-yf2n?#phuSFs8f})x*sEJZ2z}k8!V4jVOu%$ zT+hkD+c0KsqcXKkZ;XSc0_JEb6W zLHGuG_VXlwCGsbpHDFH&L!id00eeJu9YH*Sg>?9KS}5!?FqJ#5yys2qQAqGxXKhYa zkPm)Ok{q~NB$CCJKo3~%tcQHy3RlgB3Z_P4!)kQ^x3*HcF}S&MwLs8Pa&*wAu*^X0 zD661jwbHqDQP;&0W5PA0TOKzi!fYbuEzY(Wa^$d2RGXN1XTOUD^2pXZRgdNN)~zLY z48Cl08WXtD{`BK52**30_9$IRdzHoD7_@Aky8__%8I_CQf&7B5 zjhC7xz_GY+lvBGnBk2Ixu^^%eO=@5pNU5nFon^YfzCdUiMIbL-`$`B1PL|}57wRFj z#KGdY@N;zJaonmxSx!R1gDL{Gnb=t(fX*e9LSS+glAelFEIQ0>RBT=?0aQmt0M&6F z;+opNbNqARNFD{07OYjTDBcY@nAcI_mq9}mXsr0j?0ApY~3{mgw5D9coP@k3}RkG5|1 z7K5%_5zh~7L3I~TZA#8)W-Q&7fqfBu`ru?r2Js29h&K0sSsa-Dx3@R#-MO8-rD!gR z`rh^29k$=+Wa#{$uN`~mjq8@SzgQufo;HPQ=9x##{1*Z0@+p*h`aIZ6eX@@nohnUt zNv5ir_iV}cKTF1ym(6bCb0|KoJ9@+8K1xL|^R0VQxAl;4#gyn<=!shmiHT`#)h8*Z zUWTWs_xYj9mi|G?6wPm~)t>?`&`{A2d;p)Fqkr^I0&YRt23m$Kt}0zxY8HDj5-?j1krW2CpI^l&3|6S;3!e>lJ}$* zTtik9_lM)ha5NqGQX}J&OgEYyEDiJ9-i?>#mkR{FQV zj*5yFe%o?4J^Yg9YmBsr!rCc-?vj$4TYQD#XG#9p+o;Er_)cB_PNVa*R9Gj8Ws=zD z)LYu39^iV&m}CfnQ$e)JbC_*M#8lMsmdIcd=Y0+Td4mSCLA&Lu9PG33V&wu|cz7m7 zqbi4La|-?BqvT7j&)VrES|E%|_8uoBg+Hz~^YC zHCOUoWc1L9J5C$((83mM+gnw{7&H z3U#vU9@5TbS9fcGBraDhL1J-?;!{0Ze%Y5b%i~>nZR?3{ZS#^gi(k9~pZf`;nRT%( zEwib~AuX5EtR_qtYvjMtlFfqhx5|9eKU;HIk;K1!?^4Wu=BuwZNcPl{If=armn=^G z#wGt8*N)z@l;=k7oRHEWN3Fu9jpeuItjevmh%` z$s<-w7-<}Mw^>EMEH0znEkI~68<yRrPxoiVI?vJ%6$ye0I7 zo#}#Tjgbs*v*OE|sJR&*SEt*{hUMq@;Z&ZbB*%7L=#`4lI56#GYf}-{Kjlgadg8s& zHm=5F0W;Sw=&AEvS-nuGWGK&EJ#!bq zZn5hhHnrX(%#dc9Gak0e^LLpW^TFO#A^r(-`QIDYwb<7MXWesq<;LuK*!7zG!~WgV z;t#L7{n6Ma^FF_rK9#NyY|8~JeY>ga(|t<)EHL)$$YKUTC`7Itf)NkUJw-_jFWw6W9r zUxzPm?P^^gTDi$gbZrX#GVv#aE3CivcSYuHpL<{9r3>G4ePYwqpWdJBGCD$fuw{LA zZAUh1tOzf=`VG-^P0PlvvbH{%?Y?lGwXwVPj?Toof7vu2Lw3~%|3091hr(5RRTtT- z622K-8?_tqU+JJw=lnbHg5c6{d_jB8=$(Jmu*c<*qg}d;24uR$KT)XUur- z`cK%`CX8EiFknAt^@7evMoHf=&89Edc%@*m9Of!0=aNC?c7-__glS)D=-wD?YS+FW zcG^N=m9SA1n0o;b7SL7k+ln^2Z3_LiKt3P#XMR}?QYorqlY9q~@3g)i*uEEo0bOu; zNy@O)g1z{e=6fRg?5Y+f#>h_66zvisGq@GDjIlyMTfoYCqM&J7I;9tsB7%A`*X-UV zX==Qr4hzlZYMPHd-Q`qZ5jID#lCizi2+fVT8u2YcGx7T;rX&#tI?0IBPR>cAUXJ%x zRkH(yNo*vk3Sf*A;WBVnHycKan6I!Y#C%dCM%Sl|C~2r2Bz5=uFr5+0UT5k&N)oT1 zIC8@G(+P?LXw#YsF{#67esveh^irxbXjLg4k&S^0O1eXQTuw0~8ItKBr#Z~#m&6QT z9`nf!Xya(9NU`P$UZ-uLuNxe&BTSc*cl*Sp+Op}%DBYva$A7E@1&L&@!I#SOY+9;) zgG!w3_U^+n8_pWhxSmN}ZyO6S&7elsGPJ!h3-3EIgDZ?NiI=e^8g)5IF!F*YDHmLg zod|v$K~?Y)mya-Fk${Az&QriX-TTB1GZcL40&({a2dS|=s|E3xAmHA)r5aud#}pH! zw$uuM)MZuK0KO^*5-LBA+`Ixe zt(c zbZIwQ>|!_7cZLB6j5s2C(Tm>kUpGyujf%ZUsh$wjXlccEyX(ET-G)EgwOtp}b-VRq zB){)-CWF*<@9+2f+&4M%{{M5{|L^xa&+~F|P%eQVgo2jw3`pSu#rMaY!<8;Ceh<`B z3xMl^Z#r`~8@|yAf58fN0b2hj~ZT$UfKmE4y+X{z!yAu-ZE>P^p@)$?m z3NXWxdb{(+8yS;i*>oOG_zPUD0SSyFBYbB~rNUTae}6v#DI6QSxJv6)r2?yRld=o* zb5}XFnZLBEI1E#cG3RNOyL))}EVx@QC<@RWaB_pfjQPAdCUdJk3BJ>6tbr>psEQAb zzzWGs5o3y`>7dDeA75mgj&Vs%upjuGYgi@1*Dyc!tKoU9qf;aODt72$h8FVRd?ww_ zn;9d7JBO)Zi%nYV)K;x3PZGK(NAely?8Z8t^ZKNl$Mem8;0Ld-VWYM3aM|C#fb4bxwRy^Q?vAR#t3VV=f>{*2!uhn8Wzd?%U(RV*HjH3WSz0a zDFV7coJpO{{M6Ki;hQvl>NA>-_tWwIo{o3_cXrPY?yT1y4u@%_s=PAs``}^a(K)hx z@;z#FkL=I+S3~{&?*Mw!#QSGQeu4XD-kEURGiT7B&rUwfhYjp+;@Fupr;jC*2glG4 zf#vf9KJD}wjI;4G=OAOiRp)+&`)R!JXGeYwxI^u{@k);S>-iXt&_~FH{|GpwaVO1h zCw>hXsa>A?NEK&f$*C-NmF1_h9M-BlRn}QDYt^?ZbCtuf8;7j*l z=JOW?j7n9(GNEYv-8&|fVqA6nb(RHr7BBeQ%6BT`*4WtZ*GAQLECMWX#?(Iym7zB^ zuDqNv$Qe^sj+7z)F*NP*)i(QUzY2ue-uMmIl30Fhn#1w*sjF3)u|x5nIW=I1f9j>m z+jx?~pt$`SV}kaAVwr$thT63JQ4a6?8E+mjarcmk7`$lwUn)&`>D|y_A>WYw4_zdY zPZ)AkkbhJBWB~bNfIjxOSX;p}KIF1LSd2a{+q-}zVly)xyptqcg2N$1Fk|jr(uOtW7C1hM#(NXc zaA%FiRzkr%cWku(FBQnFSji(SpAs0U;$dNmHK!8DU&Ma+Em-k>uiVKip@_e7ucyZ@ z^J0DU=M_5ggW;@uWOT|a!(F~%r7K0R0Epb`j$p;3Q-+!XfDr9Y%YEeg0iyf7fBh$H zKnOo5ZD1naXKlsO>i1Sx7nj3KaXC1OFam$qPjUAr?Eo(g*CiLu9LWcu<1r#MSB0IR zjH(8R21btOC5K#)750b%y~?O?Y8({ri|{(V1ZSiwd>I;fiT4d&tgVKN92AQ6lXjuI z5Mc=j)W=+UQ;u^GUpp7!W0X-Sn#GE84c#njU_&!>mp~w;7lp1+_Ywy?4-%FX14F2e zLI})QD2SoCn#*kg8@9e)dlxwaY*09!EphT>5=z8DH>e0i0}81Oy`cO^z#BElLEx=e zWw_;_CI^zCkeMP4yu19~oFe|YDs4V_b3R1M5HM3~k3(`PWtBFzAkM`K)RGZNn_*s&?x-cWxIr=QZc$zYpoj6;m3A zc7^CmM}s|&1%T5X8RXY$zFF1*U$peD&P{Z39tb6yuexOr#nUPhFAKf65^W8ATkB@7 zGEKqRP!z!qO*XKPS4H@FaO04I#n8dhgK*0+3%o!b*Q{-_kASXm+dYah73thugr|Ry zy5=<8VgfNE$ih2`D&g_}G0Obr%Qysl;o97&Ov_+F&&eTRGQJK2{ar6il{pzsn_JO1 zKt-*1-JSNg!<|V03@!nRcnurRgrvsCZ#Rs|E652Ynup}@db%%RPQ}L2xqh4Of2k~K zYq&dVNc7>NH8`~n4ZY$DJJ?s4A22L=V2!2YW*GIPD^V8#a=CHBx-L-Ii-hIA3U|DR zE`un9A7s2QyBGj#^(VJ00!)ujT&$GwG_Yw~Z<>|KQ|eT4)1Hw41iblu;a_H=nco!4 zhW5Cn6G)Dw>uA1hZjm8z3QtzBm&W-Y%Y0X1$EzoA1j>(ZE~edt<4-(7T2CL^N(S1@ zU>3zut;#LSvOa8^?MhKzK6t&Nb-E_9_bO9SI5^#}K52%FL-IGKuJ*`)G)3VP;k-^) zD&3Es-I5*BEuR*2O^G)EsNY3fm9mDw=&u~4FHs0xq1)rtrP+n^D00WceVvCHniQ}k zDIuWabgE!4DqL%XfdevAQT|twv1zt3rw6=xMWH$>Y6i%ejS;-h-8Pfp;ZqPF13tmS zhDbnCo;>b#N7$fHh)I0)71^5gi?+{>PAL=JQ!-DvK`a6g zV<|0aQFD7}WtxVbK~y`9x#Gh*(LSt`R&9G!^QrxjRjL`4mruDEZfaX|{!!}FuIkv> zGv5vCl@&J4-q}Xs6|3Y>FsOay?$Y4U&c3`>h_s%VE9uJ1gE#!cE~1m6l^e3?j*XYE zik$jRh(>cOd;TS`I;nMNx#c@e5H89d34s-B|8ua#_ausSxg~+Q|Kr*wEnF;0(Dqx}?s!)?yC!OhEKOgp z$;|w6S5Pyi&yVFDQED$4YYTllO8G>I_DB)aF;MSSc}ts*)mm>iWumbooJG!ABcbVC zaZqO!3wnEVQR?kL81rkAYXO0Zc*bZKxOPDn^@J|7`MfSj7P5xg%jb1clNHk?ct?T% z*0M2;ATn+ifQP{04!|RW4d1=Jk1n-BkC-AAUHJ9se7afOcA(Qvg_coenHgQO)LN{% ztkN`~A=Z5DlD!Rm5tO!QTajR-W!KEebTegIyBc1=mkesUf}+;4!+T4WN1N}D-1@bt zk3@QxT-C6*-tOveUjLx;{aFnIsZ_WpAnZufc3Qv4?pikJ90hZ4zpKqT9Dc~jJk`57m3kzZDEEiEXC$XPFH{z9FMYdhTkvp0WaDFpma6sY>j!QX zORjx*S-=01#mk<&f9g$||JtuFcJ99^6g;qM2N)4HYEM2_2DkFQrL_JLoR^sB%}SfS zmbE?-O|~snZO7j_kSgPV+-o;mZ#AsnL`%~f7e;1TUGuj@owAkgdTZ>#nZdma#(%s# zmA>P9@2zigH`TBC<4R!3z0VEW{n6-xpX`c8FS?@V?nQTxSi7C|>QkjJ<*ugVo3!-5 zG_1eRdfN_vO|w8)n_Kc!)7DSz$JOA;M^gHl?%w8zvpzDtyHA+MyOYP}r&DuhbdUFL zO1Cw~1}ihCZAm|vPQMVH9+D}0*8SsG|JT)#Wsyy{?z#D^Kl~|O`}ATtxOq>s?U}Zl zQ@`3oi;sV%C6YXyil#!>qz+VaQO7p^=4T*1JlN?hvh4TD(O$c!CF(5o+kZ8y+38;5 z@cBX$Adq$ln`#UL3ATM`!b$R85_3Js*lITy9WZj7pG%jt^=`Fb-$TjW_WguF_XhiegAISlQhL4*@dBhQR6&t;g#% zY4|>*k-vpgLdAArmv$hzIvY2Fx7%77Z1>8qQ)9p|7MG~wp^z?ZDhQBV z>+{2d{XDtaks?fF*ICH=OO~49M^A2SQrH5!mg&jB^XN}8h z1n%&GSycc*CX58UIF0~!6#EnLhQl-h8Q8GBM{TkJd0q@p(@bE+&2t$dsy%8Rhx28<+dTu&@psJg0vPm;*!~dg^!d zB8`-esWYSRPo$4sJf;w4)3N!)xZ~+#xFHvc&1d4czlEL!og(8BkP7z>{~Zti^sHyk{0KL1j82^E>cVxrBV(0O@QJ=(3wmDv9WEJGr0Cqhh>O?zcj`hc zk?}gF8D!c-#v@H&hMpZbBhxHuqKYxHnQ=$9d(WhwhatkfhDlzCLvlDmlYWRXg4Y{7 z+{}CZ|Mg)W@5!+BHEi+1yn-kvKa4+mI+qXTTG*P-Zd{h?1MMTKh9zpv5>pTGM1c{5 zhkK}&gbp`I4fgsLyK4#QxqD`|^8>dgs`gdZnGTWu1LgTohW!tMc+RzO7wYW6Y1f`0 z%2&&a%gPVCy?+U0NL~V&k$ArMp*|C4;I-9o|EIjq8RztYg98V@GePa|PrSb3FaL7l z9h)wmxMO0Vvc#Fd*jYag z%{LjH{CSD#9vRDj|11Av&9CQ=Zyt4jryw#FbdP7^XWGx+0=nSR#MuFiQ|NFVr3$@E z@8S0AGd~|2V_d%~E3%66GrC`OfkevF6Jz{FcYr|o?8jD(vLxo1aL8p$PH)WITViaE zw98!9rwspHh4scitWRT74QX@h6=RUISMEFpOfN*MLKW8IZ+N{Vge)u$MH?cqhClBO{(mS2i}nJ`>Wtc6P`8(_t@@VBJx+>nA)L=orsujpUH-d8JiN^1Q?Ui(xW6c0)*?;%YbRX6#pP z5mqy{W-AxKYzd znmI~ShFv&*Vc54EXa;Hj1i6k{Wdyyc&gF(yzS%Ade58w}xXXd~9mkOh1BdEJN_$Lt=+fIwi zf3_VR3jvl}&U~_xj~4B>-l#~;+(VfYJ71%pRm)ky}(U|(8EDLs7e z<`YGkr-a_~E&*)ovh zPk)xP{itfu0@gtAJIXTu&P?K>g{HqACh7B`K!WJL*$wr+Zvni&v%z=*b*p?0#;I?m z59D3+5|^>ThK?Xs{V&&v+|zGZ*ng4?;)Bo7wv{~sZ{|x2#3JpaZ&Qz7;f2sYUW&dz zyQi*A!6S)H>T}+p@tJL!LNn`>V=k*v*4?!rJ5Z<-%-TM+r6MgV*V#GnU?WM|ATmy> z;4kR=L5fhY9ZLk5>ymmp&>zH|X443cMLNDT9Q_gKnktxL8zuAnr(WGl`fP#C{ZXRp zs{(~My$e++h_hT-&njw_pCc4>WhkM4R?7yzB!#ZZkgk8F)!3JI26ups{#Dy9^tCHA z7{faBSiv(0vOEtbe(=ZG(*(%q;@O;>r- z25k#r{Lyi*I02a>J)fc=NWjp)F+PQ@$s~v^DwryhX1!U_vlvFp4P_RBsHSAD0qk}pR?CGQ#>(Ed1oB&)ONm5)yrh>UZg;!Vryi4I|?lVaM$r&&2 z>JRdrRGa%>@4IrBzdmPvB1~%cqK%_I%4*xPXkCql{|r0XI-(O>quGR%bVTo4m3egC zH2n{zN!?p%3eL=On0DNwjoGI`cSZ_dJV1^y)0BgldG#qx8L>v{e=e*+nxZIJu^ss` z0!_tLTZ*VuA1HGFFb##qC6>wr4gw(eRvQN#$7@R75 z=j2Iyb=&3BS174AP?_AnMUmC^FOH(W>K12n2l5^0dzt}hzJd-!~|6Z=ON?`icS zJ3UZ`4f~`*J=WBc*M8J#)7H;Ye40kdPsq)WJyc4qQLVX0=Y?sF`!I)FnDgn*nky_h zduxv~8u%1_{;uF=E%gcO#8zR(N(k_SG@ouQsj%|Tr8Ry`)A!%qa|8p* z{!cWxT!GHIv+uUmFOzxte(4OsPRpBnd=>Ci7bKlvyH5HvhZ5g3khY6=zwJ(Ip?fI>b6<$tbM7QM4eVmHjc^B!=pitToN!IUh28v5Wf}!U zQjyDZU6*#@lY8=JfiZfex3fToP^dzRwQE6LQ`liS8r`dF@nF1|kWHmh80{CDKVOC@ z8w?dQswp1Uip6;((bJf}(CDBn+9g|zkuD6Sw_}devV2!rUgle*(zIf?p~Mc*H;N^Z z80WSZcgnP5T>z!ysc=lS>w9I!(K4&L zq6V#*SEQyqKo2QZEVd(&h?O&)1sTU>MX`1O66+x7u`yI!2XT^l*{+PWz=cAqEIpYm zX3CagYO|7NgPdq5iA+ILJFtY>DiH@?m4?A4^)h*C9bXKBS&RgjD!b%u>%JY5eW}P{ zhf*CK#e>%vJuMMOEqU5rv@|QWr@r5{&SXSn760H<#PG8EB|PH6BsCt5Po%|U0+!PFI^^Pw#%Yguj=&59iCp4BzbWkvmB>f!Q^@S#Stw_zvE z=x#3Eza!e#7EQ-{)-C?_>UEbiEV*iM2^}1aJb&v$SK7DE__njKXZ{uuaV+OKeTKPz zF)-Ht#Y@7wT9VVAer{m#{7UCi3LZL?G7oI*w^GwR@eH`*COX|LZCq#5l3uYzrc8V( zw8Bm-IC!aFze`x@g#EMJ;kU-y_D$=2!tDKi^x#baqxlQHf9~i%voDKL)9UHr=FitR zZE~)ReYd&ppAU?tH?7_KT_@GJ4`sjW>4cgo9xKf(qHS!eQ`;8`o8q)CV5lu z9lgEu>z_UH&*{bYt_6?v0}t-7Z%OXBF|zx{ht0Pdqm}y-ZGPZR#c0coBN&$-`wz-9w+i3u8yvEG-X>c z@_{A^qYS$-#^+d-4Ez*PF&(zS-^;{2e6YlLHVYgKW5!N5VL3p*=g^vWjgi5#lBoqX z6T`d3f{$jE=TNB>#Aj}LQujM;q_jMCP8`YMh$VD?T_VN$JUzMwx!Ytone8&r*PudI z3`$DZV<)J|Z{lvaphAMteo)0P6!-+$xF;z3Am@VGoIG!u}cr!Vsk7`BW7lhAn#9kz} z4Fzb?L~yQ7S^}|V!c!t-Gt$5-7=^V(>Qc0$5jLn*jRLbgVI<9q) zdJtKWaysw|QiAB2vfLPEU#pTNrPd+vUJm6uxHOm=`7EgL8trW5)~_k9(S&Caz!OnJ z!h;}ri-Y2O%E0n~P-Ng?We6;b>_Az(2@Z=Sn2M9*c_}}dSMWo)>OVF}4njkkH9IoM ztP6mN@hpC+fJKC^D<*X>Y|=)lb?$@c0D98QZb-t2%_!2fz8>Pen19pddpv7r0 zkpOS`5T_uSyb}1J%}SG=R{H^Vvj3buc5>pya~?ML-g}iw zW8(*U4X6W8_L~Fy$4-CnUO$~Y`L4_EE)?H-@x9W?llM&EB3*D}j*sK+3LqZ`4+4i| zb-Kz&4SKD!yO+s}lv{OyZHX zFzn80)Ud`{xbyeEfZnm@R?|7`6!H6a!`z}Rn)%V^EAy&u(Caxrrfsa1mvO~OI!BMz zk?9@zsnI!JSRRgZVO^Xz_rV!YP{0LS4-bD#eu(jDFnhFu(6t1@au_I0;0J1osA7$p zsJby$=!JtHo1vYLq+<6P-gu$T-fU;wl*`GwS5~%v|<{e%N;=ftelCz4!TNR$3xs>F?1%*oqP7( zLCpUX6HGI_fBe^Utc3fsKY&!nu}a)^@gV^>F5NS6&&3n(zdr$Cl&|4?00d6{ymZjn zzn|}lIg7h+PPc!rG(sQ~J~y%8#Ra34_V&h4Rm9O_z&iUT23|xi<9MTYjwz*3nh&nr zxzj@(|Kv1ozL`MGk5f_bP=kyf@_K;L>2!0zqkj}n7CdZk$_)X}f1&CQ1GLbczXm%R zfzI)BnIh}BHqyfan^a|#u|TgapnI+1SYL$mM_UZs*cY^PN3FB}-_thbZ1c3GJ zSjT$e#sZcf92C@jyix%B)0ubMv`@ehI_13OpTVe_O28n+67nsQ7elCXq?UsF19Ep#VA4iDC zwI8^^dQeabqPNAVZn*pdAJCw>;gO&Zn1rt#sZ!+!G=d7QV0ggxv8q@hUFyp30_RXZ z>`hG3A<72A3Un9+T}u2IC4h_?tg6w_3|qoi00#?V4VpE&sEiSk0Js>a6OQ_j#M;kDNtt;>C52lW_# z*w^#;E}Cb4B4Qi~bR;+aX+`@R5TWEZ5#Bu9aqBzHPCLFHl>frg^zB4zUKhr37Vwx= zU=5_ynm@t2Hyoq<{Q-F-0uH9q?w%7*p?qCUnv0sdx35tm_axq=CyrOyu%hfpqgkWR zZMA)mlpyD3O5+M7rLDl?wGuM(z7T1dcXSrT3U#!qh{LS>#AZE={Z|+1j|T9XpKF+| z{W`1BXYa(dG!Ri%w6tHTHZyneF2}zIv}hoU)dRK`v4V890#EHdpaBCxJ$%Ms2*lJibyldlWDzHeyEV{qUmM>}!^mNE{)|arOnwmzRRJP2xx6`mPanfrh zWn9tbg2peu4ZQFVNT);ruRI_5*-^?BRAW;{P#NP|6^zIc7cx_A2qcsdRRTdkfFx)X zbWsts5zSWubrrl_kb9w@8ZR~fO8b+%TpNXIS(k>vr>zLF+ zpjyZT4f`94uJ;X<4I$;Wq@U)sD-6eMyIt^;St1nVF}|XD1&tPUqf1IUj+Ak5C|@Ui z`n`lq5oSZfht=VnH#(PZpVqG+c5CDc&=Xby8wcxjJ%=`QQH8I~pX+EZ*I#}@Sz6cY zX1M1Q_N~Y9j+mNS{(BwnC?CFb^N~6UyiCjKv+un{`1K53=E6ajjT-1;uk4`F%P?&H z8+#iSFm2NDi!q^^pT_*C7yck=o|-H9j_5-6A4&ULKizh^8+Ri~be5OXdL5ZVzj+xS z|B7TEtWz}aKtN_3aMEqt-tpaxbd=xB#eYQizaq8amwuF_>;8+?`pb+(^OPJMLlg57 z<#%z?eo{#dP4#QgNQ}`;Qg_*7GhEWPS0$EkkqBM2rdncq9!@?mrR=yNrD=EZoikCo z!M{GWd=E~y?UuRDKhxCuo6T>0IYeK%vrj&bHb9r5$1Bu-BgTVoyG9$oP%O&cE!! zrgYl_dS)lc8ZQ@e4(6dQ*_0dJj;rt1EovLy2CVS1`i9}1iW)a$<)i%J^~#mbl3h*a zns)1klc3kuKRsw3QG2u-6#+Mxg?qUrx*ovkEUtmtWa&T4S+D#wZA7#8tLM;Y*@Y%9s~xvNQSQPCXOU!tF97OS(QkuSm$HnQ_zt76mTzzq^HIvi z!o8>@t(62}g{5Ypp;jaws5ab33|{IUEPOq=sjF|N279L7v#7x=54Hl}IBcrD-48ks zH+NrRu6K-SYwxxOTleiT!V*EoVxz1U@Gl=e)_|0UANo&oq1Zb-F>a`6kV0>rSi`7 zRXs+1bni9Yhn&h``@xyZXjbr{`H`71L!}o!-!Ln^Y~cWF&daQ@iZmYX;k= z|LL%Q+T54YVM*^++i=&Z5+aQf|5&$mVB{T-BT;tz~_<>rj{D%m8wS3)i|F@;SB65{((6 zlPK;%G=e0S9*y)0wi$zb!L$gP4kmwHfk>{5?UQY4n@A;uG&Fk)mNT8qJ*JI8 zp)s+3QzlI%d}0aVyRBwh0n^f*U^8}nF|!Z?1)`v)&R{*Z;+RO{ppqmi3eEne2y{~W znq8u3rv&xTJY%&}$prce6`k_sWtL^>4Jy{6wxspGR{y-dTa0X{niHSpJoi{%smHV* zHLz&L$$In|{Sw4)e`a6KLZKDNKCqwBt=3KjKtr?eddk$S2v+Gqj2hl=>KHW4Q&UrU zE2cQPU=c1@NrPkux!8e759xa#4R|fwadjcqzY393LGu=yR#kG-d+aPYM>^VXArM{? zeMu_pYqEKKu>eUkL6$1XM8dQ>^bkNZ8NFOH^Hx(*iHMxYx@Ee&}dbMc4N-K61#forVZ0XTQIw# zec9$keBWIU-mk60uJ7%!wn-&1NFg`Y)G?zMFke_!ha)6`CKts;t?H`;**(hC)3OQ- zqF;Qd_)}y;m_{N3H-LIvW%!2B8dDgKzQRa0pHUSq3byemlqyv#G)l`U;!TJm?Ny zHj_)Qx8El^QjNzU5uCA%{?f!RSRZwPrA(@`BL@$@=Hd=%sI#GQi|MUSx?`SPMMg|& z;h5HOVgPiA-fbGJkBwDt)fn(xnYfYf*{I&J!G0Wu{n+i|i(U2epK@ByPQ3kgr84os zz_EY+`|3tOl~4^e6<`C`3FB`;QN;;sI=eBZSHlrmXH2kWXETT4hs|2d348a= zd`OpAqfh);{X+Uhp6}1&kuY-^m=9ZvwcZb&>Y3oBe)uDL^`7nOo!or4_RMEv9=|o; z&;2kS@Ey0-*DyxLB5P&6Q0IKvucpwA>S|^!3DYFz7!*~U@jTWDKlaxWvZ}+shW$+u zzmErM9GBgY8bNV5)>+lu*sKZsK(SlRy_P1IqZY5`_8;k7#tZ$lW|R>RyLn}ve6QNO zaGqMC1G(a1#d^&QtL8aYe}LIdluCTl%l9r~PGyV~Jir=_{{9hqcEOo5KLl5_0@`@a zD5+-`F#cDi3ucN#+@{n&?l2B`=FCaRe;n`cFZI(Ipp@g*>C@^lpo0^?_>+kVp(Y@$ z^xd!g6l3-DvBwD5;P_IHO!*uN@H)mM07vGTe(TKWz_H)`fL9#)Mw%o3wS*K?k^Qe{KFqkeDMB63HA>_ z={N={katXc3!`b=x?`fh|IIglI8v($oPK!y@l=JFJ}|7;OV&lOgY6-4;rh zWt^-+ZI8VQTm!t)-wwKrF^V6*$rxaWPBicxG@*ED#MAZjeS^>QAE#Wn8(=A`DPI}$ zE+|cQdDtT8F{1DfiR*sMc0Hkvc(FlcF4D zriY}^f~{3dbRm70u}Hm@2MPRnL*b>L@aQI0B3CO1bW}@K-DUD?h~QSQ%O|v*tTTNe zV~(I_9QH6hzW!ukY|o;=Fw} zr$hSDot~ah_i}Xs(|n8<6%khtcl zbU){c<15JhBy-}4O5G>j(K~Vab1MoV71>Jp@|8TfYDhdj>bk>IblqqAxGx%bDM?5D zzUxUGg`Ep2*;x>|F#Et42Q z9C9LYu6;?Fh_CWA^pd7rrTOw(XXlTHL;7r_{Ba7XjpJjgNbWBTZ1Aw+Cd!C{)C69pu|l?Fchk@^@X~Fa z!zf+)fv?&)uj|;w6mj4KpaKjKL9t;(2t#^iwx7=&g+O8qrI7GE6#sIHxQJ1aA9W&x z#O508(-NB@RlqP&GxrX8E(u+vWB!vdWz!C_nVdOzmNSvgC zuU)KYu;HUWek$;2gum7W%fC~t?nN|JTc`H`he&RWTfj}qYj0aoPq6^N2L0l^J3|j^ zR|awt;>o*ptw#iKcx_6_A+vsd{!eMl2zAikD&&QeLr*(^PbG2bv&x|Wnn;i|uyf2Y z{i2J!FV5iwA!zDi1&*pFZKG5xT=+jwr^1;ZfsW}Y*+YI5^&Ty(2Ov95ZfzZ+YXMd^ z(TbPX(*2v3_YBde0M)9zLw!z}wnwz>uXRBFVViEKp3f&lZU}o?`s|e4Fh=Pc9k?U7 zNc#4_m?mT06twB{Jx2qI%;k1O21x5!u?wZCDei+%fTZSaC)#N@oJ1J%S!TUmw_kL>rTzI5vV%WPjhR+Y#JSIrhs2Qefly?q(-30 zua2n03`j7p>n{7LTeq1^iRL6cO|0ks_*ugRFp?X4RugK*4@Zu()RsvKtCE(RKOT-%}RF?=a- z4JpGELN^5sr0p{Ykt~_*$U~oDWFa$BatYcsTS+6SJ<9zBN?^cc70~s>d`Uq|;>1K((1;Do}$Mqu9mD~yGgZ3P*55+9t(88qcKZw9q6w}SLQphXH~K$_ib zMf#8_G0I4H(S6M?E8C2K9PX2Vc*Po`quaR%lM1+IO})}!YX77Mof8eH@@?7cVy}h? z^ocjn%UvDAe~3i2bn>~}!-BMk1LO;- z1CJgj%2z0-cW@4Jj0f>nya)(VfI;H?A){pb0@z)uG=-WwW+2p!gZk-T{ToqktGyYV z*}78OO+rSl4p<5PM@TuWyGT&`J4G(;c8x=FcbKul69sCD0C6xY zlD8Z+lbAO?Z=PrX#CF%^W6SRZ?UbCh@N*?abLXt0n!OwXg z7lx5d6q*v$sM?Fgw4QBT)0IW5H)VqHCMsq-J6eUIf*2n88Puk?mDl1D>BU-$lUXxE z2PzS7M6!fF3aV0cZ~Eo8o6iFQq`0m(YPL1pv=2>J~@l3f?ngl?#~GC&7ez_KMW zQfP(wdr9Vv)=WNT=ku);OBiBjvA9ZU<~{)#xI3gFA)!*njY1d397w}-qhPmX(XfS9 zD(>twi&{3eqnOVY;>Zvc!I@IkngdCMNouTj!2C$tL0n<&%-m}pOif>EuU!~P^%+winlayc-qLQ{XVRWf!|j9N`@15S)b}je zM-4KVa?E85?e2cNZQqjpOTLz-rqXwf7aC^T4HP)Et9$Tav%mb*!w-E^w5_*y04KDp zZy548)n^VTa~3(-rTj+ zfB3-Rz4uoFi_OIiy z+RyKsmHuz$lJ51N-<|JRKK*A=2iJ$RS?@(#(-Gr;OzHX8h;e*Q_8*-qKCfN9D746# zu{GTi{l=krhkIN01?`!`H+9eY)m1aczrWyg_gi#(s?FT^V()to4bE6^#KjRG>f(h9*Z40lI7eVS#6*B(yWa$a?1{ES=`dL zt9|3)uWflRb!}r?v1eU6dhJXr8nQEopV$jR$&`~?lKyfc+PgV{`Y^|@X_*UH##&_U zIcP=ZIEkUWGqdX67g|&o2gJ2m`~s=u<^(k`EneislF{=mT=v19W(3THl6u{ z29i~oO%B2-x*PEvEH^vCy43Iy>MEgdrqU^tBptVYb8>19u(YIVvS^h)upHz-V8yN|UmsooK~e-O;fs(L6M$vAto1u1mTciJ?G-ygRpe zlXV?70K5gjCI$4Gg1qK2d$7HQ(ZY|JMSInht^|b{U9<@lfP$S355^O~5tl>iOp%>T z{$T~ti)187m!_FauoVn2+vzeA2xFLnM()%VsnIzE*$j=P9mQ#p@qqK5Oqz~>$~nR;X5Yp8&T=_pqD@vwl2vKK*y1p;g!pb zB*I(}^xhRElt&RO&#rsTo-`;c*$oQk4%0ML3DYQ6CZ%{IgW|Beo-M$9UNIVXOMGIi zv2oxbHUq18wW@=%k$E~H2afF(U?}f`HnD~~ffnfB)HuF=upaeEf?K z;tCk>be=uSlIm)*>8g_K*rkdzR&hy2Ar~CuP*s_BRoQloKmvO_J8|~6N5AkVz#w1b z2b`;C2axN;`;*M&oG~yJR*6W$(`!GB$1w(1qje;3r?4CIT6>rybT3Sz%4c1}9W_yv z_sDh*$M%|A4fp#!{bT4Hxfe6;$nn_BPY^VWo*8l82>Zj&!VWjj zkL~|2SK~Z^pM_r5ctR^?OY~)AAYKNqI*R&ao-{svJ7R+^Yh zA91`qVdu2ipY5z`>;`o{FE%3-zXvPUJ@aHdcB`e&=Kn~6=h|TTr)LI8OuR!~6Ysn~ zacme8MZw?fLNN|G-v2uK{W)WNd}54oyAjX}<8~#TvB+`jwby=L0tz@f=JM?`>{Fqi z|CHl^N)co2wbvLsXP*zQ`F1_i8h`M1N&Ob-UOX{8ajbN3;>^GY7)SR^{Nfj9M=rS& zyxhOQ_k-Vo5?TF@KDc$_N~TTz00=2#q!yb36Wq`@PaTpv61~ zMDy)q_uzV|QTN4(0npC;_NOm`IC)}x;url)A2|*@A1Uz2IbSEk=S`kL+LC}h#zG$5 zW9%#V4370Ax%M7|F}o>GyM~0m@H3r^`GppKr_W$L_SY}-{n()?+5gtedi;Mj>_s^6 zWP6F?+fiJiSTr%7g>r`A+Hr1N7$U4m2#Tt@PsI$K{oPAsUtsiRsdBV|~Lc zT=Fo-7I~+qi}rXD>4#`1GDJ9^QeJv(bg{=9?%RPPpgi>Fu6K`i>(=~UV2(3vP{BZ_ zFfxIvmB$wx_3V>BJ9z3PaU6)A#8Mtq;-VDw_gl40|Aqk&-S)8Vf(kYNAPp0Toexjk=Xxv4jUcJHoe^MsO zhmu0jj5J8gki=Gvd@&s03Z`CB@I!gDk}MWQ3{w{R0oHj9ZlnwS zL=a?3A**IoK!%V>MUW0BZ0z8UzTlH!{ZSNyup;az6nk+S3tbqThQy=6sf5ZUA23^- zj#VQ;L{68hY!`5iQ1I6kf@KOWLP|U+hY+j@To(+q1S#qQxuAucN0W?C_&r$RGR*B`x9x(y}sr%z0G zUQ*Pt=CjQmM|Q0zZMkstb<~yfH%s3hMf9n@n@=c*?q3n_X~m$mv5j25>j9d++_HbX z7xL8F8+$0AD9|oQ z+lAMeIt}BEI@aA&Kf?US6>L0LquluV@BDa|#1)Rzlf4U8s?Pz#vJqzW+FhuNPfcqD z%%b1g#|%z5$t$FFVQp~UM7{IeRb4}14>d1Vfs1ypCkjANU~z4atZUV7+Vi^r^)9cn9vs!P6{-_nlLOsQ4$bY{CU8!Ou22@G7&IjSF)o9Q)CFtxwM zAn;$Y$NvlD2E2nZ3KtTa_D{=1FV{_znDhFllzk{1`h-suV&4GWuX@TH;vU;hBmzyz z4QOzH9!9KU>Ea9}0R=I}glzN;;%I@iO29dB-+t|jK7C6<(ty6M%aDJkQln%B1msJ; z`gmvCoQo;-V?z$gACdDJF%7*3-M_-QO4N(w;rXGe#Oc$zXf{s^Kscd;&2JOkKz1dK z5Jin#SxK7e07;dTMjIsp6xJny3ZtxP)K^YW_=w79ZX`P?C<9rRvRM#aO&iQ~J>2hqWk#yl#4 z=tWS>$dQhin!VQy3eZL=0uck!q%mX!JgBdWfDS`4>Q)Nv5g=vYWhY`Z74y=bAvREW zFWM1BGMW()(a5L{JlLwrYZcEJdTY2(KQd=6=uS+^P3>@kr`qVBL@IZ>i^9LEL~^57 z;LQ9)pf?g&deeNeH_W>S*sqwDYJ6oT&7NV8wXejN8JgRa9Ep-X+Zvn$^2zcinzoFh zJ-7Os>63NY7y%1J`MFz#NrNX#vuPx9W20ohXk21U*dph!1P# zam>QJg1eG(Hf?@MMRn$P*Ifi#P8**q>g3wV%^K_twAUF@0POLezB;9lY~xx?bgn;r z>q`&V$?NWmb_~N#GXnO!S0u_ijk+;5(NItlSiKBs4x2rt=D*7Hf#wzp;YOhq^^Wl4 zY^@->k=kz7)WzDbzD#D5bfjBnry9$8D*hv<$KRP7eECdR59`*L_9$d5=AvyQ4O#Nv zy*;%=RhJbKklAAnRSU zYcv>Wc7RD5kM23ODF!V_E@E^0;6OOzEVUMQ&S>Ll$Z z(Vj0mdfU7X0SdzPnYe6`>*9SWxu%h@70^qDUa+OmyLhRJ7FIWB`kIQJCRQ*-nU+Ep z*L^FLC!>Lol1kk&7&9m+5~?Xyuo_p#^^QbRWgv`mrz&RbOd%Y~fXXSH7d!O6#^Sw= zSv?!WQn@2TI)uSxur{htzL;0}uGIyknO|3quLJ3nc9q^)oY$QPwz(sjZCsV_%aA~y z>@aAr(x?&RNaIzy0U!x|zrnJVGt0T!S(I`X-@dmi893B!+0NyTgW7YJdBz1M$R#P-VkG?RyQZX~z z02uZ(Km14m%Czla{qVGPRO(Hl?~l{ZFTEy>?5- zMswdGf8>$F^$V$?0pzHT(XH=2=rhfHtX?cqd(DkYtv6Nre@6RdWZ*N= zH;s8(&!uA<)_?cS=%#(WeZ#lT`cL~BzFVFd{cbtB>}8>S>fqExpwZ zLAt4aUvtxv^yT-M4{fk!SfhXsYY&yXR}+ z&ghcC?&wu9`>Gwi(d0;4KODLJrPTlWQrVfl_>q!ozC=`(g_~2|q7=1L5wUbOvg2J{L4@4GN5@3}MGTbE5Z9@{->7d$E>l|EsK276K$jca+R2bf znoBL|*1gz`$>0?z3uN=wLkdjX(k%a6Tu_C1Z(FlbA?g!B0UVU_R9~;_Vsi%>jz9#b z*G@UuW`J)&_K^^fTGMJ)Xc5s;6p@uhZDeVNuc(ciHTplJ3(>2H$woM!|f8s+6l-5 zh!7Tjy$K&Io12H!<<#~pxHF8mu9tI}qU(Qkgk`GFSfUs$&+{~t~KZg8R> zyrQF(W1a6z{LZ5vV?R$_Ok)F;3ow*gg|I$(&kSR8j5}6w$VqvQz$7okAla;mD(1*| zqeq`OX-7vzV%3N7y&A^HVQLT4GvayUv z@0s&erm4J}{XHBJ;XRCWlK*;&Kv@}6tv!g(G9b_6j%KYa$o?aW@0!+TR z7)#{1zo$>etl^9`T|*jdW}Ow|rkqv~X?o=r)jXK~k^MZy)}R0U z;KZ(H7QM`4b>LV#C>k+l2SCXP%Es@N-h8uEV&?FJ2hYS2Gky|^@3DXL&9T!zRiMD^ ze;+i@kKuNxiE+jsC(a6jR7$*?C#Cfl9)5oYl2peImHueKSvq@cVC3WKgWWnj9%~I> zvO7RONH2AI_QkKh?%hGN@LxX7@*j2WTYlD?TK;k8+l)1~yi!+^&=)LTU1Iyxt3R4P zR!Cu>H&7=L4r6O)AB7#;dv7%hk#FZDHo2X7xXZa5-*mdLT*E~#-cD&5?(Cqt;W0!&Sd%BS>c*Botoxn~*{|{qt0~l3x z=8Zq+&Yj7f;U?UKfevY4&kO?{XtXyN+<^u>GYlBmhy%qox>yIK7G2wpF1Bb<&rHTR z#DD`ui!SvYK)Q&i(Q02*sy8G^P+DN!cKiOfUBkz=_G1y(cJ)Pc-ru>CSl8{o@Bbus z&iCg%pTGN@=V{ISOxYX4CEUhR;cOHEI_(C(Nr7EHQvI*$J{{eiYrpwURO#`7`wB{r zopk9QDRSbzLD*x{PTs#ZlT|`9=U&c5PG=(JH5&t>HlQPE+%Mb4)zABpDyya zSf#ZAAK8@hSFyve+!RE*6xm!<;V8@o3U2x*yV6RZa^gE~Jbr?~iga$gZ#4|DNPm^S zaZ2u#8$NtOy7@#GNo9{sIr3fC9(j9LGwi(O#NpMdywM}oa#;g8wekd_*Q;DVsq_Ip z_`7~lbILQ$bBrPb#A@CdC{KZSnf@aKsc|VPk8>o|koWlMVPJtY?#MuSoV*t%a(1Q? z7xzH)^oR4<$3=STWq$h9%yFcX&8;)1a0Wx=bm&1UuTz~5NR4#>ZXs)iZ zP!~}bdIfIpe`ySWQN!^M4Ftz}kT8nvVRQ){9F{dm07;Oa9M8a*>r;na`+xZCwjaj`2Bd{RhXeyFKd!s0-=0a+c7%SsS4rwYZ0^k>Up-o(+3hyB% zy<9Mfc2i3Cd#yZluA0r}02A8bIWp>Wekg80q|7##Z~J)1!KQ4L>^R=r z0#ueAtILKZ@>|f|?vcHe5eo@)PjqXtuT@Zq)akA_7C0vTW){=sK$y3)i4eo5MDv#)=fuw@$9a8S0KyHd-dmbg6i zXVt-7yC`;Y*I0mixb}Pn8pK2Gr=2={EF$wXH^_+rvK~v)F^hVr#_%}9)U~F!;an02 z^y`JD4RgwCHNJJnUr7+^*nZ}6+`%Q^ta6QPxM9Jv#dv*4vf z&2^JjKCrUM86=jSZ{=gyV{1BP5{D^P(#>r7$~*?0IZT%$f3(ohLg%sTe_-4izOUGP zq-@X;X=rbLs=@MiYqnudSbK0G`nRX~+!HyGT;uihiAA*Encv(pd>wUkk?$r>__`rT zcRoXFSC&mdhRHI2wn%|O=_aN#T`Nm=1HLqX z3PMZxXoLN%Pt%8p6^B61YiqjpXorF{m~PH(CI75afzqQ_VpdB!ldW17Tjx!oQ{mp$%zW4@{nmy_mfp#{lvebdOUcN&aS7q{ltL?&c^`wFOR z@j}wmmDpry*W637F%N9KHHmK)eKa1Ts!qCqUrbfTNlPK0j09DrsC`8zyAHb z*^?7QaH+Vo-MN_2&3e*4*vjMBdguc^T1$hcBm4AL;HWY-XJ8Z2Ul$W=r~Ey!Q}=~d z^^usB#wZz89&|I@Jr)|*Hj|75qcii!D94iVq+ST>?WsgSU$iBXWEvKQAa4}mdd?#n z2h>>9Vl%@yj!Fzq!zhJuU79n}ajO|0l8LlPL=bL1<0u-E8}uX=jEIVJ$dl^YUEnMbu z(?RW&&l%BhLiRL(4`hy|1SR!EeV&87F}YOF^==7Lj-z1tXrMqc9F{SekZw z;5I=dl{Q2@QpC4k*xi9MndV+&(L~}}`9@33E@O6oi8OkqFW`SN-Y450Nw-jKQ(xAX zwaamm_BX$0KAEn)irQ{8E_!9NjIbKk^Cu@~Cn{>k@jt23!7 zzJ6Qq`zx*?dyDm4(|$jHe$tn%@(X)H`|EF}wjVW@o?Y;~HDP>h-yUQ3to6@6JpDl5 zj5+*)8NIlU-AXIg1k;nReWI?dBYjnTj($;FdWCO7$ljCK@Ivjz=daGLSkU<82X9;F ze_@IB=%u%txApk_4?eT)f!*_dRP^1_n7U}sA|uq4SvPC^0`Jas#?(3Psl$|&1SM8>DZnQ38+1B-T zgTB5^?~tLUqw8XAv9^EH&G){zVumq8@0f7u+?y@1$%Xu^Xj^uiSyPwl`N^h+{a^q3 zqgv|GI`cN>j=dfv7f^xko@F5S>Q ze#O^#Cf3)ck7-N?j5(8oMr-ig&C%F3z46wZzW%N|Lv6Zke|>H?l%Y>8Us0SD`${}E zdyzK&$(Pc{`Rtqbf7@<0xZQYBPiu2|EiJaWO|q>#m*ezq2kcrJV`od4gKYE{FGf

H%OrjlG%HkkWV&%p-AIp^V53 zQyGb(LZh^ZXxO0Zg%&hE!>%OHjDp^+mz%{t4DLBvoZ5n9`PyVeVRrtFR0|n0wZ0@i zP?%WV10)l*3ugA3i$JSaByH|Ye^VcU%}InsTZFNP zd>c(un5@9}&7>B6dM={In&eo%64-PBS4UBBMWL^x3RN;CY(zR1M7Sdd%qQ?hWlb%J zn-kKa={IZ24O4_B6vGIxI;K!{Ai#jBj!D{z}$NN$jJ!Yjeu*&q;CF^Ehe2aCpVfEG} zI>>(uubqctCu&;?EgjtSCu%zsFvkR0_!3QKF-9q3a-z1ZOhTu1z)6*=4QOTxz%6=# zQU-B6pnK#x2b!lgi`XQ&KI&JGDU6R0s2Uq{EyC;SgFV8*S*g$&7#>7D^_sF_OVafx zI3hC?jvEZppnw4a6I1~#BZ&Uit<#)LkgeyrUn4D=*san7Sh72dE~q2@ni5h}u(*Z8 zUrZs8oDwqx!sQSTvI!*VwHOdu>V$UwLBIz}%KqwcE7vNFeiSUS_eneXR8hiE= zNBYqOELt8DGHLyU0>hd|dEKCHKne1YqsPxdgFKlI1etUGy6Z;iwT|L`^@TlEZW zz~`qzhV-AF?|stzV%1N%kNPQ^#f=JsWa^1#Q4-*pnDG=|IO;x%LAqfOPUSgjR{E&j zEjQvTUEz#Xd)zgH@8c++N0;}b;`xY2@qesErf$Af{XhSX(mg79GGMuYG72;n+G;wf z*+(DMN#S)LdsqxZ1dnq2I1cFNRV+|pny!MsGAnmiS7zl0_m3;(hN;W#!wg~7qf`UN zlX@7hraOu=j^_Ds{i8Aw=DcP>Or;52(v73+F_mJq+^RhPo%&EecjiOu?cuvClD<{E z;f4!)lxfeN4|VWR1x=*lq^jgv|9I%^5=e=^_Ja?O{v5Qyc+Q?h?+1^_bEg!>k3I~P z9Z2Sdz2&FM$AI{sKYw=k$3q^F?Lw~f`BM?}^K%u@L7pG_W#!#>t5`m$A}epbN8Y1D z@4oZKF^s;k@16hf7khwXf|B_2=ZD_^Jh(gtj{f}U&)=w2UW8Z|9@oICR>)Ccd5`+*u&RRvu0j0)NJ zC)!7hlF>HGS%UNiE8-6-Y%zBF-+Pr#(FezbAqv#wPC!~)xDQvIh+-@7; zG`-`fOAk5z$dT=E4>X*padoWdiq0@#gO{^%50`3#N^g0mwxo0#lL)z3VWZnKfJF)m zc52N4^ngG6w_LmOw`K-Ze658S`&7L8Y28BU6BbDJi2+5YX-qqj)1h9Ew!b8JvIw}R&Ri7>Jy^D;ED&oXb`OP0q&3nU*Rt>7&tLQg$M15z^0F5XRG4{=oA)0 zBE_^91dND^fL^PN-DEq=pj#{$npXu4a(ub92zwKRz_02LvL0cuGjxl`oO%f#bafyf zl7e|d;H+-oA`${&a}zF*RgX;zdAUS6I3k60gA({?UzS9G;6mtza0d;NiotcbO4w1g zGLcS#l>JZ2U5l0V=5n36c$hu54;rYB?gG)AE(sc%8`lX0H)J(~Jem6&^n{NngMC;T+toFzjV#gsU{|Lo z>Au+O>j=mckr#P7(8o@|&nJ{l*+)gK|JDxee@4Jc3Fm@g`jpXL8VjuQpUfEpe-w7Y z^vCikk1@>2msPjc%>&e;V{u zm$V1{{dKKcjb#GuhU{HWAH8xs=JPgW98dl9Riq^aW$6{FTNOTjGi6OJgRX+TYzW;F zjhddkjyx6})9dtv#2G7XX$y*~4K^9<6^YK0QI`L#(05~bi~}GU*0mN(QBco_ZibE( z%3yyzhlC-QYyUu0-lji_`^897%|I(;0(ElQUyVYFhI;CV?iD8xX|cw<1vyrS(#u=t93C3R$v^HYm%DEcvV0O z!%8;I8a0G83+%-{*gj9BPuZDw9V^(Ac@`#I>at|=8&)L8Ak)dvY$<-f$_qAQ*VVB z(q-oCAiJO)sF68a4S>N(I}Zg0uwmhX#$?ItkR<5=%d5mpP7Sy~1`dggZ4e zOVEdjgmW>b%yw~uzZ+c_8|N~nsV%#VjP?q(rbS)yq%oN+(59aBOIlh0Thy&Y|5_@h zn4tE~DU%HH8O)-6f^Cva(o7e(tu5X#^CWQiiA9@|KNCoJ5~g|%`dZa%G2f5L#MM;3 zdI~JuP~7G$FUmt6zw&k!)(wa{Vj5}5=$z7QhS>^0dw5wYm7h*m&!N_t>3}YKbDPQ={W}KFG*HIcrh-2FXL2S&>T!W?hi;|kvM}5+IsLg7&i^A$|(Wx;>-!#&u z_54g5B4_UEtDBcL4uoj^>^fSP^*5LH^-XOIt=~XT-ez3=$ka{gdE1v1;l{vS@9ce`!3t=QevW|VvD_wBo8{X=5TS4y?BTOXMd>ogY6 zy2h%V-15SccYdABP*YuFTdjXjEg)00K~uc*dzaRQ{Ih1;^JbxWtbfNvZ-Y9vHQAG6 z7do_G%xmm5&5+p|THF*&#+p8D^jdA(+CXAiYl%{)&%feVZ-%~>-nQ*&+y%DgwX9D+ zJRur2DLs?V(1P~9)z*U+7#w!!wKIp8`7erNS8qoCc|}uaTkX&GU-SI!Z6S@utXMxM z)Hm02Df)_{MTi4Q*nRltR{TCgzZT4lYZyasXl}!iK z29X|uSg*1RwNoP*U21&Iq?{&z>QoiBIeHrRKFH*1u5N1knwmSkVPbhf8-dIrdr+CQ zhji&pVYXB(PqDSeuaz(p)I=$J1bgIY5MXXOe2m+S?|6V$ z5f&SoTEsIx<@mkI*7BG#sSN0T$S_RIFYU7wTl`k)NzYU z08?eSFYnjWdcN0UepAyECW~v+yjg@Ul78m6#unm*bNswSZ zPR&?wh!yaTebTPe0k7hPp)~jdKnXuIi_ZFmS0Cb9_64ONtHM>_YFF|8<+m#P zi{MmOe(EVWzVTb3P?pMd`}be4_tt+<`Nn@#AVsDE=`o6~^4QU9E9c+)0KzmNXXE_~ zXa7hq7WYA&JN`z+5pP}j#{HxDyZXyLuBNcZ-_CFxg3MrrwN&2t;JqIY?cGF^8Xc>~wcuwITV&0cXJhE~91qMN z;e&b=D^zrY1hWd`S7D$lyXzJeRUPi5Zlk&iJDL_7F^}3up0L+9T%C zvcbnyA7P3p$2d+^d=cdsVdKDxp zfmeW{8&>j}&JUfb3=LK8K0oLD9OZX*Sn*1%ytNNd9eeBXJ#W25`UlrO^;8=^7gXLq8)+=RRXKxLijQOE#b45g|6Z0y<=z?a-gm*S zj;aqTzn!7z9Cwvf89^8c-UO#k{jvzt%Swv&kh6Ej?`h{=k^~B2Pqk?73pm zZHEEOSZbabQT-u-Mz&@i#mb>;?5^7(H-*e(yFW( zb+=mCt;6meYi=KYMysZ*XMbaAhT6kLrg`y^bEl2c3cR&|yg=Ua4_%4zNMSJo2Aukjf5R8R9$6IRAGX zAeNp1*(Fc?^F8I7@ARkW^lM{YcXnBnpF%ZVNQ&6t6c6Lh!5PQGK5dU;)mE&dNV3)z1en)j}&ujS6Im4qn z#12i-`xz&%12~bU{NSK7tmv!`N;s}k2egBn7~)+nPB~snoX*TwyGbfbB>p-kAsv`& z1T9llcqORZh~jDqhl?ii$^}C~)1)L0l)|H6K;cSoK@iQUMr&vA#6D6wj?7E0a+hdj zZWuys7YazEScW};H1P!zm-9Uqm%8K#q_WT&!c>q#$O2FroCt9qB?iDmARQ*G1aB}j z!8GF7DWanXJ)FsU%b*g6cn1^+9)gS*XB_)wL1DtGp;Q@25=;d>jRK+~pb#P^Q2~#J zE+h=$$3Q|jwLMeGs9nyV6k^tm+H58-veO7to=h7^@{CHx8Vl?O`kET%``0?MLsu~x z^g(7rhiM;NNJfTO_8CDf^@rq5z^v9#eu=&FRhoHc(x-Bz@>sd1wzD(wZR083R6c=aExhH0fZ2w+_UqdXh4K3A0po0XyGO)&e z1$2#cWigWk{pG||XX~(U(%awyw>C`R1EfEQd?)*FEKIPRP#k&*5W#8 z=wqKmg`An02Q*5mK_pONPVmQ`M2EfFQmz3%2JUDBLlO!k762C3`~wHw*u6eMY502D zEypK&X?(K9`AO4acF#&LA4|mty-B?fw0U3kSSb!MJE!|h{kTEd-*w#}5epm+$QO1f zsR7(q^Ms@OGC>cz37#E?u^w&}rdH$Jl!u@0?1`VgHxZmJk*|mHyLOn&e@}bxu>r*M z+`RD6gOYBIPWGPou86UFEPd#0XO^btv+WeH4hGZN9~ZURo+#)i9zAg2#2d<>joCLs)WYn!T{28Jk1x8^a)_r5>^(_caoIO4EjfxGvf2Qe`ay?xwhjV#pcgIr{K#OC)% zS|+w+Pi+#k%&KocD8x!Xa`iq)4}8ao~k^+U`#z0|^lc`fY5d;jlEyaK=P)VjFg=Zv;R;KwQEO<>q=+Q+< zz=}u?-!7O;Msw+cfS~O}gtREJoZ#R-=hwH`Y-?`1-XMjpC&Ah=u~fqa0Lx=(#rSrMr6j@F8U} z?X(sf=J>6$X-+8}y6P)^Q?HG0>zwnzBiVpmO7AI6ocj=l=Jq+0N|*LUOIKTLj`xnN zWpA@zy7T+<%;(CD8{&Oi8%zGs!->Y=_q+g7Of0Nbs z<-nZXS73got8BaYWaF&PdE3_+i(?VUAClzlCA-p$|3Zh5%riEA#+ZlD$G zX79OnuJQd28Ek7@cGo&{(!|h#nLoTD^Z>POtF683mbtY}`)j{vWnX$Eefzb5+Hu}A zjSUAnS2S(!Gw!%xbvP?p=Yj`Ad`oKGoNGF7qEK5$sA(ho$2NJI>|Zps1&#e}$2*!%eNcLed~W% zJkV;>HQSnZ)|M zbJA{WDwXK2K9W;6adb1Sdy+~V)Pf^;}HU;#V z!oCNKa-*@4nS1i)6FLbq(xY8W9mx>w_ieOA&H(p>UP**iqtHFmUS}?q64$ho@l^m) z^T7BZ5PDG`&{J&4D-5ZKG9`6#i>+L0j8nvWva@ z42pQK?Wd7F7&AcGX7{wYGtyv+#o4Qw4s?g zFvZA4*aTmcjnE{_@K}sjjz=6D6W0~<0LfudH*!I}NfNcU!ylah_^u$0$UvD)oKJi8^kU|*Hk*`2LuD_O4M+{YNM8=IETsXn}sp91j zGOFB&Wt1I{p>L3gCg21IrHq`VXq{a3*5}^(oHATEe^yDMt{mI@#}Nb(c*7~>QmMS$ zi=Q*VQ-oE zZkdUL4vQXoNKsK%sV%FNmP(rSUeIF#{{&aNihB?H=&QgXmAd5UPpUQl#4ke&lR`3} za#dL~3XfBm;V6#xal32gRm^S_H*|49+|O3Clfw8^7^N$_GLJr^Sfa8sq@n!XG@vVJ z*}Z2C98!f-@kj00Q@U<$`oJp{X32mXx)0KE(}R7Ku2Io5f|hZVrcvn|RetV+aHC~Y z@&Bx1)_-zlF&vwLD=J;#eF_)!^D18Gnw5R@8F6=UL44}{xMJ{AX{fl$-^Kc%e}pr_ z*^Q@ks8RQE9DR5syz2%(<>p6PDh;KhM}N!=tD?_@yZbZ?VtmBxhJ{(#;jWZR^QhcM z%jCNL*`I1ZftTu1r)Y2SgZDmo52K^+_j*k#9$3Xq91gJs}1b?Fd6kUt_O37*g#&;admY}!XAzf@Q zvZ~jWDPteO77!zlyHgXw-3a0VV1;3jow)Jheg`vNfEM?t^a7DvFz0hM;j76XBUkHo zF~|v4YeD&6@(wpuc=kK*&945Abkn!6!v_Wlux3iiO%M4(*T~MRyVeaf{}-y<4VOly zsd_Yw?^pT2J(3<0g!))R+ZEqR@3Q`q!XVY4{C}&wJN-@p9iv)4A}8|-!;6KF zOgqvgl-|-`#S)_mg-`yCo^ri`O;14EvnDMRGov^&_(aR^Omsq0hdU$m-k6^)_Sa0?7@o2*SugY>13ODhR-7U>0WSUW!~UQuEn-sT=I_oD?4EyiO76U@Ea_{x~|QDGg;D|gn{tR^Qu)`TJK!H3%fsQ1 zRb3KSy8FlQ(ERmfvPy`Af4wXc36*jJ4N?X< zmZcFWc?g~kQBaaVsbEduDh+m8hyY{}PFxe%2b0h^dV+zyjiXD1(>#{oNK5U;5C|nz zU;IhuURX)uaXTIo`11-L00dnHR*REO5TXK-+kx8T_-FPUGVXu&;-&0>dzgx0(WB09^x}O%G(^GuuXHs>ogvxhPonU2zA4|7l(u#!z zrWX?J8MUgDxhCsT_Wy@MpPQbOeVSKu%7@9g&o*TLVY$ZtKvu*KQ|&?Wy%I*AcLZ++ z)<@Js8cXPcg~qS&)gtcot(uwG0GSm}X?AM90IpY8n2)!2+G@Ck`<9cIqII5b@}Ck$ z>qHBocg*xx>iZe1oC@UoO&HlxCpg2kw-ixoVBM3)rAy6D1QA0QK)c(>Cz zMQbokqs*u35bFP;Sk-Tgj^0)*5Dz4nNH&MqTJj5SL_hU;X$>XSH0VDX>d%vMVYNJf}a>cqUn7S={3u1^(=H3=!A7>(nQpHE{LA*2au zl)nk+j)f`Luv zJs`SThVz~ND^9EhX$r}7j7xnLre?`E==n&)*4AmrRP`WTEqH;ng%K$d$j&0o1s-}wkXTH34sgE?QmUglR z@$>P_AN~r&FJl`1fZ0b*+0|r)IT84gtxF(-*T&?NzriI#K%v>kHlSRzNAREF`kq)~ zF9MBm*Iu*a9W-gPe6kIgg~EA5{lgTOPgt1+-#JSDE@a9CzBBmR*be0Pe;GR-AW7ZFfOL0^}e#=oI0c z%gGW!)Jbpa$pE7jRGWQf0@;sxO!FktU72LJ{?8|IPM_}+ztU+>Znf`xSmocfWIR?W zW@T{c9@phFUbfaFCsS}7*$Irs6;dd>Rx-5=>p^ooZWeJ)rZe;@Th-MtE?3%rRzcTV zgTnclu4y7=gtaZy6xO00IBIT|%@GmK@stp~y?Tep6;h2cY$)oJz00T&nuDdkp~N@m z9}a609dxmt)LN_*K8}f8u+&RwJ)A>tPW1}vi9qCw5h;)s#;tmt7H`vWw#T_Rxh1l! z$dbC0u|mR1npQql*qUFSKx-w0#TH@U)nhCyPo^|o?}boXV|j3U@6ydVU8a^761skM z58JF!Ln6_T+QPMtLMs)LGR3xu4VYO1&07kE&S<{D-?@QPFXzP>5P}njE5EIXd5Nj^e`|QG6HkC{c!J{j~uu*{X%ha=eD}F z4{uyT@%?S{CQquPdFhve@qjfuKJ$5NThsHk>3ghg`}@9^zBHbpmwW;@Q7j&7*s0mG zCfvB+zc{vRMQNLHJ4lMHb)Ed7-1fHF6SsC}Zf;Lb+v$benXBnX2PkXTbvD}LpR*@U zvg{oP(njMIZFf$7DPTX>IsS`l=N)J)K0=*M<0r?~*U#zPzWj;tEIap(*nTTc&&8jk ziMLL8IA`59{%ig(KcBfe{=k|$(;N2mwpm{@ZnNj~#n<0(TefL?>Di{2)@K{H9|(<~ zc>Cst2NtZ`^yS*g2D|f-4OpwkKjFOwsg)mraA!t#kj%o0-&@D+3p^K?UVsZM|(CH!UOX2`!8D2BhD<)STGFi}qb_jE}Eq>S+2x+dno0 zXN2^|1G1%;H?>|Ew%d66K&vlw?ZLLDe^{|Sc2j$2y4iX!-<-NN!}X}$7BQb+b8+M3 zzF1w8QMZ3Pk3HMA|0m1uYP%$x+TSUSwGXE8-DP&+ielWn;5`LIv^Cf?_3FQ9iW|Xm zMqATQXX%04+l=LH@d;Fn$LsdlbDBG?nL+SW%*1CGLw0;Wbxv-x)5g>FR@?f{FqbXs z4WG@kW%G+(R6lM7Ij+JO1W_%Zm&Y_>K8U@bnonG1FwA`dgp3`AYgg-c5)bE`I7SH9 zC6T~NV{x-iLdVu8OyDCyJ2eb&(u=F|Em|5IGpXq$%{|kD5ijMxFOcpk<`3~4EJdoyVXu<7v&QzEZ6gdnNQBb3;=$U zS5QIA;X(oNve(>w5o0!GgHsJ}MsD1(&C9zb6~h#f;5DPqYyvWe2}CV4w+hmyVcIpN zsw|UKh6Y3oRg~CzF`=xI!wgsK`IIiy4??JF5@@uPl{N^jW^Y`vE+gGCb@*+eTGB7e zn%YtLjgm01rDC)P-##!+F5E9V^ggm!iRuk5Z#3^g;bPiGu-^@K2XxiOJjGZ$9YCsU zg0$eCe1vjl-iYWxEGfM)hO6LS1lmrU+ zue*WMAlV!yQ`pK?Vh^PB5v3Xt)yEOS)zM_iMIY7SidaDNxbh}FTJ?v~$}2ZFmTG8( z&}B^jwC*-8cu=xdvVI1Mb!6o%OXq5{jr-$zG-|2Pf;WXI+`hxJCWYAGk%Sb<->&B* zbOZ0HRk?(4XPdh{cqAWSpl~KbA16Z(q8`W<*O*WYhzmo7Rf*gRMUkOWQTG>gj?i5X z=y{@pIcR%PDHTAc5zrq8bI{MVHr;h&e+__TFS^GlQ%_*X*o)#+ z?sf>Yj7J~;?B2b~@9bH8hWpaD5F50KNRz(wDzKajd*0hS_t+D zrb=I7AXTNLXe-&-U~C6T*`pG)tF}unQDGFGgBzo+OzsM3yQ=YC`H6k*oOATZTL4|Y z@gL+V8o)e1RB2Pr{q?!OQekXWY;Tl~aa4Ed7lB89(ys1ED?g>HN8x}fErk~I(*ig_x1G+p;@_6RMc+PXklk5=XHU=vwY3h!f>K@|Sz=jgt$|LsK!Cw=rx z_f7iS>AqU!?qY+$@Z302fu4uBh*MSQyUI`5M|8#G!i}T!5%+4?Y8Vx+fssBYJTe4f zS8lEv(G_<1ksCZ%Y~*Pcz+)HVPWfWoHD3%2b}=wn_fhtZDh)TTilfSEzyQp0Tr=d< zG`HjaUbWtE{Vxi9O)KvMcPu)Pr*z@NKU`R`5Ae34M*Q}_sK0Og$DJ=J^Vucu?tG)? z>=Lq{I(Bx+8$F6b^8C=-!>Zq_-nx$*9O2HtcmBNNc)oO*x@SGaF;o@Ccz0zdDXyzN z4%)}Jz6BUk)6|`7+>9e@=~`pI)U#&>tB_3sZby zZ-8{CEPUJssg50YN>g^9qDR!GU^^_J2fK`BWe?xC$;Bjj;Z@K>k_MiHE~bdf*CmA& zwj8|Dy+b`^0o;KlMw#RK*LQ9L)`(+zkKtmJmw*Eq>~yJg=^)8ojrECi&@G;+(mg(m z*9U)(#7P4>lWuw#L;au(hin*p9ar(k!`+Qn)8S%_+TY;tiBnVj*Hzt^S=D2El}-V} zkB^Zkr)H~kq2J@WV|6*UO~sq&W8j2?JLYeybjgDg5r&8|Dz#H>_jz=4z5oM{Y|g70 znor3MU?l>Ec*LcLguP2)dcY97)XHqM{HA(`I(kHPNkpix(jB(;kKTc<+QTP%-07an zDt6iGFqJ;A$_*}^VoSePT@GYb*JRO64+7>~LwJ!(cS*K%oxwM<%AXQ)wN?3e_(+$l z$4-psC-d$wjO8M3`gBCA>L+^Kr6(ruo1o&w2D%D56?yECyZ(Ugk&#-O(e7?WG}v|c zP25d}#q()AIS&ntJ4_xS=fA#7D0h%1k~7>ja7zCII4NqLaa~ie#YuQPmmUyiNn2Zm^3y?Q}T<#AtXNQhcpTVUUgrLF1%k zUKSyg;|B_NWaQvhIV;1BPz6uyhL3v1n>jE3c8dYsY{B9 za-J7SNO)kMQjmn=g8ULTsSCF@NKYw-@<0v;bg%{O{>T3-VkWR_-jc_Qf6@o9XW+x@8a&3OCW3HS_n`hq`Iz zf6#UM8B}U%7iAAVimW@P(U1>me{L+(Hc3Sz%2oS3DHtmWQ?f!YmAnXGm@=F4twbGN?vamH(Uckb&u&Ava*Ip zQqmEWXJuMn(@Wav&(wK_7YaJ)O|NwhBYbcPJvxX*(UVB2Uj3b2X&q%@v~yvtQ-ik3 zFSGykyNXnpniBV-&9_q1@H9!Uai4I2SZ9LlRtKaN;1fy1Os+-2Z44{QsHSj&EQ2;s z={g?~qk(?RqmjSt7v8OcJP&kO-hQW~5Idzfjr~KyL-Clj42Qu%2iU8c!YfcHO$AZP zWHvGRAoUBU#Kumv{32aonS69daAhYsJZDP%(anBAjLy29To)?<$-oM*0a+{N&HH zzFfhy61X+he{ZekAemQDEGImJ?)yylw-3M4QM^R&UOZh_n6Pg(5F+x8zcNAnE4F^t z!#rWfAXcWfejiyq++4Zi2P7g>NrZssZ^%y&Vi04c$7*R1$on)_SwUJ(PHsB|YsPD> z3j5#>qRrR)aSYLD^FP$dtvCIpWgl{|=PtM1z8iYK1V06YL(bS4w~+*dr(Q7hta2p} zTEii%s6Idcl)xSAi@tJlK)L%`PdvsD679DTurpR&jt@X9yKwr_iEeQFmrx7B$LStt zJ~LtK7#e?V{g|!J1EfE>I$7-P_3vuRI6i}>&i7?bb(_Xo?Ynjg*pJErU>1bh_TM8hzO%|jP)%C8&A&7}~i#3M!|nh%zWnjYDTgL60^*0hwCU^9&{j!H|l23+aPujoZB^GxD>5tbt? zNV?X}coHK_gp&!YKhlKDn=NRwF&!Nnc)nmHpC|TkRLJn=Unz8ULMab(F5X8u^(hKqZ z_Jda1zIgqt+wPdV?yhZ<`$~N+&o|MN^_`DAGUs{wg{CJ<(;o_^e{@%U;GXX-dEqO2 zzjuWZ-@cy!F|IJ`E@DgSF6voDtnF5Ry3}bK-T>MIEkOZ+?Qe0#3LCN~>@VNE-<10b zMz|?{WTVkLBwOuyA@k|<_R#jp^yN-!YtoviF@|GjN<^D`asb$?4&wXUDo(HgfG zwRz&}CWd@dd;8*soUnguZ0%mF%>ZSfk^a5C-lpifHthJ@vdwZGwL$fE0`_}!wjDzm zzZbFBH^13j-)l}hfbUjy(F;unj5WA+u`F%0Z1bIMlWB|7_)VcUTHBen{Y~_Bu;6Wx z@ogsf>dFl-Y2Y zdMuy073Yu4W^n68-@vG|Fm|xkRA*TO4umm=-X);da>>=yjai8_Q>vAN7}f~bb@V}S zjzvE!BXkocRtE3|dz+mQW+EUjG&ZDW8Ea zQLRZ?ckwfsz97KK2-3t6+7`$d6M~eaz(4*?6RGQV6GgDnbl1wKm6vI5yp(K^w)q*C zl&cTfq*fsiFcOkMwYk(vZhRy&qLe{WgsWft+qi#@K7qohU$^c`??NI~i)s>76&k)I zfUH!4(vvjzu8Uw1_i7A^h8afFIA$j-+Yp`2f&B>$GM-i;a-D#fBkX*8^(I~G^|vk+ zTqXTOTWAuZcr%=|d`qg9tqvjqTp!`9Sz?1&(46++i(@9y1Z0D77a9eK0mq$aWVkA- zUn{Rr$uJQ?!*~f?DAuEU+qFJl3Oh@w3%oIED`J;`_QPt=r~?|YcJ&&G7Ab&Fz5c4g zjRh&x@Gx58APk}6m~cUfT&3*)NpWKNPdMl~IA9hUaaQ@@Rk*n@0f{!cN`&L7DhEW~ z#VE?47qHqy*MtmxK6B+=BapRQH+5jsnAFkDcr1!I-h@gEGc{Keo65>0FBW57!(odV z$Qn7QOl&L$Dn?aB(PisV5S71**GltU4^=iObm#d1N->?f)(nzI0xp%*kH51glmE-gRa(L?48~JN2Rd%i{au&-q?A_UJG6(q#Zo_7;ax-*=rOvyTF!#Kda#92;p0rMWY$M3XUe z)p5Ma^HE`a3X61~5k8L!19WjhL}I|~Tuc&i6rSf|dL#6XRjkoQi(@zS$wy(3%54;j zRB1*>!l6UEX(~JX4fv@tp@WdZ2~{2{uF{oE?2qfpJo>0Gqv2IOM%|TpRECZUqwL_2 z?53~s_;U)Q+3jZvdmP8{C>;-L##Sua4&N%)=;|B;9d3T;%I+%YjJqb+-Sw+ltG~eb zl$#q*#l_<)6<<9lq5F)O{oM6M+3^nWs4%V$qbe)oFhD7KNSCIOyH?b@eZ(-LeUyGR ztV=72Iw_^naqIobILcEJ^~$3~WqhALPp@Lk^vS*Dy*p<_K78{0*|&!kw)oW1D%SYc zl|Mg!f933wV|(8~7X?m;kwo<~E9ZtQe^j!gE2k8d@dv+zJo&zNaQj&}9-_BSQRSWU z=PQ+;%Ci^WkCC@CQrw%SjEmX7TX_+8x_?lqr*~df)QuL_G|)a){^hIZD+KyUq=|e! z)QI1Gw=(|%e;A0?sl6D*z%muDM~nqo#U;UUazv^6;J!F`K$fL4AFchtC08vtig9!9 z4;bffslxJz+)4IP%^%r+2ER)8iHincv_?Xy^^IRah^v5bc9J@9uJy3I>DlYC!lThcqM%!3|d=dZQ zYB}uBNb~>j^)_%)Rad^~+NVxcpDIo_r<;Zp*z(&|6r^Apb7)&{L0ayvrj&;1(L!;8 z4tfhj2WQMoX>TcRd}5YtIaru~RHO{28P1e{E6oHub&fSDvW zdDw|@l7|TIzfN@_I=OFk*V$idf1dsMKWp#J{@gE2@O^qYv1!%9vw228He|Ph+?s%YA(#_tzAw{a=_H@ZM|9 z{;kCA8mmhp#Ko#bZ*J$7h;tkTyu+Nnes|9b-^$F&K`TK{c{*0AL*Y8XT>~! zk2T~j>wBajugLMizOKq+6XU|NEeICrNc)&3(&1NfE3slrl;ex7n3#7h^E*t~2RJ>_ zIJOZZ7Vxs|^*!dvKda~8pV4!GOdWNFpI#M@qk*x}3-s8(@^>*r|BF$2W6G$Wr0G{1 zr}S$5mV-kQ11uIr`@O)4(J3Bu6gUt(;EA=bo!Gth$79%neSH6@1e+H(1EXFhL$q?g z3>+{I_GZ)={TL@jddJB-P*byLNq}DSHfp^Qq3BUR+=H_Y%*r6@(a}It)2kV(dNjpT z9?2=#b~;KDoSrx8QFWt7NM*qD6N*Fx;Q|V*T}obE2LqV3KH>KcXbta8A$f3$*mwYl zxr7Ad8QC1C1gp2^0a5rT&po_3C zw)t~n1ff(~P&ukhj+gOwt+1g}d3FE5B84Z=nIi4Du>d;!!xK``rbo=*AirwCpdB(*$WS5Nbvqz#t?IsGGh5nj z-gBEff+_jhDJy9IAkmtKWgeAMR|0fwH+(%)Q6yXFjun;Ws1YK%@Q4skZG%kLQJHH( z6BkEj=0`Q^Nl@J^;U4pF*UBMHk1TB)oV^VWpJ~Y>rGj!2A1yTHKNq^=t%#=J#_H{9 zbQ+=msk^-v%(ALNjNm*tXL(T^*KMX)o}*d7Vb?EJx5r8Y?#6Of(_66Fvz zq9TM%v-!rthX`eY7d#n1;5#G%)oku|qpHOWA^ghZ=fM353XoefvzAApg>T-!n6Z|w zUy7Hp_q4e}Z{T!9$N_u{!CF(Uu>7&I{mK!EAaH&4ed>U^7_Y~C6J@OjT9k*%W;9t5 zc?CQK=9J!oZ0W3$l}}n&kvyIKQ#nGk@o)Dz%O)Ysn`W*vPH141p|05d%8*!l&dtNZ?W8O%*>!hsy++^x>~@g?YA1Jm>$V3wPX zZg*NVAv^Bw5aFv|i2eoPMJ5fTpGJG3K+C!lpT=B5I&CtIkH6T@?B_?f7@n^ojXR>~ zFM(4A;SXhe`&5+K15VT(hkSK;lH;f*O^{NqbK`m5d5_%AsEU2&BYM}|WMH$iduQ+Z zwbxAPSpFIftoYeJliT%-GAafJ*Of@l@vS(2Q5A+f_}lcCbKF`a(tY2isTxTxxTJMKpf&`j)0;9GxaI;Z6B$1?iyuAb* zRh5td+M-oFE>M>Q>a}vRJ9grFsv^!S)n-MnXf07JvZFY_huW3fdpc=ZQQPHWG95Ri zbv?kAc(^NmU3YwIT+P*1Z@-x+nQcW?O1mWm$i0}+RB+Pq&dj`o0hC^uq7*TdWz9%q zt~Rf*W05GQ3&sNKiJ83`(c~r#4$+r^~bTl(3I3`7e#L|-kY)etqgh|h4RhvmmZD6B)mM(5XQG* z*L4OIy-i^UQmd8kInL0G7pZfh`(&Z=7&Zx$JL9?q&fwI_DyL)E zMnP}r>CEM$Q*WnXH1~X$+ST#o3zuFLwP*HR7B;23s?xD*&!QIN_Qk2Zm_C2#g;!p= z`c|58{f&#JF5Xb>n6c?Q8}7Q9@^kyX`aOGJ_dP?azyADVPISTWjqYvTPnb_uvMn?6 ztM14y$W|P4{%q^^CtqBYfA0Ck?y48Q>Qru9WJm78ZrWE0_kB@Sd;UpvtN51(AnoyTZ+zzCQH)u5VTHFVKYsExw137rF$~ zk9KseGp$8syFYAF^=eo&KaZm-Y1g0s)j&(-Vf`|?hdXdlb60VZ`fN{>I?!GI-`0$Q znQqj&On0nq|7y>@5v$+5E@iDL4=>6tx-jx`$L|(o6L#e2aC!bLL8Sv&MTU>#a7{t& zNC1CSreAg743CNixYvS8v@QjvPoys@>J(6V&GvU!7XY284tp)J(m zPV^IGnp8mFfe99A34cQx9fF2nwuSWqnqVv0+CXf|cB*l;fYx`UM5Lt!hchy!=SL~x zc7oQR9~T3zz5*dF5<;&)TIb^XnnciX^bcL=G#F!3woFP+Gl=7(G6L7=6mSoY7$8ZQ zRT~oan5TfWtqIK*dZ-f=XlSTlk`gFRfkuUa!?%~2IC0-2@%yTS(gKB*Kzl^*`5;1V zZ`RE?Ns$Y!KWG^Eq#(uYIQl$;wgq=f^j1OJOi5b{YR>XL6p_P|^h^*jMX&esRyZ{z%jGZt{D}IszDa>AcvZ@!6Z*|^- z;b%~>P-TU`(OG*-_#5NqYZBXU`r!(4PU0f=fEb zAcKYbr-46yNH+k3JWZ$WI5qbBZ-4NGGfo|UeD^b+_ReY_iv$$$nJV%A>2dF;Kn#IR z{Pd?skL*23U&8*l8uZ$@>Mq2N)3stTW;YGBG+GEe_jt_9oy8YVXCWjPCCmH zXqtZf`_mY#`3Ee;J^O)I=I|%Zdt|Loj4L)|0?$_)7$mzl@W#52x=i86^o;u@HlW}? zuAZ|yFN`U`IU8Xz|M|Z*dxQU8Ic&xe88c*Jyzqkg_e{lJYQ86if4r|6GJXDCGQPQ? zpRjMZ`#hhWe;;PR2#}<#m&W1c;{deI@6Y7Nh zIrI7U&^L!ALdBZsoSK-x8F`)Lua)ZVzJ7ww=S5ra={!ER=O3p@B;m^ZiN24A!=7O8 zyF)8FRo$JjPWA)BMYjWZKUdIbNImx)*SFip3*^?I?+53G!k~kstOTa0=gm(7pGe3a( z?%VHY2vW$yj3S~fX%X+^$ei&yKoZfqw z(|>BL3j5Q0lsav*JKM2}GY~YCQ+weT3Ozge?6W;RtlxJSTeA0FO!4@|hmSxOlVkpe z@1H$WUlGtKhj1R5mZV5{68dS$Sj=w55@{;BLSTDstv5S9#wW|tKYuZ?rRZaVac_su zM|6bwBBl!aa*T%cfR8a6Us$%2?f=UMb@|6je%{hSFpJ+>j5Qju+@JZFV(Xmr0Aq&o zio@)0hI|%-E8@o&st&fN%Oe;^uqv+j;k3n1gfl*t7!M~9UK`ycOyy&VZyfG}xjpU6 zW42wg``|7%PmRAe2n@0<7LNm9;c$hIK?by_prSZbr$D$mq4O03Lnx@g=mJRZ@YT3J z!5(n0_5G|`-N$yY{2(yK6YOrqYMXt&ZoSoa$9astd?Dl!eXJ4ZKKf>f^COu*J|TbT zyjf)aKJ5V*>)^#iDr3W4oAig21+nWS}HPZ zHV%$-q6x^@()#_}a;YDVj2}GVpIaF}_z-)?9W!|6O!^_;KA{^uh(9g)=)A`|7gkSG zu*fDoHU%A#rYWy(4Sn^mKLfITQ6=v4ub8{4c!hE==- z4>28sTLzW!hu#S~kj~JEhpk_;49}VuXv(B(o}P7L#N#0|e(~|zm+doW%&?j7`~=#8kFMtr*i^E^?bz$l`QdsrWiQ0-|>&x!by z_?Vt@{D-?~bc_xy9c}togfeykNqm_g=NC;s%peDn_e6X|)<@cpblTTyUoHh@LK+7t zlBqG6TiU75;RN%v3(Oy(nwXkNsKIoMjfl`JYD`g;S=AJTzY?N}VU6W5r-20cX5|5S z^i!hcXuT}e61&hXym6_*?2 zA?ZQv%fy=A6spru?HUP)V@L;x((tAXUmJzEe6_us#F982ioh{*k+U1`!d&^On*m3O z>(+kRT(B9~?yCrYB@%dy`JJ2};?4iF-w_&U2Bzf57UeK6#|#c1&qKaD zz}a<8RmdxP7&tV3e~WGhblnlz$cqu)rhsYs#X@U5O)E6wJ%R^QP^7iXW@CzaJ?mdO*)CCh=+@-U!f~#GxRk6t#L5 z5dM$`s0e{Q&$pr~Cj&Phct0R2E-e&-2RxFxMI}}!+(8l|bBv7jQ|txlVGOSAw#P@J z#dN6n3*<(d9d|qf_XkRJM{OyI{Uj8>PE12}GxAWB$OrII#FV3d#uMr1LcozhIr9pQ zhJxI{%<>$)9_Ie0%ELb@UMS~>V}RcyaY7qr6`$~H$~aJkpEegS<0$x@Iq<7ET%%FA z92&$mj1rAX`Ib{G`yC*&;4_V()FxvS=``1T7LP=7T2U2|RIv&Zc&Xu=+A9$0Bd=2| zZ1n_ovqAVtk+D5lOyJNn!kO&NNaIe+z=kU(BLln~O%YxCRuV>4C`xM#cKiQHNZ`s` zxfR$zkhnpN3LUb-Y~G8J0c;U-{BVvP4b=@df%21nDYetIDK$6{)>WL)kWz3dNC>gH zXwYanMo7c8yAY98GWH0~70%FpC1HP9oU-DR3TsN<5~TOP8PG$c)cL*UPuQDNVjS0-(oShQPPk)fI^-X~L#M)f#w& z0&-f{v44PjgN%>KJ&rATii{lT{4w0QbTyjV(~s&sRJ8KPu0%>UTAB|;bN-5k_OpM7 za{E1Cb`Q^?kVGZHeHm#0#OUZ85B-BE;%o;f;_a6Faqc&6+DBa|yVjKjllza>w{tAt zn7pk$mp}0g!c)_Zzc>%=eiPbWG~cqa@DLKV6rJ5(qUxmUI1?ac zqDcYB7Cd=2Vy#Z=)oI~q%xv04u}w{PsB5|s+S+1iY2e;-PsmM}m=YTAz zc|~;m<&v3<#k<=JbNdam%fX$s>A9wixuyQ{W0>S=V5wVZZVU)+*(j7W7fC`GiGgLb z($J5`lqj^%)4dTx%rhk#c@`(470N}&*i!DNSZ{c{*0zlGF2jC)>6Y+aJJFks>$bKc z^()z%Rv9CMas?T90$Fl2ANh#Q($MDRh6`s@Qnmaas9X&djTf7hw z8+jL3kd&{UaaqsMbxvgQJ+D+|x=wT`_C1>iqe9D#*6Qz7tS|0bjYZ(YM=U-XW9DTkgzj`=J8@5%S8>sAj^fr6P*3vWC(DtG1-P`u{tk%xL?Wq_3 zyfP>@+`Vd$C`T1HsND@tP3OOM)|}4_BUdzZbre zEUWoZ%I8%iGCV{tV!qJw#Sm($Wf(spd+XN2!}pTixyz1RFtD;GY1rj0TK*_xQy7U@bEcholQiCk|C7vA*N4E1MH7kF+m-f|l*$^n|WI{NbS z9Y<^Sz^*RaO645q#pzBqHScP7Ln_)+cDuUmWQ&Yi?oQd^TFH0tA)sSGVzaxQ8kE*) zY#d&7eS62MF2_j?&+K%X?Zv-c)6qkn*7SSVRjr;2TeG-j2s78_mmNxJWW%+muZ}{( z^WN3g4UVQ&u2adHu9F|=aoa^IW_7nZy0yo~rIqcjJ80QG!zr?HHA#22$DL>O$c20z zf=>Y#72ns@pU|ecq?K`sZDXih)IuA-?80hw!I^b4FRu*$->4!Vd$)g*VDpxhpk zRZ<#}#;a16Gt`4rLEO9=B5oZSVIoAow}y#KoC3;dB4%_kSae~-vN{RZyaHMQl`)WN1#rpbK2LS-) zqV!EZHzl|t&gMZo>ZFrCpM?7+KzKVaP%%0VNzuM%0SlUGauO(23_Y!z{CJqtC#!%~ zo}}hpn3G74go?f1(BKS(AQb!|9(4Prp*em|r(`o-gLL@B?i?QM8WaSOFMV4xJ)sI1 z8)Vz%fBez4@Be7b0`_>=I{Yr?$L~&lmycXL1Uatq$=XXV?cF*r!YBmOncrf!n9k`*7vy9Z{OgjcX*7d zdnbP*0LiUj@C;6htoaxV?}6nTIvV?78)^EO%J?4exbtyG#ta2s8{0AN$7(~45KRx> z@q@nxKG;U7bMB2j*NiW6xIVTyfW6rGHR7%7IULkm#uyu6vW1T~y2LV;?AD045f_{N za69X=kPY|u=KtLj=YDf9ebC1kC(`MMkF;=@=XjW(`TiI&=69ZKBBm^WYU=y1r%0}i zb=;5b*n8N2yB`mT@1f>>%)aa)hsS&g?5DmW*cbhO@Fn>Al){pI> z2G07?ermY!zG~i2%|GC*=c`vXa~ys=EX&AgnD~X|1cupgZ`dPVmhWt&A_GSvI|W z?T;Yed*+O%KTuVKac&nm|HPhR=hV~~PG!(vSE%Tje zbzHuI&fjuN1F2`Up3!-BssCMknDO{)_cnOYEdHZ@JJe}R*Nx)EUz)i|@vX zEX1B|Ruh${eXP;6mK|oSG2v7l*rRfDe1v=W!aLc#;GG}%d#>vYfL8Cbmy&Ula3}fH1FUS_yaD08p1h>>jC7JFxO--zmWH>p#){?QemJDHj|EDs8acw4_V;*GeES2KnE^9InfUzmJ8*zu zKH&2u3tJOxpG3T@#@~F{4<~*Mumh)i#RKdvDO2Y7C5Z`nPOq-wFiA-4xSK!E%k zsWpx1Koj}?GblSyBM#t|pddoo&x>GeEet5^mBs=Mx7i$^+KDM6V@qJ%C|*4P-r5fX z+8Y@IHakLk%7Gvt&m{-ICteQ(y;)bz6&B3_my;cYy$ODl78HIc%!uum+7LiiFOi;zRjcDW187e%iKoOo2xkGc#}I^}e0I(DOzFA;A3jNgN`Al)3lofVno4SR z;X{gI8rvHcrvrG7S<*pNCC9^@jiXR8*i%+0BpJ(FWonJ-eM#2SXU425!oaDJ3c#jm zP@pIkByI4KK$itkRh0e2!|Nvr@C)`79%*$BKotY_FXK4FZiQ-V#hlv3?$7AROr7tz zDzqlnr|+1)WRBBi66I8sXOV!{;Kz`mdc*v3FuC{r!EEAnDJ%>^ znvASHw*LwUyvf$Q7r|!OY-oXqP-y*RYc2d!{&Gx~L%;-o6dn31(AObIl0w%V|K5WD54yWleAFp3kR=QpXtYW zb32hv)S>CmDur}`T5`R!a1sDolbnm`Y027u9QGr{4*JDpLBDyrS6PbOfDXCbH($`H zxdI}u2CyJBBS|h)Sca^pULOjgUA@``> z3XRwS3Yov4zu8mPEvcuf%Gn=mv7cE&ohP30jFE>G(fy?U1y>EvnoV}>01dV7vy5t> zV8x2Ph~hs{S>eT?D!JHgjp_L)@RFk_+zQcq1C{vB>1MRV6?fEXUkf!%tA#tXjj!&g{OLR~n*kvYS^adcGZ~$>k#GaW@$9uh9cx|A!?_#(g?kn*) zIgQl3cqlRgJS^ANH%`;kr$&m_#$yjaz7IkhUSKC}{F9D#3d|PSJ+t1ScTGB`&!v^Y!q7DNWHFGK8?ijKz z_wa5QmlkB?FgqA;(&!IEcoRfLtc%CNR}O^mg+o&)pm9+$>bVT1tWc!y7Q(&gM0m}g zafW_JG&&ov8R}X^Vyfe~8x4f}|I*won-0^SCM>2APJ;rRfC;Kf5`UrBb{*S>MQ^jp zJ-rzR3@yJ3vY)^QdPDiq%_z8zavt~F)Am0N4b8&BJfcuRf_OViMepb~O}U!}*7kOz z-wIB1_x}P*-M;?3@dJFz`0LFy45?Np;OM<5i1l$q+JelX1W=<0RfN1G-q+C(zjVAD zWuSN<0i=duTE7xUHF(S}b5unwFeg>1+75TU)RN${0ysYa>T%qGqpbERD5g6@e@>2G zY4z_9X)G5ZuD(SJQKQsT*gf#&Pvdqn>=}RRnikbdR=b(|8;;ed0AfKeWdO)SlN2Nk zfkA?VkcM1QPMGZ?n>3UW?n9CHri~JbxYmYEiC98wlud`q7O$4q7c>3J64#H7^tI>$J^Sx=7+`DlFgL1oHv6YELCimO5oI{f>}(Mg}9Vl`gjkTOF|gRpV#@d6c4|yXh2nY zz;JnYc;O&rb!68icExorb2_pWYuDg(at0$ez5vW^=*GJTDz`;mGt!*nq7GJ%dafLXM#r_t6U$> z>s1@7kgOeY^F!7nFV1LodlqNidD|j0vX`{DPrlF`w!a&F(s~@NuDP;k(cm6uWk+wv z>Qr0m?`$LT;tMvO~vKjPD2b16XZzd z&;YeaAO_*plOZQ)#Zq0#vZcGQmGwG%#LJW-AEl54$p&pT}Sl7H6`cY64f4eeap<@XnR-J zK=cU%+c%=A{OUa|sa=j7EDu*~?2ds*s*!hh-kTh{qcdfi9adQWq0`E&>ddCr_uLS5 z><;(d9?P`*Gmv$(cm71GWIU<6d*ooWV>#qFXS+HzBXvo8cX=n%Zv-i z85&7pnW*bzZUG2OQrpyRw_seLl8~?tJDQ9x!aOV3LSJtd&34%q9h&=*wry0fr50pe z7^49#7PJ^RbJDWDML3^>@M+96Fc@?yOueeK&ro7>i=kCCN02$^4@w%6yWDz7KbJ%^ z=p*#8q*IxRgd({Z2-y<-HyDuwe&T^8J~SU?kgd-n^e5*C*|xO^OP?7@ZBQAgD4XIY zKQTws1o4@0uz;->7-Jb!p$iE!q|I=bLF(;AQIQCn8u8lwl0tn|q_3H%w*}W{$GTdJ z(xg6fEB28as>hbjbNx8j)$X5$4=*hultnDSJaKxXg%1h^`AvuNT1Akqww57UmZK7q zpinI6*EBsS(JLv9c_|s4*xbErHoP+-F`N^gZ*s@cAi?Fq88I3*b-sq_<3%NXYxXih z=+~JfKTu%Ol+Y*YX47OwIGH4YHA<*V=XOO~v`ND@6fx7<=fl|GbAVsM7cfHR7RzBy zB0HFrQk)9NnI91LngpsC;0;M>nS{r%!0V7{{%B2B0lzUnG#ttc@l`ZVq=M6eAJ1-C z_1z~TJ*P)OG~78|6I>I#FdOyC#Qc^9_Gi8g$;XrZXT-5%e4bmx*lnCWdE_DNxnvf| zNomd4<9psW_PzAdnHO=N%!|CE^VHafcb(qj4g(21eD*_Ni@4Zgc=+rGWzu{D$JtYd_l^UH z>_W&V$8jhf<0?$IfaDPUktV(j8N5 zKS3DOK^i|`a;T6L2A0Qihm14&cD{Yx-M0e|V}ap4AN_oskg-DWvOOX}jhqM%yv)yG z^ImB`d>?nwc8Ck}k@*;8Y+ z8uULws~i5tLv^{}y@yX7I(hQf)l-o(h!--&kE0&~8P48!$4-;x7^aEo+ zBFl%*e(<$D-@qP#fdPyF6NFjvx$ZZ@=Q&2EOcIPGwo!Ug1-&W-+=y+-b6ntVL6-@8 zjUWI)82sfF>c#K1_~$-e@+-zFu@^c}_0M~pGJ!o#o#)>@<6vMW770B!668x<h=W=kGefScAVF! znGF&3`r*ua(^SmY{rW`w%lOk3X!}+l(`5Nc1Pr;wx;$g|!8&G0OCR$0gc}DR=J4qk$v&5)0rNPiu(gj?MlfICXx|02rqF-_DHpjW~>xa9Sxi$|@=$32T`7%DY0 zpvq~HiIcU`sw$G1Aj-Ey9=imZ#(07=>p;^O6hmv6*utFRHF|1|dSw2&%wB7XAQL^16;*eGNjAH9EdOKvfta#UZ3dh@P=TAJpC(_wSE;unt_a z6lc?o0gXDb)C-s=aJh9;=7{#l8(Hfe#B$WDp#%!T@B(zAX$rmOiKdO-0W5Iv6?ERp zfae8f1x7ZKAt@ecy5a<>z(JCqL&*P$G^$`#nMKpU7_X}AuJO-l*Z#YOM&ida0Yf?x z>m-yXS8)Ef1erxo2tX4|4*X&YqFAp?JaDHjMXNv*eH+bB%r_JXl%P?r_iPRr;cis$ zfL5AtMVXoDV4s#6D`j9I@F}H?pKWFBb6Xj;E?3Q|h+=Q(@)pCMQIPyg-G%hQm*dQ+wDthMMpD|4c4F3h>vouXH3akqXB z#gA>W`-KtEfD5yeQD6}=GEHvCL%xI3%_6+uXn?MUsy}m)D>hk_Tidcu1Yv)b(8f$n z!6PBaRT8Z>L)xg~RUB!#y*iT?zWM5R;j2Mh;6C-gg?CcyB?49l0fFe9KYI;j+ch6? zgPwtZ0eCm)Y?vLzu6EO~s*bviot9sr)JrNW>&*x@nCm5~4?VQ&*4{nBPXBl{_u6Kroz)4`)iFtz2l3^qO#TJIpTpA)`} zgb+aUMd}&OSd%cHJ*a7P6I(V2-k1l zVOTufsks_MB!-+jXE+Cp)->D@2AOeG23#^Is;1<*paY6*es^Q+iZS?*hfG9H(}} z-?yMg=4YD-aE@fjc)$$GXcbP#8X}`qCUf=*l$8-I($6%y2W4WXDi#wY^-8mC(;9@? zAopB7Q6B6zYQLqr)TDdo7hs`VM4Ms<$~nMCjM*Xg_-n`%to%BG}tZ| z+40WTe)TBUtoE{O6Xd`*PD_b^LnBqayygK{pKZHoEUJx3p!>|&892d;AUhi=%jjg_qp>Y!x=+jk_2$+_q=vVBrQqlgekdd=K*SZHr92em7{nDl)=LF&i@2FbFKLd3S zSZnuhwdvo>A>}oZxE?**AHW|COw04o^2M!b{pu~qbA{W#qU&@BcU4hx^Pe`;2~@D0 z0uUovXt*FW?AiP*qt=SBjl~}=8Ua-v_!jOg5!t{8nbbB+M z8JRKZI)m?N$i%XZ~hpnkQt*RN_ z^z5@+vo}Kca?9V%YxAO(pee%Xfud}}%xu-IH=x@jx>ZKdQXfhGv!tlRbIb1sC z43o62BdZoc0@b8Tti{zu!%;Vh6ETs+HYa^qN)C5oJMp3p8nT96`%j$f@BU0`U*Gd` z)yfpDd$D{2F05H~sgrs>`ocf-+?}_)4tr)aHE??MA9h(*HkFz|9b>`ayQ6ou+?{Ia zSlG7O?z{}LiQ^p*L$p_!gQ;w^Yq&c;Gke`3s*P^;`>2g#XGa1o~O$P7Ng4e>OH!$N-olII?LbvC#rNa~5;+1%mCHqymq=z9!g zH%1UI#r#i+Foq+1pa4eITSqCe$kb*y?3b=?Msl&}LXX6q!v9R*;YiLA8#r{5eo?cdqy#_wA6BnEv0^Bn z6KAec*p_~A3+4My`#eY*=F!LpR3`5Sv=k|Rv2Ew?c+5S_w?%j8or7L0gn;P!J zhUtuP_|W9ZJ)>;)FF&7yp-ry{}q{j~Ur8C3fi}zZI80asCf7fh-sJ@n2n5ux>Zomm7p6ZXL^O z;F9OdJvQ(}A5-M^%UB=tR^$U_IdiC^7q!aNZV?*;e6?acews5offSpYwx}E{coRr3)rKHTd|LS@Y%DctB@7myYKYAlc#<%fZFSW z^Y&y;`$PJUD4Tcv;>R=HK3aeh<#?NOEqW*xV+!*6*Sw@#hGty4}T+w@rOx;U6(ZRL_HhU}=N%5ne ze+P}6Gjag@hP~vj{Cu5_&Dq~)e3lw{?w{Q!!sVzniXJ@0UsNr*C+8n zU?n^sE3{ItZ|7)|u@(E7kLGMC@&uxa!DWJWuxicmSYb*6M|g1JSny+gU3>b#)2K2Yjf#iCV;O;JpcaUe_lpq^W;H%)1jaI#dorkCJis+D=qcgR z@dH6v(5HY>o}ic~yc(RaKikt&NWVeGXr_dXgVl>w$bs-B*RYy+!X=9e|4fzC^1 z$hz6jh$EHcc?T$pVuV&H#gHUs$3+8*VU_|_!aNn>mWb12;K$CUUBJ|H6u<1t{Q(PcQ$6IItt^1S}(?+uc5-#6o-9|{-$zezCQD1!7XNvCcD;c&HH*LDn zq_^nqW6$>fhx90NtTGwm8}0dnSSf`)s_1}nG5K~!syY+gi9*xG--UN}CV>H1R!9S* z5;R($W$5ZOwZ0hGA5e&QQrtE@rwEDOIglfwLXL2%7VIT{$UU`gQpQuPr~8d6p0%ZO za8Ed!5$HjpwN6t7Y&2-nJ>Kiu7@b8mpdR*?hvwLGON<@$=P+$G_@bB}6;QM5HI4)D z&*qcGnHvx#)%1B~!mgkISL`}@BorsBY;=>QP~VuE7ztm8r!upxxLOCvxT-!pnF1 z6vvaJxXUVDiblU@+4$x{j)%SsGjfe&)|(F*8xw{0rVxOv#vk6lIU5`})5jakGoo^dyFZZwuE83FEJVz4xLNQ6`K&`}HJEuhBe| zj4?98@pX`gXAX%v_L_o@+zhbBF=wWVdA5>4Z^JPUvXt8X&NbLrIJ)VI{I7nl#CAPX ziC=@ea^<>olcryM)OCF4w*d_~N64jwlqLOGIans;KLh^T@wNU}&kFVXHh-@RHIxjk zIDs=Sxi;UdDr4wxo*@Z2NM&4&gZ)ILnOe&OaMz($?DKmHWqPmdqkmt@K9^M_x>oUU z3#D~88C7M)wjra&6?utn%T!ldhVBq+Dk9JCpn_~GO5&A3c#FDqj*q6{LG<$G90hSU z1geyoKte_xb*v>q>me8Yb4~8&_fx*s1n7HRtB+A;10gl59Ko*BKDrn(LK+qOas*>( zji*okomi9g4Xz4NAc;875z@gFzz=!G3ktUZZXk+Ft?X7{+65!iD-z~1!_=^(3}6i% zE2T>rO;@+}8kCT7ppYmQOa03;6i<`eM%R_h*4~mVB19L+;8wJ-6$#3SwjC>^j%SuB z*=8t_3fn8%w3C!udacLO>4a2fdZ4#3*p{@ngm+>BSRgyqwX=vav9KiT)7sS0a-@v4 zeWfH&IB_esQ0hz+>*{Vdql(G~yh%M89*y#{6)RO_0nXD%%u_om=7LnOOk$9viiwPJ zKcP__v>A!_rX?ZUiY>T?DyR(-Szi~nWQ8R5R~l-lU81%`=*3WTdmJsdD`~E z%$9sEtFn{@AK^5UnS)PMZgs!7YjtJ1yIn1IBHiJx=`WJ4AD@|ZQd=)u?S!$jI(z-? z9qwZN#mGJ7yKcSkhGmPB(cz@CcVWl1)+4&7<=N{(k4Coaq8EDHmj`<~FI${_a=m?T zs%!DkWsfb`V1M!PJGbc- z-kqA>+7h;2zO3`H!RRZBUKxBLauGxto2TU?_M+?Dygjp}BSO=u<4GL-wi?F-TFC8l z)Es_=yV;>|9>))= zM=Cl*QQPU;*8R$hJx;f?rza}it-~E(>RNrsv43KArvAre%io&3m}cyVR+12Vqz?P@ z3p$+{-IgWes|e>Y)vN{C#n~OM({WG2PIRCSMpIKeX5Q;$U;aan;dBXcuiF#tIEuPS zo%hWkXQg}JqSfvl7aVox-q7!;)X7w8(c&oG1Nq;1)}p!Yoi|waww~`lsUb69^)yer zZGOn=Nu|0{uGQnFhFqLHN$v&~eMU8rzac42^!OIH4@?*wC?E%gp`q&F#CebS_KT7M zQysZt9)dsab-3(&@((p=7<@J6Ked6b69-=R(IR}4qXEKXPU~niQl&Tou$!x=WpDnaPUxA8Ngp#|e+FqnQY{Frc`P@e=?IX54uC?Fnkbwh@AF^^w8Q05WmiQYLBAxN67I7&F?jK?XB8ArquSY>C=1`# zOtPh^HO%L*NY?Z3Bk~gf%X)Q?4TpNTwEtYCUjr*ki^A}m_utANJ7#rqKs=V*BZpXVpCr^g7 z*y+=Ij-Rc|H{Nnf{q#nDUVlByG1i|ASx2_1|E>qIZT&fU@~H@;C?87YXzM@z)}!Bl z@Zp&s|LW}7*AGAZ7)7pqcHj$#508%nk{Pexh`o33IK(O;7x_o%94_eBFf>ERA2LRG zZf|lOe|)fE@5?t%;C`&XVE#RiK*q2khxi1`8=h}|X~L~x4|BsED&!J@DNcmL@{PXy z;skF)ma)NqVZ(lc&$oZc5C6Vq#uj~<#!?=+1ir}fo6!4q9LM|(?Vq?4oA1Z|NTBV! zvJqVMP-|HgoeJgA=l?#bXLlcS1doq1Hn6-sb$`AacxV7&z|9Yj%@ce+76^TVn4jbI zvA_v?bRp(Be+@?PFyALh$WPdC7>&5#bPjfI?n7BziTr=;*Zlv7K>~=w>56=Y=~wXl z@Be0-V~XVkft#0yhH7W6NV&@HCr@&_f#%&)WA8(@@zmJicYZg-SpDf!kT@I$GQaP` zU!UH4>h!78bxB6{#dPKjpEYpicV|!c+_v{nCZp*`*J{EUt!GZ2Jay>I*&`nF@Vz#Z zC*OK&9ZO_6$2zVEJQH``@QqPG?hoMx`+aAef5iRTe2df>hY?8F`j{gQc*N-kZv)rV zxcljCVh|g$$XzSn-4Qa7`Lw4 z2fnseXEMHAnr-q;#)ix`x}5f~IsW=`fCMb}I3af#-{{LPPPwUJ4zpZk+w{1=lpp>e z3NxYZQfy8)%s;PVny+G7iCiWOj5rFty9&3f9MbjkA2_T|={n+@r_LMk{rhK;{ijml zJ|{O(ehvrcKV}@?{(;WADtvxgwh{Ik?vogs{7CL`Y5knW*g?)K(y_FD&ZE_kUp%K4 zd@S^wT;tM*u^#7eEJRBg87@G!w)*jTiTtDDM5xf~)BT6k&Bq>QHSIjx}gUn=(xq)B__>Ycgp+Zk~Z33V85?^q4&B z8W|-+dB8vszXvPt0Hhm@Yalt|Efu53v5Q=tSUa-ujT6)~I=UYo{tuMq5QuMhVN?an z-x8%Ix^9%X)(VA*Nn#Ay&`JkLq{}cE8fic|JIXXnc;VHMWndm6gf!DQgSv=!#t;ek zB$*YwLL-Q+eXvlb>1a`fe@MHK(iZ6wPDO_iJ!?*dd^^U2gOrzC>Vu%2?j@Hr9o6>|3Rb+7U{C264<2|u`qqACfkz& z;rclgo|UOK-gYOP z2{W?xs>C&u1S}J~Pi}v;8ofqi3t_3g#WZh6^Vev|TL!Mm2VlQrpudgt5&7H>oEinJ z(;jr8kT_T{)m(hM%XHFHxJtsfY6l$yHX%F|OA8pP{y&MDMnQGMLaj6L{M}?c{xgMq zgttnlXS880X;TzP-TJh>&iqr0COr}IhN!nv(4WqutToUJI2F_Z$lJCkf+RKO z^?h6u$kce>&@{E=(**w|>JI95%C$u|!03mwCp;r-B#W-MwF;GB=h+ym&l98+7Zy+!V)+C3y+ExFu6m0Xjc-nqSmcI528ur&vv zD|~x_DM*f<+pD3{(a0c)m@oln7=*C@F1>VDZ@gn^z&z=#*(Q z$7dugPttaxE$zoNnK+0HyT1U>IwO5mB*Ji-WL1$s`D;?-*`-(~yh8%a`LBqAlwl`c@L2-+TG-aZG&v zVvgB!ZD=6lc#lD~PPpMk2>XuLUxR}Vxj%za(7La-6yXG@Yd#9XY1RwG5zQgEF%SN6 zm5LaH8YGoj>95Mf?{INMZW1RD7g^T1)&|qW>Mj%Pk1wws`=@x zTLd_zb;?!2dh94LPD_jR7bI%}7Hg_F>0~pFi6vL%YVEt|FLW{=*x5&S(jCe}b^q&) zVRdX6-MhA&i0+^bZODe6OwmayALrOijfcXoPB~-`uZzE#zd82Ga&<9}~SirgfXOCVg^R;e1Q`)XWf)7!4;9ZW*-t;8rH zZyx#vp(f{FLz&>hQJhPM6=XGMxECSb2Q0jA(9{lJg`P`5Y-p-4yVq821Kp8f(ry8 zU5(0FD&d=$*n+lX&YPFsO4r2@qFE?lV`Z{`6~?ug9Z_nYaOUc;DF?Mv$`n<^Y*$+h zVa#ns?<9HqV-a$T*g9^iVzFFWZed+*7zA8Inc5Irjc`1i>@JwSBCTVTrruJY5l&!O zNyv(tZlGtu!W>N)Sg`33^{v97R3s^N8OW1)HRN>|p;l;g3hfOI4g(~9b%FdYU0&Ye4xn_&`e!k`02erH0o0~^>2M1O%s_9P4v zD7Aq?OMS5&ly=eDc4TQcZLvL*j5;9VK(R0QLwD4ri>zBy<=3T3?G1?%m0huR-}>9# zwgcFIYB9UEt5qcL_c?bafOX%``y_MEzvukD=bU@)_dd@#H2<1`Pc+?BU%zJ=>BEU> zhvusv%arpJ=R!HS*Mg^)KTJTWw#8n))T6Aux#Qp6*1itvXiLXr%yEA1 z_8t^C#Kl?F^mrXLO04n26 z-lwO3wze?(AjNUO@U-R5LiF9kaks(V9BYJTp3@QY+zyY{WE&E5RYzj>wpy?0QkmGh zver8uTO0j!+n(Y!FSe$2)tdG^b+oT(+R{EPmQ8)5?b6bj*kR`z^n(Qpq7D$h9@pjN zP8(F3QBw&49!wjO7C&vj z2zn8tSKAB+LM?^yOAs%FT~+Zaw+<4*HZY*&CWdEwk|TG;lm$$UpOq*XQV6gs?x@Ln zSE4Hi{gyzImyUQCMZk>Pg)7!|9BiT2W1=@DwlqBWhkMTjs>RO~%+#3ukr`4k%xpVH zo5sCn%gD6BQZ|nBkJ}Fp!-I2y(y{TE>MvT2N8W2_HZ5nAw3mrnup|33r11 zn>910>#-}d$VqI<$YoTbN0UTubuwWwA0|M=1i#R53E;SCi4k8O-Kd};W(y?!w1a#<3x~PU0{I?DRB(^RRUpXW3OJSQQ53ELpAJt(+-jduIB;- ziicWg&I4iicFwmJ4hi2hhnX_5Aq`)PV!L(yctY?-*KqAnsge%64cR*pz zFhhLnIV4`oG%^EU*30By)%DH@r^t9E`@GY`*Y{q3XXGSX zpnrP0{Iin5VBY?hv9)VA9XfM>`AZrnY*c7;;t)=~*tZWyb$|jJZ(LXP!x1#|IFwC3 z<%7e5>w(pK_5j;l9bk=&G#)#~*drq;dyb7x)S5XMFH{IYpBXID&X{6vw&b z+!-?ldt|H;KgK1;F-i9OaNuvkV6TJ&lLY2?zC34Op9`EV(COy#y`RQq2j3SUB+7=L zNL9>Mg?8ySKf!hon~WhEJ?n~T_+e)<_##a9YeYY3dS?GS zXE^0xyqww3JS^w^o6}tPXUr!8`KxH&4IvIK78mB{|i1MtE#hONKP} z@5d6H!~J8{eH#{Q*yA6m(q+)8vZ1ZIJh0_S;Gf88!OFxG#H#)?UhT09{>ZA1Aba- zT2vK-4CE)RiVk-3QKQo>Q%3`Avh8RH#Y8!enqvW^byT4BQO+e> z&6iDgi-t2;ZWs&Q8Nup9w>=xUF1+Hc*Qz-ZT6CVTW9)8o`sAcZ&mDc4Eb?i{Ujh}~ z;p_F$;fE}oP2+bHgvH+t%m)rOK;V{cJ9-$!=4J)3Z^7SmYg>hSx9vT_(seHYUa^fNfnQzd*9zVxCZ z00UjK_JBW@sZ7Dj6~HujTvwqF!Jm_26J(-ejf)^djo9&uv#@xF7?i>)A|lo%eSJ!5 zWLc6>Q$zgP22=s-zJx6-6~c&+R!nrd6vvxsZ3#(93Y+Dq;)sy5pUSq?=6u^^vqw^&l_|2xrGOmF?8z zZCZ9E*%7csYqCyQ&~Z|?P(9LBt}l*jyiGqsayG&#vimq2i>~%UyPRCnj%^BQSM-FH zX*ZNXg;4<)m*W^DaA)~|t@YT3=_eNfZGAZ0J@ehQtWv21P%nR#(*Q zC9ARi_rkslSo1Y5>OD7OqXC0r?*bk`{og{Yfb25XJa4lI%EkYaBWpDiE}80Ol7-j3$4Qnle6SNUeDMo!$}A!JwN zw*&4RN;0?2zAbpskg6mkd8_cbzk@ErY%P#J&VeP>sR-Z~*DBuyaYpRT1vgT~MA0az zGl%#ZT@a%aXSaXf5{s=hM6Xz+#X(6ALOYW`3fY>=ivya9*6>bbuZ-L45I2+Ls$7H( z5S5CC=Gxr6g=S!!QQQVcDHP4k5qKOhhG5a$XA!-5KCQP+DdDaV-iybH8)2OuccKu) z^`LY@xeUhxLqPK*EJL?rf zHe^tvD-n)1;r?lPp#qG$Ytn-7QO35qBD!uvT|Yf`GP;d&|A0XkiDHJiyd!)&qzx~| zEkxVd&PR&_7oq6V%E@{~glkZW^Dd;Lc+#DVVaxEiZ=uSBDb`%$Gux z8{iud_ai3sQd}LYkA$Ty>`sHhU$7f&Kq6^dG>yA>qxmjWUcdcc8 zT|%Yj<}59DHYfEAnXhf0Db&s#GrR3vOH#@;TY-xu1*VUf7A<0Di%4lryH?s;;g_GgF9O8!ypCB#+R{-=Yj44ATi~rJc$uxGJvhIjBjQ|_edJoZJyt($V6rYI z68FuFdjn0gaX$Rk*qYu$bxv_Xc84oB9?CwYw)V!ny)!mdl7hr(+%FPH*_Yr75`8Xf$0@8(%gY%Q*S7?|W!_mj8Tt#b}`)q06tRCln=^A6oK z-@6wLC!^{6y z{0iArU)R<&r{nb|I-HK8EMJ=@&bD{Yty?&^xBcZ}X6SSvxH~OgKcz!Q zQ{Rf$A9okpH&4kn^&~d5^<3-9YctqP>Clz!H%>kLdQWYWoWEn>W)I7uymY*h(1P^E z>jxyBd$Oa=!}Qc^Z|Z1oq83JgTh-~jYpj!j3Hynz=d$e7BQyK z&jMbAcN;-TPRv1)Eihv+B}|eULxJ7r^Rrt<*xz=O7AE`{?%M6lW<$pdWu^!UAT5eX zOqLQ0v3j8+T##+?z82vkpKxCaPlhgDAoBD=X~GvX)r;C;ev-61%={7|Rvz&|rmzZ@ zzE)f`+bV=|E2IDdzcLnFs`E+U=JJQDL4d?ym82>j2&}`y3{O~m$H0X@n)BBM6j&i& zp)AEdb>k6S)8Ocy08>#pgH+<giC z`&BtlIU4EIwRe%y6fsp5(zy&Zi-;~HY3QqUK`qlLCVSXOy%HqRUn;&ZL8|g&`*O+G zKOu=Kp}8-hRMllw!fZ_AhTg}><>ppoZxR&S95B5Lu2)eKh9PSuPHU+XxjMuSy-n?VJuRA(kd7beHCf*m0&9nA< zbX8+i`V{e_c9({;Uqxk#%zqorp@DH}10UA=}x%(F!|8$wgZoCnGkOITs z>9N;vw#*^uiT;Sg4jjlQfmObZy&?BArU}2-;RarL`gL}nedFvKoF7t#|Jl*^#>QUz z#V^=@>~}z8;N%)G${5su(MFbU{MpagJYVjSWw}0B?$PK#V=}0n;f-T-tZQAt>&$+M zRXnjO`^fI?lOVzyWE=E`0^WXjGehP)o^f90CbL{H2borrU#&3Fm+Q{+7r%XHw-lXpTBdO9a})_r%y zs-9089FO}vYgDtp5Bss_o_pbR`JI>FeS7S8jNczSmQS)=Bx8-i$U1v$46?nflRfqq zWA9)LjIsP9^YS0Y%Daefcp1;<@x~*E#|lQwG18^d*>}&JdF#D*&%QJA_UM7{d}lT9 ztPrNvdq&5;wa0s5?>x-5Jvfuw$URoaPcWtqe22^Ve$qS*Tk+_2)>XEqSX5M)C8erk zY!NSi9}9Gu?Fnhd9BoJqz~t9L-tTehyoWeFxIZR}J=kByTf{F0*vFCQd|-*@-XR@! zBHbuu(9e+0xp~iK-E7=su^0I@ieF!iazIBL&oa29;_~1z!MPwkG;;)NN#xgq1%YHw zye^^Ku<%0>X6Ig{7oE}U@IH`Hr!yDl^0>e*73VW9Ps#Wl+|8WE`>9~$|D-TyyvUaR zEvSY=E$NV9w1xwD$do#Fjx1yXMMcj5A}y~!#DW4UyxrWA1H}+qFQb@De5xsN4A!j%MUW<^ zX8FcRBNO1l?Hvw7O&euM+VPLeMWnG28pl6%bZD4#Ga~q6Xvq@99XhgT_$c^qI5Gk3 zc!#W+0E0qu=mR?mhoMX1Puo2>#Xw^%riulJQkvXOPcY_E2!%r=wdLa#6*W$h2>X1m zaMOu#FGJ|KQrZ=?QED`Y4Icz?C-KY`%Lv}BMPgMQ!XRQuk^_15ij_91(1`?@z-Hos zfi1i`B@BvjF)N4DM!7L$IRS)9v=Y{Y##=ferM1F(R;iRDg|w3K6j>;c$^(Sp)u}Y5 zkEN zVWIBf{cNKoT5zMLFy5c3aeY1gww~ItPg1r8{OkTwSt8#!<3Xk90TSNEzu9R;uRvbr5NLs@IqHcmN0bHtj( zcQp)t7yH27v&8Gdk&aT;X9ti^&rK2H@z+ z=tw*KteowHEUBYKelQ$?N-95K9#D~JXuyjZY4~@zbF@uCb})%-_o@g55(PgAnsa=-U$InY9V?M)(k;?0_i##G{SD> z2ta#WP>gq6T(W(FfJnl|_X&t|xvcsRZwz8g^POz3l2^5mzZmmRrVlR(ifAy8@zITM zC+H`j6b4^t$x%xA>{j^I(4r*d1=sCU?Sr>R-8*r!#Ix`Zb@21n+fuR?40mp#erb{X z6+nwgG50MWc+~`FN4bnT?ToaappI;4mhSeK;&Vs%c4XHP8e(zCdhHD%ssA{YL-WVl zP6;9I2-kbRLB89=b-zD>az1}?&+i8Xs&r57XD=R7bp5<`I`u0}x!ZdF_xGM5Ov@;x zkNO}TrghpFE`J8Bkm)XLM=}>s=vp?KE{<|hwR#Ty>7u)MKgOnerYyRcYPNzAg6EjIfQw(gsT_sduA`4539?)3$3&Q@`GJDym%HJ?{5+PTB$}XWdCbzUOs8_CA1k% z-FvY@E*NYR3{G1$^|+g>P;DkjT?+6z8qI396?H}Xb`o`2U9~DlO*@3fcU=wb#B{6O zr*_QDlT-z%do*=7$DK4X)7I7ow{d1;I~BL$V@7dm9z7S0XWNpTw2g9DThl@+n&I|L zbz98-0V@@DSyUn|?JlMI(hB8C<8&yMMn`WT%hoG9^_-mzUBVFsDrmJOl^3?$x>Y6e z+NKrgfqB}d_gDpBGTMUlBo)Z&vU*ffu>!WFZq-oZ#Fd_5daCiK#my-=K{HU%2XU0?N4FK*#Q= zH$ad(jHvU*B*82I$|FLx9#{qo-4AGRJUwiUh2 zt@E2^#$t4(_eJaW%}ZljVmq(9Co*$W*t^Ny=NoBze) z-h1~?eMHZ-ozm*kvOwC@7oF#n!Q@6XPr8L7Pon`q^pdN~jcC+a7wD-xg9TUxh# z^(*&nj(xANAv}Lotwzl}p>cblG+@Tl)kHX7bpixaN&WVA8yshi^Ueb|1n z-TCItyB+Vj#`a%&_3q}j_UM^w-2Shw_3D3hRiR$QHtfDC^EVUEw%1&_y#A`fh9`c! z(W$>~!;STKC9dr5`1YKRz0-bu?Z0+hd*zLC&c@6)Z~V&0jo)dyO*UQTw0~ja`l$J%#f$MKE>tv6nI1{+bwdYamB2mhV^eU96TuaWIp zT8BAtMdq-;BY?bvEjL}M-M73p*K>d$%Z%$u+3wAj`f{{JQf371Ji0cKi0FwQi$ z2ovnpt7V#yodT1IX;7PoC0buHBd@=(nJ_cJDY5Gr)^Wffom!#j=FB#YcnP4E_!LE* zF%70VCFWqEgc+=fY>Alc$!|;2l5NOMvXc!A>FpN2|60na{hle4)1o2>0;WK*W^KH1 zMh#HDnN~fLv6CnQim5n$GndXtD++ez@l*I&_>B`9;vAVuV?H^LIHrjWle<+VI?6gu z2xgaM_#_u1f;ApSa8*tc@ia48$i5D*ek*$LUKhil#Xc4=>k#hZBTG{n@GDkr&2>Vd zn@V_ESkx-&Ta5HIHb)H7aM~c`ije}$k>6wRsxPpo4os{&AbXD=AB%=NVAo=y>rpso zGj7byMo10ecsDXl!|jNKL8j)$35RCyDuMI=i|q3PU1JZfu)36Ek4458cVBXys)Sc* zSow#%J1OpWvh@P&P_hSpoP}pATtU*56_sx>0Z7(uX&@V}U})R4()3}xaXM(7L>U2G zBEMSD;0?g08XLj5CF3++Zi9J_dw0r;mG4KDMAZ_Qr+eP?Uw-+Khwv=wx#ymtd2a#6 zkj)QK$LPFcGY|MW(6|mXu=yIu4F>1~qkQM|F$26W(9LArvWoQum}YRDHxC%&YYY(r z2YHq86`V#>e)nybuo`;}x~LHAdE*7f7V-D`8?V3j_Shfs_q)?)fNV16^7iSnW&{#) zVS#xp&o>=~p7-X1%9YlW130JV-QLk*d{{k3Lqj-HW^CTEYWctZbC!@aGLHy*e80)KAp0>NrV@sU0?ZM4R^ziD^Kdali$c37!^?Ok zhq1q**g3b5m`qx_1Akm=;WmUg=i50grfOZPcqe0z0>5z#vXYjAJkC$oM6O)+eRk+0 zZ+&>!`NOTH)WfUG{{vEpA{-t)@umL)-uO*`gzuL0duPW+flofUAA2Y=R)6fdHx`ec z9DNd+&~GyS`1kvtyp!b=*<@X4HkpsHdzLKZE6XY}YG@F5jEk{foGuq@1G!<05R4n< zI{nVE*QtcvPklxkAAR)nI{+myvd+Hy-rE9Wi{XqAB_nFU(JyJgXHj13y3xK6D)OCk(&siaCxTDF-eZ{8z^gm1R zMXjZH#KOG%MUiH#5B()haN{-A$TM25-mTyt|0{*r6;HGb9uE>r`XE zMx%r6c+cLM2A`8W(a+*Dj(jnfM;1=Y(m;;U4fcD4JfqQZcH|0Urdl%nHr70jbs~i5 zpjxycKZP>Jouc0wUtA_|xI~)-9%`^M#QG{`An!=iH7^}xsx~Nh+m?P4F4KJWjiyw; zHtrM|3>5N^{ic4&B|)<9y9yfa5>}e%6sgcd{nJC5gg?DR!y~8oW!%TcWP_n+PaO{( zpA>S1OE3A*rk+WQY!zzuLr}7&=U-*H#7VxzTGTZb?m2~g=wMr+myp*IoN2olFyYA| zi^@Yow>?nzQ2zthchZrNKIJ1b9NNq^R*oME*8qb#sfS2&Q2`mCHZ&MoLL)wIGk%bY zq)^x&@+bIESf&vB6X_b<4(!!+^(nd@@AN01K9%;3QlLN>4|SHzdY1SUOnmjiDYEqhxhb(GynTJxM|(I5{3t!h ze5Adso|S~?jVXKbgL3k<$d<1_B|3x%Tt?X??Lr(vQ%h}Ka;3^TE1}mklm`8_sNFrk zQ!E#mN!O?ohz`Z3WltBVtv}pDudmYde@~2LV#@(>h5h9Yy1|?M^)Ypv=p-$~c^h$< zZV_3cNQF!(q{UCy&ZcAtQ>>2so{Mv|2kkzBal|#KP;lprqf=hnEgnXf#~{dMu=%Nb zQ89EZ7TV&jF3@d>HM+J2>SvJTig)74lEzp20i@l8jmffF3|@pZR^$j1 zW8K0>nd)>UBc(0nwr8R-HFgJ@2y&9{q$cQUQ}2og6!lGS1ty7h(X*q2hz9I(0H2m9 ziaF;04C5&s?pA!{m89F(Pl0UUowx06I2BRWkY0=Z63FtStqF7xabm0WimwzMy^Z?* zOvh+qG}8Fdyda2Ps^lxcB9Bb-oMDCXZR_gXPRJLTRtVErl^$D^$73R2P=jB=662w5 znNoz>vNe{AB>?sx_~^Ptw|f(^bbZF!x|ZD4xq_vZ(_aC%g>;Q@YjTH##tG1uC|~F+ zNdH-(({l{>;e|(WjQiD&^tZy!W%;hTJ#)MAo%o*ImFtSTX$!Zz6Au=W=&&<$ zKq@RerS8SrOg1{Y*|yO03$&tH*j-cj15rNS>;TWG-J0sc4g#xk*k7mEC1;pVo@12nB}>fyOfPxQL6b{)Nc>RLB4aI@>xUso)3bPU|L z<$7=LUia4A;aG>cYvj?ek}Q_3icbmmaR2 z<`%Q}C+xk4+AnfqUb}nQ-#Ybr!Pfh}(ZLeAS59tfTvH1a#d~V|!h4;s4P5@k?DscZ z*S_#d=ZA@=x~V^mEe+Sj4qbY1+L}_Tc6s!^;#1*N_|}eFW7t9v0`4q?HurwYY^wWW zEjmE`H=@z{IxHE{7M_u^V@q%J?Ix@Xu4rFyycOP12zJ{#=47Lr@YHI%qC>W{daOhl z$3`d{4?3Q=X<$>-6U9ycx#IApLF8y_2)i&DUnz zzdC>A@s+J>z55Sc6OT^uX#N6Ecv5$ab~F_!;Wc)8Yns}uZAS|6LjzQT%wjg-ZJQeF zNYR=pC|x$TV{g8#wY{myU1_74*T(2@N9@veYF$3&tw}ic=ANbwfs?kiy}u{ca2T4l z*^apMqPyD;)p-+I*ETivdc6&vI|{9Dl53m1ri643p-DTW%WyL~gy|W$2#HIT(7UT7 zjRivhD5AWg7!i~(TuT+$c^irRY?!m$f526XJRaFBp%_(jB(jjM)L1)fEQpz#EJu4_)6iiT z5kie)3Wc!|!c|2zl+ZG0Y0h0&$^{?1Gjfsmk119ysDw9RwQhXz0IHbpGtTQLyeKwg zkMrWeYDiT~BgRu1suJvNpD=KZo)2tLnBpweh*&^2gdUfPGi***kCF z6+<6+@H!#(efGb;G&cG-f7JTXM+a#BoNri_V{=~qv`ioDK@-F%ER{@#ODE6%w=sor?> zM|c0|ZpJZv|IuwI+iN3q_T3SDQoEorDh{LbT*2tf87z#)<+Esc{ssh`4|pKUIWj(2 z{TVsN)?NzCY=HOe4{$`r4UL>6;uu**2{}jns%cyj=uoq6w9%nv{b>9ya3hR$rcLG2t2iNtF&T54qFNc?jhvqGtE6j~Di>2f)XU(LsE^^Tl>L0Zs{P>u z*X}!X=jrCvUw-->i``JK-FNI*Unh^A5i_n>qnce~f8=q- zvX6|}vrlE*K|UDRB>YITKTdP{9i$x5?-}bK`)l6s;GI`b<0Sg`UVm>j&_!DN$f!?$ zefEt}jF&T~&%QTS{`$`~?Z>Dc_0Q~od-Uv?N4LH4YN5a~nVRkf7CH92av3GY>|Je# z^Ub@>nKF}SZg~V)UE`GR#O!6#Zl(uxjNRT%QKNf3Y3@HAWA{aRq?JwLPtY7*sAW0B z#>+9EG4^=b(mFmPW@>6*fw4a;*&k)IaXJYXE6+wN8epBN&ttzuxW%vQcRMg?E?y&H zhGtF-|PEA9a?Q@JaNMHcnqGgXj;iM$zIMjFg7?IRn5& ziRGNW^&)8wCrrl7Z#%WaY)*mCpHd*t2<$O!V+wD1wx1s~vi-NfBmpzEEDm(9u}@;2 z!=fzC8RC!5nroe1JXC)?ylD=Oi@ zDmj1m*&)M6z%bcO>w^6mX~h=vNJ&B$+@w<}kM(qbow|MnGaV9+scR;bH}PNWSKy~M z-Oo>QDMcl|Z@B*C;+LN#EJq;m(ro)_)j6qe(lGWzq^CniL(kW|G(7$2^izHI$>TI> z5)QCvPOJV<=*W_nsQGBkkf7H>^imC7AJUVkKSX!fgwtUFP*4bxAd^Bvc)tu!m@tyM zSYg3|?kbNy?*kz`YE$Ud&`G~0G|@WgA05$HYWTD${Ze|;)k7mg*pF;_s5vxL7SQh= z3<2W=rsId2hgF&3NAhudE#L1KcW4s*L!mx!*h3fhVM|IXPkQrM=oG{qak??0X^j$$ z{!L2bWZQ%cP|o#K9^I*q^{sSyBiq zi(0HZAko-|HnK5Ag2PVWOSBXumBL~U%i}N>vQ7wnr;|`V()d=4u}d~~4ePWt6ps^5 z9vrHKDKvqs6pD!S`4z@$a4qd8A#{f#Sq=%5&MqlwNt-k^hVb1GTz^7pF6QAIRV?dA zF(oXI%<=1S*34~KC`M@hE&a~A2Y1J5uOZ`Qm z4J|U$g)(pWkmWZ2E1)Vhv8!ZjvEq)JrO92I*5e%^%zMQzj%6ooCn_$A(SzkU6>qql z^LRhmG+j}7(KWHxmr%(6#xhFW6dNqX7TZUg`cKuMQ~7gQ z<7ZSnL&Bd7{c$wow{WAy@h0e)*Sq3k^o0;s7yJelgAVp_B00Hx6DDZ^zs6&W&=dE0 zxq~0k)O@j(mEDvILAP$e*6n2Ny!tnaI*;C#&?WTUnIG!151gR(otH(d2Xad(vU*lt z)Bv-(b#~-8Au-E`{R0R+5&LVZh;Tlk=|PG*4GfKUQ7sha8ke?Ej@A;6Rn5yC4Vs*s zt-6v(1^9d`*lY#6W!@f&o=Axsgh+DVZP&Xz{{h*sUzpl(TksUg&H0ZP@Wn`CFSkzA5FZnM zq9B5YXA;peB#uE!H^Uyg{?v&WmC2n~w&Sy3gO3=sXz;NVEx8?HIy%z+hi7zO;ahbZ zpO>{PU)k$FLv%bu8M_A}oCLx4Ujf^$QS<*rlcjCy9sGZYGI*%<991OI(9_Fwr3}%3 z9=Vz<8J@9h&}PLCWxwYG$0Ms_(vYS>K5zRJr8d@B-4BG0 z=`WJn+z>&bYyP}mK67bm=(5OoLxj$?Nfub1kRRPJP`)UZ&(4(MK+ zBWlt1X}U(&K(6s_nxIp5C+3^bt_)tJaHBHP8?dR3+>5>Gcy~x#Ypw6RW0Y2?8t){; zaw)9Dio%hNYd(9iw@Ax5vS(X%Fu6(;C+W=d7(1?`GgcDjN0c}8OdRjBXq;q>;vtni zdOO+#GyP(W|MloW$pYaMRFn7k?SkSrcdH|jI{Ne??S+Zn&h>Pb_t&@4-|dWK!kAxg z{V}!fo?BEv(geW zmb6oEadXXfKG&i&_K8-MPS3Hs9Mw$roKCx0+BjRO7L&e9P=_W`bNiyo=DyfTjaE9| z)o5=MeL!fM*W^~Lg~qmrxAU~TRym!0N+`W`?zP=Jlx1PgSHeV>HcYn@PZD=MMr5*$EPmaeU(@L zgJR;|4!~30jqTw9yEvu3w6>#u!ECay+i=E-gloOSCHKoSYONR!IEqr8Ra-~B4j#BX zZh$@FiP3|Drgu%fU&bgJf?D-8?X9Aty-vDwWnsc-s)e;(bsPZTHfkSOQ-@Pj@NSuf z6lI&Wa%y{r19{2bmD%>M#hh5(;a+U8)IQbv=Z?9FDfZW9to7Dxv$id0dZN$!;l0kB zg@@yXwsUC8{zGTn#I(b-dExE_$F-EPxh?a> z|FFN-aqF6^+FPC2=Gfl4!xKIC()dp{H9fZ3>78~R6y;x}!aWUjcC5wOMhoiBd>5Jm zhrIe&tK+r*vDay_+i`~S!KuaB3%sVbg?P7!d!@ESi|58eQng2#%D`GX(6V6l1qr{&d{`ioSe6b3$Oh+uoZZMR?@DS>qH zIuP+V27<6;W2eH8lK^p70NIlBx`2X#1NL*3z91a>)y5rMk%X;nq^yvy$)w`1>)^+j z;bi9K+);Z@J177qSFR8UbB-N>=Tcj<(}YWyF)0-cE+TMT%P_~_5cuvo4gPh@x$SIp zaEV2&jW3OEXEW8)02VYB{FkGR@a6oPT)2<3x9mtzAya-%83Uq9G0I^IRDm5zRQp^KCI~=ECVBTp9-~d_Qb_wT0z~ahibf3%(y4{@@A*tnt-& z=mUD(I&L}s=Ye)|RZBV0Se`d;-o(*kfB3`Kf4<u1ty;vGjHBIBd;DfU4HdI zfRCIVts;($Iqm^fu}8)v_v~S*Mc&Wx81|ckCTQgv?C{7TH1^ix@BY<$P(pp1-ieOt zM@x^-8+&!c$HCmdV^{|4Sb?u+-*^=pe!VjG$_MUQ_urkt!kC@Y0_+YLqrvciDH>c6 z{*2$TKVx^7089LEfFCl3_4PP71{lt>%6Ae)y|_IE_M;bHT` zmGsZESK5SfBg$qlMwAmWRY7@?zQG=WI~o&sWPn+YcaL#PZ3 zyRY&?xtF0WF8sj{^)@^lZtQTwevMgs3(2{I@T{zrz#1V~VDL!f#d40O{P1UUoM303 z_m#KKV3=Gl{J5+iL=PW06MMAuoz*Y+XJV@leEsKN`mbA`;yn>{>5)gqtb%TC9wB;n zl!k}zF1(9A$zzP=fmtFrIJt$#9*vD+_r=k%GdQ~`kZug{`ZKQwJ1sIgAM|zr@@7;7 zNIl!DK5U*FE6lxb-$dYqoZhS0L-L)GyC;slefABd%B9icyl=q^TMLD2kDaD(&6|B1 zUl+#SdV3UT=7G|g{eS(}BZV^_kH@OyGD|s+j;>zKc)t%!v!L13AJin|7;JI!%sY+z zsC620IMR!A)Yfy%p|AD$4gbt)gCu1`#Pphh`2y_6@zpu{%)nbG+y2SBXv)Jn@RPjO?lScX|TrB z(1rP6$9t2n`(nU;;Wack=!fWJ==$URFZrh)EH}UOLWqWz4Eb0d)##AlKlt>L=2LeJ zQD{w*+yAUOxK}dJvg-Fq)%lZO#$gi zJl!V^qZBmhTPH&yZ9g9hi6gI#407d%EMKHqeCmd@xziUm2wYB2xGySfCEbuHITC09 z*?wG>fan1J=@wC6VrgL|aIZ?5_gjhkzTj1Br_6_4TT)13eFSMfE0lLMmZFXoN6B%g zr0T=FrKKP_i7z50Tl8qcJ1{J+ka_eCmeA4Y={;C;DTx>%bTJ%ygYJfn4FR6m+7c*O z*mgBa#mnLlKBkjYZb(zu#uSN)c~U72)U&5SD(#a(64+qNY|o<+Lun`i!EjV(o+yk^ zmbmOhwz5ZY+kF6S_@0k7Ph(Khls{K=osCNw6;$sii+^?Vhd@^h#S@Qy_U z43jp9+b$v%(SVDx%rBBz&c~JfC_&W+SMN>*72Wtj#l_Qg$V$qavB;b|i%D zYbBPyD_+oE64*ypiLPV65F z`1AEXm80Yrn?BbJ_i-v}aVOZYkK)N8$Y15Lq%KkWk!I}dTB9{r$Vc0sk`}iis2*`Z zlOPYN1t4d4mx5N)k#G+;DovVIuc^!oLB>9CXNBGYxkljw_npdaoL6AFGWh%PW5646 zv(^%gHbDM}s&DH-{e;!uFM8=Bd})yN1CZ;ZQ(qEhQ$M^Ud_Pr#{Ud8?jGQ9@^is&_ zHF8V^{L;6!m{7)JC;>#tpL?QKo>nP8BLZG({->_M;`dtQx4Hv6Knn)k1_@ zVzs-kZnl;{ziPowj2tLsJIEu9?U8UlJGqYTx)H*n-Xg6DYV}R=Q%XRT4YFEsOQW~O zg(89Vz0-pmHA`CUr)!LQ>e}Y;u zY=vsEWUVAITgW=68%1_kB;=1tJV-L9OC$sd*B(KpuADVo@+s3n+|30(B7igsyrWC| zI^+y^{W~NToQJuh74oVU$S?Zn!?)39q{l_h;C{vjZ&L^Ne~P@VEwo<3JJ;vZXpP2n z8mmQjqzNIkFOY+%Y{mO5ArdO1EILAs>gi`@k&aUPi@F2AqNb-24qA5{mn?pRaBJes zaD%Z9jDHN`liGDk@Q+S!Qso+xo>N9?d|=h(pIR39d%Mzb+cY2s$jXF@3hl=_;F$CX z&qLflTxUlGC25?q4bR>zDqj)(fWoHcMz4`4T(WuqbD;TrxGWU>Et(0ba-vf zVG3v1(?K;YZ|HUm7n?SP9zZX$lid$U_+>#yO?RROlLje_i(m zc9V^Bb~vnuRQqqYH?g_#J5ve2(1d zMbv#)iWIs%ww1@!pvjsLxx(5<^k842@v__Qx4+OYIl7?`UvWeYT3A6XTF9u?*o*@` zQXT2WVtj6HWl}X$TWcS3?_^wJnd~CU7y2y7FRpYv)z{qY%6N}R6}l{$pF>t^S(_}j z3#B>}$`8HYO(cY!G*Zn8p}@G+w#poK9!xD+m)~y`|O!bR@~Y~ ztER?P0sgtxy`8elE$oprvzXAT5z>=$MYOOjy*o)UKA3w=SIk<|-PG>3wzs5`+j^Qv z-YdEj(zaK2?M`>@mRj#vri#Vp8Es45m|d&8EVV$}J;i348PCNbMz%wv<}F%cL5P;t zmgWW_Dz-^1K`?Es&yey4+%EuN>!!$5Y~olXH@im>-RE2f2(p%H9XB#%Z@XMD;NE(v zyX(s6b@biD6CK`Tj`P%&H<8@4n-Vh}FBN^PjuIKyoqDy7d0(KE_XXXa_+n38VYjzt zVDr=zzM9dcKg<>{y`OrX`eJd`6zqL_m%O2hwZ^5I=xySojeQE=_3+TK1Cu38g;#DGYMRx8?S{yxGPhm`C zRh&t~l69xz2oz^-fqG+B>?hJ`+vKX&cG~7Psd#Jq1nOyWfE_v7K0aZ`y$7i;u2Wb( zxUu*xXy2Ih+O|Q_Gb`v|>Mz`xR4?&u=P>UViKbnFCZBYbZoCXqX#S>&vgfhi6y2Y^ zolvcZyz9Q)yTCcz-k|cmZg=YD?i=%mvvZua69zVIo|)R;;S{g<^xTfemdS-Z(S>XF zu5qu5+1|k>*>OwZC$XLh)4XktC!K{oE+yQ9p4Y2I%l}!J^?KJfyVJ%MkUR!Mau;VR|*(RqhyU;yMGe@a($XiICaq-0R>Ht8Z#{{G*R*WJ{68JGL zhk3z}!u$}}_^SD$c&u9(QdluZ;oy;vyAP}pBMkOt{0K#bUC)BGdp}YHKhoFHE+kxV z9ZO+L!9#c$V1C9|U$ROjdbpCH5z+d1&(Z2{=40qHoH4?tMt)nUm8rh~$gs*$;} zjKG;1@S|OV8Oe|}1AY!a!-#(pe{+_z7k<>P3_lmpkTLjCdI4#6aZ?~}fUgR6SezC| zLP)ZSjMghgXJms_yl)(~|`zG`!q*k%f4nX7TW|H3s!+zLsU5^gpPAy@`BiJg=9 zF$FhpJeVdH2Le-MGVQ>vgOC)*^X-rZj;zt290>;88JU1SLl>v-N?s31qyzu)-y&uN zZ25V^1JD-z%XzbCk zFZ~y^T~9wg@7AYYzpy2b_^*7g@H@;Euos8=ZFGTD^41j4SUM*TnfI~1`h#CJu8GGy2&?>XwhS;*tbT}bQ6uxn_#=Ld zGcxALKen5C!(JusfmLEW(Z~e?s}m`VvsQ&Py2pPUCM4sIfj{$9<5Y0U``!drS@j#o zGAn7ZETfTU%p-pF2i(tKfSeEP{HtPuCVs__Kyddrvoi&67^paZLoBqR0{I6In7 z<2?D(kZ^og0~0hTB4ifN9>ecF?zfQWeG{^g?}E3oUjcNlu_FQeUwZ@C;#o{TEc5t_ zyB~d_zTU`60x>-M#w%lQd<-c38*jcf_S&P{PM2AXp+Lv<$jI9m-Dlsy2zl?!em*bi zEZk#nkG(ba)`8NkPn|B8^jnWV`6lC!*ooE1TvnT+wrYVn*uogy(Tb~ieqySlj?QY}xg>73s^##<$jcWi$8PCOem zufqp8XcEIjAX}7~+{-CRg+uvu(?rX}n>`mJ|IjNM8O=6-=*!2_`ET;+zUL z*bX^Lj^F%ZU?vf-1@6?+AfEN?DHBfX0ynLw@U0sR{Fhec9fNbNWmW#M5+CPf8$MZ) zm!uc_OgU4vp#Za7_mBxsy%<8ac*gY)1@3gE-2LMXalYlJe*a5p8W|a(NhhDb<0uV< zhKBShdQdM44W77T7z?Q*L*(Ye6Z}}z0B`#CitK9hy3(IaI2&J?CuAr ze=<#d@bQPrC?a&b5ihi8Ne%fv;te&^65yKU5O#Ge`ypW||ENzRYG@*~uW9JtMkkdO z_+F#D4wuRDj|`0*Em8lZP&3vh{wX)uKQeTDusIYO8F{lzN76$m&gN+A_OhqRKU`^ffy1NjosAXsDd0spj>?L!nV9|Ct& z5oD+=7FA3rh3a9kf*s4LL{yR`5}5OBw^Srcz%8Rf!yi@QPpWxemR#o7Nyi3XZ3>g2 zgm9LPhl$jXIgttgfRvqf$#vnDSlo0H&{5R9BuFA@jYW#>#<43F(&NlE05A>_VU!nd z*@D0&`Y6e3mp>uz0f2`MM^c1IrhU_wZqNGl%1N!Ja;Y9k{9WHip-bqAk2SA*W(%;q zk3}-p6R3ZWg@gbaT9k=sK%zCY9*@8c6jR=e-I|Ki>o@w57_GRYH9J(oiHyH|aLV-C z;&j~`%M;crqA!$7-qW{{pv52iN=*S3SggI8?R?(s7ZtZpX8IRt5cyBLZTXxCFiZ+* zS`GhoF92`bj#bwpKBtA~Cp7VTE7B@<6UKw9>(|%-q z;x=)69&6ai0>D08fC6VYv^}lF1#c z_Xp8*p?-rs0#j1$)(D#D4z+VogWpbUR)}|}j@W61d_rBe`XnNTrnPmF)_*KItU@QQ zpR`grOGw{&S>u$K{oT#q-y^ZO!4|Z~UP)aFRV@L4aUq>W zi_|dA?Rd~{v^6;q$D+lwOH3n$*S<(5avM3oL{pTOEbEapFH(@+9P#mP1lX}{`YSlE zT%|G2=uW(E=$<0|nI(&IouUa5+eW{nn=lxpPa?CtDS~$Z>$as(JX8n(Eae>0mQM8y zibe{hMWoiY6kS2_EhGz}Yx=u!-X(kNLD@^s*gjW?8FP zcYUaNXRP7>ZSVV|<0$Stztz(->KV7>l05c~&Dd8OPl)UjTubQr#@ex7Nhpip3>g!W zIIQ7@AIUmAXWx)Gc}~u7C0W4O5iocSC;W`xz(S7oab(D4b53G-12Vx$$U%1ZF8q<) z6Lx;w<#K_&?B4B5*!6wB-93_QECM9EWHRaFXbahqrx2wCpW_i~=RQ-Wy zYl>_^WLzozf8P4kA>I&g;2 zzOF2b2VMGv4Vx!yh|k2k#&8nwOeX=`HkS5LLhIw4A8TwN$iPO;w=m7+DgIF`#6Q=S!;iU=Cdc`jeMWX^|qtG z{WW*}giYlO4rkHnBp@T81-8dNT&lwQ{Ri|jj%k$IdT$ zT#r>_=oe<+gPB8Bi_Z6G59Lxxk7x_&@44}Fp4CLT<#JytZD@yWDn36(*Td#WhD;-l zbf%5J9RU~pkEkL7UEIsY!4h7qK{n}_w6cvH;^p;IDMcMl`JX5K?^Q1Qtb?3HaCM|U+uSa3|-kTS_wmmR$HT8{(Nqm&e86F)Uv?oaP zBs&QU;!>~~4o{|XDp?&>)rsz0{|G+5qk2*z*;T^`IFjlfb-KqhR$qRd)ou0W+<`6Y z6iwlt>Jl_N~OdVcz~tl$FK(c zf+RI6m7DBJ>I=y)sd`D(uXjJ`Z3o{YdF}T0$Edv{IlZIe94)nbjeDGI{oYF9*6nhg zJGh;W?MT&E#og2e4Z6(RdbIk~QJKBv%5tSzl*z%(1*a%4JG>F*f~`B^sYlzzhlZ{$ z%FI2DU46UbxmA~csN>NxWxgDzI~8qjr^NP#!ar5GssG7FhwDD(ioMCb4}9gz z$&SOdBaN%qTz~JMc$?~`R{0n`ayt#~b&~hrdJXylz%s-wTprHa#?DsJ0Uk<|z0-Ly z>tfF>HZkm^9Dh?e72|Dn6l|l8OgnDvxVI@eg`KgtmUcU6o=0ulD`YEK>wLU*qUT8W_Od*zJWzrc^Ba zMG@bc{7iP;0lX(I?EWdI^iprZ={-`(!ra^E4oa+cmjmhIYfU3P`!#3V`l&2l#Av4% zGkDpdP{?d6;tMR>G9LEJR;!FWs_b-UPr;ShqI8N_*O`Gua^R(1gGx#yj$EbxEbS6PcxEf(w;Q%uDRWV3`$ywL{39qXV?fZr0 ze{%-ul|NI;Fb8G9@J3^pIk0Sh#KLq(GfSga@?(u{h+~*EC0vAT(}i*^fl~MK^2mP7 z$nxNNnq3Q>0q4Y#OK^-oH9%Mg5djB1en2L0Sb-Ml(Bt^7A#`C1Rcr@5Oq>%xfv*N( zm=-+$<7mG$<$F*rJRbbr2CKa}4k@!jvCsHF2teIMKV65!S|~uZm%&6lz8)aDH{;7U zWN99mpqdY4C)ha6NFT`NhYh^GGHzk&ih%`LIW6Xk3j1q8lu$xx?ED6XKqh=`0bFF)>SpT?mX_GEI+2Q_peZXyfyD`{x;`!&_AHFYr;xOD01fBV(O3;XsRIsFQ@5C*;U()X(0 z|NhTQuepys_Kk1wy0aIWKTqLT;?-v_H2=Eq=lwrE!aHlciZxtEs(*X>mDAWk_@``l zeBtxI_{8a7V7Crl`S^D~?KpDN{rCIb3BLrqfY`>!wz7=gr$9&#)Q7UU){BZHVEIzD(2LDc%Vs#Y=8@Mv!j>p{Xl_j*+v{5P$n(}E z?)CSIzRgb;u9LKY4eW>bb@`1vu<`l%P!h{Zs^G_dwi)_%!+c$KVdE8#PCHIee|QSE%JWX{LNGBsD#a#eoVR3Ct*Q+oOhAIAFPmH{n;-*!TwkN z#VhYUF@=4x(avEn#OEeoJN>=Wr(bBgKmX|{)d`ouFG!#M-=9DI3#|IZyVc+O-f8So z|KrntefnoF>^uD$(!pep_p@I){kKP}7vcJSw90<}7k=U3XJ7q)|LLc*f8+48ibr2- zHhm;8hb80t{6q49F56b$4|pA8!dlj!#QMO5wS4`hY5pE#=lM;OcHEbzAFuz<7atq7VHBZ z*y!?bF@89?m&bY3bzqCc&K%_Q@H$8izwEoz{a*$16>Zti@jU~xYlHA}rvh8zC3pL7 z{t~urBHbmS%`sg6I2UfkUoy^eRL^x^m}Gg~!FMASQD~E-J%KIJ1nye1*H4e{7V^oV z0dt4X&xQ3M{T~v(ynB3oRpDDfe?p@cQnx5~94{)*<_z|xwmP4k!TP}Gmc>S4g2dD) zHhM?Xp8|dD$M)J8So>lpFKI4m!U}eBCWe)au~gd(-jI&9**dk%oLsh+E^gAOhPhDN z6mzULdI95jb6IQ_28C1j0^}v?L^D%&gxSai=1eh=F80(jqbtm zWQ;DE9c^Oa(6SfLYZ6L9PJ3Allf76Qt`fYfd};=-h?irr(Uae7;c%9#1nCKFVZxwO zYAh~spDabn7I?G9it)_S@FXSKtwhqchZUwDal2&jfEQnA>B4JP0KRT>A`;!0(&GKi zWH%4|hyca;DJsr}qy70RCbZf}%wR3t8VE(C6uN!PfNg^*1){44N6Z-<*fwn?b=uO7 zQ4psz7)TGB2d*TVL=t-v*?Tk%*Nv@f+E^*A9Iap=#k>WbuOx$v7AfRI9q<@eBbPSX zH7cet+9)p4r==|q+%kURYD>*NXxb?sqq21y%EfgPoCmf?&c(B24ker(Z_;Ezi=YgmFZs zEu$?{rR}hj2%|~-#s2b#F!L3!)XUF6^oti;A0HgO_NE8-$gySulh;?2OjMEIz+McS zrI?}0GZ6csJsssomtZBsl`E`=t_BWEuZX|Ub?~W&$aRWowa@v6$*eBSyoMN`EBQcAbNLuQz8#AbFKpi@C%h*wt z@GzxJi6*Aj)sOcO?j5P)1|>{Sii);)5lGM)hfCda8|~C3OEe`&vK zWLBV{+d3R9YoYQal+f63HU7J9q=9*e4DjmAAx9@~)C98AxYEWAPqNck zH4#VS3D!4~qL>sTNTDUHh&JtaFn2PzrqUC9ec(|KDXV7DxUQQRI_&O&o3#bhXQ+;2 zQDU96usYYFiCSncC~8b$%W=pYb@JBI6;J{zsGz^SdW(*YlXS|ci_rG(iLxSfoO;rR zhMf=OMvOF050*gpXNHA7pkV9KwmG(3AK2@4-Yv*$T1MD7opa>P`6`TXw~-lq-_u$f ze|{&)0lMxEgO;7{xo!{jb)k8w3GBdtvdfm9%LqQ!4ui)rZRETwfyvGu`oB#CMIAP_ zZMZ6GiJM=2uc5L{W`tX(MIZb2g;l&;O_fvMCqla$c=-+}zKr_*GYr~DC;oD2jSN`B zu#@3dFSES%JnboCbpQ8NeM1cIwWFNvF)GYnf_97*IvROS#@Ah{ZP%Tp_P_{;v+c2XLb zOcgH-p_v1Nq=hy*B3AX}y9_QL4dc8GE%Oe6pHriF$+wsC_Gmx8hG$tLX&5oGX$xPR zw8^q2^~9C~mbNT2rFgQPo=mE|)i+L~!}bWwf_OqUJgKlI-`+@BTu_tFJsIKjI9>QG zYn6Jsv>qozS5~d0-96%N&N}ncS4U? zG-B{&*OeAbq$8;=jK8)m#-NZba>8~oMs~yOGOQG-P8$Qy1WqV}q5?=r;cVb~Kn(El zDz2)Lyv5yd)NNc@f&G~1OPW5=QFgIoSff%aW7VUc!Z&^2bL^P(YC{cZw_VZ(SS%`d zpL0Wv8ecw48#-zoe@K<`lcmR>P|IspGG5!|H9BhE`tqUD;1#K-yqi{;gSC!NUt4a# zxFL_MD!a*y?hut7@!s0zqq{DcGBudbHaxNYn#1XGYNvP1tH*b__a3c2erV`{lI1kq zy1jx9?wXeC-GtftrK8C&ep?M52b3TPX$j-Xu5-njZfd1++8V_8kMJR zU0#r%yzkmiuA|0h8gx^Kaqs=p_t)ENk5RmiCLoawh+u^xHWGKQa%rH3Pj?W`471QJ z+7-8=o%RlkSE6y_ma^`e-XvxQMO;+Id05(p+!{?gMMbjY{8biTJ6G84IpxCm0rOmr zdb92t7+T~*=tqnTbI37Be>!t?cR`V}b%-*n8)opBlP=lb^fOs}ZosKvz4XeG+ps1| z@^_2$M65SARjIz~i%vbOp~GXC5e+1k%6Q##ox(9plPK-F3TDkOr0t^J+e5vRrdK)8 zz%Dujjp#PaQk)I$cxBt}qW#iTb$f~5Fv)lx>^E$O%L6_ju@p~w6+0-r+PgL1hs@Yb#ZaAp@ z5(2G$M>;2T@EuKk%M$^gAGqLB0K?b4aK#-NjrtpKN-V zZiCOJ2~DK<<`VK14hnIsk6|WL2D{Q>0=W*lD*w-)PHGfUQeeXdDV4vb5w=Q%TR%b{ zKc^AuGjSOwhET}60bX$14BCQX!x_}g@eQA!8yxuNB>6K)*n07WX+Iipn!xi`k4~7+ z84r+L%zd+R&(8l=^DUOXC3i9YuQlF;(#Au#DgsX!eyh4TZ#!SuxD9V3c( zM-T{`$vaZ^Z(yOK2Bnt$1}gRrsuVSmcM$xj=zmHGn6NVXEmo?P?=5Ddx0~;+mh&dk z2a~}w?i&1Dt@t+~;*2D3H(&e=Der7x;arJ(*|WoMMY~oneYTvpBIDPYc41xKvRr*u zjjq6WxNi>co(&2VxXHw)1h{A^6gx~D zZZ-5U4`P%hut|x)ZE7c5@K8e$+nardtYo(1f`Y0c- zUeneTJO&TbD2Yw6Y%7l&exebz8BfQO>tVO#_W?lo_M|T#1x>&ZK~BoCut!sl#<4yO z3gAHkZ-9lTUARAn)u59VKpaZ;*b`jm8p=qU^S=SfiqC{0kgMKs)25WYKJ2#!SyhFhM8c3XEK3F2u#lp zhX+pTQx$8;3{IqxF!{O0eT~HgkJ9*=rG`9YgoV;2Q}Mtp9-}IZ6L+RM5X(tjSUjCn z%`e||OM{T;N~f9z1M3NQ7r)DTWoy_$M!H4MxOiWROU?io7oXRKx8SvGTpG4I^5rGVX1LHiz94+Aox>$Ft$ zaR?*fwD|Ket(*(4>v?A2Lz4MaXEWc4@R^sa3RRek#kpewMtdCz2op?`9GBJuUI_eN(BO!v2oFJsi!G-BwDYW>^B z+f3=lQ>ldfZL9Yi)wh$#D@kcBp2le!r$m$*SR{>8moD=clOYt@K0kTxGLm)U=g*&; zO>|uLa{k5GN!5H~`5}MN{N<)!{z5*=dt*A@OmhOYNS)}o@vD;uyyqfocAuZWTbzrF zxZ}?R@)yZ3n-ezY>|V6|Unajg$@zO0kx$2~e)&BMcHL3aM^%+MrsUG{Lp_$`N z_}a|>Y7#Y@e>A)2c+;2}YMz)yIx&NMkP_Q-d>Po!#=hQ!{N|o-J_o74dQ~)$Mb57- z$Cn`eqaq`P@Wom{hBU<`95Qv=B|$jtW{krmwLuscrGuX!VN(wYaE!Jv*ntTzL8deo zO_F8oIEP3m)rsU}Y6{4Ltt`$(X2K2>;K*Nvpkecz`Q1tw9hQ@jVg*sBo=e=~`%Moc zb~<)D(MnA?(*}tWuR3sT>f-#UL3<&N<|#@t{zCk*$LKoSpf$I)BtUOjN2fmuUr;%d|6a5~J26(f%NSV{3+y2>I>_ zk-*sjN6n=<+at$4ZPhav0I9~yCkqKeo6Tgp-E|Y zou1fo5{_X$Sq>%2IF;ZhyC`kI|6DiM2}!Bx`1xHVM2S{CXlJ6^^0a7zACP!7aC2VZ zdJmEgQU+nVF>v!xk*Ppd%x{=M@SI1h)lMn_J8>ho1N?`S3)=^m#FX$AWuKlg;u&tc zKP2%rDh|-a+zwpNzLcz|4Tg~Oks9gIf6y~@egSP(ti_}N?Ml=%Mxq%*Wx}NC6t@r1 zFy~K@bqTs&1mA!*(bNnQ_%zqfTl(ve5jy>?`pF<7v722d zF^>ws^!va@7K$_RxFa@@{)j*&`@+TKP@xnWHn+WV9l zlVeraOyvt#tv?91H8z=BHzA!IS!uVbh>}sdW=tN#&5ecQ{YB+(HMG8CRED zeMV`ckyI#EwK9~a?yBq>qkfyb@#!(?q^;6KY8>N<(0Y}iobBdEEP0vCRn3-Kt-7(( zn9i}`3A;Ym8ZgIk4O=c>T0->z~r5^Bh^sbPc#J)z-A{U%r_H}r(AKBV)$^2x?#!vJrneNNJ)ZX3gHM}L) zEpZ;7XpCJ??SD|Dj|MLtc8@ef`d=fx=6>*KZy2#EpNpyeD~UX6JyL>GcZ5|GDAe!j4Q)dRu=Yb^nT5 zrkE)>UR&RC`PIzdU43Vvcz3T?%nVEoWL>XQW@=u+!{Fp`dn*sQeUfLq62BNg2uQa) zVTXfLXeq=c#=|i^?1sF1Fo{Aue!2q}hGmEvNQ?1=FU+wkNLUtb3B+C`A~IHvuV)2s z*F=tNz1qYFFuY789nttOq_mST=qoJD+mbs3(eiz+)rZN2hMZxjOF5#OA;-2?^!Jh$ z?%0L4YXk{52aPZl^x7f&0<`4{2CMUyYvQAs~cu9^h+jLC?%S#cKa>r3sGl*c}lPnKx5eec-^8eAgx`3@f-cv{^`MVN!z5^Zbj!lGH@k<)`r|rG4M~5DSluDFKsx z15c~)ul%XGjp+#j@y=KkPDr*QS~dyk3g`fIXaQJQ6G_bTsYlr=P_A|UA<8EnqQGJ8 zd}0{^i4nLa47B)`4kPBAmeKJy)wVdN=pvq9RsTiAE{N_yXS*QyIfio6j5ZwY~tn2k{b*MDrup87YMc_}(Jc!(=_+D{)4) z`2hMumT!kc#XRH9`5eRgWB6M{zN5fL1sCI=vy|hQ5rEOXNS&!^n5`DG?ODk0^B2*H zLVkV``7)HR7U7>$=Y^58f&M*<y(7*w{{O*AbGf6W(IPP6 zc>_{!z&i&EVmXKQkLTcXR13F7*nR@DD06-a^#)1a7E3{SquI8psQ$JjgqafC0}pJF zn5s(-B#6pEB#y2h1y3c2QWe7VwG}zfcjs*iONc_D$Rfg|Eq=mdn^7nX{5BoPO@#T| zJ;uBoM81im73RZz3{TkzxS$^M)Y}OBu?p9##1{bW086Cjlf2Fs3z=R4Q$Pq@iWC~| z9ED{T{StveVUFW_M95E?AU@U%+}1JXg}z$g_BPp-L4c2E@vY-1f1dkGeXT$B<_A&! zF&maBOb{t{E?~l&)j_zo9JuX1Uj~6Uacni)ejVz4<5`(>5O#Q)4!sk8hK2G)sNsCR z6}7;h@hvSiJgb=NSA0fpHsGHhBIOh?3E-(jNUgfKp)S4Kxj&dM(=7)H-Pyox-_FMA z*Yh)8z;`tBRSvK7SYX(ne{QgD}o@wCnQgi(9GJ`P!&BwCr zK4A%I<6JwSV!?}#DCza7T(>aio!nx9ns=Z23UfP~0*?MFD)cU<-_fFAX zHSXCY_B&U>tdSS4YiyOb($q6*lWpe@ST#JzNM9vKuafI1Z6CW6b=m#7bxP+(*QZT>V!+b9!>TlFQ*C0fHf(8?yQdp1*I3G^@f=KmHQc~YO73i> zn!Cn=lZ2y$ZBojHSMdnXkv>DEMn`SeV4;DIJ6SnML-LTUxiVF2OcQOb4N>O)H64wN z++KrGGjsH4#`%xwWb(;18QCt6?Ax?E^8hu>1AV3GuAwKrnv@-K&8m(yn`Cm82jk|d zLPrPMnww2lWFxt=l)aO_QmA=by+g%@*I3gS>c})UZaQ>rp^}xUUDLO$Y)n5YOEoWB zXgs$1Nv9?&*~auL>B(Km&zRL6wDIWb#zFKZU(VDrPdQIf>xQjr>2 z@~+#7TEKLbnsS{l9CE3BXM3Tz#!F|jt}F};I9|Hw4R+f`W;33w4$5Lty((Yzc1fv@ z6_C|K2U4i`BR2+c(83F8!8H|l{jS^hqDy!KLK9OK89&7ojwF5G8vLIlEWVSayH@duB&__Kx*KOQ<-bK^Xhy#USCC^{;R>RVEiu?KHDv7A)NpAsHiVj# zBxB+xE`hKm4R|mHgmDs^pUWMaI8hW@l!o5tB;0Up$&m~qhNOL=HzgU{wCOcGqr@TM z3E_GFwa<(#8`C6h`d<5fUG|*)wf5R;@3TMuXPqMo*G>fgh>X?LoV|7Rr$4d!qw7DF zz4((i-t_*JpZ?fwOHv>3HY_R=t)UqUKi%ee>(|Y1Yoi-!#sY8t!uNXf-@D*ax{1Q` z+b{Djy=?xa^f9tNFi-*wZeMw`N6H|gYR|~9oAL}{Nc!jz&+rYS(|_0_pW~^_7xqX@ z4;vmyO4C7R`FB8xK!=q4cc9C^7Zv`qP5!;yi8J)D31i1SBl0%~3lxv!Jql@;ZY-P@ zM!d0ubUM4gSz5r6hn#;=zB9^WIcMs_;onw|e=9yTwWf;u+m=(|uekr#`QBN6qj=}E zcStdUzUB0k``8&_M+NyR?mI|%$LQZRUxmNo(wX{H^nAw>e-8|7iD8tQ@;P8@eb?V@XpHrru28t z`5!mM{0*xAru5&C{r8nD{*{9MwfX;*#s6pa|3EDue@9)_JMjOma^6AA?-FgFQD!A< zmE*17McBWBw^GiTJK!_J|B51htE`oc(Lcvr*-ZU&JipI0F7Ir5{lBe;UhRIL75jb3 zl7XOqp?<&9f)y|896Q4emBasEI~BbuN8w8Nchrl!TcurOkk?2BZay8jxGHfPuAuv< zI8m1zq;HtfRF(odJ zfGkL9W=2hp0Y^X_nUH`?wn7B+*oe>-l5mu*6t2v~qyrLMdE_aF;RJq;_-84sQ=QX> zqDzR?ol%_3TT}6QWsfS*5Y>=vlvA?g)F6B&RU`%F5OY+W$#W_kJ>@O?-X5c?&Dzal zmYw+7j?G@C2-%gAI9O8|QVsryA&!&n5T;!a$5mYRGu>5s zPwCe2Qt7(uN;Eh)J|0}hLF}uo4Y*3B;bHiuzBBZlp~*2{jnUZHxIgauiqlypQ-!zm zX6dyPgC_=$y*fEI<$b60qgP6$H|^_pmtHHq`SLd=wjVzH;{8*l(j+ASz%3;6iNdEc z8#nG=Nujd?az@glv;7+8dbVkJw$Yl^>46r(mHD0M1`4-spoXMp6a1JNHD7&n1MXTd zjToZrvJC#U1V0D7;fprJ-@NGae}2ZVM(cunVU)pg+0}U~GC00WET8%7$+N>P;N|ji zD5IR0bz>d1eiZPsZX7pV&x*W?+b|c)JC=AOi79;A@67mm-Ui@T$w$#{v!aOv znDe$ul!vebc_QFEDHCbzCkOu>T#%3RF#nlkv;@2c(l}38%VpV!$L}{$Jr-ro$1d4{ ze%g;RPwETVtoPYu4L&~p%;4iE?34Yl?0IhNggx={sjMP*P?4!o_mgPNb7ml1>)W~x{qjCa$gg>Z3iCK;l!bQ3x}KQ zhIM?)$u{BH+QHNNKJ3_)Xddm;{9^xoaocf3`{)A*E79K9Qyyl0tUL)H=`8==zM1SM zNA8P5c_%q~FCV9z=f&M(j= zoS*2%o*d_E?hNv|2XK>^io;s3L~&DDpCI~eSFn$gPrgs2yB}G@+GA-sMW3uOd0Hk5 ztg?FeN3YP~G2ie<)F_fIr4IT?FpEDP9y?kfWP?mj@GTbS508$e=J<5TvMm3@MY4YA zL&KE6D6!A?tI40iS|q@383zd^7yX8Y;k^hKclu+#FAwxW~6f=4ejlK7%B0g>79Ydf` z2*bw-0No&0KoQa*-9^Y$k~<8U(jebb)M(2b*-FUXxNVxOiEWUkU;rVaOvuFKLVfLp zNE@~$hUi4B?bacT)NrR$==Bj1QYTvz@zW`5DQE7g(^Kbx;ik^nc_+QGn|WDQDx{)x zlPURd#pEtm4rSGKv}mhJI@K2w#U6b>(Z!D}do)7L`(v7^eBmYmNe>t8Hzj3u;m&16 zEQ2`1A>;=MeZ{O$CcAo(y1szp-C=6nEjPOnm#Zh+vlWKGh1>>`C^DOAbd9aCcr@Y}Yp=W~Yd&h26iVJkRS^=oScV&JZS@1EOA108$PYj12W^rnGYrAa zbXJFZ$8x#~d4#2*E+*I39PMa;thV-1PE}zT%+)TsE~m|OQ~xK?k&TiA&{Y$+DJcFV zUj=@ais@6X*yyh1I5e>iA5l8M`E;H+y)k#EP3=aX$#Lyy(e;p{nQ#f@>yczGf`Uk{ zl7HK88n>v{4NGkLuVlv7*S(8qpB>w<*xGA&49tBFg7F9EqmKT&fZZD8)XUrpkQR-+Cw z9z#FLasO|{kI5~=5V|WUftUk*(V(!}pg-UibGRdeONDASrpc!o)8C7<&=0z4m~Pht zq{2{ftGVM;c>=8(5#)pv(VUE9oYVJI+vjZRZXO|0D(%%vqCWHTn})C;%(1IzXbjQz z%!(AUPPIwK!9>@no4hgyT*G`f{coE6xSLAA%d0Wg83hz0BC)GP2s0|0$N2EWL?fiq z=WgV28AYQw7_{`hKYN+m=uAppRgRHHe`l7*Nim2pDnQmkyiTxO!~NI(#RGOUMVp@qkI18t;@5`_bPfQ<#?-*Wows1RS%HS z_+_>JHgyAhwa3OkJKxN$fOmZ*W_sEe%rXop+<-JnbNI{8Gc1lcZ;6jL{m^f-EGL@NAX2c*z_So2+ z*haTZIWp1ZbUD&d6t%I$g}Zn3bHk(IS{&lOs?vlYehNR_Oiib?HRi7f+POl}DB9!( zgu{{V;ljbktXlqGS5?6$Gc*5ZhF$zVj^9$MdXzcSq&o+E!6H~F=S4?+ zG7!>F*V_G$_d_1)88w|~N25KjrpmVM49YVx8F$oVW9T*Eh}IO00^*{923{6LFfHXB zhfKTfUJ-RsZ@VS#d5(8++PNJ{C*Mn+Q-{VvyP&ELP{+$Nju&nB9OsVDkk_>Kj$8lm z29)MpPog~?&x)*@%|kokxE*y_tkp(lSyazGF>ih*mTpFs1b#L_r&Cl8aO*Qw+#ob9 z!U=jwIYw4ekR2Ua1h*2tGo&*g-*Acwq5A{-K@tTi?JHlr=>f>8P|z!b5Ck}6oW?0D zd?!t)DiIYo;E))Ml^Aw|*i$hGPfHIPLFf(yo-o>f8i|vvrtYR9NK+?Spl485(W`xC zIT%EOtt_vGIFHivuueODZ!9?VBx!~q6yyv1&^q{klJS%$EXw|}@RKQ(__C{XLU3ho zxeo~TpFt;YqAjMS2<`x<5r->Xsp2B)^oHadC#xj_etVhH{2YHWjTr+H70;RO+j-w! z7Uwz1chYmFq;lA*xB=r?*(>-4v$9_votm1U088ZXT_r^dY1_A#N+19D>A2t2zyN*j zC!hPto!|Y`uRisw%Jp+U0dDao=Oyo;!7kIMepLd55%|Uz4iAqn9ACI{kn^&HPyK3q zY~g>Mqyr1zpuvgBv14?U#wP}Gs+^=^L1%k9uYCNQOuv-({p-g+oBy@S)6Em}juO52 z;!F9*AD%;A|GRa{43|t`7{;?ex0YBm;JoIWEmQRWEc5#e3_TywLG}wv}<0LHJwkV zzXR4;sn2xRNS+F@Ut@v5=-98*;IH6>72a^msdUC4jaI37c~`^!27x$%{4MZvI$Xv8 z`B#z4<*=V!?FT<&i(D3MF1rNcFo$=b;?PAC zKoiG(_{$_E-Y5Aa2PO)6HBl(%JC4||d}Sra^C%iz$;jo@z;?t8s+aOp15-5NzbcLu zi-pOti9GAagHclH=>>_S^Tx(XPY=*FFDt~CN+10wkJSfjPfVT|EDikRb9o>^d5p2I ztt9vQmE(se(=Wd~nLg-$D)UI`5vu*r{%4+l?~}FLzi_B_<@Lvk5b-vW8l!VBh-hq% zM!v5xLT5>h#ugJV1Q=uTD?J*+GyMo*{RbV?;e~zo?O<&0eXsn1b{8BO2c`!s6T2jK zaay;5J(}_6r8=Fi4&qzB7Nu2K)Dk_!7$Evr?GDLU~#N;zH-Fkh9Wo&vgY^+!m;#7L$TUN zOy7^`031I>Rs%iX;D(Kq^}KKOHT>|%-c;yWIp?v|@R)kmw?Awt@Xa_-?Yl&KZ!9XG zhJCYP_`~E&dUkkZ*Wo#1kU!j@P~w={_hDUsGWYHmJN3qB1lgh7ur+5G1ESBTK4jdx zNFF(Y=mgCfOVF@2{6mYXZ5r{9qY!Xca~@1GiIIaeMH3bLJcs2nNpx(NfC1{TLQF3=6dyH|kcO>WD-)4i$BFujmz`6Rc!Ny?;py>UAk(+h$rAbq2|193hb`DMyOs_2vYw2#4wft~N=< zVJO${pmb&Dak6lQ8L|sFl-d@V5{aQu)a~Y)i5!RE0ucpN0;t7AL=Ka)EEtHilf9^l z9cj$j1=GX{&Q2FF5WsU*N|s|;2>Ajg6Cc$vSlu*P*5E*Y~rE?I6VJ$UWh; zRr0}G_Tu1Yd~`AGz3-QPmfMXUMS4^bU5n<><{_8v`j8?N(oS;eKOu_Jl8nxK$S_h) z)nEN%8=9|bb>~Og$c~%dS0vHTN5kj(;A{3NyX1SQa$j$z8?9{S7p>W~X(p|cRn!TL z$DMag-L5L4b90ILVE4@TEUQ`u#{Sy+3?cqD>d(BO&{-|M4^22v$CROnX7$CuepVVN z#|CX+(}q_z>X`Moawj3N(a{lt95;lpZj&%aRjZx3l?XT5g&1wfbeVrj?}}4H?gB0! zR0HlNv<=-ZB(<)Y!*MM1BG%RTyMo)c3t{zqEL#BoyU_1^JX$2X%W*KQR^R;t*9SP2 zK`-)`kTbXMg4h!93!5^Cr&l(jPWG*2^v=wsq@){LH|InZN#8a%bP^i;v0I&y7#T&A zxl_=TqX`*MoB}iF}{JAYCiWEf4%8H?OF&A)}nr--rNP-b1C z#ddF0CO@1d3~cHKpp6dkPpu*a<)|qRICBe82EEBJ-5#ayD};j#*6Jh$eLx?u(68~F z0%frF8gpda&|8BUqs-nOQjp1QQcdv9bZF*4^3VujB_-qGd97W(jj`Md=+tiolggGS zs`+k_zBPJ3vKS0Wz{Ut=C`G@5=9ruQ^0w|K*R(dyrh4Ca|JWwC&TRtg?&X(sgK-RP z*!ho=o;hE&8}B0X<8$1MYxU5fz9{a>2ME<(A9@(F?N~dW5_#VvqbpfQW_68$Cyf|; z!$EnJ*P!_H#M~x&o3dn7Q64zdB|i@0ovl{@Pi(-m}5wRHrYz` z{pV#10vx+s>a3#pGC$^iJs+iIX{YIMOwpgoq>E%)-A~yg(95{HkOd#DywX8aVJS#2 zqY>a|ZsQ^s^AbIFcVqTwlGIuWgooOU)hcNo{tEIB$2=c$`e$@{ro^49ry&ICrnq89 z6NWC|9scz*!~=NSB(on4*iET(9khI?C-fyQshMTr(NRNJ-`>ky>GH>FRX4mD%FWl?F90 zSkUQuxnwdWY_mI}P)-UcWwJL-D;(J?B65~&-nz6K&(eg-t3-5bQ`}XgNF>no_AE(Z zQ}pW|U^c5xOcg>>;#}w~;P2j&OElZfNyBMT4$-FmCfhT+w*q}uqF*SLY9tMy_H$#S zwxm~yk&OHQu?dQ??};h_mSIo#9Z!Uvy<&L&Mb;#ouNVN0-?{nG9Xk zpT}IC|qcdW2Pgn>nN1w*(!ROUM7;!G}=ZCks0yGtIbBl3=(K}56>Dtl5Ix?qJUIa z{nG8PU4_RxH@NXw(`@6(^|M5DMa>N>{+Hp^d%_lUS@yCGl$}S>JA{Kr9HQxVr?n~C z=ClB5r06A&dr@i^O&ysTZKyIf4wrP#%eH#)NZZHh1D+Yb%59sMc~5j!#|QYpi(BA| zWVDH*X>YYh&309^jU0+NFJ3Y;O6dr#=y2oV&EG|-HR~hG0gX?6L$oE&x1D5UB{lX# zLWdXKEFce!?TPub&=+Em8pTLJ8(|K7JAo6UhZmE8a5K(E;9$~Cih&jQ1DDEKxCWpc zOCw1s!6DfpIoByd?>rUIzG>ldDH8G1^$7|PNY%b_d1z3katJ=ojbB;F^b{m`r{WP3 zL=uj}*OUB+2ngK}j{!~%ETfW8cDcxkek{lU0I!qmUO4ccR80n1n}duP=SWs`zaWsR z$Z(eGT^+|&|h^xrO-91H4S%%=KY2~mG@Rd_JQ7OKbU9EW#o__tH-_aooA0GrT`1EU~ zk=KtNExjdaa*XY*I&<^0p7>RA0vJxs;zzT!im~r#Q_?doLo>Ed*X?S^uf~j z*uhOFV4yfb2d_L<1hSbgO}zD1sr1tGjN_=%gFt6G#^1;)D*gI9rP33ngWE6NeG$tq zQAH~*gE7U4V(oiwzWL7YG9t>@W@&5!#9V=eCFdy7*|A5bg5eEdQieYam$5y@?<$xd zV|VYKd&w7$&(-*%#u?dJ^dXpMb>{hwi#~r;?u$vtQ2GOEL6tgjAYqPaI@4*0j3z>g53QW zAFTX-VN{_#^zVL+C$=I_8CMJoWM@Cz27&hgF6xdSzi1J32=cJ|3&X5oSrrVCdG(Lw zKp#!hUFgKvV|V~59FHG|r@PwUiZsx)vhLUAAg-Ymwwaucg|ku*_MeRuU2}}F`O;@8 zp}@dMeI2F;#t-i*O&nrmu(mV+yTjq(-Ma@@@|Ald_e#D3A0$Piutpp}-csptN~fn_ zvFJ}sEk&=t3whA9gAvE$Cg|Ja-}}zc)QZ<%hc%;^T2UyRSfOa5fbl_v!m-$EFan!U z-^mXaCVa?0Hbn#UT4|h0ZvqKbN9U!fG(G{l;{ve#@g1eNC>nYFSn9g#b}Wp%j`=Iq z(ZSCV0xh>+di_eorFksv-ne}w#^2GzXaA4fGnYlD*nhS*IjFHYr_;w`!dPG6iYu?` zXDn~-^4ca~hxO+#F%-Lr9vEK*Vs3)nV!gSzCxcC6y|ul1g!zr1g(bUG*UDHhkuTzV~Q*%VyQ9!}HW8?Ovdm>+Q7hN5eD`_p=azcJapvXvq!2A_@fU$_VAG-7Wo_dM$Hi#qa#<4DvtT|y}cv* zi1x{6tM|G;YWUpnV#vVI- zs90R%(~+YMKnQI*G76MKlVu8&-nY>h-alNF?homTlm)!=M%sm%Q7^Cyxz{Ia#=dIh zU+FJC+-p5MYSHi^i}oExSCCd;3i(l_H3Fyb?8x3{5jGx149D&@=1{pLgij;b9TpO$}wVsBd661Fv66E3qubDmxLXXITqn`!qlG9jvXQ#Bx+we5kh6*M;s zri@B{lx~V7Pxc}BRIj4mIx}Qg3YM|ZGzXg*JEt5GqOjep;x6`-LUxi#gq+Q|LIn}B z5te3opJoZfvBGDeNE6`L0*=Meq>(Xg;~wh1p$QHJra zRl;5E$B34#5t$K+I@u4^(q2WBZP}dJhw|)=*b2s4>B}Z%zxDv}-q|!D>pHnyEWyOBJ3wX||jaO$5A?Ec@QD&c#XdY%kJ@CR5%SqRw@V688(IypP z23Eky+3KC0`9Zh|F}+UVZzy@B&&l|lM>e7^G6@`s=!Znb$LNwTOKQu$t2-wkplCTc zq~+&`sz|}7d1Im0_Busob3q{k_|d7fhcD8kBmIc@o==I;t@IatbeTE_wH@v06=ox5 zNM+m@>bXZqqCbRKzj$9%Z1-?u2b|BH%_s2EurF@fI=@EUZaw=CbJwMGHuh0@)- zfxl#W%{8e5L`SPvW$fq4oRa_$2!5XwFkv!%z2{{K+zO{C{)-Vq^w=%$fd${a?hu~2 zbdi;8q01MpG(t8lud@_67LJizuOtMacIsNpUb4mYoGRlX9B|KTbKP63F+h|_Ed}a= zF?&?JuV92xI&JCJ_eXRR;lJa!m^EOz;bO&ClJ>Z;E2AxB-PC6oVhiOTlB_dC?ZP-& zfi9dz_m6uk&@@ilYM?h5>mh2iHj^~Wcu0ESlM*P$VWN!Xz+e)Y(KUOZaOftvd_MGz zn03psqH)@4@)fxQRAUG->)R1oCWC7jkZ$MR|8jrUM|f>@)ZC9n5CuCJYsSw;c92mt znA0ubg1JZ85}s<}*yNfB-MsgCOawOFRK#4Mbk{W6F@(>4K$4J@Ac} zrNsPNMdD{fmYS*cUya+w!ZGeTswBA?qM_Yiq~1Q|nhE6ZHQmgFzXHlrn^Po=FbAC* zm_e?5+(cgMRGTQ837xH)4aHhiKs{hDyGPQ7D|q|>yc@kYQ$$@FLv#+8NeS@GA`()q z$3s%Jp@p)Cl-lqoo7_yXN~}Gv7^eLjiEdQY(vQXI;Y~4U)JjJbXGWvVV0;t%X{$3! zRf^8>oq9X6gWjDpV9)&|efX4r6T5*SN;aiI{r{h6fYq9 zYJZQ^tzD3|Az`Tc?xrl4P{e)%H$mN{=(cYbq_^__ie|d*QO3DBbxSr613P2lgzd6_I}W)0&k}IZtIi)*oF;Y4<6UZoSR9 z*2}DjuHE2%KK4nv1DX$sZ`%}#(r4&g5;f+fLjneuWYf+4ndl>zqc>K$6#4U|*`Z4_ z?L+@Vy0iZWog+N?D0SGei*{V!;kLTj#zzO_Wf!g8L;c>4Y=5RdMxpTa+-t)GLr=7Y zs~bjbUU9P`MO9zkU>EvroT`kt8H+~N-0q3Zc)XTvUx5~B^e_x(-`3RKwC%|ouE&Aa z+0fCL?x_*j2;9*zHLE@8PSrVa7*eJ?q8$`%>-F0361MBLW}aN%?0W0xJ89~0htTfv z4HJ$1>pNnXn@zLlr{ivXeMGvRTxT@3rDtVVlb5^Iahk*HwMFnrdxCFBXQ^m8*VTDRHShED!c=JS^MV4|K85D zpHt`HA<(_Cbr*MB92e1cn$e7B^{YFuXm|iYQ8ToJhaQC*2M4-J)zB5DE4#BSw1vfy=84SbxOX!YhS5h1nb}PJC0X$M3@)?4Q!Vj|{ z=6{8NNfHH+R0#wKlea0M;7Q8B$MX-1bg@FH;LQ#WGMOIlRgg)Cc(T+OBG#q1lX6ii zleTGB&;viFiYs+UD~FXe5MczylumfA85StX5c9b{q%s~F(9o-m0c}Dynh!2F7rWUA z@g!&5ji7*<^O0Z(1FLS2%Z(2WC3zA()K(H4OHmg{MN4raIw+Dwd2$n|R5uc-Oae`D zHT=kcxq~CI%f=OIp=89_HVKYERdh8B12s3fb@80tEf^;= zO*(*89$?vNOwfzNQA=qT=@oLY+sBpzKj_HOf_>CtXh%>hXRxVDa@baiNQt)zw=Kj6 z#COv83Rk=wf&2n;@n3LE3tt54Z%aJh2uL8zWa~uDtHWAX?K|_*DLBRvaM=gpZ>O?V zA>O(y76xf*VBx}*D{E`1R9m}pB@n!caXMkp$^&KOgWrv=U?7Z&EL`YMl#b;Gw{L%m z5{VNfU***ptynn@NmH+uN)a=#ie%fyz;_ILrqU!VvtAvaEY%*vf?Fy*S1OIIOdTsy zL5RAQrI#3o(H3P+;D7D4Qt{3AKmE-U<0r-^XliQr?x{Bh2YWmDE$gYtd}4C!RivE2 z+of+zj8FaO6{Qqy$2;Au>-cyXvC;mOEB`)S8b5aQ*wLvsj=efKFfsV{7Qvj0VXiSo zytB+$;H>cF=iDB?{Jiq-e#ZKYR$z}8ef|q)ydTZ)OKa>=)K;8;YIb8+sjYx?L%rv?TKjE^51_vmT3gS$&_y@@UyAoLZy zo_pf>`1Zl^g%h=({`BzhmDp^iaMqBi0cWc8)>{*Po=UDN?bMn?>Ker)nl*z`qz_VlW$DEaeP_n ztvtQ^-MjGYU~1s#paR~n@_uoQ#uwJ^K306O^kQlA=F+cA#bd?NiC_HsY;BUz7+_Q3 zLmDHr)QlF!0N=N_Q`-qP?+Wi=%<;k-jkp6hyo_-yV2ifD4V&J2+X*uUIE(5&#BROO z=iA!NZItZV*02tn?qeD|TzI@H$?@;YVJ8i@?G?k<{I6jd!K#2o8uK6IL|9jpld5HV z%z9GBHi@t>mT2seAp_2b(*n!Ilp3=Eiy${)pK907|8!s%S@$QjP0RZkEW9#yeZvAn z%QGShdIi7(=Q*7Mj8PQJSfRQvg{fF1${1lgFhbT+j9R=v2@0@1K}!NG5m=yJau8-$ zxDO3$tkLvGby(c;r4<}cF9h#$H^1E(^rIVr43RIbgBXj|CV;#@JTmO>+vi>}W~D6H)H!2(C18_IRbsRcfnCF7 zB}RO;PYG%mnNu|f^8H17)!q@=BhBYW`*7R?%D4E3iu(NLe^{JDYS9mAP73z5KlbU_ zA{{y0aCC8>pIC&quBoqBZPAtHUbS6H&;LC*#EWYUWPE-lV0~mq? zL-u!?5+_p&+dT^dN?{CPnnV`li;xu9v^3j>sglCr_;e!-Yx@mqHf$g4u&Z=Tqkw`a z-c7clfOHC&IVv;hh`0!m0apE7*F@%bps$djP-@k_?~`$hPqQLWf^dgSxWWPk1FelB z;xxs;sy9p-4yG;2!kJ4S+LGCshuzsvul8uhOtK%GjV#KvAB<+GYV%Adb`e(Cy2a;CpjJfh#cPjn#e3$e_r#rzHFQtG!g8r*=Y$n^Zc#D% zJ9L4YYf0@K=E=bI?7bA(2>B)izu8Ouhg><|xIZ?eXW1MuP24N1cgL)q-&Z|r*hoi6)FdqyIJf`u@%>s-Mk%5WaX;c!nTy7VUg8i9Hw{Tu4?ksb( z0i#GG9FHs7Mds4AKpZHC;#=~ha4N!SY^J-$G#nXksp7MUYY6JWJQ!a@B1$_mEyl$= zi*!C-J2ZPTB&y;Wv5bslr%m|`Ik5MQ@(pgWedXJVF&z5h5Ybm$WziqBD7DQ_5v3iw);0&JsrJN8_gI9&p7|` zj%M8Q3$Nbc%0Hy!oEGY~6wx2wO;4JvogI~^N0h38P5%KpPUxNwG~1kjMkRpj%%N-9%cOY6-hs`gEzI0Jo#Ur(ibGdimc>w5*C-IRfA;@7=UQTw4@)H{hc zF)nO09(y1{i7f*|k0E{6g^K*x%z?)Wmvs8ot$?O#@c}xAmVL>|9*SZ9+5bn~ha9u5 zF_Gvt@;?39J|i}6Yck$p?Tr&(w;9y!~O169t;sbpY0gBH1_RmSkzxj8@%hh)**_W zw`VBqg=_Gl@}=49zuk4mBTbI|*OyUbs3zkU7Eo+M^e^3^M>0`od)2vF;NLcVBo>Qp zX^KU>J077um_b73rb&+^vmX)1LL0(*xP2_O{Di zn3XoxdT-SJ=}kYE3lH^0&CXj*2kcb!@3+P0KvZSq=S?D*7WxvjTHqHWS`xwHL)->exj zjC0%8IbPckZFV+zm*%npU~4Pg5o>JS#4mTZyH3-W9nWoQ5lP3Z#miuqH=(x>8lgha zOOwQ?gol4jP9>g4SwJRF|7aNwt0?*#npMsQBDs{KfJjQLE*O5ABNX*aEh36U%*S=M zIS(nk1OYR|oJZ7)F#3l!!skU@P<*g+<7tB{6GsT3qgwh$hN;Xxo~F$vBT zrVB!?xe$HBQGZRCN|-_S0U1P{x^khX$UfyouOO5%olb?APlt9Y_!7_yBn0}uXkl-q zzpMS|nx=|g8mmMJHVy-5no4%fg8;DND}o&5 zj3@I2V#-&vW2b_j``lTGF%72Ri*zSkm>HJxd0-2L(rX9t*7P8V@w)&w3G5vwCTeTP zUwrBQ?b~CRm+pUV?BIT2kfmRJO3+U}2L;Bb zrhFRnH`ac1{8v+hKxYC=$l!~QEA_jiZ%m8@m zsW|oO&p_pQTMlhOLpnRZcuIQ z_U%&xua3WYytGG^N=GA!K`_6aD)x$%?>lN6LtuN_{&92m9Wlqsw-j}LV2mf-qz9b> ze2;nfcQOrp#FI7Sl)wP_cLt_eqp?PeaE(6#cjRw5YWvA)GAr^mj>+*X6L}bq)UyNQ zi>-_;w(EF}H*y&9oUZEzTYk-p>zULr7dsh@(2C3W9osx=Tn^Zrk;DKl|0-CamVq?J z1Su!c2EY@+LuCw7^C3;APs1g(T=4Sy&XxC{4H3xK*dt_~M##(hR4~PgU*m@rxverN zmot{*D)=IYS%(UC3j9=KrX0sV&39UXL16sF=f-|s9DnhIJ-COz{5X&w%a4qYjNA4^ zt$^+DT_u|q7D^M`jrI3S;XYV9QJVPWIMBSom9!~8{`jj04`THBQv(I$$kX8U{8h$V zZn>p)`#8dizjj(E)X>D?J>OYbI)41N7bodcnZd$OU-kXFO5a?FFBwc8-*w`|PhlNA zITn2RK=E7FFQ34O3I5%7TgUK;!O1sD#ZvM0mtK1PtyfQsUwGT(8)G9r0WX~j+^J)? zA?~#g{q#ZGUN~GDoIE6c!A>GiWT2^swoSe<*B;_bib zSr2NA(73NhV|&KWo?{F$Qg>i)T*96C0_+#b#`mwWR0!J?24uo*zWN%*81Yii0iB<$ zO&TM#=|25#HZ|00Y;)o9;5&+=0alv~fA5i3odE0P zl+!7A_qe$;_>N+8-NTsCf$#J@tg*fJ;9X^B{-I&ETXe(=JwTwyp(Xr|G$k+i-+l2_ zaOdyU*kv+#V}N10efP~~If)9Uc|{PPe1Wk>BiT}Z2Rc!HSDHrqa?Ia6iq?jUqe|d* zYWqe+4Y%lY+NMt5bV%RE@?@~4H_T3n3#-aU(sE;hw;LkBESc@#4WBEs_kBs`& zSln%@9x=#Y9O)b$eSY7tcvL;2NhtT<~94djmI{MMb!wm-B;-*n$ z`Y8OYgi*jP2lDk*h+H$}$QHSJnd?Mb0=ZM@8Q3$y#THDMfbL9L=qH;LCP+Ic^yhCZ zvyLp>VeoLg(=1u8jlD>>?Cm6zx4E6J?DVlYfb!_#1x)T1up6qE&DfDj%43c-Fo=Ot z+Q@4NY>V?YaHXU)Y-J$Q!M?+`l|(8P(Bn)f1sq%S;!9Xk86lh_1#_A>3_ArdV+BD4 zQIBS50)_PUt`TQ*Y1;yfXQM2j!*%Iu@{T;1kg zD-==iS<>r@z?HPVtBNin`tKA*54~}`|ZS~r4~ z5C#v8*DuKyU|{n%wb}-ZmK{_stM>`GyY54Kwwe;**0hb2xr5ggM{rNJDq3DxliK^_ zY;WD+&8b}@z#2wm=F1`2K|WY(?*poQ+eVXi;(L>`u0-WG!MNy3(z`OF*EE*+K&EYF z!!Zq2yL9+o%tm<=rM`_aM!~sUnKFB5)TM)c=2}CU)U(UX;_T@bt1rrQ2{f;DO^~rB z#_hmQGP1&_t)vryPj2-{yN?22!vtHx0X7| z@J$!iJAODKtTmm8|B~e*F`#K(W;OMrp{poz`B%3^uHtu{&79HQn#Q;FWOy}Dodg;o zgDtm91!RUbkm_V1agwqb%)N%|!`^~L7!FQvs2!p4Wk|juC|z$~Yiq@p<@Hk^O!f z{ji&Q)Hi&?X!p1-0iE(@fcYyQ#+7^bMpmr;Qq8TAm&rJ6W4@Y=&;Od&W{57qcRwYX z1D#mY4Xs8WWd|%Wh9&)(^*!g-?^zv`#PUhiFe?VB&?;H{kir0JU-yj>dPq@cr`t{K z4Y1%etBCf6E>LwoqZRdS1m#yNG&?MriuPu=X4E&=STj9C5$(Nu^MWh4(S|vu)&A{6 zu#>!dTlZnq$qE_X&QVGJ;7qyf!Ob-MuEvSK*h+0ZyO*zbzlZ6*w|>@=0u~A7Mv4;o z6b!M`M6hG*c5%GK_hH?-9x_*t%%%!ir`jZLsc7A*kh-bLImbQs?g!AqThSL|?%o*M z_3L49#)-GY=n9a9UmhM;EjY{*?^UpStTx(VUk$X2E~XirhO+VZmk(o@#R|RdPC-M( zbE@cY%!zy^B*@$eQRnBeNg$&xGa%WpCH*dZnil=5-|AeC`)On@47-UJ;WqSm#sgHp z`)Ie9$dh4wRmwRq%`pb@t-^aTFH&yO4qL>w%Y(+h@5=MgZFyRGkp@3|-5+6#O*S|cm zVCg&pdf2RTK+{?jiB4lnrvJ^ zqkf%+pp=oAr_4?1{Jq!$<^(L&luX$3yHxY6gtX746iSf7SI%_1Whdq4cA3-y5Ugvi>M~V0`j9J|CFS^81Db%FLBXd9eH~8&vbaQP zgPVP19)F<#cX=p`j}Tny*=gD3-uXyIVD85)@9$4vPW@3DGR08(k7W205gL-T;;Hqs zGLq;9q}~}`gY@k74cRTx$hqq?H1u7%bH_GHdrj_jbi=nI-5t)g=j{l4_7@_JH8I!y z_Uw*r+n>568B6bRZpg+Z@JI<9&t(SYWAlb2@qp9PD%cw2>{%x(ojV@?f z^>Xss=pF0b_7119wXW)y=dDE{PFvHv*S3ql+S73xxrxvJN!lH%qmE{;aedOu;VtIK z-C4bER!5un9;Yd3d$ZbFli}8Q>wD@RXz%FQke%Ot9_l07wtJ23S=`VL1w7NqJeB?U zc~0C*-chil@sE2=9zN6TdXyCyVIFEu1mASZarX$w7U)cpzc8waw+#}VtIVKIKIajL zL^C&`Wo^u0oL}O{lwlv@am7{zLpVq=O@xP>Krr?OAP6TgV53zBTSzQ4EC(Bs5aF9q zX1&65=DRfyMA&7GkZS?9E|T+MlWu#kOBQ6N%F?*tO7#Y)ixd`q#9*QbG!h7a%(66o zP63j9Ii2t{pd5j3MQBaKhR`t*Sp=7%5QM)6&SnH^;9~lqs|}!{1;C@HxR@KCtO+#Z zqIDSejtP^!cDwZzqnCHAVCuxKR3T1cA8SwyA7>yt?-}X)FU|3KMlAvbl_{Ds=w89O z49bOM=yBVSIqVtu&S1I)SHP>*z$+v!h~fR~G{OX>LxCP;6{n@2^a@sy|MLZb3iXsd zIz=-$EkVZ;HqFr)%KT_G?oviK<}}6LMvh>PP9b`_lub(%_2?v>fYn=-OB5UtNQI|d zlwcP>yG7p-eN#EA+}m^_Ry?#f`Zvme)=9`XDW)ulvw#GCI?0gKqu?{7-IM2((}{5r zCfFasa*N*}#owLCKV6zZj}Z{a5=A%PUl=@5{#K*5Mx+z=B>tMlYgbOZ{POGU{^%9Q z`TD@)PnuOWlxShUi#@vPfU4J9{cy~`A+`0KNZE_ zl*t1U9gM9?zcE5B>aDCZ-OcphVzj8?un z{&MN~cTR7OAjCF<(|?TTaad!E!o!*rgew>&=c=SLE~v4^GC%t@E;vw@39OMZM8^6~ z!yv)W6MV()k^KamlU)O4YFo^fApGw0VQ+ap{wB@YfA?4PWm`s#Q$jYoZ10oQjMf;?$M(9aiGb**KP?^O_q6X)lasf-I51F}c>3w1^d=*XZy6+sZ5PMKbIr9k zmtHQxoF5Y2;BizMD~+Wm-+J|f(G%nRJ23(D{-@s5>#vtyEEGxuAB;{OoqPlF7#9oi zVM)gL`A7XZDt)f>6V8A9cQPS%5Q^bJ@;O{QOH2VY;B0*ZYN*aDX``_6Bx^;%~p6Lwd4B!v4_( z_88bjCJFM9E!q4+Ukl3Bpod5Jo$dWcs;iF_ z#||0hnj^B{lYl;;k?LK;0%}@^X&-_BJ!wt>p0kpJ4u%A5eGDKArfm?g2U!P`EmH^* zQjnvl01g*Fg8oogf-gi0_ZE+85d(5UobH=;FT1vo5h`>Fe5+9r7;r>}nfhHx;Gy$~wVm-E=*88T#cI;H?eMB>k4 z1X&39w@M%Y-X^M|eTOdo=8dAt+iOTSn|d&k zOm(?4-c#Q}vWxm2rbXQ}yYr8I%iaGx4JaIFs5)x-slPB^#Xau3+q~yOgYY+qB%m6D z(5y22qfUbQZN`u^*4SZ+|{CiGrW^O`exHAL{80krfG|-V= zVDt@az>^SUpi_(pTWYZlXf3*IcXX+uFYTUWA_g2aAo>Ci`UcdNQfkMl{ZVV}9R_98 zX~m`8`g_`L1Gw8(ea3NZpLKC$exGwQL3G`BpXYskXXfVo|8vhhe?RB@{T_z^`Z9-> zD9S(3+z{C(XO=vD*T!yi9a%cck{=YNFmK_$yDOgnE6lj%@HHyQhl98xf|%D11|De+5-bKn{V zQZsy{a$cm)gJx+RQ8sU-O|(jGEaEXZUyKEku|slolz1cs2VjWiPGVjZ$HK7#s-eN$ z5BC-`odaS&!vO6ctRWN$UAsliKp&NG$To;nO44GiU+6`o4st&*v4Mf+8aTy8pp-d`ZMZK*{k9%H}QJQWodL8l;zqdtB z#>dU!EMZ0io6&a!$p(NeK5*qau3uwAE}eJ znzKN?U8u1DMc%AAPv8J_)iMED3VwF-Yw!a;j~3ESllBsz^LJ7qwe$7s)1c8^X+D~x zJy$>0e(1*T>Ag|E0;qQ@&HN|OexAsJue^t4C$`z5G1wInle8#WJDc7Dl!{co|7yb7 zN20nYl{;CYc`M4(cQ<&avYS358Y;R;{Y@x$g;&xw;{vvWccF=`!+(HBzWX8@*rq36 zzJjXFm|*vGbiC1wGmTxTu2aWJZNHm?hZ~>RG;@!kDs!H=&X=w4CdLtN^RiBR>AgyQ z@&2)QN75cVXxw-T_~xyscZ=<4O`8RtRvj3u(~%BdP=Pok0xP+KWhF21C@VuGYBUOx z+kBb(q8T(lBa_GSNEkDCIxh`>L=@sXOQ}*m7D<&$Y)2t23;7;HMpH9+QSse*nNJlW znQS!Wp6{GdG}?iNVuEAoG%qd-Vw1rOse;6ss;Dxwf`UC6E;G{TG*Un_RFUmu zyil}_8LEinl@L~@C>dry)I?2zY>=$pGR?GChwKHG_3(x+%m0u}^v>f`jo#dPoYyR$ z^y6EoYXOxv(&4EIfEs?_lLtUGW@K+gpWHRIfwC7h0a01F6%*_fBVbs$c?oK^7YGpe z?Osv5g!Trn33u-5TKM!c;(>d~ciDqC&00DoyLVw?Z|<2u!hG&&tNFQIV0F8~-*H3l zhHQDY-4tj_bUnN2+8>9WwZ1rW>ZQAS`O}F7$!2TvPpwrm)+eXVUluw%10T}Y-2B(c zUDUj%WB${Rmv@TER%PLHfBR*t7r@!Ie>+h;qiZ5ubd7wRMJ!6Jn3l7^Vuy_65mSmC+#Bk5d zU#1N2p{4`i{YD{rlEq*fz{X+PWhb|UX!GG9*sm9^PMXFYd$&B?zOl{N40_3p$=(FW zHU)0Y34;vMU1N|QB*zpMG1_Ee*wVTM08MIpMBDUeCS2V>^FrM)tc+2W0tdt~!02$x zxQQ`+CYIA7Ydc&C-hG~iwFNy4@!(r)pzw|e1&1Catpv5}0nzoxw;|qvux>+6V4~6P zNL_DKbgmc&pdPgiiTqtpQ?g)09~eOxl^*c0Lg~rZ%C8H9g6gz5FfL@J-1kzC76m+{ zwjjbe1?z_jlee~D%5t;m@VoD*MFY5slX7*|ie8I6QmzfyV<5#@JENwxa215=QPA*< zgh=aFuOZy5Yn3i>XQ7U|m^G9T&=7M_B-@n(8FiCHSS+3~`@&sdJ7X|7>ql{c7lt?H z8`vXQ2S5i)5Ui|ialin3JVrgZNsu?rjtfN3BLf{pN6@7)w8jK}Xg14hk51R39sYae z#zrt~;Iv|HqS_>cwo3fCK5jVt7)oIw4%b=~w|-rlK}A)*>+juU=aiAa9sz3X=hu;9&|G#&vKpfZMwz(Y`tfBm*@bwk$lBZkKff28L5v0va8uF^D4fF4J$IXHg!E2E>h(c+uW{T{H$=nu{Sk9_wZ z246bM^k5 z9DEy69^r7-e`d5A06iplN2?vBKy5x?Beu4-3MbO=6%N56 zZfz2+uH&3toAsmdJpJf!=VObSe$jOk@I&0X-KA?R0|F zqyO`tJAt2nZrneNj=o(|I)ujYhpHvCYo&%?f93guhY#voV-9`qz`=LH3w=uCl0(&> zJvm|S*N;zk{RM8QehGc$w`T@^^6t>c$eAh)4V@bP#nGRXPM!M2(ZdISS2}$7 z2bJHI=FS}ncrX}f&S{{VZ$N)T>&u~lJ-#su>hi$lf!i`#pEV072ZJMT&7Tkb;Kq$Z zZ(MHApFel_%p16Q<`C|Re`D@2Fi7B#qp#O`xbD++`e#6(qyPIqz#EP<&Z~-Z#w%T{ zapKGY7kiw0&~&lCc{d$%GzNI-n=dP^TeC9=M|`6Hp9pq8&14yT7C%kDFQ)Cm=kL-O zq(A!N_(5QdesPuekQ>ez-=poAYz9_B=Vb_N69%9Ay=_|eU;6T~L9NgJ!*Og|w0uWr zuS5fcu4e~5V3v`Og=N<+6XoFh*pk z$f@kxK{AH~X@5Z54Jdwij0 z&)?OC@FuNgMI;0IN0&$2jK26i*B$X)_t~#LlF{M#i`{KHoEUQl_87FV2aBAXpl3ES z`g~4lz5PYzmMS7^m|{$p+-V|4HFwHs-f1NOz(Ge*(mTWBICc1(GqNdS6zZ;BRz1T=qNNCmcjM?!4USiRwXyFX}%AYCxiwoyICD z#XUx2KXC^V7ZGm&)I+BoN!0<|L%j%zJ1B$$OkMV^O> zSX#jWD-ZmE>d-VqNLGYOF;s#{5iTW?jF${WIO1k#3RKX*9|78qOXPE!Z z@EX-3J`z<}2@Ii&6bs?n8ML zG4ndsbrt-Tfon4F1a{cdoTI700E|$M!M)4E>HBg;Ayeg|6*u25f^y5;fCK<67?z*k zEIl%U^xeY(9pICc(vC6#Ii7MD>iK$lNrV-ha)C@(sCAWJDSu8_|szqRVWx&Wy zX3&uED&k}JCiQ0u={h}K)Z|{+(0FhkHvFA2_uRzhLgts{1A?!>{u6ls=YPEq5kT)q zDd^l9cCOM*u<3k8L0gfb&JzmuVHa*U(zon+Ct7LOIxQx7Bd6 zQG)lj`Ol!s13jBk0^zFIEL9N$^mBB4k#2R9iq({wr{Vaz`p{Hc%IJ&)W2RSPS9U)J zRSQBku=OC?*}By)tQ;?bW7;5Z&dQ^%7``r!wG?9-tfUIsCCHyAF(&5_qkV!GJ=EkC zjZ9jhB_>@@vIT7M**w`H3oKefZ*2C>u_-NaVmqLS^4XkzC&Pf8#(096rV_^PwaoL1 zxsF;S0!ZvqsHndy3+E*&CwQ??sL3>;uz;tyi0ShQ)`Ct9-;lBl4S#01S&my0x4ht% zR*rZQj>@5>$TI#Ys_35(xvuQGLF<>f&46k&CApJZkTz&Se!7hO z(BGbaP?s6CRKc&&un9choE5^GbUMCXlwIJt^SFbubF&HMz-Yy~1HLLUygI4YJ5>YTMbPGIv!cebkC?4bysotN->Yctx+`ekwtz+QA{W!k zdMSx&p+_&&>9=Vd9kj`9m@zf|VjEpu#CWMpwt5P#Gge^RoSz7nd zE~<#HkCBtH@M>#zwEr97T^efU(kOr#IrtPMj4 z4x=a@{et8OHSw;_u0{mkey1Srpuh1zm)2YE5;<~}WL4xtpWDwx0}+>#Q=e0qBd)v0 z_0>NfWUqB0X*-Y=TM7lCc6QWmEf|HBJQ_9HY}u2|@aT3Xjc9g7I#q}pvYd_zzDp6w zA~(_n!HKb0UJBGzXY{IcXKa~-2;kOhe0+96$en`Bt&wG=9c%YFVB{3Fsq+ z{S>gll~y#8E*RSkm8ODZMU_s;NG7sNFtSB3T29SDW?MnXH$NbZWu;KeNaxkgEaw(x ztXMlp7bB`**{o-qnnOWJsn%e$$Xa4iqZkFhKrk9B#)OgZ#gr&^6x%ZfMLX2eQc*%S zWXafx7s*7KQe>b})l^w);JC&+p?a(-Hd@+rl9SD{Y+f@dXG|`4G+DCQUT<0Dh6T@R z(z#ySYft{^R7uyC{dN&m+UwsoHDGsQG`AC!UEkGJ?(*4zPP@x@JAK3MP*W1+r`qQA z%)G2+w@>*>7Cl5OAE=P^T*DK|Da3u>*mOHB3_Rm&_T58e`eNc4%kTSX!fN)-f3E47 z`CpzgwfU(~sCk!}cyN~y2rt9^NNeZKd@dTi^_%O%3wL+=zD?hnCwe;qP1Bnf_!Ifw;s>58`#Qbz%j|OoM!_6jy zVf>W5dSC^vkG5ms{HDvYn=vhd#x5kxr#8o9P04Uq(DFlKZc`|^S-j=-8{xoSd)Ts) z!Dm+6Wq-BRHa4{#{>*Q)rWp$K{vgM!;LhaMo!?xm~g-&>r=uY00$c1KvemWA`V25u?>{%b0x;wlr6bf69Z{B8G zM#640%l~|HIYKkd-&(f|tE+8|G0zG%tgc?QKID5MK`s8ImDI>+!VckeK*hQFsYEI8 z?Ce1M1GC%B)xFlU2@Cw(Vap0lX%8PZyMoWnPT!t0mB`lO}-c`WH#t z3N6#mXg4f61X?d~WlQWhFcpI;F$Xsc33kZ{2$NDFiXapz{fb?pOjh33(E!%j+bqm= zOrVgMwi_Zg#s!QXGe|*Ossm{|u+RuGq!}>^+9jyR9t_BMQ~)nzxo?FG6fD{YkHUj7 z29MMRS4Hrf_6kJc#(`SmY-tW5;Iue~Jihk-SNsda24(xj&$ zF&2*+Kt)l}k>FBOx*g_WEW}*9sqJpu8gQu-w6qV}3`C47?I&PG5-uU5YjbnOht>g2 zeJG`axTB%V{{RdA$CO^3K-GS=NuW0JbqAg{l!6;iqrqt3kE%Lya@P9!!0_wu03m@g zw%zU0ErNED_MgIfq$)K%qo&y!syZ|}GWwS@Lyzx2Gcr0fIt&ct`1`>1em*dI8~Xq> zTyKGd@yt;5m2Hqqcl7KpM&BN)zWbAx2H!W6a`-U(hTb<%4Udex^b%r^jEtQ9*H@gg zNEbY!!ykaw%W=*OTyEb6DUP>AZ;L+mnC9&6@7IW8O=;WtPYsc*xz)ne;^@#cdXR?R zcw4_y^~{i#Z3krL4cud+Ikx|-c~C!E8#P;~Yh8U#o%pX`p|2e++gA+I|4EjBT~>=deb^)n=Wa>xUJhZpKX1^jedyVU9lm&NzlG zx_Dw8R~*wd23dEnha1BsfjOf5E*&J&JzvhF#vW_*kN>$=Cd_bqzl$NV_!y1|U7PEV z#`NlDjTLI;Vu_$3bZH@hG1lX1e>P^is9IC$k*^vWpe|8i->Roq3Za9tA@uP{EGjUTV~A~IWTM1ZPASz*Q|j{R^yWBYX?`|Fx;<^$nk@> zMS<}jbkRxsa(gaN$C39&-n%^T75{C~xx=^I0u*xi?68IVolxol^qi5=!81dkj{NP% zs>8Kz2PR>(250JfqKVJl*5P82m%e|bP1|R854aefMay0K!V7HHfmh%`;W0F3*fPCG z%Y&RE`kLMQtlLsAN{uzfuljje!d-tx9S)GkVXbrP$X>0_efMNY>zBUy$}Z@9_P_QZ zK4J2z@no}eMP)HGhE`h2kQDUm*r2ON`wr=HV|wY)*rU&)0oOg{aj{6x->4d0WNLq) zBZm!<3RozQZdhY-A)CS&z+wL+Jqv9?Ax7|GW#yJ+7*J>!V>tu=dOjNVWqxQ#o5lG!h)5Rj& zU-iSP$X_V9`C1C8xJu)`m^9Y1HdkN5iZy*}1{uK}lB=}-YTbRBE{CA8d#q`RKc?-L z+8V@CRRATb`4e+7NcerS;vVu;scKH}2oFNw8L+B4C^)AFFrDRT3D#v3autt^E{XO( zU%B)7LI%BbWz<1XX7np8#3Y8IMp;FqDqUU8A92X38j3LcITN^pke;ZAs=mw;hE4r3 z&jp@=CXWYr6Y?OB?9&;)e9GY9?55LRbqrQ=B$nLKey2Z5StE-1t}z4GD>P@eS#_Ls zMx)d3(94ZRW5$8IQ|rqf&{&Sqz=R2>B%Pk7G}d_#%R10EIFdC;%}*0u<~L36Q{pqIkGu zs^pqK_Oo8oHibCg;RcFNcCh{p$qvXY1b%{$szLrEmXtSlU*@jfZb7LQDY#3y@kPI4 z`#L89s{ksycxzbtr^dGrw$iC$a9;UJEX+-seRIz&x`ybx>#sXxRU1(89gC#q)xN5` zAi-08+m$N8sJtliG9Fmh&|$RT2}^h{Lf0Sy18g3?spRu+gK!=EPraW)J!k*H@~hHD1k{EwQ~h{Ta$-tCHu6 zz{?-U_d3%|ODnvU?QfTws+O>4U#l z&VTc?B!#filLQ(L`m^Vcuw3BwrP*bRzSUQi?X1$1iZl=(@X%A$4t%9MK`)MBly#$= zW9mHY5m@4Kj33e_V;`i`c`WV+eFv(x+Kkn)% zFs;&-OTTo;)3P|c!x6#5*=5q=mx2G&uevJJk;wh=+_aa*vy+QEGm9SQNM{LE;>6Z_ zTGF4u(*Cb~G~#eUiX~4cbt$ zr(rx&sGC#U+88FQK(vH#q`Ev?^n0qqQHMC-A)A$E5a_ZqZ+^#5SM_YqokY3S_m*_Y zU=LMu4fQHP5=c*TkVLsJ##;+O`5~nM@*DFrqaElq!Py|O;+j~fAliy6B57-zk;1%Sj_kpFSDI7qsU5u9;RB9l`a-Aa7MsVZy01ySr%dqb#g^Xm1l6sOAr~H-J!>!TcC2!Q-O`BU4k^l+)Y`?V+=gA9&ME9p)&P0g;taQ zr^#NsHvq=tF6y0p4P=BavqC;BeUhu1*GxT-B^GM9x4fA`d-wK~?ak7()>{kaC9_XY zIXo}v|GfPpP z$GPN;!%H9gQNX%m8$Gum*t^>5YT~`~7c_tKnJJKB9LVBo8E@h;`{6F|>-!HRdi{ZK zGzIL+q#McCLHzb6KRsk(o<(mn=Xc=zC~TVZHsku}?DdkRzunMo1?;J>h4-zXh2ik-WO&8QXGLgY z_JGk-mT`GSh8Zi6&MdX#Gi%t3e&&Vp4IzI*7s~A(cETk2*fGTHYXgu&}(*l>hO~b zSs0&bb68|6fwnfgt=$Zx?}%pum&TGS?fA}TZwgOsPgIig!ttr?cD%gFpZIJ~aPwxg zJ_Mr@&{eB_trakA)Ec%17_4+#_)r-XHev$(l}I9KSAmNhda|N>DXE}2+vtSdLZ3oo z1B^>70zHsdCN#J|3Kx=wwBaoz1~lHz1Z7I?Os9i^7m8s7=rv|DE#=Yn3!3e=QH0l? z9O3e!G@HdRnFMq?0mdOR6JC;xdq`)iTG8VzmeF}OWRc*d$cXYO0Dm?~RgpoLOi-7P z@y^-cfiw^sBZ!sL4MBDwUMV5*OJQkgT|chU$)B$nrM!8Camw_Gg7(0IOW_rr{y+clRNBoE zbDho@O1S!%MLQswI0}OgrfqmTJaE(Dgtk*-L1_&u82q40J(lZXphnD;_R&g!Dgec) zsmPtAYGw%sB!t-otL3yp#F$PW3m`J`_^GRW&43&%Lm&?~DcGP460Sjmp+PQ%ZWVCA z8U!8~LXDsfRacz0AP8nxVMrb9JcVygknebQ^zG3P4j%eB_^8hsF#ld-CvW4DYpsK$ z^ar~i8=QM)0O$wE%7HtM48Qh^qh|&*^`hn>ZPC2h@4r(m0g*WKl8&Kyt|75;c;w&+ zA$3q{{o-gd9arz0z#ji$bma5>qa*J+qi?T@egWR2BNJC;vl;=>sSUqwk7zo_%n%R} zWAtZ(gD0VeT83Ia)ay3wUVF4(EmX}<|7yRfE%WE=bX|#%z+BF}VUL{s?dXA_w?)75t5p&yrLd(2#SyYQ0D6TfuH=8OI>A53z!wCg$( zbh~E_tZsm=+d3NX??>HEH2Q(YxJNv7$&RC=H{6gxm_cW- zq+7P5z6XA4VCxF>hL5AApBgzp!)G8d5?$i(pNB=)Po5k-dj-Ay~ZAK>#zUf=-Gp}-S+Rd4Zi*X`Xg?mS5z6Q4pk2xKFc-bwI-RgaZSB937ZDclmN)kQ#@C zEfniaH)GEA0DgOXa3stpZD!QxOPspd$i+k zj?qWrMNOoGHGr$57=aGafX1lP*U;a23e{3mwL4&@)csG^=_8|Vf|jZ` zg1a2IV5H?heoWPa5LGLUo|m0|?caFxMB|CybXS@4CTzU_L=_q+A)V?8uxT=EpQW1C zubf6Y1rO@;R4*i|Jm2R%VS$6X&$FM{GyzJg3ChuX;0nu3J9CiOgxI zd&zb0zCte_b-EiTEIQiv{Ir)Ru>MT<^V44HTLR+Dmx(*~_j~$}VxA>WwJ}2ji+-c% zH^__zL`DBfNPEoiUdrZ9y#uU9PcMMYzhlKFS28fS7N33k!1_KYwGmFxHrYqB*F4&u%i|27-z?D z9*RS3H-r~6rpa0t7tt-R3~U5o!`Kg+yWYSKHonBO_~H`o>^0iDes!;+Prt%Cn3`&I zO+(y<0M7zz*axZd%9vzC{ehOQAo#|bvFyf5)`Rq3E%rz`%VOn4%KK_FsT&ssHuh~p zeR}U=$EPav&`J6|=z-1~a5g}+uAAS|uN1x==pbjHJh=wf9WP8-3OYs>;Dp)@fy>lf#-Z|xdV%PTSG1S46lJ{*{ zNx4D+9?725ce!3V&@CrjBXGAD9J0FQdN!zl&o*zy-oa=H6s!)zktbq}n_0IEL>nhb z_Jq8&zbBBxJl8Q7I{QqzOYoBoJzsX)ZXl%&6JYiM^G2lZKd7a3UTcXRTh91R!z zZ5MNrxJR3t5nmk$is0Sy{pP0MHLDpn2?QQfXnHjhnzX1?vbxXY2AI4c z9$;|=US{NH5y-YA^-;u&eI#pcC<+Sfmxv%qfNn3Ys?29Lc~V)!-#QuJHZK}7Aj+}< zU*;OdUysm8!|;NHf_7Mzw>e+3ma;U@RU}2tMx&#bV`vTfr|(BQ&s#C0;CQxjCB$h3 zddi%k3wRO7mIsprBY=(=60mbf$I?VzphfK{3i$4g#4T`lti>Txu(uedQz9H#7&8!$ zDxhGt9C85VbG@r#Gffnz1*l2L!dsh!#OlgE*G@dsraQok)a*7e@*0XnJZ zi6>F%_Ugcq0Y%v_-P0Ah zcPhmvmb$)sMalR|A)fo(K17(g)fUqyvM&{GsJ^*HZ_VV*=^Wnox~+8j+l;M<3fun* z@obvi^5g-csSr3olN9n_O&)|d&_@WkY}IOoBkUkmtKhQ+#)a(2qo^ueL)8x-Jt~`c z*(L{#!l!6urMcmBK0v`m@!URtfUW;3b@ktiiy$AHWqEeu+mx2-h3wR2lgQ$(3!YB&men zO4r~ephA?5L)+Cc#Wt7G6-_fS1C;SG0RB9jqvpSE=_-JN$chg_{D;_U>-`M*N$TH_@6qRzG0xE?#aqBRVC><^U7@65nn_`Sio&@r?MBW`Nx}5Pqo?iv^>~#>o+#v@OK{^ z3Ln^YII!9ly@A9UbM|wT43{@1>_qUF1j!?x+SC>Tt^3}28^RzIZ_g&Phq7d5HYK}o zd(Ecc>h|OBt+ws=sY=5etpaamg;Y~|XpE=iVb zt3tgMy9HO^NIg*D$3}w(qX$M)65@J8psvt&C??UGu*$=%Nmx+XN;{hs10hLG0VNsQ z7tVdcR3QPdjbo;dlp&P~l#dbCbIT8bqXB{ZylN22p3;E&_9D?%a}wa5fQi*o9Ou2b zO{IoyQow5q5?f3Kuo8s|m`}9o{IKvN;Rnw-3L^lc*@Br|rKqJT$-|rqlMtj+Q68UF zzlvTDKeugf{}&8;83c!|04~pjj7sHrKq~u-Vi?c>^a5hzTqH_57`s#FNT% zr36(f7kd?oD$sB56j(l*k&+IgD@8!Fyg4_k^>+q!ZISpq7Mp~TT;E$HIYbsR9EYIl zzP~<8voPdsh#=18@s@^xqa6(3u(Tju zZPrSFEyqNj;G8z`4Pd}*WC_Bzw@|TDrWh54V6A!qhConx<eY!{6@Rm>lZ>9hC zxptdU2ph{~ETmaewd{033v@PyBVc{)m;jxqWs&>M<2W9wAYIIbH-_fxB!CTQ$XYhBwI?IPoo#h7)>3ga5 zEfZSTH&kmmbMOEC&z=Nr)qxM*0|E)UEznS%897i=@6LU4?$8ii-d4lF5&>I|{vJ5r z8684nm4k-{4`~|5+vp3U?~lH9eTf=q(D}jWNZ?HN{eeS=MnBj+SW=+y!W|nLYpf%R zT0b9K)V8|4jxN^1)P1J51V+AhVE+7{g9`Jk@lN#}l=jRUw`G8nYEEx{x$QsWKa)Lk zx&8KA{xg~iQddYU6#H1c=#~Q<4j7@v59=7@yOGNtI`59^b8-@yK)5=72+UDqkFAt& zG0PhM2rLo)F6KCfJJ#_^y}~*lYjo)j&r3`D{r`UaCEo;uy5av8BctQLlL#RML$ z*Pk{?Z0zyDPh*a*AKY4v8h)rTM39r|HtvSiVKly|b?TAl=o#y2o}+Kn{erOkjUgP; zaMc(#S+jif*G==IPOk03OO`$GS0Cb!EUBxdb9Y+q01TesX`r`|r5gvA`)w6&+ z0|8J#zFz^F2?Ao=cQg9_!NWtRqC?{chfiG|7y#0F@G$z|&xWesgM`WGknRIRRZShN zu}6(c?%u5>7-;p_W7@s;Xmd?zbh3_KYV+>h%U{nBIL zlF-=V*HRtYK4H%Io!WlE%##Beb8MN8+y(h5@6lK!#hfTwnlT02iZYhfQ!Gx{LV%nE z_fxz2*Ju~qTQS2~uKl_(_vtkFPpra?{?`Fr`2?G z8t#rkFwil2T=(d!<6OJGO9mOnHIKFS7r+={2c4vF3u0~6n`Y2GR$0z1*sEABK*eqx z!wlDs=}YrEzKARtv)6UVpG1Un_i>-Y9FNuBC#q_C`HV5UPqgp$s zJTF~1LHpp}X!H!wi;fG(nd1f;rzz?qpkyBEKdlB%f#?l^s*SQp#`AQF`oKRMGpo}i|PGqCAU0qj(A~00>W0hK_iSJ5_{RavZCaMg)};`m3iE9Xb7?F6~Olfa6Qox;M7Fy@-Va4f>+EH1Pk zmbcOr@bvnb!v)%grI(99fCPhdIt3CE36zAuSt2zBCF;aMBxMknC;=48igLis@iGo) zkOrY-NW$^!^lM5Qb(5nMYEp=Kijb3RX^^0S)^(H z+Nj~mKsvRBy1K64WuFWN6we6zWo0EcEQ;C@>`Dw{d~W)#sTL~+u3uHbLi4k2((54m zN_^u{%r)!RSuENNCdAWiHxSCzCGt7Z47$pJNw*#iQb(?1c`Ji^tLMraPNHyE-I